diff --git a/.gitignore b/.gitignore index d18402de39f8b0..70ad45c3202958 100644 --- a/.gitignore +++ b/.gitignore @@ -1,2 +1,34 @@ +.DS_Store +.tags +.ipynb_checkpoints +.idea +.sconsign.dblite +model2.png +a.out + +*.DSYM +*.d *.pyc +*.pyo .*.swp +.*.swo +.*.un~ +*.o +*.so +*.a +*.clb +*.class +*.pyxbldc +*.vcd +config.json +clcache + +board/obj/ +selfdrive/boardd/boardd +selfdrive/logcatd/logcatd +selfdrive/proclogd/proclogd +selfdrive/ui/ui +selfdrive/test/tests/plant/out +/src/ + +one diff --git a/.travis.yml b/.travis.yml new file mode 100644 index 00000000000000..74411b5de82281 --- /dev/null +++ b/.travis.yml @@ -0,0 +1,12 @@ +sudo: required + +services: + - docker + +install: + - docker build -t tmppilot -f Dockerfile.openpilot . + +script: + - docker run --rm + -v "$(pwd)"/selfdrive/test/tests/plant/out:/tmp/openpilot/selfdrive/test/tests/plant/out + tmppilot /bin/sh -c 'cd /tmp/openpilot/selfdrive/test/tests/plant && OPTEST=1 ./test_longitudinal.py' diff --git a/CONTRIBUTING.md b/CONTRIBUTING.md new file mode 100644 index 00000000000000..5305a72237ddb3 --- /dev/null +++ b/CONTRIBUTING.md @@ -0,0 +1,18 @@ +# How to contribute + +Our software is open source so you can solve your own problems without needing help from others. And if you solve a problem and are so kind, you can upstream it for the rest of the world to use. + +Most open source development activity is coordinated through our [Discord](https://discord.comma.ai). A lot of documentation is available on our [medium](https://medium.com/@comma_ai/) + +## Getting Started + + * Join our [Discord](https://discord.comma.ai) + * Make sure you have a [GitHub account](https://github.com/signup/free) + * Fork [our repositories](https://github.com/commaai) on GitHub + +## Car Ports (openpilot) + +We've released a [Model Port guide](https://medium.com/@comma_ai/openpilot-port-guide-for-toyota-models-e5467f4b5fe6) for porting to Toyota/Lexus models. + +If you port openpilot to a substantially new car brand, see this more generic [Brand Port guide](https://medium.com/@comma_ai/how-to-write-a-car-port-for-openpilot-7ce0785eda84). You might also be eligible for a bounty. See our bounties at [comma.ai/bounties.html](https://comma.ai/bounties.html) + diff --git a/Dockerfile.openpilot b/Dockerfile.openpilot new file mode 100644 index 00000000000000..de602f3bca96c7 --- /dev/null +++ b/Dockerfile.openpilot @@ -0,0 +1,40 @@ +FROM ubuntu:16.04 +ENV PYTHONUNBUFFERED 1 + +RUN apt-get update && apt-get install -y \ + build-essential \ + clang \ + vim \ + screen \ + wget \ + bzip2 \ + git \ + libglib2.0-0 \ + python-pip \ + capnproto \ + libcapnp-dev \ + libzmq5-dev \ + libffi-dev \ + libusb-1.0-0 \ + libssl-dev \ + ocl-icd-libopencl1 \ + ocl-icd-opencl-dev \ + opencl-headers + +RUN pip install numpy==1.11.2 scipy==0.18.1 matplotlib==2.1.2 + +COPY requirements_openpilot.txt /tmp/ +RUN pip install -r /tmp/requirements_openpilot.txt + +ENV PYTHONPATH /tmp/openpilot:$PYTHONPATH + +COPY ./common /tmp/openpilot/common +COPY ./cereal /tmp/openpilot/cereal +COPY ./opendbc /tmp/openpilot/opendbc +COPY ./selfdrive /tmp/openpilot/selfdrive +COPY ./phonelibs /tmp/openpilot/phonelibs +COPY ./pyextra /tmp/openpilot/pyextra + +RUN mkdir -p /tmp/openpilot/selfdrive/test/out +RUN make -C /tmp/openpilot/selfdrive/controls/lib/longitudinal_mpc clean +RUN make -C /tmp/openpilot/selfdrive/controls/lib/lateral_mpc clean diff --git a/LICENSE b/LICENSE new file mode 100644 index 00000000000000..7dafa9443b1545 --- /dev/null +++ b/LICENSE @@ -0,0 +1,7 @@ +Copyright (c) 2018, Comma.ai, 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. diff --git a/Makefile b/Makefile new file mode 100644 index 00000000000000..4f690b2e7e88c1 --- /dev/null +++ b/Makefile @@ -0,0 +1,9 @@ + +code_dir := $(shell pwd) + +# TODO: Add a global build system + +.PHONY: all +all: + cd selfdrive && PYTHONPATH=$(code_dir) PREPAREONLY=1 ./manager.py + diff --git a/README.md b/README.md index eec42dfefa7ff2..b3712aac26e408 100644 --- a/README.md +++ b/README.md @@ -1,53 +1,80 @@ -opendbc -====== +PLEASE DO A FRESH CLONE INSTEAD OF GIT PULL FOR THE LATEST CHANGES -The project to democratize access to the decoder ring of your car. +This is a fork of comma's openpilot, and contains tweaks for Hondas and GM vehicles +IMPORTANT! +Distance Intervals have Changed (AGAIN) +One bar: 0.9s +Two bar: 1.3s (initial value) +Three bar: 1.8s (comma default) +Four bar: 2.5s +WARNING: Do NOT depend on OP to stop the car in time if you are approaching an object which is not in motion in the same direction as your car. The radar will NOT detect the stationary object in time to slow your car enough to stop. If you are approaching a stopped vehicle you must disengage and brake as radars ignore objects that are not in motion. -### DBC file basics +NOTICE: Due to feedback I have turned on OTA updates. You will receive updates automatically on your Eon so you don't have to reclone or git pull any longer to receive new features. If you DO NOT want OTA updates then create a file called "/data/no_ota_updates" and it will not perform OTA updates as long as that file exists. -A DBC file encodes, in a humanly readable way, the information needed to understand a vehicle's CAN bus traffic. A vehicle might have multiple CAN buses and every CAN bus is represented by its own dbc file. -Wondering what's the DBC file format? [Here](http://www.socialledge.com/sjsu/index.php?title=DBC_Format) and [Here](https://github.com/stefanhoelzl/CANpy/blob/master/docs/DBC_Specification.md) a couple of good overviews. -### How to start reverse engineering cars +I will attempt to detail the changes in each of the branches here: -[opendbc](https://github.com/commaai/opendbc) is integrated with [cabana](https://community.comma.ai/cabana/). +kegman - this is the default branch which does not include Gernby's resonant feed forward steering (i.e. it's comma's default steering) - it now includes GM code (needs testing) -Use [panda](https://github.com/commaai/panda) to connect your car to a computer. +kegman-plusGernbySteering (Updated Jan 22) - this branch is everything in the kegman branch PLUS a Gernby's LATEST feed forward steering. This also includes working code for GM cars. (thx to @jamezz for the code and @cryptokylan for submitting the GM stuff!) -### DBC file preprocessor +kegman-plusPilotAwesomeness - If you have a Honda Pilot, OR Honda Ridgeline use this branch. It has everything in kegman branch, uses my PID tuning + a magical older version of Gernby's FF steering which just happened to work very well across all driving conditions including slanted (crowned roads), wind gusts, road bumps, centering on curves, and keeping proper distance from curbs. I have yet to test a combination of FF steering and PID tuning that can beat the performance of this for Honda Pilots. -DBC files for different models of the same brand have a lot of overlap. Therefore, we wrote a preprocessor to create DBC files from a brand DBC file and a model specific DBC file. The source DBC files can be found in the generator folder. After changing one of the files run the generator.py script to regenerate the output files. These output files will be placed in the root of the opendbc repository and are suffixed by _generated. +Note above comments apply to Clarity testing branches as well. -### Good practices for contributing to opendbc -- Comments: the best way to store comments is to add them directly to the DBC files. For example: - ``` - CM_ SG_ 490 LONG_ACCEL "wheel speed derivative, noisy and zero snapping"; - ``` - is a comment that refers to signal `LONG_ACCEL` in message `490`. Using comments is highly recommended, especially for doubts and uncertainties. [cabana](https://community.comma.ai/cabana/) can easily display/add/edit comments to signals and messages. +List of changes and tweaks (latest changes at the top): +- Persist some configuration data in JSON file (/data/kegman/json): Sometimes you just want to make a tweak and persist some data that doesn't get wiped out the next time OP is updated. Stuff like: -- Units: when applicable, it's recommended to convert signals into physical units, by using a proper signal factor. Using a SI unit is preferred, unless a non-SI unit rounds the signal factor much better. -For example: - ``` - SG_ VEHICLE_SPEED : 7|15@0+ (0.00278,0) [0|70] "m/s" PCM - ``` - is better than: - ``` - SG_ VEHICLE_SPEED : 7|15@0+ (0.00620,0) [0|115] "mph" PCM - ``` - However, the cleanest option is really: - ``` - SG_ VEHICLE_SPEED : 7|15@0+ (0.01,0) [0|250] "kph" PCM - ``` -- Signal's size: always use the smallest amount of bits possible. For example, let's say I'm reverse engineering the gas pedal position and I've determined that it's in a 3 bytes message. For 0% pedal position I read a message value of `0x00 0x00 0x00`, while for 100% of pedal position I read `0x64 0x00 0x00`: clearly, the gas pedal position is within the first byte of the message and I might be tempted to define the signal `GAS_POS` as: - ``` - SG_ GAS_POS : 7|8@0+ (1,0) [0|100] "%" PCM - ``` - However, I can't be sure that the very first bit of the message is referred to the pedal position: I haven't seen it changing! Therefore, a safer way of defining the signal is: - ``` - SG_ GAS_POS : 6|7@0+ (1,0) [0|100] "%" PCM - ``` - which leaves the first bit unallocated. This prevents from very erroneous reading of the gas pedal position, in case the first bit is indeed used for something else. +"battChargeMax": "70", (Max limit % to stop charging Eon battery) + +"battChargeMin": "60", (Min limit % to start charging Eon battery) + +"cameraOffset": "0.06", (CAMERA_OFFSET - distance from the center of car to Eon camera) + +"lastTrMode": "2", (last distance interval bars you used - (auto generated - do not touch this) + +"wheelTouchSeconds": "180" (time interval between wheel touches when driver facial monitoring is not on - MAX LIMIT 600 seconds) + + +^^^ This file is auto generated here: /data/kegman.json so it will remain even when you do a fresh clone. If you mess something up, just delete the file and it will auto generate to default values. Use vim or nano to edit this file to your heart's content. + +- Remember last distance bar interval: On startup, the car will bring up the last distance interval used before the car was turned off. For example: If you were at X bars before you stopped the car or shut the Eon down, the next time you start the car, the distance setting will be X bars. + +- OTA Updates turned on: Previously I had turned off OTA updates for safety reasons - I didn't want anyone to get an unexpected result when I made changes. It appears that many more users want OTA updates for convenience so I have turned this feature back on. IMPORTANT: If you DO NOT want OTA updates then create a file called "/data/no_ota_updates" and it will not perform OTA updates as long as that file exists. + +- Increase acceleration profile when lead car pulls away too quickly or no lead car: OP has two acceleration profiles, one occurs when following a lead car, and one without a lead car. Oddly the acceleration profile when following is greater than when not following. So sometimes a lead car will pull away so quickly, that the car goes from following to not following mode and the acceleration profile actually drops. I've made the acceleration profiles the same so that the the car doesn't stop accelerating at the same rate when the lead car rips away quickly from a stop. + +- FOUR (new) Step adjustable follow distance: The default behaviour for following distance is 1.8s of following distance. It is not adjustable. This typically causes, in some traffic conditions, the user to be constantly cut off by other drivers, and 1.8s of follow distance instantly becomes much shorter (like 0.2-0.5s). I wanted to reintroduce honda 'stock-like' ACC behaviour back into the mix to prevent people from getting cutoff so often. Here is a summary of follow distance in seconds: 1 bar = 0.9s, 2 bars = 1.3s, 3 bars = 1.8, 4 bars = 2.5s of follow distance. Thanks to @arne182, whose code I built upon. + +- Reduce speed dependent lane width to 2.85 to 3.5 (from 3.0 to 3.7) [meters]: This has the effect of making the car veer less towards a disappearing lane line because it assumes that the lane width is less. It may also improve curb performance. + +- Display km/h for set speed in ACC HUD: For Nidec Hondas, Openpilot overrides Honda's global metric settings and displays mph no matter what. This change makes the ACC HUD show km/h or mph and abides by the metric setting on the Eon. I plan on upstreaming this change to comma in the near future. + +- Kill the video uploader when the car is running: Some people like to tether the Eon to a wifi hotspot on their cellphone instead of purchasing a dedicated SIM card to run on the Eon. When this occurs default comma code will upload large video files even while you are driving chewing up your monthly data limits. This change stops the video from uploading when the car is running. *caution* when you stop the car, the videos will resume uploading on your cellular hotspot if you forget to disconnect it. + +- Increase brightness of Eon screen: After the NEOS 8 upgrade some have reported that the screen is too dim. I have boosted the screen brightness to compensate for this. + +- Battery limit charging: The default comma code charges the Eon to 100% and keeps it there. LiIon batteries such as the one in the Eon do not like being at 100% or low states of charge for extended periods (this is why when you first get something with a LiIon battery it is always near 50% - it is also why Tesla owners don't charge their cars to 100% if they can help it). By keeping the charge between 60-70% this will prolong the life of the battery in your Eon. *NOTE* after your battery gets to 70% the LED will turn from yellow to RED and stay there. Rest assured that while plugged in the battery will stay between 60-70%. You can (and should) verify this by plugging the Eon in, SSHing into the Eon and performing a 'tmux a' command to monitor what the charging does. When you disconnect your Eon, be sure to shut it down properly to keep it in the happy zone of 60-70%. You can also look at the battery icon to ensure the battery is approximately 60-70% by touching near the left of the eon screen. Thanks to @csouers for the initial iteration of this. + +- Tuned braking at city street speeds (Nidecs only): Some have described the default braking when slowing to a stop can be very 'late'. I have introduced a change in MPC settings to slow the car down sooner when the radar detects deceleration in the lead car. Different profiles are used for 1 bar and 2 bar distances, with a more aggressive braking profile applied to 1 bar distance. Additionally lead car stopped distance is increased so that you stop a little farther away from the car in front for a greater margin of error. Thanks to @arne182 for the MPC and TR changes which I built upon. + +- Fixed grinding sound when braking with Pedal (Pilots only): Honda Pilots with pedals installed may have noticed a loud ripping / grinding noise accompanied by oscillating pressure on the brake when the brake is pressed especially at lower speeds. This occurs because OP disengages too late when the brake is pressed and the user ends up fighting with OP for the right brake position. This fix detects brake pressure sooner so that OP disengages sooner so that the condition is significantly reduced. If you are on another model and this is happening this fix may also work for you so please message me on Slack or Discord @kegman. + +- Smoother acceration from stop (Pedal users): The default acceleration / gas profile when pedal is installed may cause a head snapping "lurch" from a stop which can be quite jarring. This fix smoothes out the acceleration when coming out of a stop. + +- Dev UI: Thanks to @zeeexaris who made this work post 0.5.7 - displays widgets with steering information and temperature as well as lead car velocity and distance. Very useful when entering turns to know how tight the turn is and more certainty as to whether you have to intervene. Also great when PID tuning. + +- Gernby's Resonant Feed Forward Steering: This is still a work in progress. Some cars respond very well while there is more variance with other cars. You may need to tweak some parameters to make it work well but once it's dialed in it makes the wheel very stiff and more impervious to wind / bumps and in some cases makes car centering better (such as on the PilotAwesomeness branch). Give it a try and let @gernby know what you find. Gernby's steering is available on kegman-plusGernbySteering, kegman-plusPilotAwesomeness. + +- Steering off when blinkers on: The default behaviour when changing lanes is the user overrides the wheel, a bunch of steering required alarms sound and the user lets go of the wheel. I didn't like fighting the wheel so when the blinkers are on I've disabled the OP steering. Note that the blinker stock must be fully left or right or held in position for the steering to be off. The "3 blink" tap of the stock does not deactivate steering for long enough to be noticeable. + +- LKAS button toggles steering: Stock Openpilot deactivates the LKAS button. In some cases while driving you may have to fight the wheel for a long period of time. By pressing the LKAS button you can toggle steering off or on so that you don't have to fight the wheel, which can get tiring and probably isn't good for the EPS motor. When LKAS is toggled off OP still controls gas and brake so it's more like standard ACC. + +- Honda Pilot and Ridgeline PID: I wasn't happy with the way Honda Pilot performed on curves where the car often would hug the inside line of the turn and this was very hazardous in 2 lane highways where it got very close to the oncoming traffic. Also, on crowned roads (where the fast lane slants to the left and where the slow lane slants to the right), the car would not overcome the gravity of the slanted road and "hug" in the direction of the slant. After many hours of on the road testing, I have mitigated this issue. When combined with Gernby's steering it is quite a robust setup. This combination is found in kegman-plusPilotAwesomeness. Apparently this branch works well with RIDGELINES too! + + +Enjoy everyone. diff --git a/README_chffrplus.md b/README_chffrplus.md new file mode 100644 index 00000000000000..dc13e8c3f264c6 --- /dev/null +++ b/README_chffrplus.md @@ -0,0 +1,36 @@ +Welcome to chffrplus +====== + +[chffrplus](https://github.com/commaai/chffrplus) is an open source dashcam. + +This is the shipping reference software for the comma EON Dashcam DevKit. It keeps many of the niceities of [openpilot](https://github.com/commaai/openpilot), like high quality sensors, great camera, and good autostart and stop. Though unlike openpilot, it cannot control your car. chffrplus can interface with your car through a [panda](https://shop.comma.ai/products/panda-obd-ii-dongle), but just like our dashcam app [chffr](https://getchffr.com/), it is read only. + +It integrates with the rest of the comma ecosystem, so you can view your drives on the [chffr](https://getchffr.com/) app for Android or iOS, and reverse engineer your car with [cabana](https://community.comma.ai/cabana/?demo=1). + + +Hardware +------ + +Right now chffrplus supports the [EON Dashcam DevKit](https://shop.comma.ai/products/eon-dashcam-devkit) for hardware to run on. + +Install chffrplus on a EON device by entering ``https://chffrplus.comma.ai`` during NEOS setup. + + +User Data / chffr Account / Crash Reporting +------ + +By default chffrplus creates an account and includes a client for chffr, our dashcam app. + +It's open source software, so you are free to disable it if you wish. + +It logs the road facing camera, CAN, GPS, IMU, magnetometer, thermal sensors, crashes, and operating system logs. +It does not log the user facing camera or the microphone. + +By using it, you agree to [our privacy policy](https://beta.comma.ai/privacy.html). You understand that use of this software or its related services will generate certain types of user data, which may be logged and stored at the sole discretion of comma.ai. By accepting this agreement, you grant an irrevocable, perpetual, worldwide right to comma.ai for the use of this data. + + +Licensing +------ + +chffrplus is released under the MIT license. + diff --git a/RELEASES.md b/RELEASES.md new file mode 100644 index 00000000000000..482f2009186302 --- /dev/null +++ b/RELEASES.md @@ -0,0 +1,333 @@ +Version 0.5.8 (2019-01-17) +======================== + * Open sourced visiond + * Auto-slowdown for upcoming turns + * Chrysler/Jeep/Fiat support thanks to adhintz! + * Honda Civic 2019 support thanks to csouers! + * Improved use of car display in Toyota thanks to arne182! + * No data upload when connected to Android or iOS hotspots and "Enable Upload Over Cellular" setting is off + * EON stops charging when 12V battery drops below 11.8V + +Version 0.5.7 (2018-12-06) +======================== + * Speed limit from OpenStreetMap added to UI + * Highlight speed limit when speed exceeds road speed limit plus a delta + * Option to limit openpilot max speed to road speed limit plus a delta + * Cadillac ATS support thanks to vntarasov! + * GMC Acadia support thanks to CryptoKylan! + * Decrease GPU power consumption + * NEOSv8 autoupdate + +Version 0.5.6 (2018-11-16) +======================== + * Refresh settings layout and add feature descriptions + * In Honda, keep stock camera on for logging and extra stock features; new openpilot giraffe setting is 0111! + * In Toyota, option to keep stock camera on for logging and extra stock features (e.g. AHB); 120Ohm resistor required on giraffe. + * Improve camera calibration stability + * More tuning to Honda positive accelerations + * Reduce brake pump use on Hondas + * Chevrolet Malibu support thanks to tylergets! + * Holden Astra support thanks to AlexHill! + +Version 0.5.5 (2018-10-20) +======================== + * Increase allowed Honda positive accelerations + * Fix sporadic unexpected braking when passing semi-trucks in Toyota + * Fix gear reading bug in Hyundai Elantra thanks to emmertex! + +Version 0.5.4 (2018-09-25) +======================== + * New Driving Model + * New Driver Monitoring Model + * Improve longitudinal mpc in mid-low speed braking + * Honda Accord hybrid support thanks to energee! + * Ship mpc binaries and sensibly reduce build time + * Calibration more stable + * More Hyundai and Kia cars supported thanks to emmertex! + * Various GM Volt improvements thanks to vntarasov! + +Version 0.5.3 (2018-09-03) +======================== + * Hyundai Santa Fe support! + * Honda Pilot 2019 support thanks to energee! + * Toyota Highlander support thanks to daehahn! + * Improve steering tuning for Honda Odyssey + +Version 0.5.2 (2018-08-16) +======================== + * New calibration: more accurate, a lot faster, open source! + * Enable orbd + * Add little endian support to CAN packer + * Fix fingerprint for Honda Accord 1.5T + * Improve driver monitoring model + +Version 0.5.1 (2018-08-01) +======================== + * Fix radar error on Civic sedan 2018 + * Improve thermal management logic + * Alpha Toyota C-HR and Camry support! + * Auto-switch Driver Monitoring to 3 min counter when inaccurate + +Version 0.5 (2018-07-11) +======================== + * Driver Monitoring (beta) option in settings! + * Make visiond, loggerd and UI use less resources + * 60 FPS UI + * Better car parameters for most cars + * New sidebar with stats + * Remove Waze and Spotify to free up system resources + * Remove rear view mirror option + * Calibration 3x faster + +Version 0.4.7.2 (2018-06-25) +========================== + * Fix loggerd lag issue + * No longer prompt for updates + * Mitigate right lane hugging for properly mounted EON (procedure on wiki) + +Version 0.4.7.1 (2018-06-18) +========================== + * Fix Acura ILX steer faults + * Fix bug in mock car + +Version 0.4.7 (2018-06-15) +========================== + * New model! + * GM Volt (and CT6 lateral) support! + * Honda Bosch lateral support! + * Improve actuator modeling to reduce lateral wobble + * Minor refactor of car abstraction layer + * Hack around orbd startup issue + +Version 0.4.6 (2018-05-18) +========================== + * NEOSv6 required! Will autoupdate + * Stability improvements + * Fix all memory leaks + * Update C++ compiler to clang6 + * Improve front camera exposure + +Version 0.4.5 (2018-04-27) +========================== + * Release notes added to the update popup + * Improve auto shut-off logic to disallow empty battery + * Added onboarding instructions + * Include orbd, the first piece of new calibration algorithm + * Show remaining upload data instead of file numbers + * Fix UI bugs + * Fix memory leaks + +Version 0.4.4 (2018-04-13) +========================== + * EON are flipped! Flip your EON's mount! + * Alpha Honda Ridgeline support thanks to energee! + * Support optional front camera recording + * Upload over cellular toggle now applies to all files, not just video + * Increase acceleration when closing lead gap + * User now prompted for future updates + * NEO no longer supported :( + +Version 0.4.3.2 (2018-03-29) +============================ + * Improve autofocus + * Improve driving when only one lane line is detected + * Added fingerprint for Toyota Corolla LE + * Fixed Toyota Corolla steer error + * Full-screen driving UI + * Improved path drawing + +Version 0.4.3.1 (2018-03-19) +============================ + * Improve autofocus + * Add check for MPC solution error + * Make first distracted warning visual only + +Version 0.4.3 (2018-03-13) +========================== + * Add HDR and autofocus + * Update UI aesthetic + * Grey panda works in Waze + * Add alpha support for 2017 Honda Pilot + * Slight increase in acceleration response from stop + * Switch CAN sending to use CANPacker + * Fix pulsing acceleration regression on Honda + * Fix openpilot bugs when stock system is in use + * Change starting logic for chffrplus to use battery voltage + +Version 0.4.2 (2018-02-05) +========================== + * Add alpha support for 2017 Lexus RX Hybrid + * Add alpha support for 2018 ACURA RDX + * Updated fingerprint to include Toyota Rav4 SE and Prius Prime + * Bugfixes for Acura ILX and Honda Odyssey + +Version 0.4.1 (2018-01-30) +========================== + * Add alpha support for 2017 Toyota Corolla + * Add alpha support for 2018 Honda Odyssey with Honda Sensing + * Add alpha support for Grey Panda + * Refactored car abstraction layer to make car ports easier + * Increased steering torque limit on Honda CR-V by 30% + +Version 0.4.0.2 (2018-01-18) +========================== + * Add focus adjustment slider + * Minor bugfixes + +Version 0.4.0.1 (2017-12-21) +========================== + * New UI to match chffrplus + * Improved lateral control tuning to fix oscillations on Civic + * Add alpha support for 2017 Toyota Rav4 Hybrid + * Reduced CPU usage + * Removed unnecessary utilization of fan at max speed + * Minor bug fixes + +Version 0.3.9 (2017-11-21) +========================== + * Add alpha support for 2017 Toyota Prius + * Improved longitudinal control using model predictive control + * Enable Forward Collision Warning + * Acura ILX now maintains openpilot engaged at standstill when brakes are applied + +Version 0.3.8.2 (2017-10-30) +========================== + * Add alpha support for 2017 Toyota RAV4 + * Smoother lateral control + * Stay silent if stock system is connected through giraffe + * Minor bug fixes + +Version 0.3.7 (2017-09-30) +========================== + * Improved lateral control using model predictive control + * Improved lane centering + * Improved GPS + * Reduced tendency of path deviation near right side exits + * Enable engagement while the accelerator pedal is pressed + * Enable engagement while the brake pedal is pressed, when stationary and with lead vehicle within 5m + * Disable engagement when park brake or brake hold are active + * Fixed sporadic longitudinal pulsing in Civic + * Cleanups to vehicle interface + +Version 0.3.6.1 (2017-08-15) +============================ + * Mitigate low speed steering oscillations on some vehicles + * Include board steering check for CR-V + +Version 0.3.6 (2017-08-08) +========================== + * Fix alpha CR-V support + * Improved GPS + * Fix display of target speed not always matching HUD + * Increased acceleration after stop + * Mitigated some vehicles driving too close to the right line + +Version 0.3.5 (2017-07-30) +========================== + * Fix bug where new devices would not begin calibration + * Minor robustness improvements + +Version 0.3.4 (2017-07-28) +========================== + * Improved model trained on more data + * Much improved controls tuning + * Performance improvements + * Bugfixes and improvements to calibration + * Driving log can play back video + * Acura only: system now stays engaged below 25mph as long as brakes are applied + +Version 0.3.3 (2017-06-28) +=========================== + * Improved model trained on more data + * Alpha CR-V support thanks to energee and johnnwvs! + * Using the opendbc project for DBC files + * Minor performance improvements + * UI update thanks to pjlao307 + * Power off button + * 6% more torque on the Civic + +Version 0.3.2 (2017-05-22) +=========================== + * Minor stability bugfixes + * Added metrics and rear view mirror disable to settings + * Update model with more crowdsourced data + +Version 0.3.1 (2017-05-17) +=========================== + * visiond stability bugfix + * Add logging for angle and flashing + +Version 0.3.0 (2017-05-12) +=========================== + * Add CarParams struct to improve the abstraction layer + * Refactor visiond IPC to support multiple clients + * Add raw GPS and beginning support for navigation + * Improve model in visiond using crowdsourced data + * Add improved system logging to diagnose instability + * Rewrite baseui in React Native + * Moved calibration to the cloud + +Version 0.2.9 (2017-03-01) +=========================== + * Retain compatibility with NEOS v1 + +Version 0.2.8 (2017-02-27) +=========================== + * Fix bug where frames were being dropped in minute 71 + +Version 0.2.7 (2017-02-08) +=========================== + * Better performance and pictures at night + * Fix ptr alignment issue in boardd + * Fix brake error light, fix crash if too cold + +Version 0.2.6 (2017-01-31) +=========================== + * Fix bug in visiond model execution + +Version 0.2.5 (2017-01-30) +=========================== + * Fix race condition in manager + +Version 0.2.4 (2017-01-27) +=========================== + * OnePlus 3T support + * Enable installation as NEOS app + * Various minor bugfixes + +Version 0.2.3 (2017-01-11) +=========================== + * Reduce space usage by 80% + * Add better logging + * Add Travis CI + +Version 0.2.2 (2017-01-10) +=========================== + * Board triggers started signal on CAN messages + * Improved autoexposure + * Handle out of space, improve upload status + +Version 0.2.1 (2016-12-14) +=========================== + * Performance improvements, removal of more numpy + * Fix boardd process priority + * Make counter timer reset on use of steering wheel + +Version 0.2 (2016-12-12) +========================= + * Car/Radar abstraction layers have shipped, see cereal/car.capnp + * controlsd has been refactored + * Shipped plant model and testing maneuvers + * visiond exits more gracefully now + * Hardware encoder in visiond should always init + * ui now turns off the screen after 30 seconds + * Switch to openpilot release branch for future releases + * Added preliminary Docker container to run tests on PC + +Version 0.1 (2016-11-29) +========================= + * Initial release of openpilot + * Adaptive cruise control is working + * Lane keep assist is working + * Support for Acura ILX 2016 with AcuraWatch Plus + * Support for Honda Civic 2016 Touring Edition diff --git a/SAFETY.md b/SAFETY.md new file mode 100644 index 00000000000000..a2f77a55093901 --- /dev/null +++ b/SAFETY.md @@ -0,0 +1,109 @@ +openpilot Safety +====== + +openpilot is an Adaptive Cruise Control (ACC) and Lane Keeping Assist (LKA) system. +Like other ACC and LKA systems, openpilot requires the driver to be alert and to +pay attention at all times. We repeat, **driver alertness is necessary, but not +sufficient, for openpilot to be used safely**. + +In order to enforce driver alertness, openpilot includes a driver monitoring feature +that alerts the driver when distracted. + +However, even with an attentive driver, we must make further efforts for the system to be +safe. We have designed openpilot with two other safety considerations. + +1. The driver must always be capable to immediately retake manual control of the vehicle, + by stepping on either pedal or by pressing the cancel button. +2. The vehicle must not alter its trajectory too quickly for the driver to safely + react. This means that while the system is engaged, the actuators are constrained + to operate within reasonable limits. + +Following are details of the car specific safety implementations: + +Honda/Acura +------ + + - While the system is engaged, gas, brake and steer commands are subject to the same limits used by + the stock system. + + - Without an interceptor, the gas is controlled by the Powertrain Control Module (PCM). + The PCM limits acceleration to what is reasonable for a cruise control system. With an + interceptor, the gas is clipped to 60%. + + - The brake is controlled by the 0x1FA CAN message. This message allows full + braking, although the panda firmware and openpilot clip it to 1/4th of the max. + This is approximately 0.3g of braking. + + - Steering is controlled by the 0xE4 CAN message. The Electronic Power Steering (EPS) + controller in the car limits the torque to a very small amount, so regardless of the + message, the controller cannot jerk the wheel. + + - Brake and gas pedal pressed signals are contained in the 0x17C CAN message. A rising edge of + either signals triggers a disengagement, which is enforced by the panda firmware and by openpilot. The + white led on the panda signifies if the panda is allowing control messages. + + - Honda CAN uses both a counter and a checksum to ensure integrity and prevent + replay of the same message. + +Toyota/Lexus +------ + + - While the system is engaged, gas, brake and steer commands are subject to the same limits used by + the stock system. + + - With the stock Driving Support Unit (DSU) connected (or in DSU-less models like Camry and C-HR), + the acceleration is controlled by the stock system and is subject to the stock adaptive cruise + control limits. Without the stock DSU connected, the acceleration command is controlled by the + 0x343 CAN message and its value is limited between .3g of deceleration and .15g of acceleration + by the panda firmware and by openpilot. The acceleration command is ignored by the Engine Control + Module (ECM) while the cruise control system is disengaged. + + - Steering torque is controlled through the 0x2E4 CAN message and it's limited by the panda firmware and by + openpilot to a value between -1500 and 1500. In addition, the vehicle EPS unit will not respond to + commands outside these limits. A steering torque rate limit is enforced by the panda firmware and by + openpilot, so that the commanded steering torque must rise from 0 to max value no faster than + 1.5s. Commanded steering torque is limited by the panda firmware and by openpilot to be no more than 350 + units above the actual EPS generated motor torque to ensure limited differences between + commanded and actual torques. + + - Brake and gas pedal pressed signals are contained in the 0x224 and 0x1D2 CAN messages, + respectively. A rising edge of either signals triggers a disengagement, which is enforced by the + panda firmware and by openpilot. Additionally, the cruise control system disengages on the rising edge of + the brake pedal pressed signal. + + - The cruise control system state is contained in the 0x1D2 message. No control messages are + allowed if the cruise control system is not active. This is enforced by openpilot and the + panda firmware. The white led on the panda signifies if the panda is allowing control messages. + +GM/Chevrolet +------ + + - While the system is engaged, gas, brake and steer commands are subject to the same limits used by + the stock system. + + - The gas and regen are controlled by the 0x2CB message and it's limited by the panda firmware and by + openpilot to a value between 1404 and 3072. the minimum value correspond to a mild decel due to regen, + while 3072 correspond to approximately 0.18g of acceleration from stop. + + - The friction brakes are controlled by the 0x315 message and its value is limited by the panda firmware + and openpilot to 350. This is approximately 0.3g of braking. + + - Steering torque is controlled through the 0x180 CAN message and it's limited by the panda firmware and by + openpilot to a value between -255 and 255. In addition, the vehicle EPS unit will not fault when + commands outside these limits. A steering torque rate limit is enforced by the panda firmware and by + openpilot, so that the commanded steering torque must rise from 0 to max value no faster than + 0.75s. Commanded steering torque is gradually limited by the panda firmware and by openpilot if the driver's + torque exceeds 12 units in the opposite dicrection to ensure limited applied torque against the + driver's will. + + - Brake pedal and gas pedal potentiometer signals are contained in the 0xF1 and 0x1A1 CAN messages, + respectively. A rising edge of either signals triggers a disengagement, which is enforced by the + panda firmware and by openpilot. Additionally, the cruise control system disengages on the rising edge of + the brake pedal pressed signal. The regen paddle pressed signal is in the 0xBD message. When the + regen paddle is pressed, a disengagement is enforced by both the firmware and by openpilot. + + - GM CAN uses both a counter and a checksum to ensure integrity and prevent + replay of the same message. + +**Extra note"**: comma.ai strongly discourages the use of openpilot forks with safety code either missing or + not fully meeting the above requirements. diff --git a/apk/ai.comma.plus.black.apk b/apk/ai.comma.plus.black.apk new file mode 100644 index 00000000000000..b9243077f351c7 Binary files /dev/null and b/apk/ai.comma.plus.black.apk differ diff --git a/apk/ai.comma.plus.frame.apk b/apk/ai.comma.plus.frame.apk new file mode 100644 index 00000000000000..02c4f181f04064 Binary files /dev/null and b/apk/ai.comma.plus.frame.apk differ diff --git a/apk/ai.comma.plus.offroad.apk b/apk/ai.comma.plus.offroad.apk new file mode 100644 index 00000000000000..ac34dca2bde7a0 Binary files /dev/null and b/apk/ai.comma.plus.offroad.apk differ diff --git a/cereal/.gitignore b/cereal/.gitignore new file mode 100644 index 00000000000000..57b5883f38d38d --- /dev/null +++ b/cereal/.gitignore @@ -0,0 +1,3 @@ +gen +node_modules +package-lock.json diff --git a/cereal/Makefile b/cereal/Makefile new file mode 100644 index 00000000000000..dc6b7f9d51fa03 --- /dev/null +++ b/cereal/Makefile @@ -0,0 +1,62 @@ +PWD := $(shell pwd) + +SRCS := log.capnp car.capnp + +GENS := gen/cpp/car.capnp.c++ gen/cpp/log.capnp.c++ +JS := gen/js/car.capnp.js gen/js/log.capnp.js + +UNAME_M ?= $(shell uname -m) +# only generate C++ for docker tests +ifneq ($(OPTEST),1) + GENS += gen/c/car.capnp.c gen/c/log.capnp.c gen/c/include/c++.capnp.h gen/c/include/java.capnp.h + + ifeq ($(UNAME_M),x86_64) + ifneq (, $(shell which capnpc-java)) + GENS += gen/java/Car.java gen/java/Log.java + else + $(warning capnpc-java not found, skipping java build) + endif + endif + +endif + +ifeq ($(UNAME_M),aarch64) + CAPNPC=PATH=$(PWD)/../phonelibs/capnp-cpp/aarch64/bin/:$$PATH capnpc +else + CAPNPC=capnpc +endif + +.PHONY: all +all: $(GENS) +js: $(JS) + +.PHONY: clean +clean: + rm -rf gen + rm -rf node_modules + rm -rf package-lock.json + +gen/c/%.capnp.c: %.capnp + @echo "[ CAPNPC C ] $@" + mkdir -p gen/c/ + $(CAPNPC) '$<' -o c:gen/c/ + +gen/js/%.capnp.js: %.capnp + @echo "[ CAPNPC JavaScript ] $@" + mkdir -p gen/js/ + sh ./generate_javascript.sh + +gen/cpp/%.capnp.c++: %.capnp + @echo "[ CAPNPC C++ ] $@" + mkdir -p gen/cpp/ + $(CAPNPC) '$<' -o c++:gen/cpp/ + +gen/java/Car.java gen/java/Log.java: $(SRCS) + @echo "[ CAPNPC java ] $@" + mkdir -p gen/java/ + $(CAPNPC) $^ -o java:gen/java + +# c-capnproto needs some empty headers +gen/c/include/c++.capnp.h gen/c/include/java.capnp.h: + mkdir -p gen/c/include + touch '$@' diff --git a/cereal/__init__.py b/cereal/__init__.py new file mode 100644 index 00000000000000..2d3b48526b2c34 --- /dev/null +++ b/cereal/__init__.py @@ -0,0 +1,8 @@ +import os +import capnp + +CEREAL_PATH = os.path.dirname(os.path.abspath(__file__)) +capnp.remove_import_hook() + +log = capnp.load(os.path.join(CEREAL_PATH, "log.capnp")) +car = capnp.load(os.path.join(CEREAL_PATH, "car.capnp")) diff --git a/cereal/car.capnp b/cereal/car.capnp new file mode 100644 index 00000000000000..6fb97db08bb806 --- /dev/null +++ b/cereal/car.capnp @@ -0,0 +1,371 @@ +using Cxx = import "./include/c++.capnp"; +$Cxx.namespace("cereal"); + +using Java = import "./include/java.capnp"; +$Java.package("ai.comma.openpilot.cereal"); +$Java.outerClassname("Car"); + +@0x8e2af1e708af8b8d; + +# ******* events causing controls state machine transition ******* + +struct CarEvent @0x9b1657f34caf3ad3 { + name @0 :EventName; + enable @1 :Bool; + noEntry @2 :Bool; + warning @3 :Bool; + userDisable @4 :Bool; + softDisable @5 :Bool; + immediateDisable @6 :Bool; + preEnable @7 :Bool; + permanent @8 :Bool; + + enum EventName @0xbaa8c5d505f727de { + # TODO: copy from error list + commIssue @0; + steerUnavailable @1; + brakeUnavailable @2; + gasUnavailable @3; + wrongGear @4; + doorOpen @5; + seatbeltNotLatched @6; + espDisabled @7; + wrongCarMode @8; + steerTempUnavailable @9; + reverseGear @10; + buttonCancel @11; + buttonEnable @12; + pedalPressed @13; + cruiseDisabled @14; + radarCommIssue @15; + dataNeeded @16; + speedTooLow @17; + outOfSpace @18; + overheat @19; + calibrationIncomplete @20; + calibrationInvalid @21; + controlsMismatch @22; + pcmEnable @23; + pcmDisable @24; + noTarget @25; + radarFault @26; + modelCommIssue @27; + brakeHold @28; + parkBrake @29; + manualRestart @30; + lowSpeedLockout @31; + plannerError @32; + ipasOverride @33; + debugAlert @34; + steerTempUnavailableMute @35; + resumeRequired @36; + preDriverDistracted @37; + promptDriverDistracted @38; + driverDistracted @39; + geofence @40; + driverMonitorOn @41; + driverMonitorOff @42; + preDriverUnresponsive @43; + promptDriverUnresponsive @44; + driverUnresponsive @45; + belowSteerSpeed @46; + calibrationProgress @47; + lowBattery @48; + invalidGiraffeHonda @49; + manualSteeringRequired @50; + manualSteeringRequiredBlinkerOnLeft @51; + manualSteeringRequiredBlinkerOnRight @52; + } +} + +# ******* main car state @ 100hz ******* +# all speeds in m/s + +struct CarState { + errorsDEPRECATED @0 :List(CarEvent.EventName); + events @13 :List(CarEvent); + + # car speed + vEgo @1 :Float32; # best estimate of speed + aEgo @16 :Float32; # best estimate of acceleration + vEgoRaw @17 :Float32; # unfiltered speed from CAN sensors + yawRate @22 :Float32; # best estimate of yaw rate + standstill @18 :Bool; + wheelSpeeds @2 :WheelSpeeds; + + # gas pedal, 0.0-1.0 + gas @3 :Float32; # this is user + computer + gasPressed @4 :Bool; # this is user pedal only + + # brake pedal, 0.0-1.0 + brake @5 :Float32; # this is user pedal only + brakePressed @6 :Bool; # this is user pedal only + brakeLights @19 :Bool; + + # steering wheel + steeringAngle @7 :Float32; # deg + steeringRate @15 :Float32; # deg/s + steeringTorque @8 :Float32; # TODO: standardize units + steeringPressed @9 :Bool; # if the user is using the steering wheel + + # cruise state + cruiseState @10 :CruiseState; + + # gear + gearShifter @14 :GearShifter; + + # button presses + buttonEvents @11 :List(ButtonEvent); + leftBlinker @20 :Bool; + rightBlinker @21 :Bool; + genericToggle @23 :Bool; + readdistancelines @26 :Float32; + lkMode @27 :Bool; + + # lock info + doorOpen @24 :Bool; + seatbeltUnlatched @25 :Bool; + + # which packets this state came from + canMonoTimes @12: List(UInt64); + + struct WheelSpeeds { + # optional wheel speeds + fl @0 :Float32; + fr @1 :Float32; + rl @2 :Float32; + rr @3 :Float32; + } + + struct CruiseState { + enabled @0 :Bool; + speed @1 :Float32; + available @2 :Bool; + speedOffset @3 :Float32; + standstill @4 :Bool; + } + + enum GearShifter { + unknown @0; + park @1; + drive @2; + neutral @3; + reverse @4; + sport @5; + low @6; + brake @7; + } + + + # send on change + struct ButtonEvent { + pressed @0 :Bool; + type @1 :Type; + + enum Type { + unknown @0; + leftBlinker @1; + rightBlinker @2; + accelCruise @3; + decelCruise @4; + cancel @5; + altButton1 @6; + altButton2 @7; + altButton3 @8; + } + } +} + +# ******* radar state @ 20hz ******* + +struct RadarState { + errors @0 :List(Error); + points @1 :List(RadarPoint); + + # which packets this state came from + canMonoTimes @2 :List(UInt64); + + enum Error { + commIssue @0; + fault @1; + wrongConfig @2; + } + + # similar to LiveTracks + # is one timestamp valid for all? I think so + struct RadarPoint { + trackId @0 :UInt64; # no trackId reuse + + # these 3 are the minimum required + dRel @1 :Float32; # m from the front bumper of the car + yRel @2 :Float32; # m + vRel @3 :Float32; # m/s + + # these are optional and valid if they are not NaN + aRel @4 :Float32; # m/s^2 + yvRel @5 :Float32; # m/s + + # some radars flag measurements VS estimates + measured @6 :Bool; + } +} + +# ******* car controls @ 100hz ******* + +struct CarControl { + # must be true for any actuator commands to work + enabled @0 :Bool; + active @7 :Bool; + + gasDEPRECATED @1 :Float32; + brakeDEPRECATED @2 :Float32; + steeringTorqueDEPRECATED @3 :Float32; + + actuators @6 :Actuators; + + cruiseControl @4 :CruiseControl; + hudControl @5 :HUDControl; + + struct Actuators { + # range from 0.0 - 1.0 + gas @0: Float32; + brake @1: Float32; + # range from -1.0 - 1.0 + steer @2: Float32; + steerAngle @3: Float32; + } + + struct CruiseControl { + cancel @0: Bool; + override @1: Bool; + speedOverride @2: Float32; + accelOverride @3: Float32; + } + + struct HUDControl { + speedVisible @0: Bool; + setSpeed @1: Float32; + lanesVisible @2: Bool; + leadVisible @3: Bool; + visualAlert @4: VisualAlert; + audibleAlert @5: AudibleAlert; + rightLaneVisible @6: Bool; + leftLaneVisible @7: Bool; + + enum VisualAlert { + # these are the choices from the Honda + # map as good as you can for your car + none @0; + fcw @1; + steerRequired @2; + brakePressed @3; + wrongGear @4; + seatbeltUnbuckled @5; + speedTooHigh @6; + } + + enum AudibleAlert { + # these are the choices from the Honda + # map as good as you can for your car + none @0; + chimeEngage @1; + chimeDisengage @2; + chimeError @3; + chimeWarning1 @4; + chimeWarning2 @5; + chimeWarningRepeat @6; + chimePrompt @7; + } + } +} + +# ****** car param ****** + +struct CarParams { + carName @0 :Text; + radarNameDEPRECATED @1 :Text; + carFingerprint @2 :Text; + + enableSteerDEPRECATED @3 :Bool; + enableGasInterceptor @4 :Bool; + enableBrakeDEPRECATED @5 :Bool; + enableCruise @6 :Bool; + enableCamera @26 :Bool; + enableDsu @27 :Bool; # driving support unit + enableApgs @28 :Bool; # advanced parking guidance system + + minEnableSpeed @17 :Float32; + minSteerSpeed @49 :Float32; + safetyModel @18 :Int16; + safetyParam @41 :Int16; + + steerMaxBP @19 :List(Float32); + steerMaxV @20 :List(Float32); + gasMaxBP @21 :List(Float32); + gasMaxV @22 :List(Float32); + brakeMaxBP @23 :List(Float32); + brakeMaxV @24 :List(Float32); + + longPidDeadzoneBP @32 :List(Float32); + longPidDeadzoneV @33 :List(Float32); + + enum SafetyModels { + # does NOT match board setting + noOutput @0; + honda @1; + toyota @2; + elm327 @3; + gm @4; + hondaBosch @5; + ford @6; + cadillac @7; + hyundai @8; + chrysler @9; + tesla @10; + } + + # things about the car in the manual + mass @7 :Float32; # [kg] running weight + wheelbase @8 :Float32; # [m] distance from rear to front axle + centerToFront @9 :Float32; # [m] GC distance to front axle + steerRatio @10 :Float32; # [] ratio between front wheels and steering wheel angles + steerRatioRear @11 :Float32; # [] rear steering ratio wrt front steering (usually 0) + + # things we can derive + rotationalInertia @12 :Float32; # [kg*m2] body rotational inertia + tireStiffnessFront @13 :Float32; # [N/rad] front tire coeff of stiff + tireStiffnessRear @14 :Float32; # [N/rad] rear tire coeff of stiff + + # Kp and Ki for the lateral control + steerKpBP @42 :List(Float32); + steerKpV @43 :List(Float32); + steerKiBP @44 :List(Float32); + steerKiV @45 :List(Float32); + steerKpDEPRECATED @15 :Float32; + steerKiDEPRECATED @16 :Float32; + steerKf @25 :Float32; + + # Kp and Ki for the longitudinal control + longitudinalKpBP @36 :List(Float32); + longitudinalKpV @37 :List(Float32); + longitudinalKiBP @38 :List(Float32); + longitudinalKiV @39 :List(Float32); + + steerLimitAlert @29 :Bool; + + vEgoStopping @30 :Float32; # Speed at which the car goes into stopping state + directAccelControl @31 :Bool; # Does the car have direct accel control or just gas/brake + stoppingControl @34 :Bool; # Does the car allows full control even at lows speeds when stopping + startAccel @35 :Float32; # Required acceleraton to overcome creep braking + steerRateCost @40 :Float32; # Lateral MPC cost on steering rate + steerControlType @46 :SteerControlType; + radarOffCan @47 :Bool; # True when radar objects aren't visible on CAN + + steerActuatorDelay @48 :Float32; # Steering wheel actuator delay in seconds + openpilotLongitudinalControl @50 :Bool; # is openpilot doing the longitudinal control? + + enum SteerControlType { + torque @0; + angle @1; + } +} diff --git a/cereal/include/c++.capnp b/cereal/include/c++.capnp new file mode 100644 index 00000000000000..2bda54717920ab --- /dev/null +++ b/cereal/include/c++.capnp @@ -0,0 +1,26 @@ +# Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +# Licensed under the MIT License: +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in +# all copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +# THE SOFTWARE. + +@0xbdf87d7bb8304e81; +$namespace("capnp::annotations"); + +annotation namespace(file): Text; +annotation name(field, enumerant, struct, enum, interface, method, param, group, union): Text; diff --git a/cereal/include/java.capnp b/cereal/include/java.capnp new file mode 100644 index 00000000000000..cddf6eba3d9777 --- /dev/null +++ b/cereal/include/java.capnp @@ -0,0 +1,28 @@ +# Copyright (c) 2013-2015 Sandstorm Development Group, Inc. and contributors +# Licensed under the MIT License: +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in +# all copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +# THE SOFTWARE. + +@0xc5f1af96651f70ea; + +annotation package @0x9ee4c8f803b3b596 (file) : Text; +# Name of the package, such as "org.example.foo", in which the generated code will reside. + +annotation outerClassname @0x9b066bb4881f7cd3 (file) : Text; +# Name of the outer class that will wrap the generated code. diff --git a/cereal/log.capnp b/cereal/log.capnp new file mode 100644 index 00000000000000..0ebf6a730094e4 --- /dev/null +++ b/cereal/log.capnp @@ -0,0 +1,1675 @@ +using Cxx = import "./include/c++.capnp"; +$Cxx.namespace("cereal"); + +using Java = import "./include/java.capnp"; +$Java.package("ai.comma.openpilot.cereal"); +$Java.outerClassname("Log"); + +using Car = import "car.capnp"; + +@0xf3b1f17e25a4285b; + +const logVersion :Int32 = 1; + +struct Map(Key, Value) { + entries @0 :List(Entry); + struct Entry { + key @0 :Key; + value @1 :Value; + } +} + +struct InitData { + kernelArgs @0 :List(Text); + kernelVersion @15 :Text; + + gctx @1 :Text; + dongleId @2 :Text; + + deviceType @3 :DeviceType; + version @4 :Text; + gitCommit @10 :Text; + gitBranch @11 :Text; + gitRemote @13 :Text; + + androidBuildInfo @5 :AndroidBuildInfo; + androidSensors @6 :List(AndroidSensor); + androidProperties @16 :Map(Text, Text); + chffrAndroidExtra @7 :ChffrAndroidExtra; + iosBuildInfo @14 :IosBuildInfo; + + pandaInfo @8 :PandaInfo; + + dirty @9 :Bool; + passive @12 :Bool; + params @17 :Map(Text, Text); + + enum DeviceType { + unknown @0; + neo @1; + chffrAndroid @2; + chffrIos @3; + } + + struct AndroidBuildInfo { + board @0 :Text; + bootloader @1 :Text; + brand @2 :Text; + device @3 :Text; + display @4 :Text; + fingerprint @5 :Text; + hardware @6 :Text; + host @7 :Text; + id @8 :Text; + manufacturer @9 :Text; + model @10 :Text; + product @11 :Text; + radioVersion @12 :Text; + serial @13 :Text; + supportedAbis @14 :List(Text); + tags @15 :Text; + time @16 :Int64; + type @17 :Text; + user @18 :Text; + + versionCodename @19 :Text; + versionRelease @20 :Text; + versionSdk @21 :Int32; + versionSecurityPatch @22 :Text; + } + + struct AndroidSensor { + id @0 :Int32; + name @1 :Text; + vendor @2 :Text; + version @3 :Int32; + handle @4 :Int32; + type @5 :Int32; + maxRange @6 :Float32; + resolution @7 :Float32; + power @8 :Float32; + minDelay @9 :Int32; + fifoReservedEventCount @10 :UInt32; + fifoMaxEventCount @11 :UInt32; + stringType @12 :Text; + maxDelay @13 :Int32; + } + + struct ChffrAndroidExtra { + allCameraCharacteristics @0 :Map(Text, Text); + } + + struct IosBuildInfo { + appVersion @0 :Text; + appBuild @1 :UInt32; + osVersion @2 :Text; + deviceModel @3 :Text; + } + + struct PandaInfo { + hasPanda @0 :Bool; + dongleId @1 :Text; + stVersion @2 :Text; + espVersion @3 :Text; + } +} + +struct FrameData { + frameId @0 :UInt32; + encodeId @1 :UInt32; # DEPRECATED + timestampEof @2 :UInt64; + frameLength @3 :Int32; + integLines @4 :Int32; + globalGain @5 :Int32; + lensPos @11 :Int32; + lensSag @12 :Float32; + lensErr @13 :Float32; + lensTruePos @14 :Float32; + image @6 :Data; + + frameType @7 :FrameType; + timestampSof @8 :UInt64; + transform @10 :List(Float32); + + androidCaptureResult @9 :AndroidCaptureResult; + + enum FrameType { + unknown @0; + neo @1; + chffrAndroid @2; + } + + struct AndroidCaptureResult { + sensitivity @0 :Int32; + frameDuration @1 :Int64; + exposureTime @2 :Int64; + rollingShutterSkew @3 :UInt64; + colorCorrectionTransform @4 :List(Int32); + colorCorrectionGains @5 :List(Float32); + displayRotation @6 :Int8; + } +} + +struct GPSNMEAData { + timestamp @0 :Int64; + localWallTime @1 :UInt64; + nmea @2 :Text; +} + +# android sensor_event_t +struct SensorEventData { + version @0 :Int32; + sensor @1 :Int32; + type @2 :Int32; + timestamp @3 :Int64; + uncalibratedDEPRECATED @10 :Bool; + + union { + acceleration @4 :SensorVec; + magnetic @5 :SensorVec; + orientation @6 :SensorVec; + gyro @7 :SensorVec; + pressure @9 :SensorVec; + magneticUncalibrated @11 :SensorVec; + gyroUncalibrated @12 :SensorVec; + proximity @13: Float32; + light @14: Float32; + } + source @8 :SensorSource; + + struct SensorVec { + v @0 :List(Float32); + status @1 :Int8; + } + + enum SensorSource { + android @0; + iOS @1; + fiber @2; + velodyne @3; # Velodyne IMU + bno055 @4; # Bosch accelerometer + lsm6ds3 @5; # accelerometer (c2) + bmp280 @6; # barometer (c2) + mmc3416x @7; # magnetometer (c2) + } +} + +# android struct GpsLocation +struct GpsLocationData { + # Contains GpsLocationFlags bits. + flags @0 :UInt16; + + # Represents latitude in degrees. + latitude @1 :Float64; + + # Represents longitude in degrees. + longitude @2 :Float64; + + # Represents altitude in meters above the WGS 84 reference ellipsoid. + altitude @3 :Float64; + + # Represents speed in meters per second. + speed @4 :Float32; + + # Represents heading in degrees. + bearing @5 :Float32; + + # Represents expected accuracy in meters. (presumably 1 sigma?) + accuracy @6 :Float32; + + # Timestamp for the location fix. + # Milliseconds since January 1, 1970. + timestamp @7 :Int64; + + source @8 :SensorSource; + + # Represents NED velocity in m/s. + vNED @9 :List(Float32); + + # Represents expected vertical accuracy in meters. (presumably 1 sigma?) + verticalAccuracy @10 :Float32; + + # Represents bearing accuracy in degrees. (presumably 1 sigma?) + bearingAccuracy @11 :Float32; + + # Represents velocity accuracy in m/s. (presumably 1 sigma?) + speedAccuracy @12 :Float32; + + enum SensorSource { + android @0; + iOS @1; + car @2; + velodyne @3; # Velodyne IMU + fusion @4; + external @5; + ublox @6; + trimble @7; + } +} + +struct CanData { + address @0 :UInt32; + busTime @1 :UInt16; + dat @2 :Data; + src @3 :UInt8; +} + +struct ThermalData { + cpu0 @0 :UInt16; + cpu1 @1 :UInt16; + cpu2 @2 :UInt16; + cpu3 @3 :UInt16; + mem @4 :UInt16; + gpu @5 :UInt16; + bat @6 :UInt32; + + # not thermal + freeSpace @7 :Float32; + batteryPercent @8 :Int16; + batteryStatus @9 :Text; + batteryCurrent @15 :Int32; + batteryVoltage @16 :Int32; + usbOnline @12 :Bool; + + fanSpeed @10 :UInt16; + started @11 :Bool; + startedTs @13 :UInt64; + + thermalStatus @14 :ThermalStatus; + chargingError @17 :Bool; + chargingDisabled @18 :Bool; + + enum ThermalStatus { + green @0; # all processes run + yellow @1; # critical processes run (kill uploader), engage still allowed + red @2; # no engage, will disengage + danger @3; # immediate process shutdown + } +} + +struct HealthData { + # from can health + voltage @0 :UInt32; + current @1 :UInt32; + started @2 :Bool; + controlsAllowed @3 :Bool; + gasInterceptorDetected @4 :Bool; + startedSignalDetected @5 :Bool; + isGreyPanda @6 :Bool; +} + +struct LiveUI { + rearViewCam @0 :Bool; + alertText1 @1 :Text; + alertText2 @2 :Text; + awarenessStatus @3 :Float32; +} + +struct Live20Data { + canMonoTimes @10 :List(UInt64); + mdMonoTime @6 :UInt64; + ftMonoTimeDEPRECATED @7 :UInt64; + l100MonoTime @11 :UInt64; + radarErrors @12 :List(Car.RadarState.Error); + + # all deprecated + warpMatrixDEPRECATED @0 :List(Float32); + angleOffsetDEPRECATED @1 :Float32; + calStatusDEPRECATED @2 :Int8; + calCycleDEPRECATED @8 :Int32; + calPercDEPRECATED @9 :Int8; + + leadOne @3 :LeadData; + leadTwo @4 :LeadData; + cumLagMs @5 :Float32; + + struct LeadData { + dRel @0 :Float32; + yRel @1 :Float32; + vRel @2 :Float32; + aRel @3 :Float32; + vLead @4 :Float32; + aLeadDEPRECATED @5 :Float32; + dPath @6 :Float32; + vLat @7 :Float32; + vLeadK @8 :Float32; + aLeadK @9 :Float32; + fcw @10 :Bool; + status @11 :Bool; + aLeadTau @12 :Float32; + } +} + +struct LiveCalibrationData { + # deprecated + warpMatrix @0 :List(Float32); + # camera_frame_from_model_frame + warpMatrix2 @5 :List(Float32); + warpMatrixBig @6 :List(Float32); + calStatus @1 :Int8; + calCycle @2 :Int32; + calPerc @3 :Int8; + + # view_frame_from_road_frame + # ui's is inversed needs new + extrinsicMatrix @4 :List(Float32); +} + +struct LiveTracks { + trackId @0 :Int32; + dRel @1 :Float32; + yRel @2 :Float32; + vRel @3 :Float32; + aRel @4 :Float32; + timeStamp @5 :Float32; + status @6 :Float32; + currentTime @7 :Float32; + stationary @8 :Bool; + oncoming @9 :Bool; +} + +struct Live100Data { + canMonoTimeDEPRECATED @16 :UInt64; + canMonoTimes @21 :List(UInt64); + l20MonoTimeDEPRECATED @17 :UInt64; + mdMonoTimeDEPRECATED @18 :UInt64; + planMonoTime @28 :UInt64; + + state @31 :ControlState; + vEgo @0 :Float32; + vEgoRaw @32 :Float32; + aEgoDEPRECATED @1 :Float32; + longControlState @30 :LongControlState; + vPid @2 :Float32; + vTargetLead @3 :Float32; + upAccelCmd @4 :Float32; + uiAccelCmd @5 :Float32; + ufAccelCmd @33 :Float32; + yActualDEPRECATED @6 :Float32; + yDesDEPRECATED @7 :Float32; + upSteer @8 :Float32; + uiSteer @9 :Float32; + ufSteer @34 :Float32; + aTargetMinDEPRECATED @10 :Float32; + aTargetMaxDEPRECATED @11 :Float32; + aTarget @35 :Float32; + jerkFactor @12 :Float32; + angleSteers @13 :Float32; # Steering angle in degrees. + angleSteersDes @29 :Float32; + curvature @37 :Float32; # path curvature from vehicle model + hudLeadDEPRECATED @14 :Int32; + cumLagMs @15 :Float32; + startMonoTime @48 :UInt64; + mapValid @49 :Bool; + + enabled @19 :Bool; + active @36 :Bool; + steerOverride @20 :Bool; + + vCruise @22 :Float32; + + rearViewCam @23 :Bool; + alertText1 @24 :Text; + alertText2 @25 :Text; + alertStatus @38 :AlertStatus; + alertSize @39 :AlertSize; + alertBlinkingRate @42 :Float32; + alertType @44 :Text; + alertSound @45 :Text; + awarenessStatus @26 :Float32; + angleOffset @27 :Float32; + gpsPlannerActive @40 :Bool; + engageable @41 :Bool; # can OP be engaged? + driverMonitoringOn @43 :Bool; + + # maps + vCurvature @46 :Float32; + decelForTurn @47 :Bool; + + enum ControlState { + disabled @0; + preEnabled @1; + enabled @2; + softDisabling @3; + } + + enum LongControlState { + off @0; + pid @1; + stopping @2; + starting @3; + } + + enum AlertStatus { + normal @0; # low priority alert for user's convenience + userPrompt @1; # mid piority alert that might require user intervention + critical @2; # high priority alert that needs immediate user intervention + } + + enum AlertSize { + none @0; # don't display the alert + small @1; # small box + mid @2; # mid screen + full @3; # full screen + } + +} + +struct LiveEventData { + name @0 :Text; + value @1 :Int32; +} + +struct ModelData { + frameId @0 :UInt32; + + path @1 :PathData; + leftLane @2 :PathData; + rightLane @3 :PathData; + lead @4 :LeadData; + freePath @6 :List(Float32); + + settings @5 :ModelSettings; + + struct PathData { + points @0 :List(Float32); + prob @1 :Float32; + std @2 :Float32; + } + + struct LeadData { + dist @0 :Float32; + prob @1 :Float32; + std @2 :Float32; + } + + struct ModelSettings { + bigBoxX @0 :UInt16; + bigBoxY @1 :UInt16; + bigBoxWidth @2 :UInt16; + bigBoxHeight @3 :UInt16; + boxProjection @4 :List(Float32); + yuvCorrection @5 :List(Float32); + inputTransform @6 :List(Float32); + } +} + +struct CalibrationFeatures { + frameId @0 :UInt32; + + p0 @1 :List(Float32); + p1 @2 :List(Float32); + status @3 :List(Int8); +} + +struct EncodeIndex { + # picture from camera + frameId @0 :UInt32; + type @1 :Type; + # index of encoder from start of route + encodeId @2 :UInt32; + # minute long segment this frame is in + segmentNum @3 :Int32; + # index into camera file in segment in presentation order + segmentId @4 :UInt32; + # index into camera file in segment in encode order + segmentIdEncode @5 :UInt32; + + enum Type { + bigBoxLossless @0; # rcamera.mkv + fullHEVC @1; # fcamera.hevc + bigBoxHEVC @2; # bcamera.hevc + chffrAndroidH264 @3; # acamera + fullLosslessClip @4; # prcamera.mkv + front @5; # dcamera.hevc + } +} + +struct AndroidLogEntry { + id @0 :UInt8; + ts @1 :UInt64; + priority @2 :UInt8; + pid @3 :Int32; + tid @4 :Int32; + tag @5 :Text; + message @6 :Text; +} + +struct LogRotate { + segmentNum @0 :Int32; + path @1 :Text; +} + +struct Plan { + mdMonoTime @9 :UInt64; + l20MonoTime @10 :UInt64; + events @13 :List(Car.CarEvent); + + # lateral, 3rd order polynomial + lateralValid @0 :Bool; + dPoly @1 :List(Float32); + laneWidth @11 :Float32; + + # longitudinal + longitudinalValid @2 :Bool; + vCruise @16 :Float32; + aCruise @17 :Float32; + vTarget @3 :Float32; + vTargetFuture @14 :Float32; + vMax @20 :Float32; + aTargetMinDEPRECATED @4 :Float32; + aTargetMaxDEPRECATED @5 :Float32; + aTarget @18 :Float32; + jerkFactor @6 :Float32; + hasLead @7 :Bool; + hasLeftLane @23 :Bool; + hasRightLane @24 :Bool; + fcw @8 :Bool; + longitudinalPlanSource @15 :LongitudinalPlanSource; + + # gps trajectory in car frame + gpsTrajectory @12 :GpsTrajectory; + + gpsPlannerActive @19 :Bool; + + # maps + vCurvature @21 :Float32; + decelForTurn @22 :Bool; + mapValid @25 :Bool; + + struct GpsTrajectory { + x @0 :List(Float32); + y @1 :List(Float32); + } + + enum LongitudinalPlanSource { + cruise @0; + mpc1 @1; + mpc2 @2; + mpc3 @3; + } +} + +struct LiveLocationData { + status @0 :UInt8; + + # 3D fix + lat @1 :Float64; + lon @2 :Float64; + alt @3 :Float32; # m + + # speed + speed @4 :Float32; # m/s + + # NED velocity components + vNED @5 :List(Float32); + + # roll, pitch, heading (x,y,z) + roll @6 :Float32; # WRT to center of earth? + pitch @7 :Float32; # WRT to center of earth? + heading @8 :Float32; # WRT to north? + + # what are these? + wanderAngle @9 :Float32; + trackAngle @10 :Float32; + + # car frame -- https://upload.wikimedia.org/wikipedia/commons/f/f5/RPY_angles_of_cars.png + + # gyro, in car frame, deg/s + gyro @11 :List(Float32); + + # accel, in car frame, m/s^2 + accel @12 :List(Float32); + + accuracy @13 :Accuracy; + + source @14 :SensorSource; + # if we are fixing a location in the past + fixMonoTime @15 :UInt64; + + gpsWeek @16 :Int32; + timeOfWeek @17 :Float64; + + positionECEF @18 :List(Float64); + poseQuatECEF @19 :List(Float32); + pitchCalibration @20 :Float32; + yawCalibration @21 :Float32; + imuFrame @22 :List(Float32); + + struct Accuracy { + pNEDError @0 :List(Float32); + vNEDError @1 :List(Float32); + rollError @2 :Float32; + pitchError @3 :Float32; + headingError @4 :Float32; + ellipsoidSemiMajorError @5 :Float32; + ellipsoidSemiMinorError @6 :Float32; + ellipsoidOrientationError @7 :Float32; + } + + enum SensorSource { + applanix @0; + kalman @1; + orbslam @2; + timing @3; + dummy @4; + } +} + +struct EthernetPacket { + pkt @0 :Data; + ts @1 :Float32; +} + +struct NavUpdate { + isNavigating @0 :Bool; + curSegment @1 :Int32; + segments @2 :List(Segment); + + struct LatLng { + lat @0 :Float64; + lng @1 :Float64; + } + + struct Segment { + from @0 :LatLng; + to @1 :LatLng; + updateTime @2 :Int32; + distance @3 :Int32; + crossTime @4 :Int32; + exitNo @5 :Int32; + instruction @6 :Instruction; + + parts @7 :List(LatLng); + + enum Instruction { + turnLeft @0; + turnRight @1; + keepLeft @2; + keepRight @3; + straight @4; + roundaboutExitNumber @5; + roundaboutExit @6; + roundaboutTurnLeft @7; + unkn8 @8; + roundaboutStraight @9; + unkn10 @10; + roundaboutTurnRight @11; + unkn12 @12; + roundaboutUturn @13; + unkn14 @14; + arrive @15; + exitLeft @16; + exitRight @17; + unkn18 @18; + uturn @19; + # ... + } + } +} + +struct NavStatus { + isNavigating @0 :Bool; + currentAddress @1 :Address; + + struct Address { + title @0 :Text; + lat @1 :Float64; + lng @2 :Float64; + house @3 :Text; + address @4 :Text; + street @5 :Text; + city @6 :Text; + state @7 :Text; + country @8 :Text; + } +} + +struct CellInfo { + timestamp @0 :UInt64; + repr @1 :Text; # android toString() for now +} + +struct WifiScan { + bssid @0 :Text; + ssid @1 :Text; + capabilities @2 :Text; + frequency @3 :Int32; + level @4 :Int32; + timestamp @5 :Int64; + + centerFreq0 @6 :Int32; + centerFreq1 @7 :Int32; + channelWidth @8 :ChannelWidth; + operatorFriendlyName @9 :Text; + venueName @10 :Text; + is80211mcResponder @11 :Bool; + passpoint @12 :Bool; + + distanceCm @13 :Int32; + distanceSdCm @14 :Int32; + + enum ChannelWidth { + w20Mhz @0; + w40Mhz @1; + w80Mhz @2; + w160Mhz @3; + w80Plus80Mhz @4; + } +} + +struct AndroidGnss { + union { + measurements @0 :Measurements; + navigationMessage @1 :NavigationMessage; + } + + struct Measurements { + clock @0 :Clock; + measurements @1 :List(Measurement); + + struct Clock { + timeNanos @0 :Int64; + hardwareClockDiscontinuityCount @1 :Int32; + + hasTimeUncertaintyNanos @2 :Bool; + timeUncertaintyNanos @3 :Float64; + + hasLeapSecond @4 :Bool; + leapSecond @5 :Int32; + + hasFullBiasNanos @6 :Bool; + fullBiasNanos @7 :Int64; + + hasBiasNanos @8 :Bool; + biasNanos @9 :Float64; + + hasBiasUncertaintyNanos @10 :Bool; + biasUncertaintyNanos @11 :Float64; + + hasDriftNanosPerSecond @12 :Bool; + driftNanosPerSecond @13 :Float64; + + hasDriftUncertaintyNanosPerSecond @14 :Bool; + driftUncertaintyNanosPerSecond @15 :Float64; + } + + struct Measurement { + svId @0 :Int32; + constellation @1 :Constellation; + + timeOffsetNanos @2 :Float64; + state @3 :Int32; + receivedSvTimeNanos @4 :Int64; + receivedSvTimeUncertaintyNanos @5 :Int64; + cn0DbHz @6 :Float64; + pseudorangeRateMetersPerSecond @7 :Float64; + pseudorangeRateUncertaintyMetersPerSecond @8 :Float64; + accumulatedDeltaRangeState @9 :Int32; + accumulatedDeltaRangeMeters @10 :Float64; + accumulatedDeltaRangeUncertaintyMeters @11 :Float64; + + hasCarrierFrequencyHz @12 :Bool; + carrierFrequencyHz @13 :Float32; + hasCarrierCycles @14 :Bool; + carrierCycles @15 :Int64; + hasCarrierPhase @16 :Bool; + carrierPhase @17 :Float64; + hasCarrierPhaseUncertainty @18 :Bool; + carrierPhaseUncertainty @19 :Float64; + hasSnrInDb @20 :Bool; + snrInDb @21 :Float64; + + multipathIndicator @22 :MultipathIndicator; + + enum Constellation { + unknown @0; + gps @1; + sbas @2; + glonass @3; + qzss @4; + beidou @5; + galileo @6; + } + + enum State { + unknown @0; + codeLock @1; + bitSync @2; + subframeSync @3; + towDecoded @4; + msecAmbiguous @5; + symbolSync @6; + gloStringSync @7; + gloTodDecoded @8; + bdsD2BitSync @9; + bdsD2SubframeSync @10; + galE1bcCodeLock @11; + galE1c2ndCodeLock @12; + galE1bPageSync @13; + sbasSync @14; + } + + enum MultipathIndicator { + unknown @0; + detected @1; + notDetected @2; + } + } + } + + struct NavigationMessage { + type @0 :Int32; + svId @1 :Int32; + messageId @2 :Int32; + submessageId @3 :Int32; + data @4 :Data; + status @5 :Status; + + enum Status { + unknown @0; + parityPassed @1; + parityRebuilt @2; + } + } +} + +struct QcomGnss { + logTs @0 :UInt64; + union { + measurementReport @1 :MeasurementReport; + clockReport @2 :ClockReport; + drMeasurementReport @3 :DrMeasurementReport; + drSvPoly @4 :DrSvPolyReport; + rawLog @5 :Data; + } + + enum MeasurementSource @0xd71a12b6faada7ee { + gps @0; + glonass @1; + beidou @2; + } + + enum SVObservationState @0xe81e829a0d6c83e9 { + idle @0; + search @1; + searchVerify @2; + bitEdge @3; + trackVerify @4; + track @5; + restart @6; + dpo @7; + glo10msBe @8; + glo10msAt @9; + } + + struct MeasurementStatus @0xe501010e1bcae83b { + subMillisecondIsValid @0 :Bool; + subBitTimeIsKnown @1 :Bool; + satelliteTimeIsKnown @2 :Bool; + bitEdgeConfirmedFromSignal @3 :Bool; + measuredVelocity @4 :Bool; + fineOrCoarseVelocity @5 :Bool; + lockPointValid @6 :Bool; + lockPointPositive @7 :Bool; + lastUpdateFromDifference @8 :Bool; + lastUpdateFromVelocityDifference @9 :Bool; + strongIndicationOfCrossCorelation @10 :Bool; + tentativeMeasurement @11 :Bool; + measurementNotUsable @12 :Bool; + sirCheckIsNeeded @13 :Bool; + probationMode @14 :Bool; + + glonassMeanderBitEdgeValid @15 :Bool; + glonassTimeMarkValid @16 :Bool; + + gpsRoundRobinRxDiversity @17 :Bool; + gpsRxDiversity @18 :Bool; + gpsLowBandwidthRxDiversityCombined @19 :Bool; + gpsHighBandwidthNu4 @20 :Bool; + gpsHighBandwidthNu8 @21 :Bool; + gpsHighBandwidthUniform @22 :Bool; + multipathIndicator @23 :Bool; + + imdJammingIndicator @24 :Bool; + lteB13TxJammingIndicator @25 :Bool; + freshMeasurementIndicator @26 :Bool; + + multipathEstimateIsValid @27 :Bool; + directionIsValid @28 :Bool; + } + + struct MeasurementReport { + source @0 :MeasurementSource; + + fCount @1 :UInt32; + + gpsWeek @2 :UInt16; + glonassCycleNumber @3 :UInt8; + glonassNumberOfDays @4 :UInt16; + + milliseconds @5 :UInt32; + timeBias @6 :Float32; + clockTimeUncertainty @7 :Float32; + clockFrequencyBias @8 :Float32; + clockFrequencyUncertainty @9 :Float32; + + sv @10 :List(SV); + + struct SV { + svId @0 :UInt8; + observationState @2 :SVObservationState; + observations @3 :UInt8; + goodObservations @4 :UInt8; + gpsParityErrorCount @5 :UInt16; + glonassFrequencyIndex @1 :Int8; + glonassHemmingErrorCount @6 :UInt8; + filterStages @7 :UInt8; + carrierNoise @8 :UInt16; + latency @9 :Int16; + predetectInterval @10 :UInt8; + postdetections @11 :UInt16; + + unfilteredMeasurementIntegral @12 :UInt32; + unfilteredMeasurementFraction @13 :Float32; + unfilteredTimeUncertainty @14 :Float32; + unfilteredSpeed @15 :Float32; + unfilteredSpeedUncertainty @16 :Float32; + measurementStatus @17 :MeasurementStatus; + multipathEstimate @18 :UInt32; + azimuth @19 :Float32; + elevation @20 :Float32; + carrierPhaseCyclesIntegral @21 :Int32; + carrierPhaseCyclesFraction @22 :UInt16; + fineSpeed @23 :Float32; + fineSpeedUncertainty @24 :Float32; + cycleSlipCount @25 :UInt8; + } + + } + + struct ClockReport { + hasFCount @0 :Bool; + fCount @1 :UInt32; + + hasGpsWeek @2 :Bool; + gpsWeek @3 :UInt16; + hasGpsMilliseconds @4 :Bool; + gpsMilliseconds @5 :UInt32; + gpsTimeBias @6 :Float32; + gpsClockTimeUncertainty @7 :Float32; + gpsClockSource @8 :UInt8; + + hasGlonassYear @9 :Bool; + glonassYear @10 :UInt8; + hasGlonassDay @11 :Bool; + glonassDay @12 :UInt16; + hasGlonassMilliseconds @13 :Bool; + glonassMilliseconds @14 :UInt32; + glonassTimeBias @15 :Float32; + glonassClockTimeUncertainty @16 :Float32; + glonassClockSource @17 :UInt8; + + bdsWeek @18 :UInt16; + bdsMilliseconds @19 :UInt32; + bdsTimeBias @20 :Float32; + bdsClockTimeUncertainty @21 :Float32; + bdsClockSource @22 :UInt8; + + galWeek @23 :UInt16; + galMilliseconds @24 :UInt32; + galTimeBias @25 :Float32; + galClockTimeUncertainty @26 :Float32; + galClockSource @27 :UInt8; + + clockFrequencyBias @28 :Float32; + clockFrequencyUncertainty @29 :Float32; + frequencySource @30 :UInt8; + gpsLeapSeconds @31 :UInt8; + gpsLeapSecondsUncertainty @32 :UInt8; + gpsLeapSecondsSource @33 :UInt8; + + gpsToGlonassTimeBiasMilliseconds @34 :Float32; + gpsToGlonassTimeBiasMillisecondsUncertainty @35 :Float32; + gpsToBdsTimeBiasMilliseconds @36 :Float32; + gpsToBdsTimeBiasMillisecondsUncertainty @37 :Float32; + bdsToGloTimeBiasMilliseconds @38 :Float32; + bdsToGloTimeBiasMillisecondsUncertainty @39 :Float32; + gpsToGalTimeBiasMilliseconds @40 :Float32; + gpsToGalTimeBiasMillisecondsUncertainty @41 :Float32; + galToGloTimeBiasMilliseconds @42 :Float32; + galToGloTimeBiasMillisecondsUncertainty @43 :Float32; + galToBdsTimeBiasMilliseconds @44 :Float32; + galToBdsTimeBiasMillisecondsUncertainty @45 :Float32; + + hasRtcTime @46 :Bool; + systemRtcTime @47 :UInt32; + fCountOffset @48 :UInt32; + lpmRtcCount @49 :UInt32; + clockResets @50 :UInt32; + } + + struct DrMeasurementReport { + + reason @0 :UInt8; + seqNum @1 :UInt8; + seqMax @2 :UInt8; + rfLoss @3 :UInt16; + + systemRtcValid @4 :Bool; + fCount @5 :UInt32; + clockResets @6 :UInt32; + systemRtcTime @7 :UInt64; + + gpsLeapSeconds @8 :UInt8; + gpsLeapSecondsUncertainty @9 :UInt8; + gpsToGlonassTimeBiasMilliseconds @10 :Float32; + gpsToGlonassTimeBiasMillisecondsUncertainty @11 :Float32; + + gpsWeek @12 :UInt16; + gpsMilliseconds @13 :UInt32; + gpsTimeBiasMs @14 :UInt32; + gpsClockTimeUncertaintyMs @15 :UInt32; + gpsClockSource @16 :UInt8; + + glonassClockSource @17 :UInt8; + glonassYear @18 :UInt8; + glonassDay @19 :UInt16; + glonassMilliseconds @20 :UInt32; + glonassTimeBias @21 :Float32; + glonassClockTimeUncertainty @22 :Float32; + + clockFrequencyBias @23 :Float32; + clockFrequencyUncertainty @24 :Float32; + frequencySource @25 :UInt8; + + source @26 :MeasurementSource; + + sv @27 :List(SV); + + struct SV { + svId @0 :UInt8; + glonassFrequencyIndex @1 :Int8; + observationState @2 :SVObservationState; + observations @3 :UInt8; + goodObservations @4 :UInt8; + filterStages @5 :UInt8; + predetectInterval @6 :UInt8; + cycleSlipCount @7 :UInt8; + postdetections @8 :UInt16; + + measurementStatus @9 :MeasurementStatus; + + carrierNoise @10 :UInt16; + rfLoss @11 :UInt16; + latency @12 :Int16; + + filteredMeasurementFraction @13 :Float32; + filteredMeasurementIntegral @14 :UInt32; + filteredTimeUncertainty @15 :Float32; + filteredSpeed @16 :Float32; + filteredSpeedUncertainty @17 :Float32; + + unfilteredMeasurementFraction @18 :Float32; + unfilteredMeasurementIntegral @19 :UInt32; + unfilteredTimeUncertainty @20 :Float32; + unfilteredSpeed @21 :Float32; + unfilteredSpeedUncertainty @22 :Float32; + + multipathEstimate @23 :UInt32; + azimuth @24 :Float32; + elevation @25 :Float32; + dopplerAcceleration @26 :Float32; + fineSpeed @27 :Float32; + fineSpeedUncertainty @28 :Float32; + + carrierPhase @29 :Float64; + fCount @30 :UInt32; + + parityErrorCount @31 :UInt16; + goodParity @32 :Bool; + } + } + + struct DrSvPolyReport { + svId @0 :UInt16; + frequencyIndex @1 :Int8; + + hasPosition @2 :Bool; + hasIono @3 :Bool; + hasTropo @4 :Bool; + hasElevation @5 :Bool; + polyFromXtra @6 :Bool; + hasSbasIono @7 :Bool; + + iode @8 :UInt16; + t0 @9 :Float64; + xyz0 @10 :List(Float64); + xyzN @11 :List(Float64); + other @12 :List(Float32); + + positionUncertainty @13 :Float32; + ionoDelay @14 :Float32; + ionoDot @15 :Float32; + sbasIonoDelay @16 :Float32; + sbasIonoDot @17 :Float32; + tropoDelay @18 :Float32; + elevation @19 :Float32; + elevationDot @20 :Float32; + elevationUncertainty @21 :Float32; + + velocityCoeff @22 :List(Float64); + + } +} + +struct LidarPts { + r @0 :List(UInt16); # uint16 m*500.0 + theta @1 :List(UInt16); # uint16 deg*100.0 + reflect @2 :List(UInt8); # uint8 0-255 + + # For storing out of file. + idx @3 :UInt64; + + # For storing in file + pkt @4 :Data; +} + +struct ProcLog { + cpuTimes @0 :List(CPUTimes); + mem @1 :Mem; + procs @2 :List(Process); + + struct Process { + pid @0 :Int32; + name @1 :Text; + state @2 :UInt8; + ppid @3 :Int32; + + cpuUser @4 :Float32; + cpuSystem @5 :Float32; + cpuChildrenUser @6 :Float32; + cpuChildrenSystem @7 :Float32; + priority @8 :Int64; + nice @9 :Int32; + numThreads @10 :Int32; + startTime @11 :Float64; + + memVms @12 :UInt64; + memRss @13 :UInt64; + + processor @14 :Int32; + + cmdline @15 :List(Text); + exe @16 :Text; + } + + struct CPUTimes { + cpuNum @0 :Int64; + user @1 :Float32; + nice @2 :Float32; + system @3 :Float32; + idle @4 :Float32; + iowait @5 :Float32; + irq @6 :Float32; + softirq @7 :Float32; + } + + struct Mem { + total @0 :UInt64; + free @1 :UInt64; + available @2 :UInt64; + buffers @3 :UInt64; + cached @4 :UInt64; + active @5 :UInt64; + inactive @6 :UInt64; + shared @7 :UInt64; + } + +} + +struct UbloxGnss { + union { + measurementReport @0 :MeasurementReport; + ephemeris @1 :Ephemeris; + ionoData @2 :IonoData; + } + + struct MeasurementReport { + #received time of week in gps time in seconds and gps week + rcvTow @0 :Float64; + gpsWeek @1 :UInt16; + # leap seconds in seconds + leapSeconds @2 :UInt16; + # receiver status + receiverStatus @3 :ReceiverStatus; + # num of measurements to follow + numMeas @4 :UInt8; + measurements @5 :List(Measurement); + + struct ReceiverStatus { + # leap seconds have been determined + leapSecValid @0 :Bool; + # Clock reset applied + clkReset @1 :Bool; + } + + struct Measurement { + svId @0 :UInt8; + trackingStatus @1 :TrackingStatus; + # pseudorange in meters + pseudorange @2 :Float64; + # carrier phase measurement in cycles + carrierCycles @3 :Float64; + # doppler measurement in Hz + doppler @4 :Float32; + # GNSS id, 0 is gps + gnssId @5 :UInt8; + glonassFrequencyIndex @6 :UInt8; + # carrier phase locktime counter in ms + locktime @7 :UInt16; + # Carrier-to-noise density ratio (signal strength) in dBHz + cno @8 :UInt8; + # pseudorange standard deviation in meters + pseudorangeStdev @9 :Float32; + # carrier phase standard deviation in cycles + carrierPhaseStdev @10 :Float32; + # doppler standard deviation in Hz + dopplerStdev @11 :Float32; + + struct TrackingStatus { + # pseudorange valid + pseudorangeValid @0 :Bool; + # carrier phase valid + carrierPhaseValid @1 :Bool; + # half cycle valid + halfCycleValid @2 :Bool; + # half sycle subtracted from phase + halfCycleSubtracted @3 :Bool; + } + } + } + + struct Ephemeris { + # This is according to the rinex (2?) format + svId @0 :UInt16; + year @1 :UInt16; + month @2 :UInt16; + day @3 :UInt16; + hour @4 :UInt16; + minute @5 :UInt16; + second @6 :Float32; + af0 @7 :Float64; + af1 @8 :Float64; + af2 @9 :Float64; + + iode @10 :Float64; + crs @11 :Float64; + deltaN @12 :Float64; + m0 @13 :Float64; + + cuc @14 :Float64; + ecc @15 :Float64; + cus @16 :Float64; + a @17 :Float64; # note that this is not the root!! + + toe @18 :Float64; + cic @19 :Float64; + omega0 @20 :Float64; + cis @21 :Float64; + + i0 @22 :Float64; + crc @23 :Float64; + omega @24 :Float64; + omegaDot @25 :Float64; + + iDot @26 :Float64; + codesL2 @27 :Float64; + gpsWeek @28 :Float64; + l2 @29 :Float64; + + svAcc @30 :Float64; + svHealth @31 :Float64; + tgd @32 :Float64; + iodc @33 :Float64; + + transmissionTime @34 :Float64; + fitInterval @35 :Float64; + + toc @36 :Float64; + + ionoCoeffsValid @37 :Bool; + ionoAlpha @38 :List(Float64); + ionoBeta @39 :List(Float64); + + } + + struct IonoData { + svHealth @0 :UInt32; + tow @1 :Float64; + gpsWeek @2 :Float64; + + ionoAlpha @3 :List(Float64); + ionoBeta @4 :List(Float64); + + healthValid @5 :Bool; + ionoCoeffsValid @6 :Bool; + } +} + + +struct Clocks { + bootTimeNanos @0 :UInt64; + monotonicNanos @1 :UInt64; + monotonicRawNanos @2 :UInt64; + wallTimeNanos @3 :UInt64; + modemUptimeMillis @4 :UInt64; +} + +struct LiveMpcData { + x @0 :List(Float32); + y @1 :List(Float32); + psi @2 :List(Float32); + delta @3 :List(Float32); + qpIterations @4 :UInt32; + calculationTime @5 :UInt64; + cost @6 :Float64; +} + +struct LiveLongitudinalMpcData { + xEgo @0 :List(Float32); + vEgo @1 :List(Float32); + aEgo @2 :List(Float32); + xLead @3 :List(Float32); + vLead @4 :List(Float32); + aLead @5 :List(Float32); + aLeadTau @6 :Float32; # lead accel time constant + qpIterations @7 :UInt32; + mpcId @8 :UInt32; + calculationTime @9 :UInt64; + cost @10 :Float64; +} + + +struct ECEFPointDEPRECATED @0xe10e21168db0c7f7 { + x @0 :Float32; + y @1 :Float32; + z @2 :Float32; +} + +struct ECEFPoint @0xc25bbbd524983447 { + x @0 :Float64; + y @1 :Float64; + z @2 :Float64; +} + +struct GPSPlannerPoints { + curPosDEPRECATED @0 :ECEFPointDEPRECATED; + pointsDEPRECATED @1 :List(ECEFPointDEPRECATED); + curPos @6 :ECEFPoint; + points @7 :List(ECEFPoint); + valid @2 :Bool; + trackName @3 :Text; + speedLimit @4 :Float32; + accelTarget @5 :Float32; +} + +struct GPSPlannerPlan { + valid @0 :Bool; + poly @1 :List(Float32); + trackName @2 :Text; + speed @3 :Float32; + acceleration @4 :Float32; + pointsDEPRECATED @5 :List(ECEFPointDEPRECATED); + points @6 :List(ECEFPoint); + xLookahead @7 :Float32; +} + +struct TrafficEvent @0xacfa74a094e62626 { + type @0 :Type; + distance @1 :Float32; + action @2 :Action; + resuming @3 :Bool; + + enum Type { + stopSign @0; + lightRed @1; + lightYellow @2; + lightGreen @3; + stopLight @4; + } + + enum Action { + none @0; + yield @1; + stop @2; + resumeReady @3; + } + +} + +struct OrbslamCorrection { + correctionMonoTime @0 :UInt64; + prePositionECEF @1 :List(Float64); + postPositionECEF @2 :List(Float64); + prePoseQuatECEF @3 :List(Float32); + postPoseQuatECEF @4 :List(Float32); + numInliers @5 :UInt32; +} + +struct OrbObservation { + observationMonoTime @0 :UInt64; + normalizedCoordinates @1 :List(Float32); + locationECEF @2 :List(Float64); + matchDistance @3: UInt32; +} + +struct UiNavigationEvent { + type @0: Type; + status @1: Status; + distanceTo @2: Float32; + endRoadPointDEPRECATED @3: ECEFPointDEPRECATED; + endRoadPoint @4: ECEFPoint; + + enum Type { + none @0; + laneChangeLeft @1; + laneChangeRight @2; + mergeLeft @3; + mergeRight @4; + turnLeft @5; + turnRight @6; + } + + enum Status { + none @0; + passive @1; + approaching @2; + active @3; + } +} + +struct UiLayoutState { + activeApp @0 :App; + sidebarCollapsed @1 :Bool; + mapEnabled @2 :Bool; + + enum App { + home @0; + music @1; + nav @2; + } +} + +struct Joystick { + # convenient for debug and live tuning + axes @0: List(Float32); + buttons @1: List(Bool); +} + +struct OrbOdometry { + # timing first + startMonoTime @0 :UInt64; + endMonoTime @1 :UInt64; + + # fundamental matrix and error + f @2: List(Float64); + err @3: Float64; + + # number of inlier points + inliers @4: Int32; + + # for debug only + # indexed by endMonoTime features + # value is startMonoTime feature match + # -1 if no match + matches @5: List(Int16); +} + +struct OrbFeatures { + timestampEof @0 :UInt64; + # transposed arrays of normalized image coordinates + # len(xs) == len(ys) == len(descriptors) * 32 + xs @1 :List(Float32); + ys @2 :List(Float32); + descriptors @3 :Data; + octaves @4 :List(Int8); + + # match index to last OrbFeatures + # -1 if no match + timestampLastEof @5 :UInt64; + matches @6: List(Int16); +} + +struct OrbFeaturesSummary { + timestampEof @0 :UInt64; + timestampLastEof @1 :UInt64; + + featureCount @2 :UInt16; + matchCount @3 :UInt16; + computeNs @4 :UInt64; +} + +struct OrbKeyFrame { + # this is a globally unique id for the KeyFrame + id @0: UInt64; + + # this is the location of the KeyFrame + pos @1: ECEFPoint; + + # these are the features in the world + # len(dpos) == len(descriptors) * 32 + dpos @2 :List(ECEFPoint); + descriptors @3 :Data; +} + +struct DriverMonitoring { + frameId @0 :UInt32; + descriptor @1 :List(Float32); + std @2 :Float32; +} + +struct Boot { + wallTimeNanos @0 :UInt64; + lastKmsg @1 :Data; + lastPmsg @2 :Data; +} + +struct LiveParametersData { + valid @0 :Bool; + gyroBias @1 :Float32; + angleOffset @2 :Float32; +} + +struct LiveMapData { + speedLimitValid @0 :Bool; + speedLimit @1 :Float32; + curvatureValid @2 :Bool; + curvature @3 :Float32; + wayId @4 :UInt64; + roadX @5 :List(Float32); + roadY @6 :List(Float32); + lastGps @7: GpsLocationData; + roadCurvatureX @8 :List(Float32); + roadCurvature @9 :List(Float32); + distToTurn @10 :Float32; + mapValid @11 :Bool; +} + +struct CameraOdometry { + trans @0 :List(Float32); # m/s in device frame + rot @1 :List(Float32); # rad/s in device frame + transStd @2 :List(Float32); # std m/s in device frame + rotStd @3 :List(Float32); # std rad/s in device frame +} + +struct Event { + # in nanoseconds? + logMonoTime @0 :UInt64; + + union { + initData @1 :InitData; + frame @2 :FrameData; + gpsNMEA @3 :GPSNMEAData; + sensorEventDEPRECATED @4 :SensorEventData; + can @5 :List(CanData); + thermal @6 :ThermalData; + live100 @7 :Live100Data; + liveEventDEPRECATED @8 :List(LiveEventData); + model @9 :ModelData; + features @10 :CalibrationFeatures; + sensorEvents @11 :List(SensorEventData); + health @12 :HealthData; + live20 @13 :Live20Data; + liveUIDEPRECATED @14 :LiveUI; + encodeIdx @15 :EncodeIndex; + liveTracks @16 :List(LiveTracks); + sendcan @17 :List(CanData); + logMessage @18 :Text; + liveCalibration @19 :LiveCalibrationData; + androidLogEntry @20 :AndroidLogEntry; + gpsLocation @21 :GpsLocationData; + carState @22 :Car.CarState; + carControl @23 :Car.CarControl; + plan @24 :Plan; + liveLocation @25 :LiveLocationData; + ethernetData @26 :List(EthernetPacket); + navUpdate @27 :NavUpdate; + cellInfo @28 :List(CellInfo); + wifiScan @29 :List(WifiScan); + androidGnss @30 :AndroidGnss; + qcomGnss @31 :QcomGnss; + lidarPts @32 :LidarPts; + procLog @33 :ProcLog; + ubloxGnss @34 :UbloxGnss; + clocks @35 :Clocks; + liveMpc @36 :LiveMpcData; + liveLongitudinalMpc @37 :LiveLongitudinalMpcData; + navStatus @38 :NavStatus; + ubloxRaw @39 :Data; + gpsPlannerPoints @40 :GPSPlannerPoints; + gpsPlannerPlan @41 :GPSPlannerPlan; + applanixRaw @42 :Data; + trafficEvents @43 :List(TrafficEvent); + liveLocationTiming @44 :LiveLocationData; + orbslamCorrectionDEPRECATED @45 :OrbslamCorrection; + liveLocationCorrected @46 :LiveLocationData; + orbObservation @47 :List(OrbObservation); + gpsLocationExternal @48 :GpsLocationData; + location @49 :LiveLocationData; + uiNavigationEvent @50 :UiNavigationEvent; + liveLocationKalman @51 :LiveLocationData; + testJoystick @52 :Joystick; + orbOdometry @53 :OrbOdometry; + orbFeatures @54 :OrbFeatures; + applanixLocation @55 :LiveLocationData; + orbKeyFrame @56 :OrbKeyFrame; + uiLayoutState @57 :UiLayoutState; + orbFeaturesSummary @58 :OrbFeaturesSummary; + driverMonitoring @59 :DriverMonitoring; + boot @60 :Boot; + liveParameters @61 :LiveParametersData; + liveMapData @62 :LiveMapData; + cameraOdometry @63 :CameraOdometry; + } +} diff --git a/common/__init__.py b/common/__init__.py new file mode 100644 index 00000000000000..e69de29bb2d1d6 diff --git a/common/api/__init__.py b/common/api/__init__.py new file mode 100644 index 00000000000000..2dc2ffa990533b --- /dev/null +++ b/common/api/__init__.py @@ -0,0 +1,15 @@ +import requests + +from selfdrive.version import version + +def api_get(endpoint, method='GET', timeout=None, access_token=None, **params): + backend = "https://api.commadotai.com/" + + headers = {} + if access_token is not None: + headers['Authorization'] = "JWT "+access_token + + headers['User-Agent'] = "openpilot-" + version + + return requests.request(method, backend+endpoint, timeout=timeout, headers = headers, params=params) + diff --git a/common/basedir.py b/common/basedir.py new file mode 100644 index 00000000000000..99760fa3343653 --- /dev/null +++ b/common/basedir.py @@ -0,0 +1,4 @@ +import os +BASEDIR = os.path.abspath(os.path.join(os.path.dirname(os.path.realpath(__file__)), "../")) + + diff --git a/common/dbc.py b/common/dbc.py new file mode 100755 index 00000000000000..6accad43f82bec --- /dev/null +++ b/common/dbc.py @@ -0,0 +1,286 @@ +import re +import os +import struct +import sys +import numbers +from collections import namedtuple, defaultdict + +def int_or_float(s): + # return number, trying to maintain int format + try: + return int(s) + except ValueError: + return float(s) + +DBCSignal = namedtuple( + "DBCSignal", ["name", "start_bit", "size", "is_little_endian", "is_signed", + "factor", "offset", "tmin", "tmax", "units"]) + + +class dbc(object): + def __init__(self, fn): + self.name, _ = os.path.splitext(os.path.basename(fn)) + with open(fn) as f: + self.txt = f.read().split("\n") + self._warned_addresses = set() + + # regexps from https://github.com/ebroecker/canmatrix/blob/master/canmatrix/importdbc.py + bo_regexp = re.compile(r"^BO\_ (\w+) (\w+) *: (\w+) (\w+)") + sg_regexp = re.compile(r"^SG\_ (\w+) : (\d+)\|(\d+)@(\d+)([\+|\-]) \(([0-9.+\-eE]+),([0-9.+\-eE]+)\) \[([0-9.+\-eE]+)\|([0-9.+\-eE]+)\] \"(.*)\" (.*)") + sgm_regexp = re.compile(r"^SG\_ (\w+) (\w+) *: (\d+)\|(\d+)@(\d+)([\+|\-]) \(([0-9.+\-eE]+),([0-9.+\-eE]+)\) \[([0-9.+\-eE]+)\|([0-9.+\-eE]+)\] \"(.*)\" (.*)") + val_regexp = re.compile(r"VAL\_ (\w+) (\w+) (\s*[-+]?[0-9]+\s+\".+?\"[^;]*)") + + # A dictionary which maps message ids to tuples ((name, size), signals). + # name is the ASCII name of the message. + # size is the size of the message in bytes. + # signals is a list signals contained in the message. + # signals is a list of DBCSignal in order of increasing start_bit. + self.msgs = {} + + # A dictionary which maps message ids to a list of tuples (signal name, definition value pairs) + self.def_vals = defaultdict(list) + + # lookup to bit reverse each byte + self.bits_index = [(i & ~0b111) + ((-i-1) & 0b111) for i in xrange(64)] + + for l in self.txt: + l = l.strip() + + if l.startswith("BO_ "): + # new group + dat = bo_regexp.match(l) + + if dat is None: + print "bad BO", l + name = dat.group(2) + size = int(dat.group(3)) + ids = int(dat.group(1), 0) # could be hex + if ids in self.msgs: + sys.exit("Duplicate address detected %d %s" % (ids, self.name)) + + self.msgs[ids] = ((name, size), []) + + if l.startswith("SG_ "): + # new signal + dat = sg_regexp.match(l) + go = 0 + if dat is None: + dat = sgm_regexp.match(l) + go = 1 + if dat is None: + print "bad SG", l + + sgname = dat.group(1) + start_bit = int(dat.group(go+2)) + signal_size = int(dat.group(go+3)) + is_little_endian = int(dat.group(go+4))==1 + is_signed = dat.group(go+5)=='-' + factor = int_or_float(dat.group(go+6)) + offset = int_or_float(dat.group(go+7)) + tmin = int_or_float(dat.group(go+8)) + tmax = int_or_float(dat.group(go+9)) + units = dat.group(go+10) + + self.msgs[ids][1].append( + DBCSignal(sgname, start_bit, signal_size, is_little_endian, + is_signed, factor, offset, tmin, tmax, units)) + + if l.startswith("VAL_ "): + # new signal value/definition + dat = val_regexp.match(l) + + if dat is None: + print "bad VAL", l + ids = int(dat.group(1), 0) # could be hex + sgname = dat.group(2) + defvals = dat.group(3) + + defvals = defvals.replace("?","\?") #escape sequence in C++ + defvals = defvals.split('"')[:-1] + + defs = defvals[1::2] + #cleanup, convert to UPPER_CASE_WITH_UNDERSCORES + for i,d in enumerate(defs): + d = defs[i].strip().upper() + defs[i] = d.replace(" ","_") + + defvals[1::2] = defs + defvals = '"'+"".join(str(i) for i in defvals)+'"' + + self.def_vals[ids].append((sgname, defvals)) + + for msg in self.msgs.viewvalues(): + msg[1].sort(key=lambda x: x.start_bit) + + self.msg_name_to_address = {} + for address, m in self.msgs.items(): + name = m[0][0] + self.msg_name_to_address[name] = address + + def lookup_msg_id(self, msg_id): + if not isinstance(msg_id, numbers.Number): + msg_id = self.msg_name_to_address[msg_id] + return msg_id + + def reverse_bytes(self, x): + return ((x & 0xff00000000000000) >> 56) | \ + ((x & 0x00ff000000000000) >> 40) | \ + ((x & 0x0000ff0000000000) >> 24) | \ + ((x & 0x000000ff00000000) >> 8) | \ + ((x & 0x00000000ff000000) << 8) | \ + ((x & 0x0000000000ff0000) << 24) | \ + ((x & 0x000000000000ff00) << 40) | \ + ((x & 0x00000000000000ff) << 56) + + def encode(self, msg_id, dd): + """Encode a CAN message using the dbc. + + Inputs: + msg_id: The message ID. + dd: A dictionary mapping signal name to signal data. + """ + msg_id = self.lookup_msg_id(msg_id) + + msg_def = self.msgs[msg_id] + size = msg_def[0][1] + + result = 0 + for s in msg_def[1]: + ival = dd.get(s.name) + if ival is not None: + + b2 = s.size + if s.is_little_endian: + b1 = s.start_bit + else: + b1 = (s.start_bit // 8) * 8 + (-s.start_bit - 1) % 8 + bo = 64 - (b1 + s.size) + + ival = (ival / s.factor) - s.offset + ival = int(round(ival)) + + if s.is_signed and ival < 0: + ival = (1 << b2) + ival + + shift = b1 if s.is_little_endian else bo + mask = ((1 << b2) - 1) << shift + dat = (ival & ((1 << b2) - 1)) << shift + + if s.is_little_endian: + mask = self.reverse_bytes(mask) + dat = self.reverse_bytes(dat) + + result &= ~mask + result |= dat + + result = struct.pack('>Q', result) + return result[:size] + + def decode(self, x, arr=None, debug=False): + """Decode a CAN message using the dbc. + + Inputs: + x: A collection with elements (address, time, data), where address is + the CAN address, time is the bus time, and data is the CAN data as a + hex string. + arr: Optional list of signals which should be decoded and returned. + debug: True to print debugging statements. + + Returns: + A tuple (name, data), where name is the name of the CAN message and data + is the decoded result. If arr is None, data is a dict of properties. + Otherwise data is a list of the same length as arr. + + Returns (None, None) if the message could not be decoded. + """ + + if arr is None: + out = {} + else: + out = [None]*len(arr) + + msg = self.msgs.get(x[0]) + if msg is None: + if x[0] not in self._warned_addresses: + #print("WARNING: Unknown message address {}".format(x[0])) + self._warned_addresses.add(x[0]) + return None, None + + name = msg[0][0] + if debug: + print name + + st = x[2].ljust(8, '\x00') + le, be = None, None + + for s in msg[1]: + if arr is not None and s[0] not in arr: + continue + + start_bit = s[1] + signal_size = s[2] + little_endian = s[3] + signed = s[4] + factor = s[5] + offset = s[6] + + b2 = signal_size + if little_endian: + b1 = start_bit + else: + b1 = (start_bit // 8) * 8 + (-start_bit - 1) % 8 + bo = 64 - (b1 + signal_size) + + if little_endian: + if le is None: + le = struct.unpack("Q", st)[0] + shift_amount = bo + tmp = be + + if shift_amount < 0: + continue + + tmp = (tmp >> shift_amount) & ((1 << b2) - 1) + if signed and (tmp >> (b2 - 1)): + tmp -= (1 << b2) + + tmp = tmp * factor + offset + + # if debug: + # print "%40s %2d %2d %7.2f %s" % (s[0], s[1], s[2], tmp, s[-1]) + + if arr is None: + out[s[0]] = tmp + else: + out[arr.index(s[0])] = tmp + return name, out + + def get_signals(self, msg): + msg = self.lookup_msg_id(msg) + return [sgs.name for sgs in self.msgs[msg][1]] + + +if __name__ == "__main__": + from opendbc import DBC_PATH + import numpy as np + + dbc_test = dbc(os.path.join(DBC_PATH, 'toyota_prius_2017_pt_generated.dbc')) + msg = ('STEER_ANGLE_SENSOR', {'STEER_ANGLE': -6.0, 'STEER_RATE': 4, 'STEER_FRACTION': -0.2}) + encoded = dbc_test.encode(*msg) + decoded = dbc_test.decode((0x25, 0, encoded)) + assert decoded == msg + + dbc_test = dbc(os.path.join(DBC_PATH, 'hyundai_santa_fe_2019_ccan.dbc')) + decoded = dbc_test.decode((0x2b0, 0, "\xfa\xfe\x00\x07\x12")) + assert np.isclose(decoded[1]['SAS_Angle'], -26.2) + + msg = ('SAS11', {'SAS_Stat': 7.0, 'MsgCount': 0.0, 'SAS_Angle': -26.200000000000003, 'SAS_Speed': 0.0, 'CheckSum': 0.0}) + encoded = dbc_test.encode(*msg) + decoded = dbc_test.decode((0x2b0, 0, encoded)) + + assert decoded == msg diff --git a/common/ffi_wrapper.py b/common/ffi_wrapper.py new file mode 100644 index 00000000000000..65b790a803469e --- /dev/null +++ b/common/ffi_wrapper.py @@ -0,0 +1,42 @@ +import os +import sys +import fcntl +import hashlib +from cffi import FFI + +TMPDIR = "/tmp/ccache" + +def ffi_wrap(name, c_code, c_header, tmpdir=TMPDIR, cflags="", libraries=[]): + cache = name + "_" + hashlib.sha1(c_code).hexdigest() + try: + os.mkdir(tmpdir) + except OSError: + pass + + fd = os.open(tmpdir, 0) + fcntl.flock(fd, fcntl.LOCK_EX) + try: + sys.path.append(tmpdir) + try: + mod = __import__(cache) + except Exception: + print "cache miss", cache + compile_code(cache, c_code, c_header, tmpdir, cflags, libraries) + mod = __import__(cache) + finally: + os.close(fd) + + return mod.ffi, mod.lib + +def compile_code(name, c_code, c_header, directory, cflags="", libraries=[]): + ffibuilder = FFI() + ffibuilder.set_source(name, c_code, source_extension='.cpp', libraries=libraries) + ffibuilder.cdef(c_header) + os.environ['OPT'] = "-fwrapv -O2 -DNDEBUG -std=c++11" + os.environ['CFLAGS'] = cflags + ffibuilder.compile(verbose=True, debug=False, tmpdir=directory) + +def wrap_compiled(name, directory): + sys.path.append(directory) + mod = __import__(name) + return mod.ffi, mod.lib diff --git a/common/filter_simple.py b/common/filter_simple.py new file mode 100644 index 00000000000000..a3206db1cc5684 --- /dev/null +++ b/common/filter_simple.py @@ -0,0 +1,10 @@ +class FirstOrderFilter(): + # first order filter + def __init__(self, x0, ts, dt): + self.k = (dt / ts) / (1. + dt / ts) + self.x = x0 + + def update(self, x): + self.x = (1. - self.k) * self.x + self.k * x + + diff --git a/common/fingerprints.py b/common/fingerprints.py new file mode 100644 index 00000000000000..d4845f8d416a0a --- /dev/null +++ b/common/fingerprints.py @@ -0,0 +1,64 @@ +import os +from common.basedir import BASEDIR + +def get_fingerprint_list(): + # read all the folders in selfdrive/car and return a dict where: + # - keys are all the car models for which we have a fingerprint + # - values are lists dicts of messages that constitute the unique + # CAN fingerprint of each car model and all its variants + fingerprints = {} + for car_folder in [x[0] for x in os.walk(BASEDIR + '/selfdrive/car')]: + try: + car_name = car_folder.split('/')[-1] + values = __import__('selfdrive.car.%s.values' % car_name, fromlist=['FINGERPRINTS']) + if hasattr(values, 'FINGERPRINTS'): + car_fingerprints = values.FINGERPRINTS + else: + continue + for f, v in car_fingerprints.items(): + fingerprints[f] = v + except (ImportError, IOError): + pass + return fingerprints + + +_FINGERPRINTS = get_fingerprint_list() + +_DEBUG_ADDRESS = {1880: 8} # reserved for debug purposes + +def is_valid_for_fingerprint(msg, car_fingerprint): + adr = msg.address + bus = msg.src + # ignore addresses that are more than 11 bits + return (adr in car_fingerprint and car_fingerprint[adr] == len(msg.dat)) or \ + bus != 0 or adr >= 0x800 + + +def eliminate_incompatible_cars(msg, candidate_cars): + """Removes cars that could not have sent msg. + + Inputs: + msg: A cereal/log CanData message from the car. + candidate_cars: A list of cars to consider. + + Returns: + A list containing the subset of candidate_cars that could have sent msg. + """ + compatible_cars = [] + + for car_name in candidate_cars: + car_fingerprints = _FINGERPRINTS[car_name] + + for fingerprint in car_fingerprints: + fingerprint.update(_DEBUG_ADDRESS) # add alien debug address + + if is_valid_for_fingerprint(msg, fingerprint): + compatible_cars.append(car_name) + break + + return compatible_cars + + +def all_known_cars(): + """Returns a list of all known car strings.""" + return _FINGERPRINTS.keys() diff --git a/common/kalman/__init__.py b/common/kalman/__init__.py new file mode 100644 index 00000000000000..e69de29bb2d1d6 diff --git a/common/kalman/ekf.py b/common/kalman/ekf.py new file mode 100644 index 00000000000000..fbed218f7a7b38 --- /dev/null +++ b/common/kalman/ekf.py @@ -0,0 +1,253 @@ +# pylint: skip-file +from __future__ import print_function +import abc +import numpy as np +# The EKF class contains the framework for an Extended Kalman Filter, but must be subclassed to use. +# A subclass must implement: +# 1) calc_transfer_fun(); see bottom of file for more info. +# 2) __init__() to initialize self.state, self.covar, and self.process_noise appropriately + +# Alternatively, the existing implementations of EKF can be used (e.g. EKF2D) + +# Sensor classes are optionally used to pass measurement information into the EKF, to keep +# sensor parameters and processing methods for a each sensor together. +# Sensor classes have a read() method which takes raw sensor data and returns +# a SensorReading object, which can be passed to the EKF update() method. + +# For usage, see run_ekf1d.py in selfdrive/new for a simple example. +# ekf.predict(dt) should be called between update cycles with the time since it was last called. +# Ideally, predict(dt) should be called at a relatively constant rate. +# update() should be called once per sensor, and can be called multiple times between predict steps. +# Access and set the state of the filter directly with ekf.state and ekf.covar. + + +class SensorReading: + # Given a perfect model and no noise, data = obs_model * state + def __init__(self, data, covar, obs_model): + self.data = data + self.obs_model = obs_model + self.covar = covar + + def __repr__(self): + return "SensorReading(data={}, covar={}, obs_model={})".format( + repr(self.data), repr(self.covar), repr(self.obs_model)) + + +# A generic sensor class that does no pre-processing of data +class SimpleSensor: + # obs_model can be + # a full observation model matrix, or + # an integer or tuple of indices into ekf.state, indicating which variables are being directly observed + # covar can be + # a full covariance matrix + # a float or tuple of individual covars for each component of the sensor reading + # dims is the number of states in the EKF + def __init__(self, obs_model, covar, dims): + # Allow for integer covar/obs_model + if not hasattr(obs_model, "__len__"): + obs_model = (obs_model, ) + if not hasattr(covar, "__len__"): + covar = (covar, ) + + # Full observation model passed + if dims in np.array(obs_model).shape: + self.obs_model = np.asmatrix(obs_model) + self.covar = np.asmatrix(covar) + # Indices of unit observations passed + else: + self.obs_model = np.matlib.zeros((len(obs_model), dims)) + self.obs_model[:, list(obs_model)] = np.identity(len(obs_model)) + if np.asarray(covar).ndim == 2: + self.covar = np.asmatrix(covar) + elif len(covar) == len(obs_model): + self.covar = np.matlib.diag(covar) + else: + self.covar = np.matlib.identity(len(obs_model)) * covar + + def read(self, data, covar=None): + if covar: + self.covar = covar + return SensorReading(data, self.covar, self.obs_model) + + +class EKF: + __metaclass__ = abc.ABCMeta + + def __init__(self, debug=False): + self.DEBUG = debug + + + def __str__(self): + return "EKF(state={}, covar={})".format(self.state, self.covar) + + # Measurement update + # Reading should be a SensorReading object with data, covar, and obs_model attributes + def update(self, reading): + # Potential improvements: + # deal with negative covars + # add noise to really low covars to ensure stability + # use mahalanobis distance to reject outliers + # wrap angles after state updates and innovation + + # y = z - H*x + innovation = reading.data - reading.obs_model * self.state + + if self.DEBUG: + print("reading:\n",reading.data) + print("innovation:\n",innovation) + + # S = H*P*H' + R + innovation_covar = reading.obs_model * self.covar * reading.obs_model.T + reading.covar + + # K = P*H'*S^-1 + kalman_gain = self.covar * reading.obs_model.T * np.linalg.inv( + innovation_covar) + + if self.DEBUG: + print("gain:\n", kalman_gain) + print("innovation_covar:\n", innovation_covar) + print("innovation: ", innovation) + print("test: ", self.covar * reading.obs_model.T * ( + reading.obs_model * self.covar * reading.obs_model.T + reading.covar * + 0).I) + + # x = x + K*y + self.state += kalman_gain*innovation + + # print "covar", np.diag(self.covar) + #self.state[(roll_vel, yaw_vel, pitch_vel),:] = reading.data + + # Standard form: P = (I - K*H)*P + # self.covar = (self.identity - kalman_gain*reading.obs_model) * self.covar + + # Use the Joseph form for numerical stability: P = (I-K*H)*P*(I - K*H)' + K*R*K' + aux_mtrx = (self.identity - kalman_gain * reading.obs_model) + self.covar = aux_mtrx * self.covar * aux_mtrx.T + kalman_gain * reading.covar * kalman_gain.T + + if self.DEBUG: + print("After update") + print("state\n", self.state) + print("covar:\n",self.covar) + + def update_scalar(self, reading): + # like update but knowing that measurement is a scalar + # this avoids matrix inversions and speeds up (surprisingly) drived.py a lot + + # innovation = reading.data - np.matmul(reading.obs_model, self.state) + # innovation_covar = np.matmul(np.matmul(reading.obs_model, self.covar), reading.obs_model.T) + reading.covar + # kalman_gain = np.matmul(self.covar, reading.obs_model.T)/innovation_covar + # self.state += np.matmul(kalman_gain, innovation) + # aux_mtrx = self.identity - np.matmul(kalman_gain, reading.obs_model) + # self.covar = np.matmul(aux_mtrx, np.matmul(self.covar, aux_mtrx.T)) + np.matmul(kalman_gain, np.matmul(reading.covar, kalman_gain.T)) + + # written without np.matmul + es = np.einsum + ABC_T = "ij,jk,lk->il" + AB_T = "ij,kj->ik" + AB = "ij,jk->ik" + innovation = reading.data - es(AB, reading.obs_model, self.state) + innovation_covar = es(ABC_T, reading.obs_model, self.covar, + reading.obs_model) + reading.covar + kalman_gain = es(AB_T, self.covar, reading.obs_model) / innovation_covar + + self.state += es(AB, kalman_gain, innovation) + aux_mtrx = self.identity - es(AB, kalman_gain, reading.obs_model) + self.covar = es(ABC_T, aux_mtrx, self.covar, aux_mtrx) + \ + es(ABC_T, kalman_gain, reading.covar, kalman_gain) + + # Prediction update + def predict(self, dt): + es = np.einsum + ABC_T = "ij,jk,lk->il" + AB = "ij,jk->ik" + + # State update + transfer_fun, transfer_fun_jacobian = self.calc_transfer_fun(dt) + + # self.state = np.matmul(transfer_fun, self.state) + # self.covar = np.matmul(np.matmul(transfer_fun_jacobian, self.covar), transfer_fun_jacobian.T) + self.process_noise * dt + + # x = f(x, u), written in the form x = A(x, u)*x + self.state = es(AB, transfer_fun, self.state) + + # P = J*P*J' + Q + self.covar = es(ABC_T, transfer_fun_jacobian, self.covar, + transfer_fun_jacobian) + self.process_noise * dt #!dt + + #! Clip covariance to avoid explosions + self.covar = np.clip(self.covar,-1e10,1e10) + + @abc.abstractmethod + def calc_transfer_fun(self, dt): + """Return a tuple with the transfer function and transfer function jacobian + The transfer function and jacobian should both be a numpy matrix of size DIMSxDIMS + + The transfer function matrix A should satisfy the state-update equation + x_(k+1) = A * x_k + + The jacobian J is the direct jacobian A*x_k. For linear systems J=A. + + Current implementations calculate A and J as functions of state. Control input + can be added trivially by adding a control parameter to predict() and calc_tranfer_update(), + and using it during calculation of A and J + """ + + +class FastEKF1D(EKF): + """Fast version of EKF for 1D problems with scalar readings.""" + + def __init__(self, dt, var_init, Q): + super(FastEKF1D, self).__init__(False) + self.state = [0, 0] + self.covar = [var_init, var_init, 0] + + # Process Noise + self.dtQ0 = dt * Q[0] + self.dtQ1 = dt * Q[1] + + def update(self, reading): + raise NotImplementedError + + def update_scalar(self, reading): + # TODO(mgraczyk): Delete this for speed. + # assert np.all(reading.obs_model == [1, 0]) + + rcov = reading.covar[0, 0] + + x = self.state + S = self.covar + + innovation = reading.data - x[0] + innovation_covar = S[0] + rcov + + k0 = S[0] / innovation_covar + k1 = S[2] / innovation_covar + + x[0] += k0 * innovation + x[1] += k1 * innovation + + mk = 1 - k0 + S[1] += k1 * (k1 * (S[0] + rcov) - 2 * S[2]) + S[2] = mk * (S[2] - k1 * S[0]) + rcov * k0 * k1 + S[0] = mk * mk * S[0] + rcov * k0 * k0 + + def predict(self, dt): + # State update + x = self.state + + x[0] += dt * x[1] + + # P = J*P*J' + Q + S = self.covar + S[0] += dt * (2 * S[2] + dt * S[1]) + self.dtQ0 + S[2] += dt * S[1] + S[1] += self.dtQ1 + + # Clip covariance to avoid explosions + S = max(-1e10, min(S, 1e10)) + + def calc_transfer_fun(self, dt): + tf = np.identity(2) + tf[0, 1] = dt + tfj = tf + return tf, tfj diff --git a/common/kalman/simple_kalman.py b/common/kalman/simple_kalman.py new file mode 100644 index 00000000000000..3f7d049cc55342 --- /dev/null +++ b/common/kalman/simple_kalman.py @@ -0,0 +1,23 @@ +import numpy as np + + +class KF1D: + # this EKF assumes constant covariance matrix, so calculations are much simpler + # the Kalman gain also needs to be precomputed using the control module + + def __init__(self, x0, A, C, K): + self.x = x0 + self.A = A + self.C = C + self.K = K + + self.A_K = self.A - np.dot(self.K, self.C) + + # K matrix needs to be pre-computed as follow: + # import control + # (x, l, K) = control.dare(np.transpose(self.A), np.transpose(self.C), Q, R) + # self.K = np.transpose(K) + + def update(self, meas): + self.x = np.dot(self.A_K, self.x) + np.dot(self.K, meas) + return self.x diff --git a/common/logging_extra.py b/common/logging_extra.py new file mode 100644 index 00000000000000..43ae48882b956e --- /dev/null +++ b/common/logging_extra.py @@ -0,0 +1,174 @@ +import os +import sys +import copy +import json +import socket +import logging +from threading import local +from collections import OrderedDict +from contextlib import contextmanager + +def json_handler(obj): + # if isinstance(obj, (datetime.date, datetime.time)): + # return obj.isoformat() + return repr(obj) + +def json_robust_dumps(obj): + return json.dumps(obj, default=json_handler) + +class NiceOrderedDict(OrderedDict): + def __str__(self): + return json_robust_dumps(self) + +class SwagFormatter(logging.Formatter): + def __init__(self, swaglogger): + logging.Formatter.__init__(self, None, '%a %b %d %H:%M:%S %Z %Y') + + self.swaglogger = swaglogger + self.host = socket.gethostname() + + def format_dict(self, record): + record_dict = NiceOrderedDict() + + if isinstance(record.msg, dict): + record_dict['msg'] = record.msg + else: + try: + record_dict['msg'] = record.getMessage() + except (ValueError, TypeError): + record_dict['msg'] = [record.msg]+record.args + + record_dict['ctx'] = self.swaglogger.get_ctx() + + if record.exc_info: + record_dict['exc_info'] = self.formatException(record.exc_info) + + record_dict['level'] = record.levelname + record_dict['levelnum'] = record.levelno + record_dict['name'] = record.name + record_dict['filename'] = record.filename + record_dict['lineno'] = record.lineno + record_dict['pathname'] = record.pathname + record_dict['module'] = record.module + record_dict['funcName'] = record.funcName + record_dict['host'] = self.host + record_dict['process'] = record.process + record_dict['thread'] = record.thread + record_dict['threadName'] = record.threadName + record_dict['created'] = record.created + + return record_dict + + def format(self, record): + return json_robust_dumps(self.format_dict(record)) + +class SwagErrorFilter(logging.Filter): + def filter(self, record): + return record.levelno < logging.ERROR + +_tmpfunc = lambda: 0 +_srcfile = os.path.normcase(_tmpfunc.__code__.co_filename) + +class SwagLogger(logging.Logger): + def __init__(self): + logging.Logger.__init__(self, "swaglog") + + self.global_ctx = {} + + self.log_local = local() + self.log_local.ctx = {} + + def findCaller(self, stack_info=None): + """ + Find the stack frame of the caller so that we can note the source + file name, line number and function name. + """ + # f = currentframe() + f = sys._getframe(3) + #On some versions of IronPython, currentframe() returns None if + #IronPython isn't run with -X:Frames. + if f is not None: + f = f.f_back + rv = "(unknown file)", 0, "(unknown function)" + while hasattr(f, "f_code"): + co = f.f_code + filename = os.path.normcase(co.co_filename) + if filename in (logging._srcfile, _srcfile): + f = f.f_back + continue + rv = (co.co_filename, f.f_lineno, co.co_name) + break + return rv + + def local_ctx(self): + try: + return self.log_local.ctx + except AttributeError: + self.log_local.ctx = {} + return self.log_local.ctx + + def get_ctx(self): + return dict(self.local_ctx(), **self.global_ctx) + + @contextmanager + def ctx(self, **kwargs): + old_ctx = self.local_ctx() + self.log_local.ctx = copy.copy(old_ctx) or {} + self.log_local.ctx.update(kwargs) + try: + yield + finally: + self.log_local.ctx = old_ctx + + def bind(self, **kwargs): + self.local_ctx().update(kwargs) + + def bind_global(self, **kwargs): + self.global_ctx.update(kwargs) + + def event(self, event_name, *args, **kwargs): + evt = NiceOrderedDict() + evt['event'] = event_name + if args: + evt['args'] = args + evt.update(kwargs) + ctx = self.get_ctx() + if ctx: + evt['ctx'] = self.get_ctx() + if 'error' in kwargs: + self.error(evt) + else: + self.info(evt) + +if __name__ == "__main__": + log = SwagLogger() + + stdout_handler = logging.StreamHandler(sys.stdout) + stdout_handler.setLevel(logging.INFO) + stdout_handler.addFilter(SwagErrorFilter()) + log.addHandler(stdout_handler) + + stderr_handler = logging.StreamHandler(sys.stderr) + stderr_handler.setLevel(logging.ERROR) + log.addHandler(stderr_handler) + + log.info("asdasd %s", "a") + log.info({'wut': 1}) + log.warning("warning") + log.error("error") + log.critical("critical") + log.event("test", x="y") + + with log.ctx(): + stdout_handler.setFormatter(SwagFormatter(log)) + stderr_handler.setFormatter(SwagFormatter(log)) + log.bind(user="some user") + log.info("in req") + print("") + log.warning("warning") + print("") + log.error("error") + print("") + log.critical("critical") + print("") + log.event("do_req", a=1, b="c") diff --git a/common/numpy_fast.py b/common/numpy_fast.py new file mode 100644 index 00000000000000..eb706a908ff643 --- /dev/null +++ b/common/numpy_fast.py @@ -0,0 +1,18 @@ +def int_rnd(x): + return int(round(x)) + +def clip(x, lo, hi): + return max(lo, min(hi, x)) + +def interp(x, xp, fp): + N = len(xp) + def get_interp(xv): + hi = 0 + while hi < N and xv > xp[hi]: + hi += 1 + low = hi - 1 + return fp[-1] if hi == N and xv > xp[low] else ( + fp[0] if hi == 0 else + (xv - xp[low]) * (fp[hi] - fp[low]) / (xp[hi] - xp[low]) + fp[low]) + return [get_interp(v) for v in x] if hasattr( + x, '__iter__') else get_interp(x) diff --git a/common/params.py b/common/params.py new file mode 100755 index 00000000000000..cc137d5a7b15c4 --- /dev/null +++ b/common/params.py @@ -0,0 +1,361 @@ +#!/usr/bin/env python +"""ROS has a parameter server, we have files. + +The parameter store is a persistent key value store, implemented as a directory with a writer lock. +On Android, we store params under params_dir = /data/params. The writer lock is a file +"/.lock" taken using flock(), and data is stored in a directory symlinked to by +"/d". + +Each key, value pair is stored as a file with named with contents , located in + /d/ + +Readers of a single key can just open("/d/") and read the file contents. +Readers who want a consistent snapshot of multiple keys should take the lock. + +Writers should take the lock before modifying anything. Writers should also leave the DB in a +consistent state after a crash. The implementation below does this by copying all params to a temp +directory /, then atomically symlinking / to / +before deleting the old / directory. + +Writers that only modify a single key can simply take the lock, then swap the corresponding value +file in place without messing with /d. +""" +import time +import os +import errno +import sys +import shutil +import fcntl +import tempfile +from enum import Enum + +def mkdirs_exists_ok(path): + try: + os.makedirs(path) + except OSError: + if not os.path.isdir(path): + raise + +class TxType(Enum): + PERSISTENT = 1 + CLEAR_ON_MANAGER_START = 2 + CLEAR_ON_CAR_START = 3 + +class UnknownKeyName(Exception): + pass + +keys = { +# written: manager +# read: loggerd, uploaderd, offroad + "DongleId": TxType.PERSISTENT, + "AccessToken": TxType.PERSISTENT, + "Version": TxType.PERSISTENT, + "TrainingVersion": TxType.PERSISTENT, + "GitCommit": TxType.PERSISTENT, + "GitBranch": TxType.PERSISTENT, + "GitRemote": TxType.PERSISTENT, +# written: baseui +# read: ui, controls + "IsMetric": TxType.PERSISTENT, + "IsFcwEnabled": TxType.PERSISTENT, + "HasAcceptedTerms": TxType.PERSISTENT, + "CompletedTrainingVersion": TxType.PERSISTENT, + "IsUploadVideoOverCellularEnabled": TxType.PERSISTENT, + "IsDriverMonitoringEnabled": TxType.PERSISTENT, + "IsGeofenceEnabled": TxType.PERSISTENT, + "SpeedLimitOffset": TxType.PERSISTENT, +# written: visiond +# read: visiond, controlsd + "CalibrationParams": TxType.PERSISTENT, +# written: controlsd +# read: radard + "CarParams": TxType.CLEAR_ON_CAR_START, + + "Passive": TxType.PERSISTENT, + "DoUninstall": TxType.CLEAR_ON_MANAGER_START, + "ShouldDoUpdate": TxType.CLEAR_ON_MANAGER_START, + "IsUpdateAvailable": TxType.PERSISTENT, + "LongitudinalControl": TxType.PERSISTENT, + "LimitSetSpeed": TxType.PERSISTENT, + + "RecordFront": TxType.PERSISTENT, +} + +def fsync_dir(path): + fd = os.open(path, os.O_RDONLY) + try: + os.fsync(fd) + finally: + os.close(fd) + + +class FileLock(object): + def __init__(self, path, create): + self._path = path + self._create = create + self._fd = None + + def acquire(self): + self._fd = os.open(self._path, os.O_CREAT if self._create else 0) + fcntl.flock(self._fd, fcntl.LOCK_EX) + + def release(self): + if self._fd is not None: + os.close(self._fd) + self._fd = None + + +class DBAccessor(object): + def __init__(self, path): + self._path = path + self._vals = None + + def keys(self): + self._check_entered() + return self._vals.keys() + + def get(self, key): + self._check_entered() + try: + return self._vals[key] + except KeyError: + return None + + def _get_lock(self, create): + lock = FileLock(os.path.join(self._path, ".lock"), create) + lock.acquire() + return lock + + def _read_values_locked(self): + """Callers should hold a lock while calling this method.""" + vals = {} + try: + data_path = self._data_path() + keys = os.listdir(data_path) + for key in keys: + with open(os.path.join(data_path, key), "rb") as f: + vals[key] = f.read() + except (OSError, IOError) as e: + # Either the DB hasn't been created yet, or somebody wrote a bug and left the DB in an + # inconsistent state. Either way, return empty. + if e.errno == errno.ENOENT: + return {} + + return vals + + def _data_path(self): + return os.path.join(self._path, "d") + + def _check_entered(self): + if self._vals is None: + raise Exception("Must call __enter__ before using DB") + + +class DBReader(DBAccessor): + def __enter__(self): + try: + lock = self._get_lock(False) + except OSError as e: + # Do not create lock if it does not exist. + if e.errno == errno.ENOENT: + self._vals = {} + return self + + try: + # Read everything. + self._vals = self._read_values_locked() + return self + finally: + lock.release() + + def __exit__(self, type, value, traceback): pass + + +class DBWriter(DBAccessor): + def __init__(self, path): + super(DBWriter, self).__init__(path) + self._lock = None + self._prev_umask = None + + def put(self, key, value): + self._vals[key] = value + + def delete(self, key): + self._vals.pop(key, None) + + def __enter__(self): + mkdirs_exists_ok(self._path) + + # Make sure we can write and that permissions are correct. + self._prev_umask = os.umask(0) + + try: + os.chmod(self._path, 0o777) + self._lock = self._get_lock(True) + self._vals = self._read_values_locked() + except: + os.umask(self._prev_umask) + self._prev_umask = None + raise + + return self + + def __exit__(self, type, value, traceback): + self._check_entered() + + try: + # data_path refers to the externally used path to the params. It is a symlink. + # old_data_path is the path currently pointed to by data_path. + # tempdir_path is a path where the new params will go, which the new data path will point to. + # new_data_path is a temporary symlink that will atomically overwrite data_path. + # + # The current situation is: + # data_path -> old_data_path + # We're going to write params data to tempdir_path + # tempdir_path -> params data + # Then point new_data_path to tempdir_path + # new_data_path -> tempdir_path + # Then atomically overwrite data_path with new_data_path + # data_path -> tempdir_path + old_data_path = None + new_data_path = None + tempdir_path = tempfile.mkdtemp(prefix=".tmp", dir=self._path) + + try: + # Write back all keys. + os.chmod(tempdir_path, 0o777) + for k, v in self._vals.items(): + with open(os.path.join(tempdir_path, k), "wb") as f: + f.write(v) + f.flush() + os.fsync(f.fileno()) + fsync_dir(tempdir_path) + + data_path = self._data_path() + try: + old_data_path = os.path.join(self._path, os.readlink(data_path)) + except (OSError, IOError): + # NOTE(mgraczyk): If other DB implementations have bugs, this could cause + # copies to be left behind, but we still want to overwrite. + pass + + new_data_path = "{}.link".format(tempdir_path) + os.symlink(os.path.basename(tempdir_path), new_data_path) + os.rename(new_data_path, data_path) + fsync_dir(self._path) + finally: + # If the rename worked, we can delete the old data. Otherwise delete the new one. + success = new_data_path is not None and os.path.exists(data_path) and ( + os.readlink(data_path) == os.path.basename(tempdir_path)) + + if success: + if old_data_path is not None: + shutil.rmtree(old_data_path) + else: + shutil.rmtree(tempdir_path) + + # Regardless of what happened above, there should be no link at new_data_path. + if new_data_path is not None and os.path.islink(new_data_path): + os.remove(new_data_path) + finally: + os.umask(self._prev_umask) + self._prev_umask = None + + # Always release the lock. + self._lock.release() + self._lock = None + + +def read_db(params_path, key): + path = "%s/d/%s" % (params_path, key) + try: + with open(path, "rb") as f: + return f.read() + except IOError: + return None + +def write_db(params_path, key, value): + prev_umask = os.umask(0) + lock = FileLock(params_path+"/.lock", True) + lock.acquire() + + try: + tmp_path = tempfile.mktemp(prefix=".tmp", dir=params_path) + with open(tmp_path, "wb") as f: + f.write(value) + f.flush() + os.fsync(f.fileno()) + + path = "%s/d/%s" % (params_path, key) + os.rename(tmp_path, path) + fsync_dir(os.path.dirname(path)) + finally: + os.umask(prev_umask) + lock.release() + +class Params(object): + def __init__(self, db='/data/params'): + self.db = db + + # create the database if it doesn't exist... + if not os.path.exists(self.db+"/d"): + with self.transaction(write=True): + pass + + def transaction(self, write=False): + if write: + return DBWriter(self.db) + else: + return DBReader(self.db) + + def _clear_keys_with_type(self, tx_type): + with self.transaction(write=True) as txn: + for key in keys: + if keys[key] == tx_type: + txn.delete(key) + + def manager_start(self): + self._clear_keys_with_type(TxType.CLEAR_ON_MANAGER_START) + + def car_start(self): + self._clear_keys_with_type(TxType.CLEAR_ON_CAR_START) + + def delete(self, key): + with self.transaction(write=True) as txn: + txn.delete(key) + + def get(self, key, block=False): + if key not in keys: + raise UnknownKeyName(key) + + while 1: + ret = read_db(self.db, key) + if not block or ret is not None: + break + # is polling really the best we can do? + time.sleep(0.05) + return ret + + def put(self, key, dat): + if key not in keys: + raise UnknownKeyName(key) + + write_db(self.db, key, dat) + +if __name__ == "__main__": + params = Params() + if len(sys.argv) > 2: + params.put(sys.argv[1], sys.argv[2]) + else: + for k in keys: + pp = params.get(k) + if pp is None: + print("%s is None" % k) + elif all(ord(c) < 128 and ord(c) >= 32 for c in pp): + print("%s = %s" % (k, pp)) + else: + print("%s = %s" % (k, pp.encode("hex"))) + + # Test multiprocess: + # seq 0 100000 | xargs -P20 -I{} python common/params.py DongleId {} && sleep 0.05 + # while python common/params.py DongleId; do sleep 0.05; done diff --git a/common/profiler.py b/common/profiler.py new file mode 100644 index 00000000000000..7f9b1a41ffb188 --- /dev/null +++ b/common/profiler.py @@ -0,0 +1,46 @@ +import time + +class Profiler(object): + def __init__(self, enabled=False): + self.enabled = enabled + self.cp = {} + self.cp_ignored = [] + self.iter = 0 + self.start_time = time.time() + self.last_time = self.start_time + self.tot = 0. + + def reset(self, enabled=False): + self.enabled = enabled + self.cp = {} + self.cp_ignored = [] + self.iter = 0 + self.start_time = time.time() + self.last_time = self.start_time + + def checkpoint(self, name, ignore=False): + # ignore flag needed when benchmarking threads with ratekeeper + if not self.enabled: + return + tt = time.time() + if name not in self.cp: + self.cp[name] = 0. + if ignore: + self.cp_ignored.append(name) + self.cp[name] += tt - self.last_time + if not ignore: + self.tot += tt - self.last_time + self.last_time = tt + + def display(self): + if not self.enabled: + return + self.iter += 1 + print("******* Profiling *******") + for n, ms in sorted(self.cp.items(), key=lambda x: -x[1]): + if n in self.cp_ignored: + print("%30s: %7.2f percent: %3.0f IGNORED" % (n, ms*1000.0, ms/self.tot*100)) + else: + print("%30s: %7.2f percent: %3.0f" % (n, ms*1000.0, ms/self.tot*100)) + print("Iter clock: %2.6f TOTAL: %2.2f" % (self.tot/self.iter, self.tot)) + diff --git a/common/realtime.py b/common/realtime.py new file mode 100644 index 00000000000000..7fe183fb23abca --- /dev/null +++ b/common/realtime.py @@ -0,0 +1,108 @@ +"""Utilities for reading real time clocks and keeping soft real time constraints.""" +import os +import time +import platform +import threading +import subprocess +import multiprocessing + +from cffi import FFI +ffi = FFI() +ffi.cdef(""" + +typedef int clockid_t; +struct timespec { + long tv_sec; /* Seconds. */ + long tv_nsec; /* Nanoseconds. */ +}; +int clock_gettime (clockid_t clk_id, struct timespec *tp); + +long syscall(long number, ...); + +""" +) +libc = ffi.dlopen(None) + + +# see +CLOCK_MONOTONIC_RAW = 4 +CLOCK_BOOTTIME = 7 + +if platform.system() != 'Darwin' and hasattr(libc, 'clock_gettime'): + c_clock_gettime = libc.clock_gettime + + tlocal = threading.local() + def clock_gettime(clk_id): + if not hasattr(tlocal, 'ts'): + tlocal.ts = ffi.new('struct timespec *') + + ts = tlocal.ts + + r = c_clock_gettime(clk_id, ts) + if r != 0: + raise OSError("clock_gettime") + return ts.tv_sec + ts.tv_nsec * 1e-9 +else: + # hack. only for OS X < 10.12 + def clock_gettime(clk_id): + return time.time() + +def monotonic_time(): + return clock_gettime(CLOCK_MONOTONIC_RAW) + +def sec_since_boot(): + return clock_gettime(CLOCK_BOOTTIME) + + +def set_realtime_priority(level): + if os.getuid() != 0: + print("not setting priority, not root") + return + if platform.machine() == "x86_64": + NR_gettid = 186 + elif platform.machine() == "aarch64": + NR_gettid = 178 + else: + raise NotImplementedError + + tid = libc.syscall(NR_gettid) + return subprocess.call(['chrt', '-f', '-p', str(level), str(tid)]) + + +class Ratekeeper(object): + def __init__(self, rate, print_delay_threshold=0.): + """Rate in Hz for ratekeeping. print_delay_threshold must be nonnegative.""" + self._interval = 1. / rate + self._next_frame_time = sec_since_boot() + self._interval + self._print_delay_threshold = print_delay_threshold + self._frame = 0 + self._remaining = 0 + self._process_name = multiprocessing.current_process().name + + @property + def frame(self): + return self._frame + + @property + def remaining(self): + return self._remaining + + # Maintain loop rate by calling this at the end of each loop + def keep_time(self): + lagged = self.monitor_time() + if self._remaining > 0: + time.sleep(self._remaining) + return lagged + + # this only monitor the cumulative lag, but does not enforce a rate + def monitor_time(self): + lagged = False + remaining = self._next_frame_time - sec_since_boot() + self._next_frame_time += self._interval + if remaining < -self._print_delay_threshold: + print("%s lagging by %.2f ms" % (self._process_name, -remaining * 1000)) + lagged = True + self._frame += 1 + self._remaining = remaining + return lagged + diff --git a/common/testing.py b/common/testing.py new file mode 100644 index 00000000000000..7e8b16d5cfefc3 --- /dev/null +++ b/common/testing.py @@ -0,0 +1,9 @@ +import os +from nose.tools import nottest + +def phone_only(x): + if os.path.isfile("/init.qcom.rc"): + return x + else: + return nottest(x) + diff --git a/common/transformations/__init__.py b/common/transformations/__init__.py new file mode 100644 index 00000000000000..e69de29bb2d1d6 diff --git a/common/transformations/camera.py b/common/transformations/camera.py new file mode 100644 index 00000000000000..6cf517cf50efb7 --- /dev/null +++ b/common/transformations/camera.py @@ -0,0 +1,148 @@ +import numpy as np +import common.transformations.orientation as orient +import cv2 + +FULL_FRAME_SIZE = (1164, 874) +W, H = FULL_FRAME_SIZE[0], FULL_FRAME_SIZE[1] +eon_focal_length = FOCAL = 910.0 + +# aka 'K' aka camera_frame_from_view_frame +eon_intrinsics = np.array([ + [FOCAL, 0., W/2.], + [ 0., FOCAL, H/2.], + [ 0., 0., 1.]]) + +# aka 'K_inv' aka view_frame_from_camera_frame +eon_intrinsics_inv = np.linalg.inv(eon_intrinsics) + + +# device/mesh : x->forward, y-> right, z->down +# view : x->right, y->down, z->forward +device_frame_from_view_frame = np.array([ + [ 0., 0., 1.], + [ 1., 0., 0.], + [ 0., 1., 0.] +]) +view_frame_from_device_frame = device_frame_from_view_frame.T + + +def get_calib_from_vp(vp): + vp_norm = normalize(vp) + yaw_calib = np.arctan(vp_norm[0]) + pitch_calib = np.arctan(vp_norm[1]*np.cos(yaw_calib)) + # TODO should be, this but written + # to be compatible with meshcalib and + # get_view_frame_from_road_fram + #pitch_calib = -np.arctan(vp_norm[1]*np.cos(yaw_calib)) + roll_calib = 0 + return roll_calib, pitch_calib, yaw_calib + +# aka 'extrinsic_matrix' +# road : x->forward, y -> left, z->up +def get_view_frame_from_road_frame(roll, pitch, yaw, height): + # TODO + # calibration pitch is currently defined + # opposite to pitch in device frame + pitch = -pitch + device_from_road = orient.rot_from_euler([roll, pitch, yaw]).dot(np.diag([1, -1, -1])) + view_from_road = view_frame_from_device_frame.dot(device_from_road) + return np.hstack((view_from_road, [[0], [height], [0]])) + + +def vp_from_ke(m): + """ + Computes the vanishing point from the product of the intrinsic and extrinsic + matrices C = KE. + + The vanishing point is defined as lim x->infinity C (x, 0, 0, 1).T + """ + return (m[0, 0]/m[2,0], m[1,0]/m[2,0]) + +def roll_from_ke(m): + # note: different from calibration.h/RollAnglefromKE: i think that one's just wrong + return np.arctan2(-(m[1, 0] - m[1, 1] * m[2, 0] / m[2, 1]), + -(m[0, 0] - m[0, 1] * m[2, 0] / m[2, 1])) + + +def normalize(img_pts, intrinsics=eon_intrinsics): + # normalizes image coordinates + # accepts single pt or array of pts + intrinsics_inv = np.linalg.inv(intrinsics) + img_pts = np.array(img_pts) + input_shape = img_pts.shape + img_pts = np.atleast_2d(img_pts) + img_pts = np.hstack((img_pts, np.ones((img_pts.shape[0],1)))) + img_pts_normalized = intrinsics_inv.dot(img_pts.T).T + img_pts_normalized[(img_pts < 0).any(axis=1)] = np.nan + return img_pts_normalized[:,:2].reshape(input_shape) + + +def denormalize(img_pts, intrinsics=eon_intrinsics): + # denormalizes image coordinates + # accepts single pt or array of pts + img_pts = np.array(img_pts) + input_shape = img_pts.shape + img_pts = np.atleast_2d(img_pts) + img_pts = np.hstack((img_pts, np.ones((img_pts.shape[0],1)))) + img_pts_denormalized = intrinsics.dot(img_pts.T).T + img_pts_denormalized[img_pts_denormalized[:,0] > W] = np.nan + img_pts_denormalized[img_pts_denormalized[:,0] < 0] = np.nan + img_pts_denormalized[img_pts_denormalized[:,1] > H] = np.nan + img_pts_denormalized[img_pts_denormalized[:,1] < 0] = np.nan + return img_pts_denormalized[:,:2].reshape(input_shape) + + +def device_from_ecef(pos_ecef, orientation_ecef, pt_ecef): + # device from ecef frame + # device frame is x -> forward, y-> right, z -> down + # accepts single pt or array of pts + input_shape = pt_ecef.shape + pt_ecef = np.atleast_2d(pt_ecef) + ecef_from_device_rot = orient.rotations_from_quats(orientation_ecef) + device_from_ecef_rot = ecef_from_device_rot.T + pt_ecef_rel = pt_ecef - pos_ecef + pt_device = np.einsum('jk,ik->ij', device_from_ecef_rot, pt_ecef_rel) + return pt_device.reshape(input_shape) + + +def img_from_device(pt_device): + # img coordinates from pts in device frame + # first transforms to view frame, then to img coords + # accepts single pt or array of pts + input_shape = pt_device.shape + pt_device = np.atleast_2d(pt_device) + pt_view = np.einsum('jk,ik->ij', view_frame_from_device_frame, pt_device) + + # This function should never return negative depths + pt_view[pt_view[:,2] < 0] = np.nan + + pt_img = pt_view/pt_view[:,2:3] + return pt_img.reshape(input_shape)[:,:2] + + +def rotate_img(img, eulers, crop=None, intrinsics=eon_intrinsics): + size = img.shape[:2] + rot = orient.rot_from_euler(eulers) + quadrangle = np.array([[0, 0], + [size[1]-1, 0], + [0, size[0]-1], + [size[1]-1, size[0]-1]], dtype=np.float32) + quadrangle_norm = np.hstack((normalize(quadrangle, intrinsics=intrinsics), np.ones((4,1)))) + warped_quadrangle_full = np.einsum('ij, kj->ki', intrinsics.dot(rot), quadrangle_norm) + warped_quadrangle = np.column_stack((warped_quadrangle_full[:,0]/warped_quadrangle_full[:,2], + warped_quadrangle_full[:,1]/warped_quadrangle_full[:,2])).astype(np.float32) + if crop: + W_border = (size[1] - crop[0])/2 + H_border = (size[0] - crop[1])/2 + outside_crop = (((warped_quadrangle[:,0] < W_border) | + (warped_quadrangle[:,0] >= size[1] - W_border)) & + ((warped_quadrangle[:,1] < H_border) | + (warped_quadrangle[:,1] >= size[0] - H_border))) + if not outside_crop.all(): + raise ValueError("warped image not contained inside crop") + else: + H_border, W_border = 0, 0 + M = cv2.getPerspectiveTransform(quadrangle, warped_quadrangle) + img_warped = cv2.warpPerspective(img, M, size[::-1]) + return img_warped[H_border: size[0] - H_border, + W_border: size[1] - W_border] diff --git a/common/transformations/coordinates.py b/common/transformations/coordinates.py new file mode 100644 index 00000000000000..568fb9bf2b3f4e --- /dev/null +++ b/common/transformations/coordinates.py @@ -0,0 +1,108 @@ +import numpy as np +""" +Coordinate transformation module. All methods accept arrays as input +with each row as a position. +""" + + + +a = 6378137 +b = 6356752.3142 +esq = 6.69437999014 * 0.001 +e1sq = 6.73949674228 * 0.001 + + +def geodetic2ecef(geodetic, radians=False): + geodetic = np.array(geodetic) + input_shape = geodetic.shape + geodetic = np.atleast_2d(geodetic) + + ratio = 1.0 if radians else (np.pi / 180.0) + lat = ratio*geodetic[:,0] + lon = ratio*geodetic[:,1] + alt = geodetic[:,2] + + xi = np.sqrt(1 - esq * np.sin(lat)**2) + x = (a / xi + alt) * np.cos(lat) * np.cos(lon) + y = (a / xi + alt) * np.cos(lat) * np.sin(lon) + z = (a / xi * (1 - esq) + alt) * np.sin(lat) + ecef = np.array([x, y, z]).T + return ecef.reshape(input_shape) + + +def ecef2geodetic(ecef, radians=False): + """ + Convert ECEF coordinates to geodetic using ferrari's method + """ + # Save shape and export column + ecef = np.atleast_1d(ecef) + input_shape = ecef.shape + ecef = np.atleast_2d(ecef) + x, y, z = ecef[:, 0], ecef[:, 1], ecef[:, 2] + + ratio = 1.0 if radians else (180.0 / np.pi) + + # Conver from ECEF to geodetic using Ferrari's methods + # https://en.wikipedia.org/wiki/Geographic_coordinate_conversion#Ferrari.27s_solution + r = np.sqrt(x * x + y * y) + Esq = a * a - b * b + F = 54 * b * b * z * z + G = r * r + (1 - esq) * z * z - esq * Esq + C = (esq * esq * F * r * r) / (pow(G, 3)) + S = np.cbrt(1 + C + np.sqrt(C * C + 2 * C)) + P = F / (3 * pow((S + 1 / S + 1), 2) * G * G) + Q = np.sqrt(1 + 2 * esq * esq * P) + r_0 = -(P * esq * r) / (1 + Q) + np.sqrt(0.5 * a * a*(1 + 1.0 / Q) - \ + P * (1 - esq) * z * z / (Q * (1 + Q)) - 0.5 * P * r * r) + U = np.sqrt(pow((r - esq * r_0), 2) + z * z) + V = np.sqrt(pow((r - esq * r_0), 2) + (1 - esq) * z * z) + Z_0 = b * b * z / (a * V) + h = U * (1 - b * b / (a * V)) + lat = ratio*np.arctan((z + e1sq * Z_0) / r) + lon = ratio*np.arctan2(y, x) + + # stack the new columns and return to the original shape + geodetic = np.column_stack((lat, lon, h)) + return geodetic.reshape(input_shape) + +class LocalCoord(object): + """ + Allows conversions to local frames. In this case NED. + That is: North East Down from the start position in + meters. + """ + def __init__(self, init_geodetic, init_ecef): + self.init_ecef = init_ecef + lat, lon, _ = (np.pi/180)*np.array(init_geodetic) + self.ned2ecef_matrix = np.array([[-np.sin(lat)*np.cos(lon), -np.sin(lon), -np.cos(lat)*np.cos(lon)], + [-np.sin(lat)*np.sin(lon), np.cos(lon), -np.cos(lat)*np.sin(lon)], + [np.cos(lat), 0, -np.sin(lat)]]) + self.ecef2ned_matrix = self.ned2ecef_matrix.T + + @classmethod + def from_geodetic(cls, init_geodetic): + init_ecef = geodetic2ecef(init_geodetic) + return LocalCoord(init_geodetic, init_ecef) + + @classmethod + def from_ecef(cls, init_ecef): + init_geodetic = ecef2geodetic(init_ecef) + return LocalCoord(init_geodetic, init_ecef) + + + def ecef2ned(self, ecef): + ecef = np.array(ecef) + return np.dot(self.ecef2ned_matrix, (ecef - self.init_ecef).T).T + + def ned2ecef(self, ned): + ned = np.array(ned) + # Transpose so that init_ecef will broadcast correctly for 1d or 2d ned. + return (np.dot(self.ned2ecef_matrix, ned.T).T + self.init_ecef) + + def geodetic2ned(self, geodetic): + ecef = geodetic2ecef(geodetic) + return self.ecef2ned(ecef) + + def ned2geodetic(self, ned): + ecef = self.ned2ecef(ned) + return ecef2geodetic(ecef) diff --git a/common/transformations/model.py b/common/transformations/model.py new file mode 100644 index 00000000000000..424bd6158e43c1 --- /dev/null +++ b/common/transformations/model.py @@ -0,0 +1,112 @@ +import numpy as np + +from common.transformations.camera import eon_focal_length, \ + vp_from_ke, \ + get_view_frame_from_road_frame, \ + FULL_FRAME_SIZE + +# segnet + +SEGNET_SIZE = (512, 384) + +segnet_frame_from_camera_frame = np.array([ + [float(SEGNET_SIZE[0])/FULL_FRAME_SIZE[0], 0., ], + [ 0., float(SEGNET_SIZE[1])/FULL_FRAME_SIZE[1]]]) + + +# model + +MODEL_INPUT_SIZE = (320, 160) +MODEL_YUV_SIZE = (MODEL_INPUT_SIZE[0], MODEL_INPUT_SIZE[1] * 3 // 2) +MODEL_CX = MODEL_INPUT_SIZE[0]/2. +MODEL_CY = 21. + +model_zoom = 1.25 +model_height = 1.22 + +# canonical model transform +model_intrinsics = np.array( + [[ eon_focal_length / model_zoom, 0. , MODEL_CX], + [ 0. , eon_focal_length / model_zoom, MODEL_CY], + [ 0. , 0. , 1.]]) + + +# BIG model + +BIGMODEL_INPUT_SIZE = (864, 288) +BIGMODEL_YUV_SIZE = (BIGMODEL_INPUT_SIZE[0], BIGMODEL_INPUT_SIZE[1] * 3 // 2) + +bigmodel_zoom = 1. +bigmodel_intrinsics = np.array( + [[ eon_focal_length / bigmodel_zoom, 0. , 0.5 * BIGMODEL_INPUT_SIZE[0]], + [ 0. , eon_focal_length / bigmodel_zoom, 0.2 * BIGMODEL_INPUT_SIZE[1]], + [ 0. , 0. , 1.]]) + + +bigmodel_border = np.array([ + [0,0,1], + [BIGMODEL_INPUT_SIZE[0], 0, 1], + [BIGMODEL_INPUT_SIZE[0], BIGMODEL_INPUT_SIZE[1], 1], + [0, BIGMODEL_INPUT_SIZE[1], 1], +]) + + +model_frame_from_road_frame = np.dot(model_intrinsics, + get_view_frame_from_road_frame(0, 0, 0, model_height)) + +bigmodel_frame_from_road_frame = np.dot(bigmodel_intrinsics, + get_view_frame_from_road_frame(0, 0, 0, model_height)) + +model_frame_from_bigmodel_frame = np.dot(model_intrinsics, np.linalg.inv(bigmodel_intrinsics)) + +# 'camera from model camera' +def get_model_height_transform(camera_frame_from_road_frame, height): + camera_frame_from_road_ground = np.dot(camera_frame_from_road_frame, np.array([ + [1, 0, 0], + [0, 1, 0], + [0, 0, 0], + [0, 0, 1], + ])) + + camera_frame_from_road_high = np.dot(camera_frame_from_road_frame, np.array([ + [1, 0, 0], + [0, 1, 0], + [0, 0, height - model_height], + [0, 0, 1], + ])) + + road_high_from_camera_frame = np.linalg.inv(camera_frame_from_road_high) + high_camera_from_low_camera = np.dot(camera_frame_from_road_ground, road_high_from_camera_frame) + + return high_camera_from_low_camera + + +# camera_frame_from_model_frame aka 'warp matrix' +# was: calibration.h/CalibrationTransform +def get_camera_frame_from_model_frame(camera_frame_from_road_frame, height=model_height): + vp = vp_from_ke(camera_frame_from_road_frame) + + model_camera_from_model_frame = np.array([ + [model_zoom, 0., vp[0] - MODEL_CX * model_zoom], + [ 0., model_zoom, vp[1] - MODEL_CY * model_zoom], + [ 0., 0., 1.], + ]) + + # This function is super slow, so skip it if height is very close to canonical + # TODO: speed it up! + if abs(height - model_height) > 0.001: # + camera_from_model_camera = get_model_height_transform(camera_frame_from_road_frame, height) + else: + camera_from_model_camera = np.eye(3) + + return np.dot(camera_from_model_camera, model_camera_from_model_frame) + + +def get_camera_frame_from_bigmodel_frame(camera_frame_from_road_frame): + camera_frame_from_ground = camera_frame_from_road_frame[:, (0, 1, 3)] + bigmodel_frame_from_ground = bigmodel_frame_from_road_frame[:, (0, 1, 3)] + + ground_from_bigmodel_frame = np.linalg.inv(bigmodel_frame_from_ground) + camera_frame_from_bigmodel_frame = np.dot(camera_frame_from_ground, ground_from_bigmodel_frame) + + return camera_frame_from_bigmodel_frame diff --git a/common/transformations/orientation.py b/common/transformations/orientation.py new file mode 100644 index 00000000000000..33a822ca3fd498 --- /dev/null +++ b/common/transformations/orientation.py @@ -0,0 +1,295 @@ +import numpy as np +from numpy import dot, inner, array, linalg +from common.transformations.coordinates import LocalCoord + + +''' +Vectorized functions that transform between +rotation matrices, euler angles and quaternions. +All support lists, array or array of arrays as inputs. +Supports both x2y and y_from_x format (y_from_x preferred!). +''' + +def euler2quat(eulers): + eulers = array(eulers) + if len(eulers.shape) > 1: + output_shape = (-1,4) + else: + output_shape = (4,) + eulers = np.atleast_2d(eulers) + gamma, theta, psi = eulers[:,0], eulers[:,1], eulers[:,2] + + q0 = np.cos(gamma / 2) * np.cos(theta / 2) * np.cos(psi / 2) + \ + np.sin(gamma / 2) * np.sin(theta / 2) * np.sin(psi / 2) + q1 = np.sin(gamma / 2) * np.cos(theta / 2) * np.cos(psi / 2) - \ + np.cos(gamma / 2) * np.sin(theta / 2) * np.sin(psi / 2) + q2 = np.cos(gamma / 2) * np.sin(theta / 2) * np.cos(psi / 2) + \ + np.sin(gamma / 2) * np.cos(theta / 2) * np.sin(psi / 2) + q3 = np.cos(gamma / 2) * np.cos(theta / 2) * np.sin(psi / 2) - \ + np.sin(gamma / 2) * np.sin(theta / 2) * np.cos(psi / 2) + + quats = array([q0, q1, q2, q3]).T + for i in xrange(len(quats)): + if quats[i,0] < 0: + quats[i] = -quats[i] + return quats.reshape(output_shape) + + +def quat2euler(quats): + quats = array(quats) + if len(quats.shape) > 1: + output_shape = (-1,3) + else: + output_shape = (3,) + quats = np.atleast_2d(quats) + q0, q1, q2, q3 = quats[:,0], quats[:,1], quats[:,2], quats[:,3] + + gamma = np.arctan2(2 * (q0 * q1 + q2 * q3), 1 - 2 * (q1**2 + q2**2)) + theta = np.arcsin(2 * (q0 * q2 - q3 * q1)) + psi = np.arctan2(2 * (q0 * q3 + q1 * q2), 1 - 2 * (q2**2 + q3**2)) + + eulers = array([gamma, theta, psi]).T + return eulers.reshape(output_shape) + + +def quat2rot(quats): + quats = array(quats) + input_shape = quats.shape + quats = np.atleast_2d(quats) + Rs = np.zeros((quats.shape[0], 3, 3)) + q0 = quats[:, 0] + q1 = quats[:, 1] + q2 = quats[:, 2] + q3 = quats[:, 3] + Rs[:, 0, 0] = q0 * q0 + q1 * q1 - q2 * q2 - q3 * q3 + Rs[:, 0, 1] = 2 * (q1 * q2 - q0 * q3) + Rs[:, 0, 2] = 2 * (q0 * q2 + q1 * q3) + Rs[:, 1, 0] = 2 * (q1 * q2 + q0 * q3) + Rs[:, 1, 1] = q0 * q0 - q1 * q1 + q2 * q2 - q3 * q3 + Rs[:, 1, 2] = 2 * (q2 * q3 - q0 * q1) + Rs[:, 2, 0] = 2 * (q1 * q3 - q0 * q2) + Rs[:, 2, 1] = 2 * (q0 * q1 + q2 * q3) + Rs[:, 2, 2] = q0 * q0 - q1 * q1 - q2 * q2 + q3 * q3 + + if len(input_shape) < 2: + return Rs[0] + else: + return Rs + + +def rot2quat(rots): + input_shape = rots.shape + if len(input_shape) < 3: + rots = array([rots]) + K3 = np.empty((len(rots), 4, 4)) + K3[:, 0, 0] = (rots[:, 0, 0] - rots[:, 1, 1] - rots[:, 2, 2]) / 3.0 + K3[:, 0, 1] = (rots[:, 1, 0] + rots[:, 0, 1]) / 3.0 + K3[:, 0, 2] = (rots[:, 2, 0] + rots[:, 0, 2]) / 3.0 + K3[:, 0, 3] = (rots[:, 1, 2] - rots[:, 2, 1]) / 3.0 + K3[:, 1, 0] = K3[:, 0, 1] + K3[:, 1, 1] = (rots[:, 1, 1] - rots[:, 0, 0] - rots[:, 2, 2]) / 3.0 + K3[:, 1, 2] = (rots[:, 2, 1] + rots[:, 1, 2]) / 3.0 + K3[:, 1, 3] = (rots[:, 2, 0] - rots[:, 0, 2]) / 3.0 + K3[:, 2, 0] = K3[:, 0, 2] + K3[:, 2, 1] = K3[:, 1, 2] + K3[:, 2, 2] = (rots[:, 2, 2] - rots[:, 0, 0] - rots[:, 1, 1]) / 3.0 + K3[:, 2, 3] = (rots[:, 0, 1] - rots[:, 1, 0]) / 3.0 + K3[:, 3, 0] = K3[:, 0, 3] + K3[:, 3, 1] = K3[:, 1, 3] + K3[:, 3, 2] = K3[:, 2, 3] + K3[:, 3, 3] = (rots[:, 0, 0] + rots[:, 1, 1] + rots[:, 2, 2]) / 3.0 + q = np.empty((len(rots), 4)) + for i in xrange(len(rots)): + _, eigvecs = linalg.eigh(K3[i].T) + eigvecs = eigvecs[:,3:] + q[i, 0] = eigvecs[-1] + q[i, 1:] = -eigvecs[:-1].flatten() + if q[i, 0] < 0: + q[i] = -q[i] + + if len(input_shape) < 3: + return q[0] + else: + return q + + +def euler2rot(eulers): + return rotations_from_quats(euler2quat(eulers)) + + +def rot2euler(rots): + return quat2euler(quats_from_rotations(rots)) + + +quats_from_rotations = rot2quat +quat_from_rot = rot2quat +rotations_from_quats = quat2rot +rot_from_quat= quat2rot +rot_from_quat= quat2rot +euler_from_rot = rot2euler +euler_from_quat = quat2euler +rot_from_euler = euler2rot +quat_from_euler = euler2quat + + + + + + +''' +Random helpers below +''' + + +def quat_product(q, r): + t = np.zeros(4) + t[0] = r[0] * q[0] - r[1] * q[1] - r[2] * q[2] - r[3] * q[3] + t[1] = r[0] * q[1] + r[1] * q[0] - r[2] * q[3] + r[3] * q[2] + t[2] = r[0] * q[2] + r[1] * q[3] + r[2] * q[0] - r[3] * q[1] + t[3] = r[0] * q[3] - r[1] * q[2] + r[2] * q[1] + r[3] * q[0] + return t + + +def rot_matrix(roll, pitch, yaw): + cr, sr = np.cos(roll), np.sin(roll) + cp, sp = np.cos(pitch), np.sin(pitch) + cy, sy = np.cos(yaw), np.sin(yaw) + rr = array([[1,0,0],[0, cr,-sr],[0, sr, cr]]) + rp = array([[cp,0,sp],[0, 1,0],[-sp, 0, cp]]) + ry = array([[cy,-sy,0],[sy, cy,0],[0, 0, 1]]) + return ry.dot(rp.dot(rr)) + + +def rot(axis, angle): + # Rotates around an arbitrary axis + ret_1 = (1 - np.cos(angle)) * array([[axis[0]**2, axis[0] * axis[1], axis[0] * axis[2]], [ + axis[1] * axis[0], axis[1]**2, axis[1] * axis[2] + ], [axis[2] * axis[0], axis[2] * axis[1], axis[2]**2]]) + ret_2 = np.cos(angle) * np.eye(3) + ret_3 = np.sin(angle) * array([[0, -axis[2], axis[1]], [axis[2], 0, -axis[0]], + [-axis[1], axis[0], 0]]) + return ret_1 + ret_2 + ret_3 + + +def ecef_euler_from_ned(ned_ecef_init, ned_pose): + ''' + Got it from here: + Using Rotations to Build Aerospace Coordinate Systems + -Don Koks + ''' + converter = LocalCoord.from_ecef(ned_ecef_init) + x0 = converter.ned2ecef([1, 0, 0]) - converter.ned2ecef([0, 0, 0]) + y0 = converter.ned2ecef([0, 1, 0]) - converter.ned2ecef([0, 0, 0]) + z0 = converter.ned2ecef([0, 0, 1]) - converter.ned2ecef([0, 0, 0]) + + x1 = rot(z0, ned_pose[2]).dot(x0) + y1 = rot(z0, ned_pose[2]).dot(y0) + z1 = rot(z0, ned_pose[2]).dot(z0) + + x2 = rot(y1, ned_pose[1]).dot(x1) + y2 = rot(y1, ned_pose[1]).dot(y1) + z2 = rot(y1, ned_pose[1]).dot(z1) + + x3 = rot(x2, ned_pose[0]).dot(x2) + y3 = rot(x2, ned_pose[0]).dot(y2) + #z3 = rot(x2, ned_pose[0]).dot(z2) + + x0 = array([1, 0, 0]) + y0 = array([0, 1, 0]) + z0 = array([0, 0, 1]) + + psi = np.arctan2(inner(x3, y0), inner(x3, x0)) + theta = np.arctan2(-inner(x3, z0), np.sqrt(inner(x3, x0)**2 + inner(x3, y0)**2)) + y2 = rot(z0, psi).dot(y0) + z2 = rot(y2, theta).dot(z0) + phi = np.arctan2(inner(y3, z2), inner(y3, y2)) + + ret = array([phi, theta, psi]) + return ret + + +def ned_euler_from_ecef(ned_ecef_init, ecef_poses): + ''' + Got the math from here: + Using Rotations to Build Aerospace Coordinate Systems + -Don Koks + + Also accepts array of ecef_poses and array of ned_ecef_inits. + Where each row is a pose and an ecef_init. + ''' + ned_ecef_init = array(ned_ecef_init) + ecef_poses = array(ecef_poses) + output_shape = ecef_poses.shape + ned_ecef_init = np.atleast_2d(ned_ecef_init) + if ned_ecef_init.shape[0] == 1: + ned_ecef_init = np.tile(ned_ecef_init[0], (output_shape[0], 1)) + ecef_poses = np.atleast_2d(ecef_poses) + + ned_poses = np.zeros(ecef_poses.shape) + for i, ecef_pose in enumerate(ecef_poses): + converter = LocalCoord.from_ecef(ned_ecef_init[i]) + x0 = array([1, 0, 0]) + y0 = array([0, 1, 0]) + z0 = array([0, 0, 1]) + + x1 = rot(z0, ecef_pose[2]).dot(x0) + y1 = rot(z0, ecef_pose[2]).dot(y0) + z1 = rot(z0, ecef_pose[2]).dot(z0) + + x2 = rot(y1, ecef_pose[1]).dot(x1) + y2 = rot(y1, ecef_pose[1]).dot(y1) + z2 = rot(y1, ecef_pose[1]).dot(z1) + + x3 = rot(x2, ecef_pose[0]).dot(x2) + y3 = rot(x2, ecef_pose[0]).dot(y2) + #z3 = rot(x2, ecef_pose[0]).dot(z2) + + x0 = converter.ned2ecef([1, 0, 0]) - converter.ned2ecef([0, 0, 0]) + y0 = converter.ned2ecef([0, 1, 0]) - converter.ned2ecef([0, 0, 0]) + z0 = converter.ned2ecef([0, 0, 1]) - converter.ned2ecef([0, 0, 0]) + + psi = np.arctan2(inner(x3, y0), inner(x3, x0)) + theta = np.arctan2(-inner(x3, z0), np.sqrt(inner(x3, x0)**2 + inner(x3, y0)**2)) + y2 = rot(z0, psi).dot(y0) + z2 = rot(y2, theta).dot(z0) + phi = np.arctan2(inner(y3, z2), inner(y3, y2)) + ned_poses[i] = array([phi, theta, psi]) + + return ned_poses.reshape(output_shape) + + +def ecef2car(car_ecef, psi, theta, points_ecef, ned_converter): + """ + TODO: add roll rotation + Converts an array of points in ecef coordinates into + x-forward, y-left, z-up coordinates + Parameters + ---------- + psi: yaw, radian + theta: pitch, radian + Returns + ------- + [x, y, z] coordinates in car frame + """ + + # input is an array of points in ecef cocrdinates + # output is an array of points in car's coordinate (x-front, y-left, z-up) + + # convert points to NED + points_ned = [] + for p in points_ecef: + points_ned.append(ned_converter.ecef2ned_matrix.dot(array(p) - car_ecef)) + + points_ned = np.vstack(points_ned).T + + # n, e, d -> x, y, z + # Calculate relative postions and rotate wrt to heading and pitch of car + invert_R = array([[1., 0., 0.], [0., -1., 0.], [0., 0., -1.]]) + + c, s = np.cos(psi), np.sin(psi) + yaw_R = array([[c, s, 0.], [-s, c, 0.], [0., 0., 1.]]) + + c, s = np.cos(theta), np.sin(theta) + pitch_R = array([[c, 0., -s], [0., 1., 0.], [s, 0., c]]) + + return dot(pitch_R, dot(yaw_R, dot(invert_R, points_ned))) diff --git a/installer/updater/updater b/installer/updater/updater new file mode 100755 index 00000000000000..0b8602b3550175 Binary files /dev/null and b/installer/updater/updater differ diff --git a/kegman.json b/kegman.json new file mode 100644 index 00000000000000..76db132acce649 --- /dev/null +++ b/kegman.json @@ -0,0 +1,3 @@ +{ + "lastTrMode": "2" +} \ No newline at end of file diff --git a/launch_chffrplus.sh b/launch_chffrplus.sh new file mode 100755 index 00000000000000..7607fd1956348d --- /dev/null +++ b/launch_chffrplus.sh @@ -0,0 +1,36 @@ +#!/usr/bin/bash + +if [ -z "$PASSIVE" ]; then + export PASSIVE="1" +fi + +function launch { + # apply update only if no_ota_updates does not exist in /data directory + file="/data/no_ota_updates" + if ! [ -f "$file" ]; then + if [ "$(git rev-parse HEAD)" != "$(git rev-parse @{u})" ]; then + git reset --hard @{u} && + git clean -xdf && + exec "${BASH_SOURCE[0]}" + fi + fi + + # no cpu rationing for now + echo 0-3 > /dev/cpuset/background/cpus + echo 0-3 > /dev/cpuset/system-background/cpus + echo 0-3 > /dev/cpuset/foreground/boost/cpus + echo 0-3 > /dev/cpuset/foreground/cpus + echo 0-3 > /dev/cpuset/android/cpus + + export PYTHONPATH="$PWD" + + # start manager + cd selfdrive + #./manager.py + ./manager.py > log.txt + + # if broken, keep on screen error + while true; do sleep 1; done +} + +launch diff --git a/launch_openpilot.sh b/launch_openpilot.sh new file mode 100755 index 00000000000000..1525e1715f99c2 --- /dev/null +++ b/launch_openpilot.sh @@ -0,0 +1,5 @@ +#!/usr/bin/bash + +export PASSIVE="0" +exec ./launch_chffrplus.sh + diff --git a/models/driving_model.dlc b/models/driving_model.dlc new file mode 100644 index 00000000000000..a33c1feb084a55 Binary files /dev/null and b/models/driving_model.dlc differ diff --git a/models/monitoring_model.dlc b/models/monitoring_model.dlc new file mode 100644 index 00000000000000..de5bdbb1fc97ee Binary files /dev/null and b/models/monitoring_model.dlc differ diff --git a/opendbc/.gitignore b/opendbc/.gitignore new file mode 100644 index 00000000000000..d18402de39f8b0 --- /dev/null +++ b/opendbc/.gitignore @@ -0,0 +1,2 @@ +*.pyc +.*.swp diff --git a/opendbc/README.md b/opendbc/README.md new file mode 100644 index 00000000000000..eec42dfefa7ff2 --- /dev/null +++ b/opendbc/README.md @@ -0,0 +1,53 @@ +opendbc +====== + +The project to democratize access to the decoder ring of your car. + + + +### DBC file basics + +A DBC file encodes, in a humanly readable way, the information needed to understand a vehicle's CAN bus traffic. A vehicle might have multiple CAN buses and every CAN bus is represented by its own dbc file. +Wondering what's the DBC file format? [Here](http://www.socialledge.com/sjsu/index.php?title=DBC_Format) and [Here](https://github.com/stefanhoelzl/CANpy/blob/master/docs/DBC_Specification.md) a couple of good overviews. + +### How to start reverse engineering cars + +[opendbc](https://github.com/commaai/opendbc) is integrated with [cabana](https://community.comma.ai/cabana/). + +Use [panda](https://github.com/commaai/panda) to connect your car to a computer. + +### DBC file preprocessor + +DBC files for different models of the same brand have a lot of overlap. Therefore, we wrote a preprocessor to create DBC files from a brand DBC file and a model specific DBC file. The source DBC files can be found in the generator folder. After changing one of the files run the generator.py script to regenerate the output files. These output files will be placed in the root of the opendbc repository and are suffixed by _generated. + +### Good practices for contributing to opendbc + +- Comments: the best way to store comments is to add them directly to the DBC files. For example: + ``` + CM_ SG_ 490 LONG_ACCEL "wheel speed derivative, noisy and zero snapping"; + ``` + is a comment that refers to signal `LONG_ACCEL` in message `490`. Using comments is highly recommended, especially for doubts and uncertainties. [cabana](https://community.comma.ai/cabana/) can easily display/add/edit comments to signals and messages. + +- Units: when applicable, it's recommended to convert signals into physical units, by using a proper signal factor. Using a SI unit is preferred, unless a non-SI unit rounds the signal factor much better. +For example: + ``` + SG_ VEHICLE_SPEED : 7|15@0+ (0.00278,0) [0|70] "m/s" PCM + ``` + is better than: + ``` + SG_ VEHICLE_SPEED : 7|15@0+ (0.00620,0) [0|115] "mph" PCM + ``` + However, the cleanest option is really: + ``` + SG_ VEHICLE_SPEED : 7|15@0+ (0.01,0) [0|250] "kph" PCM + ``` + +- Signal's size: always use the smallest amount of bits possible. For example, let's say I'm reverse engineering the gas pedal position and I've determined that it's in a 3 bytes message. For 0% pedal position I read a message value of `0x00 0x00 0x00`, while for 100% of pedal position I read `0x64 0x00 0x00`: clearly, the gas pedal position is within the first byte of the message and I might be tempted to define the signal `GAS_POS` as: + ``` + SG_ GAS_POS : 7|8@0+ (1,0) [0|100] "%" PCM + ``` + However, I can't be sure that the very first bit of the message is referred to the pedal position: I haven't seen it changing! Therefore, a safer way of defining the signal is: + ``` + SG_ GAS_POS : 6|7@0+ (1,0) [0|100] "%" PCM + ``` + which leaves the first bit unallocated. This prevents from very erroneous reading of the gas pedal position, in case the first bit is indeed used for something else. diff --git a/__init__.py b/opendbc/__init__.py similarity index 100% rename from __init__.py rename to opendbc/__init__.py diff --git a/acura_ilx_2016_can_generated.dbc b/opendbc/acura_ilx_2016_can_generated.dbc similarity index 100% rename from acura_ilx_2016_can_generated.dbc rename to opendbc/acura_ilx_2016_can_generated.dbc diff --git a/acura_ilx_2016_nidec.dbc b/opendbc/acura_ilx_2016_nidec.dbc similarity index 100% rename from acura_ilx_2016_nidec.dbc rename to opendbc/acura_ilx_2016_nidec.dbc diff --git a/acura_rdx_2018_can_generated.dbc b/opendbc/acura_rdx_2018_can_generated.dbc similarity index 100% rename from acura_rdx_2018_can_generated.dbc rename to opendbc/acura_rdx_2018_can_generated.dbc diff --git a/cadillac_ct6_chassis.dbc b/opendbc/cadillac_ct6_chassis.dbc similarity index 100% rename from cadillac_ct6_chassis.dbc rename to opendbc/cadillac_ct6_chassis.dbc diff --git a/cadillac_ct6_object.dbc b/opendbc/cadillac_ct6_object.dbc similarity index 100% rename from cadillac_ct6_object.dbc rename to opendbc/cadillac_ct6_object.dbc diff --git a/cadillac_ct6_powertrain.dbc b/opendbc/cadillac_ct6_powertrain.dbc similarity index 100% rename from cadillac_ct6_powertrain.dbc rename to opendbc/cadillac_ct6_powertrain.dbc diff --git a/chrysler_pacifica_2017_hybrid.dbc b/opendbc/chrysler_pacifica_2017_hybrid.dbc similarity index 100% rename from chrysler_pacifica_2017_hybrid.dbc rename to opendbc/chrysler_pacifica_2017_hybrid.dbc diff --git a/chrysler_pacifica_2017_hybrid_private_fusion.dbc b/opendbc/chrysler_pacifica_2017_hybrid_private_fusion.dbc similarity index 100% rename from chrysler_pacifica_2017_hybrid_private_fusion.dbc rename to opendbc/chrysler_pacifica_2017_hybrid_private_fusion.dbc diff --git a/ford_cgea1_2_bodycan_2011.dbc b/opendbc/ford_cgea1_2_bodycan_2011.dbc similarity index 100% rename from ford_cgea1_2_bodycan_2011.dbc rename to opendbc/ford_cgea1_2_bodycan_2011.dbc diff --git a/ford_cgea1_2_ptcan_2011.dbc b/opendbc/ford_cgea1_2_ptcan_2011.dbc similarity index 100% rename from ford_cgea1_2_ptcan_2011.dbc rename to opendbc/ford_cgea1_2_ptcan_2011.dbc diff --git a/ford_fusion_2018_adas.dbc b/opendbc/ford_fusion_2018_adas.dbc similarity index 100% rename from ford_fusion_2018_adas.dbc rename to opendbc/ford_fusion_2018_adas.dbc diff --git a/ford_fusion_2018_pt.dbc b/opendbc/ford_fusion_2018_pt.dbc similarity index 100% rename from ford_fusion_2018_pt.dbc rename to opendbc/ford_fusion_2018_pt.dbc diff --git a/generator/generator.py b/opendbc/generator/generator.py similarity index 100% rename from generator/generator.py rename to opendbc/generator/generator.py diff --git a/generator/honda/_bosch_2018.dbc b/opendbc/generator/honda/_bosch_2018.dbc similarity index 100% rename from generator/honda/_bosch_2018.dbc rename to opendbc/generator/honda/_bosch_2018.dbc diff --git a/generator/honda/_comma.dbc b/opendbc/generator/honda/_comma.dbc similarity index 100% rename from generator/honda/_comma.dbc rename to opendbc/generator/honda/_comma.dbc diff --git a/generator/honda/_honda_2017.dbc b/opendbc/generator/honda/_honda_2017.dbc similarity index 100% rename from generator/honda/_honda_2017.dbc rename to opendbc/generator/honda/_honda_2017.dbc diff --git a/generator/honda/acura_ilx_2016_can.dbc b/opendbc/generator/honda/acura_ilx_2016_can.dbc similarity index 100% rename from generator/honda/acura_ilx_2016_can.dbc rename to opendbc/generator/honda/acura_ilx_2016_can.dbc diff --git a/generator/honda/acura_rdx_2018_can.dbc b/opendbc/generator/honda/acura_rdx_2018_can.dbc similarity index 100% rename from generator/honda/acura_rdx_2018_can.dbc rename to opendbc/generator/honda/acura_rdx_2018_can.dbc diff --git a/generator/honda/honda_accord_lx15t_2018_can.dbc b/opendbc/generator/honda/honda_accord_lx15t_2018_can.dbc similarity index 100% rename from generator/honda/honda_accord_lx15t_2018_can.dbc rename to opendbc/generator/honda/honda_accord_lx15t_2018_can.dbc diff --git a/generator/honda/honda_accord_s2t_2018_can.dbc b/opendbc/generator/honda/honda_accord_s2t_2018_can.dbc similarity index 100% rename from generator/honda/honda_accord_s2t_2018_can.dbc rename to opendbc/generator/honda/honda_accord_s2t_2018_can.dbc diff --git a/generator/honda/honda_civic_hatchback_ex_2017_can.dbc b/opendbc/generator/honda/honda_civic_hatchback_ex_2017_can.dbc similarity index 100% rename from generator/honda/honda_civic_hatchback_ex_2017_can.dbc rename to opendbc/generator/honda/honda_civic_hatchback_ex_2017_can.dbc diff --git a/generator/honda/honda_civic_touring_2016_can.dbc b/opendbc/generator/honda/honda_civic_touring_2016_can.dbc similarity index 100% rename from generator/honda/honda_civic_touring_2016_can.dbc rename to opendbc/generator/honda/honda_civic_touring_2016_can.dbc diff --git a/generator/honda/honda_crv_ex_2017_can.dbc b/opendbc/generator/honda/honda_crv_ex_2017_can.dbc similarity index 100% rename from generator/honda/honda_crv_ex_2017_can.dbc rename to opendbc/generator/honda/honda_crv_ex_2017_can.dbc diff --git a/generator/honda/honda_crv_touring_2016_can.dbc b/opendbc/generator/honda/honda_crv_touring_2016_can.dbc similarity index 100% rename from generator/honda/honda_crv_touring_2016_can.dbc rename to opendbc/generator/honda/honda_crv_touring_2016_can.dbc diff --git a/generator/honda/honda_fit_ex_2018_can.dbc b/opendbc/generator/honda/honda_fit_ex_2018_can.dbc similarity index 100% rename from generator/honda/honda_fit_ex_2018_can.dbc rename to opendbc/generator/honda/honda_fit_ex_2018_can.dbc diff --git a/generator/honda/honda_insight_ex_2019_can.dbc b/opendbc/generator/honda/honda_insight_ex_2019_can.dbc similarity index 100% rename from generator/honda/honda_insight_ex_2019_can.dbc rename to opendbc/generator/honda/honda_insight_ex_2019_can.dbc diff --git a/generator/honda/honda_odyssey_exl_2018.dbc b/opendbc/generator/honda/honda_odyssey_exl_2018.dbc similarity index 100% rename from generator/honda/honda_odyssey_exl_2018.dbc rename to opendbc/generator/honda/honda_odyssey_exl_2018.dbc diff --git a/generator/honda/honda_pilot_touring_2017_can.dbc b/opendbc/generator/honda/honda_pilot_touring_2017_can.dbc similarity index 100% rename from generator/honda/honda_pilot_touring_2017_can.dbc rename to opendbc/generator/honda/honda_pilot_touring_2017_can.dbc diff --git a/generator/honda/honda_ridgeline_black_edition_2017_can.dbc b/opendbc/generator/honda/honda_ridgeline_black_edition_2017_can.dbc similarity index 100% rename from generator/honda/honda_ridgeline_black_edition_2017_can.dbc rename to opendbc/generator/honda/honda_ridgeline_black_edition_2017_can.dbc diff --git a/generator/toyota/_comma.dbc b/opendbc/generator/toyota/_comma.dbc similarity index 100% rename from generator/toyota/_comma.dbc rename to opendbc/generator/toyota/_comma.dbc diff --git a/generator/toyota/_toyota_2017.dbc b/opendbc/generator/toyota/_toyota_2017.dbc similarity index 100% rename from generator/toyota/_toyota_2017.dbc rename to opendbc/generator/toyota/_toyota_2017.dbc diff --git a/generator/toyota/lexus_is_2018_pt.dbc b/opendbc/generator/toyota/lexus_is_2018_pt.dbc similarity index 100% rename from generator/toyota/lexus_is_2018_pt.dbc rename to opendbc/generator/toyota/lexus_is_2018_pt.dbc diff --git a/generator/toyota/lexus_rx_hybrid_2017_pt.dbc b/opendbc/generator/toyota/lexus_rx_hybrid_2017_pt.dbc similarity index 100% rename from generator/toyota/lexus_rx_hybrid_2017_pt.dbc rename to opendbc/generator/toyota/lexus_rx_hybrid_2017_pt.dbc diff --git a/generator/toyota/toyota_avalon_2017_pt.dbc b/opendbc/generator/toyota/toyota_avalon_2017_pt.dbc similarity index 100% rename from generator/toyota/toyota_avalon_2017_pt.dbc rename to opendbc/generator/toyota/toyota_avalon_2017_pt.dbc diff --git a/generator/toyota/toyota_camry_hybrid_2018_pt.dbc b/opendbc/generator/toyota/toyota_camry_hybrid_2018_pt.dbc similarity index 100% rename from generator/toyota/toyota_camry_hybrid_2018_pt.dbc rename to opendbc/generator/toyota/toyota_camry_hybrid_2018_pt.dbc diff --git a/generator/toyota/toyota_chr_2018_pt.dbc b/opendbc/generator/toyota/toyota_chr_2018_pt.dbc similarity index 100% rename from generator/toyota/toyota_chr_2018_pt.dbc rename to opendbc/generator/toyota/toyota_chr_2018_pt.dbc diff --git a/generator/toyota/toyota_chr_hybrid_2018_pt.dbc b/opendbc/generator/toyota/toyota_chr_hybrid_2018_pt.dbc similarity index 100% rename from generator/toyota/toyota_chr_hybrid_2018_pt.dbc rename to opendbc/generator/toyota/toyota_chr_hybrid_2018_pt.dbc diff --git a/generator/toyota/toyota_corolla_2017_pt.dbc b/opendbc/generator/toyota/toyota_corolla_2017_pt.dbc similarity index 100% rename from generator/toyota/toyota_corolla_2017_pt.dbc rename to opendbc/generator/toyota/toyota_corolla_2017_pt.dbc diff --git a/generator/toyota/toyota_highlander_2017_pt.dbc b/opendbc/generator/toyota/toyota_highlander_2017_pt.dbc similarity index 100% rename from generator/toyota/toyota_highlander_2017_pt.dbc rename to opendbc/generator/toyota/toyota_highlander_2017_pt.dbc diff --git a/generator/toyota/toyota_highlander_hybrid_2018_pt.dbc b/opendbc/generator/toyota/toyota_highlander_hybrid_2018_pt.dbc similarity index 100% rename from generator/toyota/toyota_highlander_hybrid_2018_pt.dbc rename to opendbc/generator/toyota/toyota_highlander_hybrid_2018_pt.dbc diff --git a/generator/toyota/toyota_prius_2017_pt.dbc b/opendbc/generator/toyota/toyota_prius_2017_pt.dbc similarity index 100% rename from generator/toyota/toyota_prius_2017_pt.dbc rename to opendbc/generator/toyota/toyota_prius_2017_pt.dbc diff --git a/generator/toyota/toyota_rav4_2017_pt.dbc b/opendbc/generator/toyota/toyota_rav4_2017_pt.dbc similarity index 100% rename from generator/toyota/toyota_rav4_2017_pt.dbc rename to opendbc/generator/toyota/toyota_rav4_2017_pt.dbc diff --git a/generator/toyota/toyota_rav4_hybrid_2017_pt.dbc b/opendbc/generator/toyota/toyota_rav4_hybrid_2017_pt.dbc similarity index 100% rename from generator/toyota/toyota_rav4_hybrid_2017_pt.dbc rename to opendbc/generator/toyota/toyota_rav4_hybrid_2017_pt.dbc diff --git a/generator/toyota/toyota_sienna_xle_2018_pt.dbc b/opendbc/generator/toyota/toyota_sienna_xle_2018_pt.dbc similarity index 100% rename from generator/toyota/toyota_sienna_xle_2018_pt.dbc rename to opendbc/generator/toyota/toyota_sienna_xle_2018_pt.dbc diff --git a/gm_global_a_chassis.dbc b/opendbc/gm_global_a_chassis.dbc similarity index 100% rename from gm_global_a_chassis.dbc rename to opendbc/gm_global_a_chassis.dbc diff --git a/gm_global_a_lowspeed.dbc b/opendbc/gm_global_a_lowspeed.dbc similarity index 100% rename from gm_global_a_lowspeed.dbc rename to opendbc/gm_global_a_lowspeed.dbc diff --git a/gm_global_a_lowspeed_1818125.dbc b/opendbc/gm_global_a_lowspeed_1818125.dbc similarity index 100% rename from gm_global_a_lowspeed_1818125.dbc rename to opendbc/gm_global_a_lowspeed_1818125.dbc diff --git a/gm_global_a_object.dbc b/opendbc/gm_global_a_object.dbc similarity index 100% rename from gm_global_a_object.dbc rename to opendbc/gm_global_a_object.dbc diff --git a/gm_global_a_powertrain.dbc b/opendbc/gm_global_a_powertrain.dbc similarity index 100% rename from gm_global_a_powertrain.dbc rename to opendbc/gm_global_a_powertrain.dbc diff --git a/honda_accord_lx15t_2018_can_generated.dbc b/opendbc/honda_accord_lx15t_2018_can_generated.dbc similarity index 100% rename from honda_accord_lx15t_2018_can_generated.dbc rename to opendbc/honda_accord_lx15t_2018_can_generated.dbc diff --git a/honda_accord_s2t_2018_can_generated.dbc b/opendbc/honda_accord_s2t_2018_can_generated.dbc similarity index 100% rename from honda_accord_s2t_2018_can_generated.dbc rename to opendbc/honda_accord_s2t_2018_can_generated.dbc diff --git a/honda_accord_touring_2016_can.dbc b/opendbc/honda_accord_touring_2016_can.dbc similarity index 100% rename from honda_accord_touring_2016_can.dbc rename to opendbc/honda_accord_touring_2016_can.dbc diff --git a/honda_civic_hatchback_ex_2017_can_generated.dbc b/opendbc/honda_civic_hatchback_ex_2017_can_generated.dbc similarity index 100% rename from honda_civic_hatchback_ex_2017_can_generated.dbc rename to opendbc/honda_civic_hatchback_ex_2017_can_generated.dbc diff --git a/honda_civic_touring_2016_can_generated.dbc b/opendbc/honda_civic_touring_2016_can_generated.dbc similarity index 100% rename from honda_civic_touring_2016_can_generated.dbc rename to opendbc/honda_civic_touring_2016_can_generated.dbc diff --git a/honda_clarity_hybrid_2018_can.dbc b/opendbc/honda_clarity_hybrid_2018_can.dbc similarity index 100% rename from honda_clarity_hybrid_2018_can.dbc rename to opendbc/honda_clarity_hybrid_2018_can.dbc diff --git a/honda_crv_ex_2017_can_generated.dbc b/opendbc/honda_crv_ex_2017_can_generated.dbc similarity index 100% rename from honda_crv_ex_2017_can_generated.dbc rename to opendbc/honda_crv_ex_2017_can_generated.dbc diff --git a/honda_crv_touring_2016_can_generated.dbc b/opendbc/honda_crv_touring_2016_can_generated.dbc similarity index 100% rename from honda_crv_touring_2016_can_generated.dbc rename to opendbc/honda_crv_touring_2016_can_generated.dbc diff --git a/honda_fit_ex_2018_can_generated.dbc b/opendbc/honda_fit_ex_2018_can_generated.dbc similarity index 100% rename from honda_fit_ex_2018_can_generated.dbc rename to opendbc/honda_fit_ex_2018_can_generated.dbc diff --git a/honda_insight_ex_2019_can_generated.dbc b/opendbc/honda_insight_ex_2019_can_generated.dbc similarity index 100% rename from honda_insight_ex_2019_can_generated.dbc rename to opendbc/honda_insight_ex_2019_can_generated.dbc diff --git a/honda_odyssey_exl_2018_generated.dbc b/opendbc/honda_odyssey_exl_2018_generated.dbc similarity index 100% rename from honda_odyssey_exl_2018_generated.dbc rename to opendbc/honda_odyssey_exl_2018_generated.dbc diff --git a/honda_odyssey_extreme_edition_2018_china_can.dbc b/opendbc/honda_odyssey_extreme_edition_2018_china_can.dbc similarity index 100% rename from honda_odyssey_extreme_edition_2018_china_can.dbc rename to opendbc/honda_odyssey_extreme_edition_2018_china_can.dbc diff --git a/honda_pilot_touring_2017_can_generated.dbc b/opendbc/honda_pilot_touring_2017_can_generated.dbc similarity index 100% rename from honda_pilot_touring_2017_can_generated.dbc rename to opendbc/honda_pilot_touring_2017_can_generated.dbc diff --git a/honda_ridgeline_black_edition_2017_can_generated.dbc b/opendbc/honda_ridgeline_black_edition_2017_can_generated.dbc similarity index 100% rename from honda_ridgeline_black_edition_2017_can_generated.dbc rename to opendbc/honda_ridgeline_black_edition_2017_can_generated.dbc diff --git a/hyundai_2015_ccan.dbc b/opendbc/hyundai_2015_ccan.dbc similarity index 100% rename from hyundai_2015_ccan.dbc rename to opendbc/hyundai_2015_ccan.dbc diff --git a/hyundai_2015_mcan.dbc b/opendbc/hyundai_2015_mcan.dbc similarity index 100% rename from hyundai_2015_mcan.dbc rename to opendbc/hyundai_2015_mcan.dbc diff --git a/hyundai_i30_2014.dbc b/opendbc/hyundai_i30_2014.dbc similarity index 100% rename from hyundai_i30_2014.dbc rename to opendbc/hyundai_i30_2014.dbc diff --git a/hyundai_kia_generic.dbc b/opendbc/hyundai_kia_generic.dbc similarity index 100% rename from hyundai_kia_generic.dbc rename to opendbc/hyundai_kia_generic.dbc diff --git a/lexus_is_2018_pt_generated.dbc b/opendbc/lexus_is_2018_pt_generated.dbc similarity index 100% rename from lexus_is_2018_pt_generated.dbc rename to opendbc/lexus_is_2018_pt_generated.dbc diff --git a/lexus_rx_hybrid_2017_pt_generated.dbc b/opendbc/lexus_rx_hybrid_2017_pt_generated.dbc similarity index 100% rename from lexus_rx_hybrid_2017_pt_generated.dbc rename to opendbc/lexus_rx_hybrid_2017_pt_generated.dbc diff --git a/mercedes_benz_e350_2010.dbc b/opendbc/mercedes_benz_e350_2010.dbc similarity index 100% rename from mercedes_benz_e350_2010.dbc rename to opendbc/mercedes_benz_e350_2010.dbc diff --git a/subaru_outback_2016_eyesight.dbc b/opendbc/subaru_outback_2016_eyesight.dbc similarity index 100% rename from subaru_outback_2016_eyesight.dbc rename to opendbc/subaru_outback_2016_eyesight.dbc diff --git a/tesla_can.dbc b/opendbc/tesla_can.dbc similarity index 100% rename from tesla_can.dbc rename to opendbc/tesla_can.dbc diff --git a/toyota_avalon_2017_pt_generated.dbc b/opendbc/toyota_avalon_2017_pt_generated.dbc similarity index 100% rename from toyota_avalon_2017_pt_generated.dbc rename to opendbc/toyota_avalon_2017_pt_generated.dbc diff --git a/toyota_camry_hybrid_2018_pt_generated.dbc b/opendbc/toyota_camry_hybrid_2018_pt_generated.dbc similarity index 100% rename from toyota_camry_hybrid_2018_pt_generated.dbc rename to opendbc/toyota_camry_hybrid_2018_pt_generated.dbc diff --git a/toyota_chr_2018_pt_generated.dbc b/opendbc/toyota_chr_2018_pt_generated.dbc similarity index 100% rename from toyota_chr_2018_pt_generated.dbc rename to opendbc/toyota_chr_2018_pt_generated.dbc diff --git a/toyota_chr_hybrid_2018_pt_generated.dbc b/opendbc/toyota_chr_hybrid_2018_pt_generated.dbc similarity index 100% rename from toyota_chr_hybrid_2018_pt_generated.dbc rename to opendbc/toyota_chr_hybrid_2018_pt_generated.dbc diff --git a/toyota_corolla_2017_pt_generated.dbc b/opendbc/toyota_corolla_2017_pt_generated.dbc similarity index 100% rename from toyota_corolla_2017_pt_generated.dbc rename to opendbc/toyota_corolla_2017_pt_generated.dbc diff --git a/toyota_highlander_2017_pt_generated.dbc b/opendbc/toyota_highlander_2017_pt_generated.dbc similarity index 100% rename from toyota_highlander_2017_pt_generated.dbc rename to opendbc/toyota_highlander_2017_pt_generated.dbc diff --git a/toyota_highlander_hybrid_2018_pt_generated.dbc b/opendbc/toyota_highlander_hybrid_2018_pt_generated.dbc similarity index 100% rename from toyota_highlander_hybrid_2018_pt_generated.dbc rename to opendbc/toyota_highlander_hybrid_2018_pt_generated.dbc diff --git a/toyota_iQ_2009_can.dbc b/opendbc/toyota_iQ_2009_can.dbc similarity index 100% rename from toyota_iQ_2009_can.dbc rename to opendbc/toyota_iQ_2009_can.dbc diff --git a/toyota_prius_2010_pt.dbc b/opendbc/toyota_prius_2010_pt.dbc similarity index 100% rename from toyota_prius_2010_pt.dbc rename to opendbc/toyota_prius_2010_pt.dbc diff --git a/toyota_prius_2017_adas.dbc b/opendbc/toyota_prius_2017_adas.dbc similarity index 100% rename from toyota_prius_2017_adas.dbc rename to opendbc/toyota_prius_2017_adas.dbc diff --git a/toyota_prius_2017_pt_generated.dbc b/opendbc/toyota_prius_2017_pt_generated.dbc similarity index 100% rename from toyota_prius_2017_pt_generated.dbc rename to opendbc/toyota_prius_2017_pt_generated.dbc diff --git a/toyota_rav4_2017_pt_generated.dbc b/opendbc/toyota_rav4_2017_pt_generated.dbc similarity index 100% rename from toyota_rav4_2017_pt_generated.dbc rename to opendbc/toyota_rav4_2017_pt_generated.dbc diff --git a/toyota_rav4_hybrid_2017_pt_generated.dbc b/opendbc/toyota_rav4_hybrid_2017_pt_generated.dbc similarity index 100% rename from toyota_rav4_hybrid_2017_pt_generated.dbc rename to opendbc/toyota_rav4_hybrid_2017_pt_generated.dbc diff --git a/toyota_sienna_xle_2018_pt_generated.dbc b/opendbc/toyota_sienna_xle_2018_pt_generated.dbc similarity index 100% rename from toyota_sienna_xle_2018_pt_generated.dbc rename to opendbc/toyota_sienna_xle_2018_pt_generated.dbc diff --git a/vw_golf_mk4.dbc b/opendbc/vw_golf_mk4.dbc similarity index 100% rename from vw_golf_mk4.dbc rename to opendbc/vw_golf_mk4.dbc diff --git a/vw_mqb_2010.dbc b/opendbc/vw_mqb_2010.dbc similarity index 100% rename from vw_mqb_2010.dbc rename to opendbc/vw_mqb_2010.dbc diff --git a/panda/.circleci/config.yml b/panda/.circleci/config.yml new file mode 100644 index 00000000000000..2c7805a5bb6c78 --- /dev/null +++ b/panda/.circleci/config.yml @@ -0,0 +1,49 @@ +version: 2 +jobs: + safety: + machine: + docker_layer_caching: true + steps: + - checkout + - run: + name: Build image + command: "docker build -t panda_safety -f tests/safety/Dockerfile ." + - run: + name: Run safety test + command: | + docker run panda_safety /bin/bash -c "cd /panda/tests/safety; ./test.sh" + build: + machine: + docker_layer_caching: true + steps: + - checkout + - run: + name: Build image + command: "docker build -t panda_build -f tests/build/Dockerfile ." + - run: + name: Test python package installer + command: | + docker run panda_build /bin/bash -c "cd /panda; python setup.py install" + - run: + name: Build Panda STM image + command: | + docker run panda_build /bin/bash -c "cd /panda/board; make bin" + - run: + name: Build Pedal STM image + command: | + docker run panda_build /bin/bash -c "cd /panda/board/pedal; make obj/comma.bin" + - run: + name: Build NEO STM image + command: | + docker run panda_build /bin/bash -c "cd /panda/board; make clean; make -f Makefile.legacy obj/comma.bin" + - run: + name: Build ESP image + command: | + docker run panda_build /bin/bash -c "cd /panda/boardesp; make user1.bin" + +workflows: + version: 2 + main: + jobs: + - safety + - build diff --git a/panda/.gitignore b/panda/.gitignore new file mode 100644 index 00000000000000..7b7762ef490663 --- /dev/null +++ b/panda/.gitignore @@ -0,0 +1,14 @@ +*.pyc +.*.swp +.*.swo +*.o +*.so +*.d +a.out +*~ +.#* +dist/ +pandacan.egg-info/ +board/obj/ +examples/output.csv +.DS_Store diff --git a/panda/LICENSE b/panda/LICENSE new file mode 100644 index 00000000000000..8a6c6976b70de3 --- /dev/null +++ b/panda/LICENSE @@ -0,0 +1,7 @@ +Copyright (c) 2016, Comma.ai, 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. diff --git a/panda/README.md b/panda/README.md new file mode 100644 index 00000000000000..42f432dfc32a38 --- /dev/null +++ b/panda/README.md @@ -0,0 +1,95 @@ +Welcome to panda +====== + +[panda](http://github.com/commaai/panda) is the nicest universal car interface ever. + + + + + +It supports 3x CAN, 2x LIN, and 1x GMLAN. It also charges a phone. On the computer side, it has both USB and Wi-Fi. + +It uses an [STM32F413](http://www.st.com/en/microcontrollers/stm32f413-423.html?querycriteria=productId=LN2004) for low level stuff and an [ESP8266](https://en.wikipedia.org/wiki/ESP8266) for Wi-Fi. They are connected over high speed SPI, so the panda is actually capable of dumping the full contents of the busses over Wi-Fi, unlike every other dongle on amazon. ELM327 is weak, panda is strong. + +It is 2nd gen hardware, reusing code and parts from the [NEO](https://github.com/commaai/neo) interface board. + +[![CircleCI](https://circleci.com/gh/commaai/panda.svg?style=svg)](https://circleci.com/gh/commaai/panda) + +Usage (Python) +------ + +To install the library: +``` +# pip install pandacan +``` + +See [this class](https://github.com/commaai/panda/blob/master/python/__init__.py#L80) for how to interact with the panda. + +For example, to receive CAN messages: +``` +>>> from panda import Panda +>>> panda = Panda() +>>> panda.can_recv() +``` +And to send one on bus 0: +``` +>>> panda.can_send(0x1aa, "message", 0) +``` +Find user made scripts on the [wiki](https://community.comma.ai/wiki/index.php/Panda_scripts) + +Usage (JavaScript) +------- + +See [PandaJS](https://github.com/commaai/pandajs) + + +Software interface support +------ + +As a universal car interface, it should support every reasonable software interface. + +- [User space](https://github.com/commaai/panda/tree/master/python) +- [socketcan in kernel](https://github.com/commaai/panda/tree/master/drivers/linux) (alpha) +- [ELM327](https://github.com/commaai/panda/blob/master/boardesp/elm327.c) +- [Windows J2534](https://github.com/commaai/panda/tree/master/drivers/windows) + +Directory structure +------ + +- board -- Code that runs on the STM32 +- boardesp -- Code that runs on the ESP8266 +- drivers -- Drivers (not needed for use with python) +- python   -- Python userspace library for interfacing with the panda +- tests -- Tests and helper programs for panda + +Programming (over USB) +------ + +[Programming the Board (STM32)](board/README.md) + +[Programming the ESP](boardesp/README.md) + + +Debugging +------ + +To print out the serial console from the STM32, run tests/debug_console.py + +To print out the serial console from the ESP8266, run PORT=1 tests/debug_console.py + +Safety Model +------ + +When a panda powers up, by default it's in "SAFETY_NOOUTPUT" mode. While in no output mode, the buses are also forced to be silent. In order to send messages, you have to select a safety mode. Currently, setting safety modes is only supported over USB. + +Safety modes can also optionally support "controls_allowed", which allows or blocks a subset of messages based on a piece of state in the board. + +Hardware +------ + +Check out the hardware [guide](https://github.com/commaai/panda/blob/master/docs/guide.pdf) + +Licensing +------ + +panda software is released under the MIT license unless otherwise specified. diff --git a/panda/TODO b/panda/TODO new file mode 100644 index 00000000000000..4e4a3551549dc1 --- /dev/null +++ b/panda/TODO @@ -0,0 +1,31 @@ +** Projects ** + +== ELM327 Emulator == + +Write an elm327 emulator in boardesp/elm327.c and make it work with Torque + +You'll find a start at this in the "elm327" branch. + +== socketcan Kernel Driver == + +Write a kernel driver version of lib/panda.py that exposes the Panda on socketcan and makes it work with those tools. + +You may want to switch to interrupt endpoint first. Should LIN be exposed as a serial interface? + +== Windows J2534 DLL == + +Write a Windows DLL that exposes the J2534 API. + +Will make the Panda work with car diagnostic software. + + +** Refactors ** + +== USB Interrupt Endpoint == + +Switch USB to use an interrupt endpoint instead of a bulk endpoint for can recv + +== WebSocket Support == + +Add CAN streaming over WebSocket to the ELM code in addition to the UDP pipe. + diff --git a/panda/UPDATING.md b/panda/UPDATING.md new file mode 100644 index 00000000000000..100acc6bab5fbc --- /dev/null +++ b/panda/UPDATING.md @@ -0,0 +1,9 @@ +# Updating your panda + +Panda should update automatically via the [Chffr](http://chffr.comma.ai/) app ([apple](https://itunes.apple.com/us/app/chffr-dash-cam-that-remembers/id1146683979) and [android](https://play.google.com/store/apps/details?id=ai.comma.chffr)) + +If it doesn't however, you can use the following commands on linux or Mac OSX + `sudo pip install --upgrade pandacan` +` PYTHONPATH="" sudo python -c "import panda; panda.flash_release()"` + +(You'll need to have `pip` and `sudo` installed.) diff --git a/panda/VERSION b/panda/VERSION new file mode 100644 index 00000000000000..02e8c95da5fd8a --- /dev/null +++ b/panda/VERSION @@ -0,0 +1 @@ +v1.1.8 \ No newline at end of file diff --git a/panda/__init__.py b/panda/__init__.py new file mode 100644 index 00000000000000..b802cf5a59582a --- /dev/null +++ b/panda/__init__.py @@ -0,0 +1 @@ +from .python import Panda, PandaWifiStreaming, PandaDFU, ESPROM, CesantaFlasher, flash_release, BASEDIR, ensure_st_up_to_date, build_st, PandaSerial diff --git a/panda/board/Makefile b/panda/board/Makefile new file mode 100644 index 00000000000000..ed6dcaa0309fc8 --- /dev/null +++ b/panda/board/Makefile @@ -0,0 +1,8 @@ +PROJ_NAME = panda +CFLAGS = -g -Wall + +CFLAGS += -mlittle-endian -mthumb -mcpu=cortex-m4 +CFLAGS += -mhard-float -DSTM32F4 -DSTM32F413xx -mfpu=fpv4-sp-d16 -fsingle-precision-constant +STARTUP_FILE = startup_stm32f413xx + +include build.mk diff --git a/panda/board/Makefile.legacy b/panda/board/Makefile.legacy new file mode 100644 index 00000000000000..f6f9f9f32822fc --- /dev/null +++ b/panda/board/Makefile.legacy @@ -0,0 +1,9 @@ +# :set noet +PROJ_NAME = comma +CFLAGS = -g -Wall + +CFLAGS += -mlittle-endian -mthumb -mcpu=cortex-m3 +CFLAGS += -msoft-float -DSTM32F2 -DSTM32F205xx +STARTUP_FILE = startup_stm32f205xx + +include build.mk diff --git a/panda/board/README.md b/panda/board/README.md new file mode 100644 index 00000000000000..b3be654be31ebe --- /dev/null +++ b/panda/board/README.md @@ -0,0 +1,41 @@ +Dependencies +-------- + +**Mac** + +``` +./get_sdk_mac.sh +``` + +**Debian / Ubuntu** + +``` +./get_sdk.sh +``` + + +Programming +---- + +**Panda** + +``` +make +``` + +**NEO** + +``` +make -f Makefile.legacy +``` + +Troubleshooting +---- + +If your panda will not flash and is quickly blinking a single Green LED, use: +``` +make recover +``` + + +[dfu-util](http://github.com/dsigma/dfu-util.git) for flashing diff --git a/panda/board/__init__.py b/panda/board/__init__.py new file mode 100644 index 00000000000000..e69de29bb2d1d6 diff --git a/panda/board/bootstub.c b/panda/board/bootstub.c new file mode 100644 index 00000000000000..e44986c29ec47c --- /dev/null +++ b/panda/board/bootstub.c @@ -0,0 +1,100 @@ +#define BOOTSTUB + +#include "config.h" +#include "obj/gitversion.h" + +#ifdef STM32F4 + #define PANDA + #include "stm32f4xx.h" + #include "stm32f4xx_hal_gpio_ex.h" +#else + #include "stm32f2xx.h" + #include "stm32f2xx_hal_gpio_ex.h" +#endif + +#include "libc.h" +#include "provision.h" + +#include "drivers/drivers.h" + +#include "drivers/llgpio.h" +#include "gpio.h" + +#include "drivers/spi.h" +#include "drivers/usb.h" +//#include "drivers/uart.h" + +#ifdef PEDAL +#define CUSTOM_CAN_INTERRUPTS +#include "safety.h" +#include "drivers/can.h" +#endif + +int puts(const char *a) { return 0; } +void puth(unsigned int i) {} + +#include "crypto/rsa.h" +#include "crypto/sha.h" + +#include "obj/cert.h" + +#include "spi_flasher.h" + +void __initialize_hardware_early() { + early(); +} + +void fail() { + soft_flasher_start(); +} + +// know where to sig check +extern void *_app_start[]; + +// FIXME: sometimes your panda will fail flashing and will quickly blink a single Green LED +// BOUNTY: $200 coupon on shop.comma.ai or $100 check. + +int main() { + __disable_irq(); + clock_init(); + detect(); + + if (revision == PANDA_REV_C) { + set_usb_power_mode(USB_POWER_CLIENT); + } + + if (enter_bootloader_mode == ENTER_SOFTLOADER_MAGIC) { + enter_bootloader_mode = 0; + soft_flasher_start(); + } + + // validate length + int len = (int)_app_start[0]; + if ((len < 8) || (len > (0x1000000 - 0x4000 - 4 - RSANUMBYTES))) goto fail; + + // compute SHA hash + uint8_t digest[SHA_DIGEST_SIZE]; + SHA_hash(&_app_start[1], len-4, digest); + + // verify RSA signature + if (RSA_verify(&release_rsa_key, ((void*)&_app_start[0]) + len, RSANUMBYTES, digest, SHA_DIGEST_SIZE)) { + goto good; + } + + // allow debug if built from source +#ifdef ALLOW_DEBUG + if (RSA_verify(&debug_rsa_key, ((void*)&_app_start[0]) + len, RSANUMBYTES, digest, SHA_DIGEST_SIZE)) { + goto good; + } +#endif + +// here is a failure +fail: + fail(); + return 0; +good: + // jump to flash + ((void(*)()) _app_start[1])(); + return 0; +} + diff --git a/panda/board/build.mk b/panda/board/build.mk new file mode 100644 index 00000000000000..9f2c4250c2c772 --- /dev/null +++ b/panda/board/build.mk @@ -0,0 +1,62 @@ +CFLAGS += -I inc -I ../ -nostdlib -fno-builtin -std=gnu11 -Os + +CFLAGS += -Tstm32_flash.ld + +CC = arm-none-eabi-gcc +OBJCOPY = arm-none-eabi-objcopy +OBJDUMP = arm-none-eabi-objdump + +ifeq ($(RELEASE),1) + CERT = ../../pandaextra/certs/release +else + # enable the debug cert + CERT = ../certs/debug + CFLAGS += "-DALLOW_DEBUG" +endif + +DFU_UTIL = "dfu-util" + +# this no longer pushes the bootstub +flash: obj/$(PROJ_NAME).bin + PYTHONPATH=../ python -c "from python import Panda; Panda().flash('obj/$(PROJ_NAME).bin')" + +ota: obj/$(PROJ_NAME).bin + curl http://192.168.0.10/stupdate --upload-file $< + +bin: obj/$(PROJ_NAME).bin + +# this flashes everything +recover: obj/bootstub.$(PROJ_NAME).bin obj/$(PROJ_NAME).bin + -PYTHONPATH=../ python -c "from python import Panda; Panda().reset(enter_bootloader=True)" + sleep 1.0 + $(DFU_UTIL) -d 0483:df11 -a 0 -s 0x08004000 -D obj/$(PROJ_NAME).bin + $(DFU_UTIL) -d 0483:df11 -a 0 -s 0x08000000:leave -D obj/bootstub.$(PROJ_NAME).bin + +include ../common/version.mk + +obj/cert.h: ../crypto/getcertheader.py + ../crypto/getcertheader.py ../certs/debug.pub ../certs/release.pub > $@ + +obj/%.$(PROJ_NAME).o: %.c obj/cert.h obj/gitversion.h config.h drivers/*.h gpio.h libc.h provision.h safety.h safety/*.h spi_flasher.h + $(CC) $(CFLAGS) -o $@ -c $< + +obj/%.$(PROJ_NAME).o: ../crypto/%.c + $(CC) $(CFLAGS) -o $@ -c $< + +obj/$(STARTUP_FILE).o: $(STARTUP_FILE).s + $(CC) $(CFLAGS) -o $@ -c $< + +obj/$(PROJ_NAME).bin: obj/$(STARTUP_FILE).o obj/main.$(PROJ_NAME).o + # hack + $(CC) -Wl,--section-start,.isr_vector=0x8004000 $(CFLAGS) -o obj/$(PROJ_NAME).elf $^ + $(OBJCOPY) -v -O binary obj/$(PROJ_NAME).elf obj/code.bin + SETLEN=1 ../crypto/sign.py obj/code.bin $@ $(CERT) + @BINSIZE=$$(du -b "obj/$(PROJ_NAME).bin" | cut -f 1) ; if [ $$BINSIZE -ge 32768 ]; then echo "ERROR obj/$(PROJ_NAME).bin is too big!"; exit 1; fi; + + +obj/bootstub.$(PROJ_NAME).bin: obj/$(STARTUP_FILE).o obj/bootstub.$(PROJ_NAME).o obj/sha.$(PROJ_NAME).o obj/rsa.$(PROJ_NAME).o + $(CC) $(CFLAGS) -o obj/bootstub.$(PROJ_NAME).elf $^ + $(OBJCOPY) -v -O binary obj/bootstub.$(PROJ_NAME).elf $@ + +clean: + @rm -f obj/* diff --git a/panda/board/config.h b/panda/board/config.h new file mode 100644 index 00000000000000..e83429980d4163 --- /dev/null +++ b/panda/board/config.h @@ -0,0 +1,40 @@ +#ifndef PANDA_CONFIG_H +#define PANDA_CONFIG_H + +//#define DEBUG +//#define DEBUG_USB +//#define DEBUG_SPI + +#ifdef STM32F4 + #define PANDA + #include "stm32f4xx.h" +#else + #include "stm32f2xx.h" +#endif + +#define USB_VID 0xbbaa + +#ifdef BOOTSTUB +#define USB_PID 0xddee +#else +#define USB_PID 0xddcc +#endif + +#include +#define NULL ((void*)0) +#define COMPILE_TIME_ASSERT(pred) switch(0){case 0:case pred:;} + +#define min(a,b) \ + ({ __typeof__ (a) _a = (a); \ + __typeof__ (b) _b = (b); \ + _a < _b ? _a : _b; }) + +#define max(a,b) \ + ({ __typeof__ (a) _a = (a); \ + __typeof__ (b) _b = (b); \ + _a > _b ? _a : _b; }) + +#define MAX_RESP_LEN 0x40 + +#endif + diff --git a/panda/board/drivers/adc.h b/panda/board/drivers/adc.h new file mode 100644 index 00000000000000..cb2aeede03958a --- /dev/null +++ b/panda/board/drivers/adc.h @@ -0,0 +1,38 @@ +// ACCEL1 = ADC10 +// ACCEL2 = ADC11 +// VOLT_S = ADC12 +// CURR_S = ADC13 + +#define ADCCHAN_ACCEL0 10 +#define ADCCHAN_ACCEL1 11 +#define ADCCHAN_VOLTAGE 12 +#define ADCCHAN_CURRENT 13 + +void adc_init() { + // global setup + ADC->CCR = ADC_CCR_TSVREFE | ADC_CCR_VBATE; + //ADC1->CR2 = ADC_CR2_ADON | ADC_CR2_EOCS | ADC_CR2_DDS; + ADC1->CR2 = ADC_CR2_ADON; + + // long + //ADC1->SMPR1 = ADC_SMPR1_SMP10 | ADC_SMPR1_SMP11 | ADC_SMPR1_SMP12 | ADC_SMPR1_SMP13; + ADC1->SMPR1 = ADC_SMPR1_SMP12 | ADC_SMPR1_SMP13; +} + +uint32_t adc_get(int channel) { + // includes length + //ADC1->SQR1 = 0; + + // select channel + ADC1->JSQR = channel << 15; + + //ADC1->CR1 = ADC_CR1_DISCNUM_0; + //ADC1->CR1 = ADC_CR1_EOCIE; + + ADC1->SR &= ~(ADC_SR_JEOC); + ADC1->CR2 |= ADC_CR2_JSWSTART; + while (!(ADC1->SR & ADC_SR_JEOC)); + + return ADC1->JDR1; +} + diff --git a/panda/board/drivers/can.h b/panda/board/drivers/can.h new file mode 100644 index 00000000000000..b837094c9a0d38 --- /dev/null +++ b/panda/board/drivers/can.h @@ -0,0 +1,485 @@ +// IRQs: CAN1_TX, CAN1_RX0, CAN1_SCE, CAN2_TX, CAN2_RX0, CAN2_SCE, CAN3_TX, CAN3_RX0, CAN3_SCE +#define ALL_CAN_SILENT 0xFF +#define ALL_CAN_BUT_MAIN_SILENT 0xFE +#define ALL_CAN_LIVE 0 + +int can_live = 0, pending_can_live = 0, can_loopback = 0, can_silent = ALL_CAN_SILENT; + +// ********************* instantiate queues ********************* + +#define can_buffer(x, size) \ + CAN_FIFOMailBox_TypeDef elems_##x[size]; \ + can_ring can_##x = { .w_ptr = 0, .r_ptr = 0, .fifo_size = size, .elems = (CAN_FIFOMailBox_TypeDef *)&elems_##x }; + +can_buffer(rx_q, 0x1000) +can_buffer(tx1_q, 0x100) +can_buffer(tx2_q, 0x100) + +#ifdef PANDA + can_buffer(tx3_q, 0x100) + can_buffer(txgmlan_q, 0x100) + can_ring *can_queues[] = {&can_tx1_q, &can_tx2_q, &can_tx3_q, &can_txgmlan_q}; +#else + can_ring *can_queues[] = {&can_tx1_q, &can_tx2_q}; +#endif + +// ********************* interrupt safe queue ********************* + +int can_pop(can_ring *q, CAN_FIFOMailBox_TypeDef *elem) { + int ret = 0; + + enter_critical_section(); + if (q->w_ptr != q->r_ptr) { + *elem = q->elems[q->r_ptr]; + if ((q->r_ptr + 1) == q->fifo_size) q->r_ptr = 0; + else q->r_ptr += 1; + ret = 1; + } + exit_critical_section(); + + return ret; +} + +int can_push(can_ring *q, CAN_FIFOMailBox_TypeDef *elem) { + int ret = 0; + uint32_t next_w_ptr; + + enter_critical_section(); + if ((q->w_ptr + 1) == q->fifo_size) next_w_ptr = 0; + else next_w_ptr = q->w_ptr + 1; + if (next_w_ptr != q->r_ptr) { + q->elems[q->w_ptr] = *elem; + q->w_ptr = next_w_ptr; + ret = 1; + } + exit_critical_section(); + if (ret == 0) puts("can_push failed!\n"); + return ret; +} + +void can_clear(can_ring *q) { + enter_critical_section(); + q->w_ptr = 0; + q->r_ptr = 0; + exit_critical_section(); +} + +// assign CAN numbering +// bus num: Can bus number on ODB connector. Sent to/from USB +// Min: 0; Max: 127; Bit 7 marks message as receipt (bus 129 is receipt for but 1) +// cans: Look up MCU can interface from bus number +// can number: numeric lookup for MCU CAN interfaces (0 = CAN1, 1 = CAN2, etc); +// bus_lookup: Translates from 'can number' to 'bus number'. +// can_num_lookup: Translates from 'bus number' to 'can number'. +// can_forwarding: Given a bus num, lookup bus num to forward to. -1 means no forward. + +int can_rx_cnt = 0; +int can_tx_cnt = 0; +int can_txd_cnt = 0; +int can_err_cnt = 0; + +// NEO: Bus 1=CAN1 Bus 2=CAN2 +// Panda: Bus 0=CAN1 Bus 1=CAN2 Bus 2=CAN3 +#ifdef PANDA + CAN_TypeDef *cans[] = {CAN1, CAN2, CAN3}; + uint8_t bus_lookup[] = {0,1,2}; + uint8_t can_num_lookup[] = {0,1,2,-1}; + int8_t can_forwarding[] = {-1,-1,-1,-1}; + uint32_t can_speed[] = {5000, 5000, 5000, 333}; + bool can_autobaud_enabled[] = {false, false, false, false}; + #define CAN_MAX 3 +#else + CAN_TypeDef *cans[] = {CAN1, CAN2}; + uint8_t bus_lookup[] = {1,0}; + uint8_t can_num_lookup[] = {1,0}; + int8_t can_forwarding[] = {-1,-1}; + uint32_t can_speed[] = {5000, 5000}; + bool can_autobaud_enabled[] = {false, false}; + #define CAN_MAX 2 +#endif + +uint32_t can_autobaud_speeds[] = {5000, 2500, 1250, 1000, 10000}; +#define AUTOBAUD_SPEEDS_LEN (sizeof(can_autobaud_speeds) / sizeof(can_autobaud_speeds[0])) + +#define CANIF_FROM_CAN_NUM(num) (cans[num]) +#ifdef PANDA +#define CAN_NUM_FROM_CANIF(CAN) (CAN==CAN1 ? 0 : (CAN==CAN2 ? 1 : 2)) +#define CAN_NAME_FROM_CANIF(CAN) (CAN==CAN1 ? "CAN1" : (CAN==CAN2 ? "CAN2" : "CAN3")) +#else +#define CAN_NUM_FROM_CANIF(CAN) (CAN==CAN1 ? 0 : 1) +#define CAN_NAME_FROM_CANIF(CAN) (CAN==CAN1 ? "CAN1" : "CAN2") +#endif +#define BUS_NUM_FROM_CAN_NUM(num) (bus_lookup[num]) +#define CAN_NUM_FROM_BUS_NUM(num) (can_num_lookup[num]) + +// other option +/*#define CAN_QUANTA 16 +#define CAN_SEQ1 13 +#define CAN_SEQ2 2*/ + +// this is needed for 1 mbps support +#define CAN_QUANTA 8 +#define CAN_SEQ1 6 // roundf(quanta * 0.875f) - 1; +#define CAN_SEQ2 1 // roundf(quanta * 0.125f); + +#define CAN_PCLK 24000 +// 333 = 33.3 kbps +// 5000 = 500 kbps +#define can_speed_to_prescaler(x) (CAN_PCLK / CAN_QUANTA * 10 / (x)) + +void can_autobaud_speed_increment(uint8_t can_number) { + uint32_t autobaud_speed = can_autobaud_speeds[0]; + uint8_t bus_number = BUS_NUM_FROM_CAN_NUM(can_number); + for (int i = 0; i < AUTOBAUD_SPEEDS_LEN; i++) { + if (can_speed[bus_number] == can_autobaud_speeds[i]) { + if (i+1 < AUTOBAUD_SPEEDS_LEN) { + autobaud_speed = can_autobaud_speeds[i+1]; + } + break; + } + } + can_speed[bus_number] = autobaud_speed; +#ifdef DEBUG + CAN_TypeDef* CAN = CANIF_FROM_CAN_NUM(can_number); + puts(CAN_NAME_FROM_CANIF(CAN)); + puts(" auto-baud test "); + putui(can_speed[bus_number]); + puts(" cbps\n"); +#endif +} + +void process_can(uint8_t can_number); + +void can_set_speed(uint8_t can_number) { + CAN_TypeDef *CAN = CANIF_FROM_CAN_NUM(can_number); + uint8_t bus_number = BUS_NUM_FROM_CAN_NUM(can_number); + + while (true) { + // initialization mode + CAN->MCR = CAN_MCR_TTCM | CAN_MCR_INRQ; + while((CAN->MSR & CAN_MSR_INAK) != CAN_MSR_INAK); + + // set time quanta from defines + CAN->BTR = (CAN_BTR_TS1_0 * (CAN_SEQ1-1)) | + (CAN_BTR_TS2_0 * (CAN_SEQ2-1)) | + (can_speed_to_prescaler(can_speed[bus_number]) - 1); + + // silent loopback mode for debugging + if (can_loopback) { + CAN->BTR |= CAN_BTR_SILM | CAN_BTR_LBKM; + } + if (can_silent & (1 << can_number)) { + CAN->BTR |= CAN_BTR_SILM; + } + + // reset + CAN->MCR = CAN_MCR_TTCM | CAN_MCR_ABOM; + + #define CAN_TIMEOUT 1000000 + int tmp = 0; + while((CAN->MSR & CAN_MSR_INAK) == CAN_MSR_INAK && tmp < CAN_TIMEOUT) tmp++; + if (tmp < CAN_TIMEOUT) { + return; + } + + if (can_autobaud_enabled[bus_number]) { + can_autobaud_speed_increment(can_number); + } else { + puts("CAN init FAILED!!!!!\n"); + puth(can_number); puts(" "); + puth(BUS_NUM_FROM_CAN_NUM(can_number)); puts("\n"); + return; + } + } +} + +void can_init(uint8_t can_number) { + if (can_number == 0xff) return; + + CAN_TypeDef *CAN = CANIF_FROM_CAN_NUM(can_number); + set_can_enable(CAN, 1); + can_set_speed(can_number); + + // accept all filter + CAN->FMR |= CAN_FMR_FINIT; + + // no mask + CAN->sFilterRegister[0].FR1 = 0; + CAN->sFilterRegister[0].FR2 = 0; + CAN->sFilterRegister[14].FR1 = 0; + CAN->sFilterRegister[14].FR2 = 0; + CAN->FA1R |= 1 | (1 << 14); + + CAN->FMR &= ~(CAN_FMR_FINIT); + + // enable certain CAN interrupts + CAN->IER |= CAN_IER_TMEIE | CAN_IER_FMPIE0; + + switch (can_number) { + case 0: + NVIC_EnableIRQ(CAN1_TX_IRQn); + NVIC_EnableIRQ(CAN1_RX0_IRQn); + NVIC_EnableIRQ(CAN1_SCE_IRQn); + break; + case 1: + NVIC_EnableIRQ(CAN2_TX_IRQn); + NVIC_EnableIRQ(CAN2_RX0_IRQn); + NVIC_EnableIRQ(CAN2_SCE_IRQn); + break; +#ifdef CAN3 + case 2: + NVIC_EnableIRQ(CAN3_TX_IRQn); + NVIC_EnableIRQ(CAN3_RX0_IRQn); + NVIC_EnableIRQ(CAN3_SCE_IRQn); + break; +#endif + } + + // in case there are queued up messages + process_can(can_number); +} + +void can_init_all() { + for (int i=0; i < CAN_MAX; i++) { + can_init(i); + } +} + +void can_set_gmlan(int bus) { + #ifdef PANDA + if (bus == -1 || bus != can_num_lookup[3]) { + // GMLAN OFF + switch (can_num_lookup[3]) { + case 1: + puts("disable GMLAN on CAN2\n"); + set_can_mode(1, 0); + bus_lookup[1] = 1; + can_num_lookup[1] = 1; + can_num_lookup[3] = -1; + can_init(1); + break; + case 2: + puts("disable GMLAN on CAN3\n"); + set_can_mode(2, 0); + bus_lookup[2] = 2; + can_num_lookup[2] = 2; + can_num_lookup[3] = -1; + can_init(2); + break; + } + } + + if (bus == 1) { + puts("GMLAN on CAN2\n"); + // GMLAN on CAN2 + set_can_mode(1, 1); + bus_lookup[1] = 3; + can_num_lookup[1] = -1; + can_num_lookup[3] = 1; + can_init(1); + } else if (bus == 2 && revision == PANDA_REV_C) { + puts("GMLAN on CAN3\n"); + // GMLAN on CAN3 + set_can_mode(2, 1); + bus_lookup[2] = 3; + can_num_lookup[2] = -1; + can_num_lookup[3] = 2; + can_init(2); + } + #endif +} + +// CAN error +void can_sce(CAN_TypeDef *CAN) { + enter_critical_section(); + + can_err_cnt += 1; + #ifdef DEBUG + if (CAN==CAN1) puts("CAN1: "); + if (CAN==CAN2) puts("CAN2: "); + #ifdef CAN3 + if (CAN==CAN3) puts("CAN3: "); + #endif + puts("MSR:"); + puth(CAN->MSR); + puts(" TSR:"); + puth(CAN->TSR); + puts(" RF0R:"); + puth(CAN->RF0R); + puts(" RF1R:"); + puth(CAN->RF1R); + puts(" ESR:"); + puth(CAN->ESR); + puts("\n"); + #endif + + uint8_t can_number = CAN_NUM_FROM_CANIF(CAN); + uint8_t bus_number = BUS_NUM_FROM_CAN_NUM(can_number); + if (can_autobaud_enabled[bus_number] && (CAN->ESR & CAN_ESR_LEC)) { + can_autobaud_speed_increment(can_number); + can_set_speed(can_number); + } + + // clear current send + CAN->TSR |= CAN_TSR_ABRQ0; + CAN->MSR &= ~(CAN_MSR_ERRI); + CAN->MSR = CAN->MSR; + + exit_critical_section(); +} + +// ***************************** CAN ***************************** + +void process_can(uint8_t can_number) { + if (can_number == 0xff) return; + + enter_critical_section(); + + CAN_TypeDef *CAN = CANIF_FROM_CAN_NUM(can_number); + uint8_t bus_number = BUS_NUM_FROM_CAN_NUM(can_number); + #ifdef DEBUG + puts("process CAN TX\n"); + #endif + + // check for empty mailbox + CAN_FIFOMailBox_TypeDef to_send; + if ((CAN->TSR & CAN_TSR_TME0) == CAN_TSR_TME0) { + // add successfully transmitted message to my fifo + if ((CAN->TSR & CAN_TSR_RQCP0) == CAN_TSR_RQCP0) { + can_txd_cnt += 1; + + if ((CAN->TSR & CAN_TSR_TXOK0) == CAN_TSR_TXOK0) { + CAN_FIFOMailBox_TypeDef to_push; + to_push.RIR = CAN->sTxMailBox[0].TIR; + to_push.RDTR = (CAN->sTxMailBox[0].TDTR & 0xFFFF000F) | ((CAN_BUS_RET_FLAG | bus_number) << 4); + to_push.RDLR = CAN->sTxMailBox[0].TDLR; + to_push.RDHR = CAN->sTxMailBox[0].TDHR; + can_push(&can_rx_q, &to_push); + } + + if ((CAN->TSR & CAN_TSR_TERR0) == CAN_TSR_TERR0) { + #ifdef DEBUG + puts("CAN TX ERROR!\n"); + #endif + } + + if ((CAN->TSR & CAN_TSR_ALST0) == CAN_TSR_ALST0) { + #ifdef DEBUG + puts("CAN TX ARBITRATION LOST!\n"); + #endif + } + + // clear interrupt + // careful, this can also be cleared by requesting a transmission + CAN->TSR |= CAN_TSR_RQCP0; + } + + if (can_pop(can_queues[bus_number], &to_send)) { + can_tx_cnt += 1; + // only send if we have received a packet + CAN->sTxMailBox[0].TDLR = to_send.RDLR; + CAN->sTxMailBox[0].TDHR = to_send.RDHR; + CAN->sTxMailBox[0].TDTR = to_send.RDTR; + CAN->sTxMailBox[0].TIR = to_send.RIR; + } + } + + exit_critical_section(); +} + +// CAN receive handlers +// blink blue when we are receiving CAN messages +void can_rx(uint8_t can_number) { + CAN_TypeDef *CAN = CANIF_FROM_CAN_NUM(can_number); + uint8_t bus_number = BUS_NUM_FROM_CAN_NUM(can_number); + while (CAN->RF0R & CAN_RF0R_FMP0) { + if (can_autobaud_enabled[bus_number]) { + can_autobaud_enabled[bus_number] = false; + puts(CAN_NAME_FROM_CANIF(CAN)); + #ifdef DEBUG + puts(" auto-baud "); + putui(can_speed[bus_number]); + puts(" cbps\n"); + #endif + } + + can_rx_cnt += 1; + + // can is live + pending_can_live = 1; + + // add to my fifo + CAN_FIFOMailBox_TypeDef to_push; + to_push.RIR = CAN->sFIFOMailBox[0].RIR; + to_push.RDTR = CAN->sFIFOMailBox[0].RDTR; + to_push.RDLR = CAN->sFIFOMailBox[0].RDLR; + to_push.RDHR = CAN->sFIFOMailBox[0].RDHR; + + // modify RDTR for our API + to_push.RDTR = (to_push.RDTR & 0xFFFF000F) | (bus_number << 4); + + // forwarding (panda only) + #ifdef PANDA + int bus_fwd_num = can_forwarding[bus_number] != -1 ? can_forwarding[bus_number] : safety_fwd_hook(bus_number, &to_push); + if (bus_fwd_num != -1) { + CAN_FIFOMailBox_TypeDef to_send; + to_send.RIR = to_push.RIR | 1; // TXRQ + to_send.RDTR = to_push.RDTR; + to_send.RDLR = to_push.RDLR; + to_send.RDHR = to_push.RDHR; + can_send(&to_send, bus_fwd_num); + } + #endif + + safety_rx_hook(&to_push); + + #ifdef PANDA + set_led(LED_BLUE, 1); + #endif + can_push(&can_rx_q, &to_push); + + // next + CAN->RF0R |= CAN_RF0R_RFOM0; + } +} + +#ifndef CUSTOM_CAN_INTERRUPTS + +void CAN1_TX_IRQHandler() { process_can(0); } +void CAN1_RX0_IRQHandler() { can_rx(0); } +void CAN1_SCE_IRQHandler() { can_sce(CAN1); } + +void CAN2_TX_IRQHandler() { process_can(1); } +void CAN2_RX0_IRQHandler() { can_rx(1); } +void CAN2_SCE_IRQHandler() { can_sce(CAN2); } + +#ifdef CAN3 +void CAN3_TX_IRQHandler() { process_can(2); } +void CAN3_RX0_IRQHandler() { can_rx(2); } +void CAN3_SCE_IRQHandler() { can_sce(CAN3); } +#endif + +#endif + +void can_send(CAN_FIFOMailBox_TypeDef *to_push, uint8_t bus_number) { + if (safety_tx_hook(to_push) && !can_autobaud_enabled[bus_number]) { + if (bus_number < BUS_MAX) { + // add CAN packet to send queue + // bus number isn't passed through + to_push->RDTR &= 0xF; + if (bus_number == 3 && can_num_lookup[3] == 0xFF) { + #ifdef PANDA + // TODO: why uint8 bro? only int8? + bitbang_gmlan(to_push); + #endif + } else { + can_push(can_queues[bus_number], to_push); + process_can(CAN_NUM_FROM_BUS_NUM(bus_number)); + } + } + } +} + +void can_set_forwarding(int from, int to) { + can_forwarding[from] = to; +} diff --git a/panda/board/drivers/dac.h b/panda/board/drivers/dac.h new file mode 100644 index 00000000000000..b8833dc4a62cfe --- /dev/null +++ b/panda/board/drivers/dac.h @@ -0,0 +1,16 @@ +void dac_init() { + // no buffers required since we have an opamp + //DAC->CR = DAC_CR_EN1 | DAC_CR_BOFF1 | DAC_CR_EN2 | DAC_CR_BOFF2; + DAC->DHR12R1 = 0; + DAC->DHR12R2 = 0; + DAC->CR = DAC_CR_EN1 | DAC_CR_EN2; +} + +void dac_set(int channel, uint32_t value) { + if (channel == 0) { + DAC->DHR12R1 = value; + } else if (channel == 1) { + DAC->DHR12R2 = value; + } +} + diff --git a/panda/board/drivers/drivers.h b/panda/board/drivers/drivers.h new file mode 100644 index 00000000000000..d3409d60994eed --- /dev/null +++ b/panda/board/drivers/drivers.h @@ -0,0 +1,141 @@ +#ifndef PANDA_DRIVERS_H +#define PANDA_DRIVERS_H + +// ********************* LLGPIO ********************* + +#define MODE_INPUT 0 +#define MODE_OUTPUT 1 +#define MODE_ALTERNATE 2 +#define MODE_ANALOG 3 + +#define PULL_NONE 0 +#define PULL_UP 1 +#define PULL_DOWN 2 + +void set_gpio_mode(GPIO_TypeDef *GPIO, int pin, int mode); +void set_gpio_output(GPIO_TypeDef *GPIO, int pin, int val); +void set_gpio_alternate(GPIO_TypeDef *GPIO, int pin, int mode); +void set_gpio_pullup(GPIO_TypeDef *GPIO, int pin, int mode); + +int get_gpio_input(GPIO_TypeDef *GPIO, int pin); + + +// ********************* USB ********************* +// IRQs: OTG_FS + +typedef union { + uint16_t w; + struct BW { + uint8_t msb; + uint8_t lsb; + } + bw; +} +uint16_t_uint8_t; + +typedef union _USB_Setup { + uint32_t d8[2]; + struct _SetupPkt_Struc + { + uint8_t bmRequestType; + uint8_t bRequest; + uint16_t_uint8_t wValue; + uint16_t_uint8_t wIndex; + uint16_t_uint8_t wLength; + } b; +} +USB_Setup_TypeDef; + +void usb_init(); +int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, int hardwired); +int usb_cb_ep1_in(uint8_t *usbdata, int len, int hardwired); +void usb_cb_ep2_out(uint8_t *usbdata, int len, int hardwired); +void usb_cb_ep3_out(uint8_t *usbdata, int len, int hardwired); +void usb_cb_enumeration_complete(); + + +// ********************* UART ********************* +// IRQs: USART1, USART2, USART3, UART5 + +#define FIFO_SIZE 0x400 +typedef struct uart_ring { + uint16_t w_ptr_tx; + uint16_t r_ptr_tx; + uint8_t elems_tx[FIFO_SIZE]; + uint16_t w_ptr_rx; + uint16_t r_ptr_rx; + uint8_t elems_rx[FIFO_SIZE]; + USART_TypeDef *uart; + void (*callback)(struct uart_ring*); +} uart_ring; + +void uart_init(USART_TypeDef *u, int baud); + +int getc(uart_ring *q, char *elem); +int putc(uart_ring *q, char elem); + +int puts(const char *a); +void puth(unsigned int i); +void hexdump(const void *a, int l); + + +// ********************* ADC ********************* + +void adc_init(); +uint32_t adc_get(int channel); + + +// ********************* DAC ********************* + +void dac_init(); +void dac_set(int channel, uint32_t value); + + +// ********************* TIMER ********************* + +void timer_init(TIM_TypeDef *TIM, int psc); + + +// ********************* SPI ********************* +// IRQs: DMA2_Stream2, DMA2_Stream3, EXTI4 + +void spi_init(); +int spi_cb_rx(uint8_t *data, int len, uint8_t *data_out); + + +// ********************* CAN ********************* +// IRQs: CAN1_TX, CAN1_RX0, CAN1_SCE +// CAN2_TX, CAN2_RX0, CAN2_SCE +// CAN3_TX, CAN3_RX0, CAN3_SCE + +typedef struct { + uint32_t w_ptr; + uint32_t r_ptr; + uint32_t fifo_size; + CAN_FIFOMailBox_TypeDef *elems; +} can_ring; + +#define CAN_BUS_RET_FLAG 0x80 +#define CAN_BUS_NUM_MASK 0x7F + +#ifdef PANDA + #define BUS_MAX 4 +#else + #define BUS_MAX 2 +#endif + +extern int can_live, pending_can_live; + +// must reinit after changing these +extern int can_loopback, can_silent; +extern uint32_t can_speed[]; + +void can_set_forwarding(int from, int to); + +void can_init(uint8_t can_number); +void can_init_all(); +void can_send(CAN_FIFOMailBox_TypeDef *to_push, uint8_t bus_number); +int can_pop(can_ring *q, CAN_FIFOMailBox_TypeDef *elem); + +#endif + diff --git a/panda/board/drivers/gmlan_alt.h b/panda/board/drivers/gmlan_alt.h new file mode 100644 index 00000000000000..8521100a88083a --- /dev/null +++ b/panda/board/drivers/gmlan_alt.h @@ -0,0 +1,276 @@ +#define GMLAN_TICKS_PER_SECOND 33300 //1sec @ 33.3kbps +#define GMLAN_TICKS_PER_TIMEOUT_TICKLE 500 //15ms @ 33.3kbps +#define GMLAN_HIGH 0 //0 is high on bus (dominant) +#define GMLAN_LOW 1 //1 is low on bus + +#define DISABLED -1 +#define BITBANG 0 +#define GPIO_SWITCH 1 + +#define MAX_BITS_CAN_PACKET (200) + +int gmlan_alt_mode = DISABLED; + +// returns out_len +int do_bitstuff(char *out, char *in, int in_len) { + int last_bit = -1; + int bit_cnt = 0; + int j = 0; + for (int i = 0; i < in_len; i++) { + char bit = in[i]; + out[j++] = bit; + + // do the stuffing + if (bit == last_bit) { + bit_cnt++; + if (bit_cnt == 5) { + // 5 in a row the same, do stuff + last_bit = !bit; + out[j++] = last_bit; + bit_cnt = 1; + } + } else { + // this is a new bit + last_bit = bit; + bit_cnt = 1; + } + } + return j; +} + +int append_crc(char *in, int in_len) { + int crc = 0; + for (int i = 0; i < in_len; i++) { + crc <<= 1; + if (in[i] ^ ((crc>>15)&1)) { + crc = crc ^ 0x4599; + } + crc &= 0x7fff; + } + for (int i = 14; i >= 0; i--) { + in[in_len++] = (crc>>i)&1; + } + return in_len; +} + +int append_bits(char *in, int in_len, char *app, int app_len) { + for (int i = 0; i < app_len; i++) { + in[in_len++] = app[i]; + } + return in_len; +} + +int append_int(char *in, int in_len, int val, int val_len) { + for (int i = val_len-1; i >= 0; i--) { + in[in_len++] = (val&(1<RDTR & 0xF; + len = append_int(pkt, len, 0, 1); // Start-of-frame + + if (to_bang->RIR & 4) { + // extended identifier + len = append_int(pkt, len, to_bang->RIR >> 21, 11); // Identifier + len = append_int(pkt, len, 3, 2); // SRR+IDE + len = append_int(pkt, len, (to_bang->RIR >> 3) & ((1<<18)-1), 18); // Identifier + len = append_int(pkt, len, 0, 3); // RTR+r1+r0 + } else { + // standard identifier + len = append_int(pkt, len, to_bang->RIR >> 21, 11); // Identifier + len = append_int(pkt, len, 0, 3); // RTR+IDE+reserved + } + + len = append_int(pkt, len, dlc_len, 4); // Data length code + + // append data + for (int i = 0; i < dlc_len; i++) { + unsigned char dat = ((unsigned char *)(&(to_bang->RDLR)))[i]; + len = append_int(pkt, len, dat, 8); + } + + // append crc + len = append_crc(pkt, len); + + // do bitstuffing + len = do_bitstuff(out, pkt, len); + + // append footer + len = append_bits(out, len, footer, sizeof(footer)); + return len; +} + +#ifdef PANDA + +void setup_timer4() { + // setup + TIM4->PSC = 48-1; // tick on 1 us + TIM4->CR1 = TIM_CR1_CEN; // enable + TIM4->ARR = 30-1; // 33.3 kbps + + // in case it's disabled + NVIC_EnableIRQ(TIM4_IRQn); + + // run the interrupt + TIM4->DIER = TIM_DIER_UIE; // update interrupt + TIM4->SR = 0; +} + +int gmlan_timeout_counter = GMLAN_TICKS_PER_TIMEOUT_TICKLE; //GMLAN transceiver times out every 17ms held high; tickle every 15ms +int can_timeout_counter = GMLAN_TICKS_PER_SECOND; //1 second + +int inverted_bit_to_send = GMLAN_HIGH; +int gmlan_switch_below_timeout = -1; +int gmlan_switch_timeout_enable = 0; + +void gmlan_switch_init(int timeout_enable) { + gmlan_switch_timeout_enable = timeout_enable; + gmlan_alt_mode = GPIO_SWITCH; + gmlan_switch_below_timeout = 1; + set_gpio_mode(GPIOB, 13, MODE_OUTPUT); + + setup_timer4(); + + inverted_bit_to_send = GMLAN_LOW; //We got initialized, set the output low +} + +void set_gmlan_digital_output(int to_set) { + inverted_bit_to_send = to_set; + /* + puts("Writing "); + puth(inverted_bit_to_send); + puts("\n"); + */ +} + +void reset_gmlan_switch_timeout(void) { + can_timeout_counter = GMLAN_TICKS_PER_SECOND; + gmlan_switch_below_timeout = 1; + gmlan_alt_mode = GPIO_SWITCH; +} + +void set_bitbanged_gmlan(int val) { + if (val) { + GPIOB->ODR |= (1 << 13); + } else { + GPIOB->ODR &= ~(1 << 13); + } +} + +char pkt_stuffed[MAX_BITS_CAN_PACKET]; +int gmlan_sending = -1; +int gmlan_sendmax = -1; + +int gmlan_silent_count = 0; +int gmlan_fail_count = 0; +#define REQUIRED_SILENT_TIME 10 +#define MAX_FAIL_COUNT 10 + +void TIM4_IRQHandler(void) { + if (gmlan_alt_mode == BITBANG) { + if (TIM4->SR & TIM_SR_UIF && gmlan_sendmax != -1) { + int read = get_gpio_input(GPIOB, 12); + if (gmlan_silent_count < REQUIRED_SILENT_TIME) { + if (read == 0) { + gmlan_silent_count = 0; + } else { + gmlan_silent_count++; + } + } else if (gmlan_silent_count == REQUIRED_SILENT_TIME) { + int retry = 0; + // in send loop + if (gmlan_sending > 0 && // not first bit + (read == 0 && pkt_stuffed[gmlan_sending-1] == 1) && // bus wrongly dominant + gmlan_sending != (gmlan_sendmax-11)) { //not ack bit + puts("GMLAN ERR: bus driven at "); + puth(gmlan_sending); + puts("\n"); + retry = 1; + } else if (read == 1 && gmlan_sending == (gmlan_sendmax-11)) { // recessive during ACK + puts("GMLAN ERR: didn't recv ACK\n"); + retry = 1; + } + if (retry) { + // reset sender (retry after 7 silent) + set_bitbanged_gmlan(1); // recessive + gmlan_silent_count = 0; + gmlan_sending = 0; + gmlan_fail_count++; + if (gmlan_fail_count == MAX_FAIL_COUNT) { + puts("GMLAN ERR: giving up send\n"); + } + } else { + set_bitbanged_gmlan(pkt_stuffed[gmlan_sending]); + gmlan_sending++; + } + } + if (gmlan_sending == gmlan_sendmax || gmlan_fail_count == MAX_FAIL_COUNT) { + set_bitbanged_gmlan(1); // recessive + set_gpio_mode(GPIOB, 13, MODE_INPUT); + TIM4->DIER = 0; // no update interrupt + TIM4->CR1 = 0; // disable timer + gmlan_sendmax = -1; // exit + } + } + TIM4->SR = 0; + } //bit bang mode + + else if (gmlan_alt_mode == GPIO_SWITCH) { + if (TIM4->SR & TIM_SR_UIF && gmlan_switch_below_timeout != -1) { + if (can_timeout_counter == 0 && gmlan_switch_timeout_enable) { + //it has been more than 1 second since timeout was reset; disable timer and restore the GMLAN output + set_gpio_output(GPIOB, 13, GMLAN_LOW); + gmlan_switch_below_timeout = -1; + gmlan_timeout_counter = GMLAN_TICKS_PER_TIMEOUT_TICKLE; + gmlan_alt_mode = DISABLED; + } + else { + can_timeout_counter--; + if (gmlan_timeout_counter == 0) { + //Send a 1 (bus low) every 15ms to reset the GMLAN transceivers timeout + gmlan_timeout_counter = GMLAN_TICKS_PER_TIMEOUT_TICKLE; + set_gpio_output(GPIOB, 13, GMLAN_LOW); + } + else { + set_gpio_output(GPIOB, 13, inverted_bit_to_send); + gmlan_timeout_counter--; + } + } + } + TIM4->SR = 0; + } //gmlan switch mode +} + +void bitbang_gmlan(CAN_FIFOMailBox_TypeDef *to_bang) { + gmlan_alt_mode = BITBANG; + // TODO: make failure less silent + if (gmlan_sendmax != -1) return; + + int len = get_bit_message(pkt_stuffed, to_bang); + gmlan_fail_count = 0; + gmlan_silent_count = 0; + gmlan_sending = 0; + gmlan_sendmax = len; + + // setup for bitbang loop + set_bitbanged_gmlan(1); // recessive + set_gpio_mode(GPIOB, 13, MODE_OUTPUT); + + setup_timer4(); +} + +#endif diff --git a/panda/board/drivers/llgpio.h b/panda/board/drivers/llgpio.h new file mode 100644 index 00000000000000..e1835ec0f40c91 --- /dev/null +++ b/panda/board/drivers/llgpio.h @@ -0,0 +1,35 @@ +void set_gpio_mode(GPIO_TypeDef *GPIO, int pin, int mode) { + uint32_t tmp = GPIO->MODER; + tmp &= ~(3 << (pin*2)); + tmp |= (mode << (pin*2)); + GPIO->MODER = tmp; +} + +void set_gpio_output(GPIO_TypeDef *GPIO, int pin, int val) { + if (val) { + GPIO->ODR |= (1 << pin); + } else { + GPIO->ODR &= ~(1 << pin); + } + set_gpio_mode(GPIO, pin, MODE_OUTPUT); +} + +void set_gpio_alternate(GPIO_TypeDef *GPIO, int pin, int mode) { + uint32_t tmp = GPIO->AFR[pin>>3]; + tmp &= ~(0xF << ((pin&7)*4)); + tmp |= mode << ((pin&7)*4); + GPIO->AFR[pin>>3] = tmp; + set_gpio_mode(GPIO, pin, MODE_ALTERNATE); +} + +void set_gpio_pullup(GPIO_TypeDef *GPIO, int pin, int mode) { + uint32_t tmp = GPIO->PUPDR; + tmp &= ~(3 << (pin*2)); + tmp |= (mode << (pin*2)); + GPIO->PUPDR = tmp; +} + +int get_gpio_input(GPIO_TypeDef *GPIO, int pin) { + return (GPIO->IDR & (1 << pin)) == (1 << pin); +} + diff --git a/panda/board/drivers/spi.h b/panda/board/drivers/spi.h new file mode 100644 index 00000000000000..7a5945d37257cb --- /dev/null +++ b/panda/board/drivers/spi.h @@ -0,0 +1,122 @@ +// IRQs: DMA2_Stream2, DMA2_Stream3, EXTI4 + +#define SPI_BUF_SIZE 256 +uint8_t spi_buf[SPI_BUF_SIZE]; +int spi_buf_count = 0; +int spi_total_count = 0; + +void spi_init() { + //puts("SPI init\n"); + SPI1->CR1 = SPI_CR1_SPE; + + // enable SPI interrupts + //SPI1->CR2 = SPI_CR2_RXNEIE | SPI_CR2_ERRIE | SPI_CR2_TXEIE; + SPI1->CR2 = SPI_CR2_RXNEIE; + + NVIC_EnableIRQ(DMA2_Stream2_IRQn); + NVIC_EnableIRQ(DMA2_Stream3_IRQn); + //NVIC_EnableIRQ(SPI1_IRQn); + + // reset handshake back to pull up + set_gpio_mode(GPIOB, 0, MODE_INPUT); + set_gpio_pullup(GPIOB, 0, PULL_UP); + + // setup interrupt on falling edge of SPI enable (on PA4) + SYSCFG->EXTICR[2] = SYSCFG_EXTICR2_EXTI4_PA; + EXTI->IMR = (1 << 4); + EXTI->FTSR = (1 << 4); + NVIC_EnableIRQ(EXTI4_IRQn); +} + +void spi_tx_dma(void *addr, int len) { + // disable DMA + SPI1->CR2 &= ~SPI_CR2_TXDMAEN; + DMA2_Stream3->CR &= ~DMA_SxCR_EN; + + // DMA2, stream 3, channel 3 + DMA2_Stream3->M0AR = (uint32_t)addr; + DMA2_Stream3->NDTR = len; + DMA2_Stream3->PAR = (uint32_t)&(SPI1->DR); + + // channel3, increment memory, memory -> periph, enable + DMA2_Stream3->CR = DMA_SxCR_CHSEL_1 | DMA_SxCR_CHSEL_0 | DMA_SxCR_MINC | DMA_SxCR_DIR_0 | DMA_SxCR_EN; + delay(0); + DMA2_Stream3->CR |= DMA_SxCR_TCIE; + + SPI1->CR2 |= SPI_CR2_TXDMAEN; + + // signal data is ready by driving low + // esp must be configured as input by this point + set_gpio_output(GPIOB, 0, 0); +} + +void spi_rx_dma(void *addr, int len) { + // disable DMA + SPI1->CR2 &= ~SPI_CR2_RXDMAEN; + DMA2_Stream2->CR &= ~DMA_SxCR_EN; + + // drain the bus + volatile uint8_t dat = SPI1->DR; + (void)dat; + + // DMA2, stream 2, channel 3 + DMA2_Stream2->M0AR = (uint32_t)addr; + DMA2_Stream2->NDTR = len; + DMA2_Stream2->PAR = (uint32_t)&(SPI1->DR); + + // channel3, increment memory, periph -> memory, enable + DMA2_Stream2->CR = DMA_SxCR_CHSEL_1 | DMA_SxCR_CHSEL_0 | DMA_SxCR_MINC | DMA_SxCR_EN; + delay(0); + DMA2_Stream2->CR |= DMA_SxCR_TCIE; + + SPI1->CR2 |= SPI_CR2_RXDMAEN; +} + +// ***************************** SPI IRQs ***************************** + +// can't go on the stack cause it's DMAed +uint8_t spi_tx_buf[0x44]; + +// SPI RX +void DMA2_Stream2_IRQHandler(void) { + int *resp_len = (int*)spi_tx_buf; + memset(spi_tx_buf, 0xaa, 0x44); + *resp_len = spi_cb_rx(spi_buf, 0x14, spi_tx_buf+4); + #ifdef DEBUG_SPI + puts("SPI write: "); + puth(*resp_len); + puts("\n"); + #endif + spi_tx_dma(spi_tx_buf, *resp_len + 4); + + // ack + DMA2->LIFCR = DMA_LIFCR_CTCIF2; +} + +// SPI TX +void DMA2_Stream3_IRQHandler(void) { + #ifdef DEBUG_SPI + puts("SPI handshake\n"); + #endif + + // reset handshake back to pull up + set_gpio_mode(GPIOB, 0, MODE_INPUT); + set_gpio_pullup(GPIOB, 0, PULL_UP); + + // ack + DMA2->LIFCR = DMA_LIFCR_CTCIF3; +} + +void EXTI4_IRQHandler(void) { + volatile int pr = EXTI->PR; + #ifdef DEBUG_SPI + puts("exti4\n"); + #endif + // SPI CS falling + if (pr & (1 << 4)) { + spi_total_count = 0; + spi_rx_dma(spi_buf, 0x14); + } + EXTI->PR = pr; +} + diff --git a/panda/board/drivers/timer.h b/panda/board/drivers/timer.h new file mode 100644 index 00000000000000..a14b619e4b81e3 --- /dev/null +++ b/panda/board/drivers/timer.h @@ -0,0 +1,7 @@ +void timer_init(TIM_TypeDef *TIM, int psc) { + TIM->PSC = psc-1; + TIM->DIER = TIM_DIER_UIE; + TIM->CR1 = TIM_CR1_CEN; + TIM->SR = 0; +} + diff --git a/panda/board/drivers/uart.h b/panda/board/drivers/uart.h new file mode 100644 index 00000000000000..5ca82888d4fe7a --- /dev/null +++ b/panda/board/drivers/uart.h @@ -0,0 +1,304 @@ +// IRQs: USART1, USART2, USART3, UART5 + +// ***************************** serial port queues ***************************** + +// esp = USART1 +uart_ring esp_ring = { .w_ptr_tx = 0, .r_ptr_tx = 0, + .w_ptr_rx = 0, .r_ptr_rx = 0, + .uart = USART1, + .callback = NULL}; + +// lin1, K-LINE = UART5 +// lin2, L-LINE = USART3 +uart_ring lin1_ring = { .w_ptr_tx = 0, .r_ptr_tx = 0, + .w_ptr_rx = 0, .r_ptr_rx = 0, + .uart = UART5, + .callback = NULL}; +uart_ring lin2_ring = { .w_ptr_tx = 0, .r_ptr_tx = 0, + .w_ptr_rx = 0, .r_ptr_rx = 0, + .uart = USART3, + .callback = NULL}; + +// debug = USART2 +void debug_ring_callback(uart_ring *ring); +uart_ring debug_ring = { .w_ptr_tx = 0, .r_ptr_tx = 0, + .w_ptr_rx = 0, .r_ptr_rx = 0, + .uart = USART2, + .callback = debug_ring_callback}; + + +uart_ring *get_ring_by_number(int a) { + switch(a) { + case 0: + return &debug_ring; + case 1: + return &esp_ring; + case 2: + return &lin1_ring; + case 3: + return &lin2_ring; + default: + return NULL; + } +} + +// ***************************** serial port ***************************** + +void uart_ring_process(uart_ring *q) { + enter_critical_section(); + // TODO: check if external serial is connected + int sr = q->uart->SR; + + if (q->w_ptr_tx != q->r_ptr_tx) { + if (sr & USART_SR_TXE) { + q->uart->DR = q->elems_tx[q->r_ptr_tx]; + q->r_ptr_tx = (q->r_ptr_tx + 1) % FIFO_SIZE; + } else { + // push on interrupt later + q->uart->CR1 |= USART_CR1_TXEIE; + } + } else { + // nothing to send + q->uart->CR1 &= ~USART_CR1_TXEIE; + } + + if (sr & USART_SR_RXNE || sr & USART_SR_ORE) { + uint8_t c = q->uart->DR; // TODO: can drop packets + if (q != &esp_ring) { + uint16_t next_w_ptr = (q->w_ptr_rx + 1) % FIFO_SIZE; + if (next_w_ptr != q->r_ptr_rx) { + q->elems_rx[q->w_ptr_rx] = c; + q->w_ptr_rx = next_w_ptr; + if (q->callback) q->callback(q); + } + } + } + + if (sr & USART_SR_ORE) { + // set dropped packet flag? + } + + exit_critical_section(); +} + +// interrupt boilerplate + +void USART1_IRQHandler(void) { uart_ring_process(&esp_ring); } +void USART2_IRQHandler(void) { uart_ring_process(&debug_ring); } +void USART3_IRQHandler(void) { uart_ring_process(&lin2_ring); } +void UART5_IRQHandler(void) { uart_ring_process(&lin1_ring); } + +int getc(uart_ring *q, char *elem) { + int ret = 0; + + enter_critical_section(); + if (q->w_ptr_rx != q->r_ptr_rx) { + *elem = q->elems_rx[q->r_ptr_rx]; + q->r_ptr_rx = (q->r_ptr_rx + 1) % FIFO_SIZE; + ret = 1; + } + exit_critical_section(); + + return ret; +} + +int injectc(uart_ring *q, char elem) { + int ret = 0; + uint16_t next_w_ptr; + + enter_critical_section(); + next_w_ptr = (q->w_ptr_rx + 1) % FIFO_SIZE; + if (next_w_ptr != q->r_ptr_rx) { + q->elems_rx[q->w_ptr_rx] = elem; + q->w_ptr_rx = next_w_ptr; + ret = 1; + } + exit_critical_section(); + + return ret; +} + +int putc(uart_ring *q, char elem) { + int ret = 0; + uint16_t next_w_ptr; + + enter_critical_section(); + next_w_ptr = (q->w_ptr_tx + 1) % FIFO_SIZE; + if (next_w_ptr != q->r_ptr_tx) { + q->elems_tx[q->w_ptr_tx] = elem; + q->w_ptr_tx = next_w_ptr; + ret = 1; + } + exit_critical_section(); + + uart_ring_process(q); + + return ret; +} + +void clear_uart_buff(uart_ring *q) { + enter_critical_section(); + q->w_ptr_tx = 0; + q->r_ptr_tx = 0; + q->w_ptr_rx = 0; + q->r_ptr_rx = 0; + exit_critical_section(); +} + +// ***************************** start UART code ***************************** + +#define __DIV(_PCLK_, _BAUD_) (((_PCLK_)*25)/(4*(_BAUD_))) +#define __DIVMANT(_PCLK_, _BAUD_) (__DIV((_PCLK_), (_BAUD_))/100) +#define __DIVFRAQ(_PCLK_, _BAUD_) (((__DIV((_PCLK_), (_BAUD_)) - (__DIVMANT((_PCLK_), (_BAUD_)) * 100)) * 16 + 50) / 100) +#define __USART_BRR(_PCLK_, _BAUD_) ((__DIVMANT((_PCLK_), (_BAUD_)) << 4)|(__DIVFRAQ((_PCLK_), (_BAUD_)) & 0x0F)) + +void uart_set_baud(USART_TypeDef *u, int baud) { + if (u == USART1) { + // USART1 is on APB2 + u->BRR = __USART_BRR(48000000, baud); + } else { + u->BRR = __USART_BRR(24000000, baud); + } +} + +#define USART1_DMA_LEN 0x20 +char usart1_dma[USART1_DMA_LEN]; + +void uart_dma_drain() { + uart_ring *q = &esp_ring; + + enter_critical_section(); + + if (DMA2->HISR & DMA_HISR_TCIF5 || DMA2->HISR & DMA_HISR_HTIF5 || DMA2_Stream5->NDTR != USART1_DMA_LEN) { + // disable DMA + q->uart->CR3 &= ~USART_CR3_DMAR; + DMA2_Stream5->CR &= ~DMA_SxCR_EN; + while (DMA2_Stream5->CR & DMA_SxCR_EN); + + int i; + for (i = 0; i < USART1_DMA_LEN - DMA2_Stream5->NDTR; i++) { + char c = usart1_dma[i]; + uint16_t next_w_ptr = (q->w_ptr_rx + 1) % FIFO_SIZE; + if (next_w_ptr != q->r_ptr_rx) { + q->elems_rx[q->w_ptr_rx] = c; + q->w_ptr_rx = next_w_ptr; + } + } + + // reset DMA len + DMA2_Stream5->NDTR = USART1_DMA_LEN; + + // clear interrupts + DMA2->HIFCR = DMA_HIFCR_CTCIF5 | DMA_HIFCR_CHTIF5; + //DMA2->HIFCR = DMA_HIFCR_CTEIF5 | DMA_HIFCR_CDMEIF5 | DMA_HIFCR_CFEIF5; + + // enable DMA + DMA2_Stream5->CR |= DMA_SxCR_EN; + q->uart->CR3 |= USART_CR3_DMAR; + } + + exit_critical_section(); +} + +void DMA2_Stream5_IRQHandler(void) { + //set_led(LED_BLUE, 1); + uart_dma_drain(); + //set_led(LED_BLUE, 0); +} + +void uart_init(USART_TypeDef *u, int baud) { + // enable uart and tx+rx mode + u->CR1 = USART_CR1_UE; + uart_set_baud(u, baud); + + u->CR1 |= USART_CR1_TE | USART_CR1_RE; + //u->CR2 = USART_CR2_STOP_0 | USART_CR2_STOP_1; + //u->CR2 = USART_CR2_STOP_0; + // ** UART is ready to work ** + + // enable interrupts + if (u != USART1) { + u->CR1 |= USART_CR1_RXNEIE; + } + + if (u == USART1) { + // DMA2, stream 2, channel 3 + DMA2_Stream5->M0AR = (uint32_t)usart1_dma; + DMA2_Stream5->NDTR = USART1_DMA_LEN; + DMA2_Stream5->PAR = (uint32_t)&(USART1->DR); + + // channel4, increment memory, periph -> memory, enable + DMA2_Stream5->CR = DMA_SxCR_CHSEL_2 | DMA_SxCR_MINC | DMA_SxCR_HTIE | DMA_SxCR_TCIE | DMA_SxCR_EN; + + // this one uses DMA receiver + u->CR3 = USART_CR3_DMAR; + + NVIC_EnableIRQ(DMA2_Stream5_IRQn); + NVIC_EnableIRQ(USART1_IRQn); + } else if (u == USART2) { + NVIC_EnableIRQ(USART2_IRQn); + } else if (u == USART3) { + NVIC_EnableIRQ(USART3_IRQn); + } else if (u == UART5) { + NVIC_EnableIRQ(UART5_IRQn); + } +} + +void putch(const char a) { + if (has_external_debug_serial) { + /*while ((debug_ring.uart->SR & USART_SR_TXE) == 0); + debug_ring.uart->DR = a;*/ + + // assuming debugging is important if there's external serial connected + while (!putc(&debug_ring, a)); + + //putc(&debug_ring, a); + } else { + injectc(&debug_ring, a); + } +} + +int puts(const char *a) { + for (;*a;a++) { + if (*a == '\n') putch('\r'); + putch(*a); + } + return 0; +} + +void putui(uint32_t i) { + char str[11]; + uint8_t idx = 10; + str[idx--] = '\0'; + do { + str[idx--] = (i % 10) + 0x30; + i /= 10; + } while (i); + puts(str + idx + 1); +} + +void puth(unsigned int i) { + int pos; + char c[] = "0123456789abcdef"; + for (pos = 28; pos != -4; pos -= 4) { + putch(c[(i >> pos) & 0xF]); + } +} + +void puth2(unsigned int i) { + int pos; + char c[] = "0123456789abcdef"; + for (pos = 4; pos != -4; pos -= 4) { + putch(c[(i >> pos) & 0xF]); + } +} + +void hexdump(const void *a, int l) { + int i; + for (i=0;i>8)&0xFF) + +// take in string length and return the first 2 bytes of a string descriptor +#define STRING_DESCRIPTOR_HEADER(size)\ + (((size * 2 + 2)&0xFF) | 0x0300) + +uint8_t device_desc[] = { + DSCR_DEVICE_LEN, USB_DESC_TYPE_DEVICE, //Length, Type + 0x10, 0x02, // bcdUSB max version of USB supported (2.1) + 0xFF, 0xFF, 0xFF, 0x40, // Class, Subclass, Protocol, Max Packet Size + TOUSBORDER(USB_VID), // idVendor + TOUSBORDER(USB_PID), // idProduct +#ifdef STM32F4 + 0x00, 0x23, // bcdDevice +#else + 0x00, 0x22, // bcdDevice +#endif + 0x01, 0x02, // Manufacturer, Product + 0x03, 0x01 // Serial Number, Num Configurations +}; + +uint8_t device_qualifier[] = { + 0x0a, USB_DESC_TYPE_DEVICE_QUALIFIER, //Length, Type + 0x10, 0x02, // bcdUSB max version of USB supported (2.1) + 0xFF, 0xFF, 0xFF, 0x40, // bDeviceClass, bDeviceSubClass, bDeviceProtocol, bMaxPacketSize0 + 0x01, 0x00 // bNumConfigurations, bReserved +}; + +#define ENDPOINT_RCV 0x80 +#define ENDPOINT_SND 0x00 + +uint8_t configuration_desc[] = { + DSCR_CONFIG_LEN, USB_DESC_TYPE_CONFIGURATION, // Length, Type, + TOUSBORDER(0x0045), // Total Len (uint16) + 0x01, 0x01, STRING_OFFSET_ICONFIGURATION, // Num Interface, Config Value, Configuration + 0xc0, 0x32, // Attributes, Max Power + // interface 0 ALT 0 + DSCR_INTERFACE_LEN, USB_DESC_TYPE_INTERFACE, // Length, Type + 0x00, 0x00, 0x03, // Index, Alt Index idx, Endpoint count + 0XFF, 0xFF, 0xFF, // Class, Subclass, Protocol + 0x00, // Interface + // endpoint 1, read CAN + DSCR_ENDPOINT_LEN, USB_DESC_TYPE_ENDPOINT, // Length, Type + ENDPOINT_RCV | 1, ENDPOINT_TYPE_BULK, // Endpoint Num/Direction, Type + TOUSBORDER(0x0040), // Max Packet (0x0040) + 0x00, // Polling Interval (NA) + // endpoint 2, send serial + DSCR_ENDPOINT_LEN, USB_DESC_TYPE_ENDPOINT, // Length, Type + ENDPOINT_SND | 2, ENDPOINT_TYPE_BULK, // Endpoint Num/Direction, Type + TOUSBORDER(0x0040), // Max Packet (0x0040) + 0x00, // Polling Interval + // endpoint 3, send CAN + DSCR_ENDPOINT_LEN, USB_DESC_TYPE_ENDPOINT, // Length, Type + ENDPOINT_SND | 3, ENDPOINT_TYPE_BULK, // Endpoint Num/Direction, Type + TOUSBORDER(0x0040), // Max Packet (0x0040) + 0x00, // Polling Interval + // interface 0 ALT 1 + DSCR_INTERFACE_LEN, USB_DESC_TYPE_INTERFACE, // Length, Type + 0x00, 0x01, 0x03, // Index, Alt Index idx, Endpoint count + 0XFF, 0xFF, 0xFF, // Class, Subclass, Protocol + 0x00, // Interface + // endpoint 1, read CAN + DSCR_ENDPOINT_LEN, USB_DESC_TYPE_ENDPOINT, // Length, Type + ENDPOINT_RCV | 1, ENDPOINT_TYPE_INT, // Endpoint Num/Direction, Type + TOUSBORDER(0x0040), // Max Packet (0x0040) + 0x05, // Polling Interval (5 frames) + // endpoint 2, send serial + DSCR_ENDPOINT_LEN, USB_DESC_TYPE_ENDPOINT, // Length, Type + ENDPOINT_SND | 2, ENDPOINT_TYPE_BULK, // Endpoint Num/Direction, Type + TOUSBORDER(0x0040), // Max Packet (0x0040) + 0x00, // Polling Interval + // endpoint 3, send CAN + DSCR_ENDPOINT_LEN, USB_DESC_TYPE_ENDPOINT, // Length, Type + ENDPOINT_SND | 3, ENDPOINT_TYPE_BULK, // Endpoint Num/Direction, Type + TOUSBORDER(0x0040), // Max Packet (0x0040) + 0x00, // Polling Interval +}; + +// STRING_DESCRIPTOR_HEADER is for uint16 string descriptors +// it takes in a string length, which is bytes/2 because unicode +uint16_t string_language_desc[] = { + STRING_DESCRIPTOR_HEADER(1), + 0x0409 // american english +}; + +// these strings are all uint16's so that we don't need to spam ,0 after every character +uint16_t string_manufacturer_desc[] = { + STRING_DESCRIPTOR_HEADER(8), + 'c', 'o', 'm', 'm', 'a', '.', 'a', 'i' +}; + +#ifdef PANDA +uint16_t string_product_desc[] = { + STRING_DESCRIPTOR_HEADER(5), + 'p', 'a', 'n', 'd', 'a' +}; +#else +uint16_t string_product_desc[] = { + STRING_DESCRIPTOR_HEADER(5), + 'N', 'E', 'O', 'v', '1' +}; +#endif + +// default serial number when we're not a panda +uint16_t string_serial_desc[] = { + STRING_DESCRIPTOR_HEADER(4), + 'n', 'o', 'n', 'e' +}; + +// a string containing the default configuration index +uint16_t string_configuration_desc[] = { + STRING_DESCRIPTOR_HEADER(2), + '0', '1' // "01" +}; + +#ifdef PANDA +// WCID (auto install WinUSB driver) +// https://github.com/pbatard/libwdi/wiki/WCID-Devices +// https://docs.microsoft.com/en-us/windows-hardware/drivers/usbcon/winusb-installation#automatic-installation-of--winusb-without-an-inf-file +// WinUSB 1.0 descriptors, this is mostly used by Windows XP +uint8_t string_238_desc[] = { + 0x12, USB_DESC_TYPE_STRING, // bLength, bDescriptorType + 'M',0, 'S',0, 'F',0, 'T',0, '1',0, '0',0, '0',0, // qwSignature (MSFT100) + MS_VENDOR_CODE, 0x00 // bMS_VendorCode, bPad +}; +uint8_t winusb_ext_compatid_os_desc[] = { + 0x28, 0x00, 0x00, 0x00, // dwLength + 0x00, 0x01, // bcdVersion + 0x04, 0x00, // wIndex + 0x01, // bCount + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // Reserved + 0x00, // bFirstInterfaceNumber + 0x00, // Reserved + 'W', 'I', 'N', 'U', 'S', 'B', 0x00, 0x00, // compatible ID (WINUSB) + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // subcompatible ID (none) + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 // Reserved +}; +uint8_t winusb_ext_prop_os_desc[] = { + 0x8e, 0x00, 0x00, 0x00, // dwLength + 0x00, 0x01, // bcdVersion + 0x05, 0x00, // wIndex + 0x01, 0x00, // wCount + // first property + 0x84, 0x00, 0x00, 0x00, // dwSize + 0x01, 0x00, 0x00, 0x00, // dwPropertyDataType + 0x28, 0x00, // wPropertyNameLength + 'D',0, 'e',0, 'v',0, 'i',0, 'c',0, 'e',0, 'I',0, 'n',0, 't',0, 'e',0, 'r',0, 'f',0, 'a',0, 'c',0, 'e',0, 'G',0, 'U',0, 'I',0, 'D',0, 0, 0, // bPropertyName (DeviceInterfaceGUID) + 0x4e, 0x00, 0x00, 0x00, // dwPropertyDataLength + '{',0, 'c',0, 'c',0, 'e',0, '5',0, '2',0, '9',0, '1',0, 'c',0, '-',0, 'a',0, '6',0, '9',0, 'f',0, '-',0, '4',0 ,'9',0 ,'9',0 ,'5',0 ,'-',0, 'a',0, '4',0, 'c',0, '2',0, '-',0, '2',0, 'a',0, 'e',0, '5',0, '7',0, 'a',0, '5',0, '1',0, 'a',0, 'd',0, 'e',0, '9',0, '}',0, 0, 0, // bPropertyData ({CCE5291C-A69F-4995-A4C2-2AE57A51ADE9}) +}; + +/* +Binary Object Store descriptor used to expose WebUSB (and more WinUSB) metadata +comments are from the wicg spec +References used: + https://wicg.github.io/webusb/#webusb-platform-capability-descriptor + https://github.com/sowbug/weblight/blob/192ad7a0e903542e2aa28c607d98254a12a6399d/firmware/webusb.c + https://os.mbed.com/users/larsgk/code/USBDevice_WebUSB/file/1d8a6665d607/WebUSBDevice/ + +*/ +uint8_t binary_object_store_desc[] = { + // BOS header + BINARY_OBJECT_STORE_DESCRIPTOR_LENGTH, // bLength, this is only the length of the header + BINARY_OBJECT_STORE_DESCRIPTOR, // bDescriptorType + 0x40, 0x00, // wTotalLength (LSB, MSB) + 0x03, // bNumDeviceCaps (USB 2.0 + WebUSB + WinUSB) + + // ------------------------------------------------- + // USB 2.0 extension descriptor + 0x07, // bLength, Descriptor size + 0x10, // bDescriptorType, Device Capability Descriptor Type + 0x02, // bDevCapabilityType, USB 2.0 extension capability type + 0x00, 0x00, 0x00, 0x00, // bmAttributes, LIBUSB_BM_LPM_SUPPORT = 2 and its the only option + + // ------------------------------------------------- + // WebUSB descriptor + // header + 0x18, // bLength, Size of this descriptor. Must be set to 24. + 0x10, // bDescriptorType, DEVICE CAPABILITY descriptor + 0x05, // bDevCapabilityType, PLATFORM capability + 0x00, // bReserved, This field is reserved and shall be set to zero. + + // PlatformCapabilityUUID, Must be set to {3408b638-09a9-47a0-8bfd-a0768815b665}. + 0x38, 0xB6, 0x08, 0x34, + 0xA9, 0x09, 0xA0, 0x47, + 0x8B, 0xFD, 0xA0, 0x76, + 0x88, 0x15, 0xB6, 0x65, + // + + 0x00, 0x01, // bcdVersion, Protocol version supported. Must be set to 0x0100. + WEBUSB_VENDOR_CODE, // bVendorCode, bRequest value used for issuing WebUSB requests. + // there used to be a concept of "allowed origins", but it was removed from the spec + // it was intended to be a security feature, but then the entire security model relies on domain ownership + // https://github.com/WICG/webusb/issues/49 + // other implementations use various other indexed to leverate this no-longer-valid feature. we wont. + // the spec says we *must* reply to index 0x03 with the url, so we'll hint that that's the right index + 0x03, // iLandingPage, URL descriptor index of the device’s landing page. + + // ------------------------------------------------- + // WinUSB descriptor + // header + 0x1C, // Descriptor size (28 bytes) + 0x10, // Descriptor type (Device Capability) + 0x05, // Capability type (Platform) + 0x00, // Reserved + + // MS OS 2.0 Platform Capability ID (D8DD60DF-4589-4CC7-9CD2-659D9E648A9F) + // Indicates the device supports the Microsoft OS 2.0 descriptor + 0xDF, 0x60, 0xDD, 0xD8, + 0x89, 0x45, 0xC7, 0x4C, + 0x9C, 0xD2, 0x65, 0x9D, + 0x9E, 0x64, 0x8A, 0x9F, + + 0x00, 0x00, 0x03, 0x06, // Windows version, currently set to 8.1 (0x06030000) + + WINUSB_PLATFORM_DESCRIPTOR_LENGTH, 0x00, // MS OS 2.0 descriptor size (word) + MS_VENDOR_CODE, 0x00 // vendor code, no alternate enumeration +}; + +uint8_t webusb_url_descriptor[] = { + 0x14, /* bLength */ + WEBUSB_DESC_TYPE_URL, // bDescriptorType + WEBUSB_URL_SCHEME_HTTPS, // bScheme + 'u', 's', 'b', 'p', 'a', 'n', 'd', 'a', '.', 'c', 'o', 'm', 'm', 'a', '.', 'a', 'i' +}; + +// WinUSB 2.0 descriptor. This is what modern systems use +// https://github.com/sowbug/weblight/blob/192ad7a0e903542e2aa28c607d98254a12a6399d/firmware/webusb.c +// http://janaxelson.com/files/ms_os_20_descriptors.c +// https://books.google.com/books?id=pkefBgAAQBAJ&pg=PA353&lpg=PA353 +uint8_t winusb_20_desc[WINUSB_PLATFORM_DESCRIPTOR_LENGTH] = { + // Microsoft OS 2.0 descriptor set header (table 10) + 0x0A, 0x00, // Descriptor size (10 bytes) + 0x00, 0x00, // MS OS 2.0 descriptor set header + + 0x00, 0x00, 0x03, 0x06, // Windows version (8.1) (0x06030000) + WINUSB_PLATFORM_DESCRIPTOR_LENGTH, 0x00, // Total size of MS OS 2.0 descriptor set + + // Microsoft OS 2.0 compatible ID descriptor + 0x14, 0x00, // Descriptor size (20 bytes) + 0x03, 0x00, // MS OS 2.0 compatible ID descriptor + 'W', 'I', 'N', 'U', 'S', 'B', 0x00, 0x00, // compatible ID (WINUSB) + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // Sub-compatible ID + + // Registry property descriptor + 0x80, 0x00, // Descriptor size (130 bytes) + 0x04, 0x00, // Registry Property descriptor + 0x01, 0x00, // Strings are null-terminated Unicode + 0x28, 0x00, // Size of Property Name (40 bytes) "DeviceInterfaceGUID" + + // bPropertyName (DeviceInterfaceGUID) + 'D', 0x00, 'e', 0x00, 'v', 0x00, 'i', 0x00, 'c', 0x00, 'e', 0x00, 'I', 0x00, 'n', 0x00, + 't', 0x00, 'e', 0x00, 'r', 0x00, 'f', 0x00, 'a', 0x00, 'c', 0x00, 'e', 0x00, 'G', 0x00, + 'U', 0x00, 'I', 0x00, 'D', 0x00, 0x00, 0x00, + + 0x4E, 0x00, // Size of Property Data (78 bytes) + + // Vendor-defined property data: {CCE5291C-A69F-4995-A4C2-2AE57A51ADE9} + '{', 0x00, 'c', 0x00, 'c', 0x00, 'e', 0x00, '5', 0x00, '2', 0x00, '9', 0x00, '1', 0x00, // 16 + 'c', 0x00, '-', 0x00, 'a', 0x00, '6', 0x00, '9', 0x00, 'f', 0x00, '-', 0x00, '4', 0x00, // 32 + '9', 0x00, '9', 0x00, '5', 0x00, '-', 0x00, 'a', 0x00, '4', 0x00, 'c', 0x00, '2', 0x00, // 48 + '-', 0x00, '2', 0x00, 'a', 0x00, 'e', 0x00, '5', 0x00, '7', 0x00, 'a', 0x00, '5', 0x00, // 64 + '1', 0x00, 'a', 0x00, 'd', 0x00, 'e', 0x00, '9', 0x00, '}', 0x00, 0x00, 0x00 // 78 bytes +}; + +#endif + +// current packet +USB_Setup_TypeDef setup; +uint8_t usbdata[0x100]; +uint8_t* ep0_txdata = NULL; +uint16_t ep0_txlen = 0; + +// Store the current interface alt setting. +int current_int0_alt_setting = 0; + +// packet read and write + +void *USB_ReadPacket(void *dest, uint16_t len) { + uint32_t i=0; + uint32_t count32b = (len + 3) / 4; + + for ( i = 0; i < count32b; i++, dest += 4 ) { + // packed? + *(__attribute__((__packed__)) uint32_t *)dest = USBx_DFIFO(0); + } + return ((void *)dest); +} + +void USB_WritePacket(const uint8_t *src, uint16_t len, uint32_t ep) { + #ifdef DEBUG_USB + puts("writing "); + hexdump(src, len); + #endif + + uint8_t numpacket = (len+(MAX_RESP_LEN-1))/MAX_RESP_LEN; + uint32_t count32b = 0, i = 0; + count32b = (len + 3) / 4; + + // bullshit + USBx_INEP(ep)->DIEPTSIZ = ((numpacket << 19) & USB_OTG_DIEPTSIZ_PKTCNT) | + (len & USB_OTG_DIEPTSIZ_XFRSIZ); + USBx_INEP(ep)->DIEPCTL |= (USB_OTG_DIEPCTL_CNAK | USB_OTG_DIEPCTL_EPENA); + + // load the FIFO + for (i = 0; i < count32b; i++, src += 4) { + USBx_DFIFO(ep) = *((__attribute__((__packed__)) uint32_t *)src); + } +} + +// IN EP 0 TX FIFO has a max size of 127 bytes (much smaller than the rest) +// so use TX FIFO empty interrupt to send larger amounts of data +void USB_WritePacket_EP0(uint8_t *src, uint16_t len) { + #ifdef DEBUG_USB + puts("writing "); + hexdump(src, len); + #endif + + uint16_t wplen = min(len, 0x40); + USB_WritePacket(src, wplen, 0); + + if (wplen < len) { + ep0_txdata = src + wplen; + ep0_txlen = len - wplen; + USBx_DEVICE->DIEPEMPMSK |= 1; + } else { + USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK; + } +} + +void usb_reset() { + // unmask endpoint interrupts, so many sets + USBx_DEVICE->DAINT = 0xFFFFFFFF; + USBx_DEVICE->DAINTMSK = 0xFFFFFFFF; + //USBx_DEVICE->DOEPMSK = (USB_OTG_DOEPMSK_STUPM | USB_OTG_DOEPMSK_XFRCM | USB_OTG_DOEPMSK_EPDM); + //USBx_DEVICE->DIEPMSK = (USB_OTG_DIEPMSK_TOM | USB_OTG_DIEPMSK_XFRCM | USB_OTG_DIEPMSK_EPDM | USB_OTG_DIEPMSK_ITTXFEMSK); + //USBx_DEVICE->DIEPMSK = (USB_OTG_DIEPMSK_TOM | USB_OTG_DIEPMSK_XFRCM | USB_OTG_DIEPMSK_EPDM); + + // all interrupts for debugging + USBx_DEVICE->DIEPMSK = 0xFFFFFFFF; + USBx_DEVICE->DOEPMSK = 0xFFFFFFFF; + + // clear interrupts + USBx_INEP(0)->DIEPINT = 0xFF; + USBx_OUTEP(0)->DOEPINT = 0xFF; + + // unset the address + USBx_DEVICE->DCFG &= ~USB_OTG_DCFG_DAD; + + // set up USB FIFOs + // RX start address is fixed to 0 + USBx->GRXFSIZ = 0x40; + + // 0x100 to offset past GRXFSIZ + USBx->DIEPTXF0_HNPTXFSIZ = (0x40 << 16) | 0x40; + + // EP1, massive + USBx->DIEPTXF[0] = (0x40 << 16) | 0x80; + + // flush TX fifo + USBx->GRSTCTL = USB_OTG_GRSTCTL_TXFFLSH | USB_OTG_GRSTCTL_TXFNUM_4; + while ((USBx->GRSTCTL & USB_OTG_GRSTCTL_TXFFLSH) == USB_OTG_GRSTCTL_TXFFLSH); + // flush RX FIFO + USBx->GRSTCTL = USB_OTG_GRSTCTL_RXFFLSH; + while ((USBx->GRSTCTL & USB_OTG_GRSTCTL_RXFFLSH) == USB_OTG_GRSTCTL_RXFFLSH); + + // no global NAK + USBx_DEVICE->DCTL |= USB_OTG_DCTL_CGINAK; + + // ready to receive setup packets + USBx_OUTEP(0)->DOEPTSIZ = USB_OTG_DOEPTSIZ_STUPCNT | (USB_OTG_DOEPTSIZ_PKTCNT & (1 << 19)) | (3 * 8); +} + +char to_hex_char(int a) { + if (a < 10) { + return '0' + a; + } else { + return 'a' + (a-10); + } +} + +void usb_setup() { + int resp_len; + // setup packet is ready + switch (setup.b.bRequest) { + case USB_REQ_SET_CONFIGURATION: + // enable other endpoints, has to be here? + USBx_INEP(1)->DIEPCTL = (0x40 & USB_OTG_DIEPCTL_MPSIZ) | (2 << 18) | (1 << 22) | + USB_OTG_DIEPCTL_SD0PID_SEVNFRM | USB_OTG_DIEPCTL_USBAEP; + USBx_INEP(1)->DIEPINT = 0xFF; + + USBx_OUTEP(2)->DOEPTSIZ = (1 << 19) | 0x40; + USBx_OUTEP(2)->DOEPCTL = (0x40 & USB_OTG_DOEPCTL_MPSIZ) | (2 << 18) | + USB_OTG_DOEPCTL_SD0PID_SEVNFRM | USB_OTG_DOEPCTL_USBAEP; + USBx_OUTEP(2)->DOEPINT = 0xFF; + + USBx_OUTEP(3)->DOEPTSIZ = (1 << 19) | 0x40; + USBx_OUTEP(3)->DOEPCTL = (0x40 & USB_OTG_DOEPCTL_MPSIZ) | (2 << 18) | + USB_OTG_DOEPCTL_SD0PID_SEVNFRM | USB_OTG_DOEPCTL_USBAEP; + USBx_OUTEP(3)->DOEPINT = 0xFF; + + // mark ready to receive + USBx_OUTEP(2)->DOEPCTL |= USB_OTG_DOEPCTL_EPENA | USB_OTG_DOEPCTL_CNAK; + USBx_OUTEP(3)->DOEPCTL |= USB_OTG_DOEPCTL_EPENA | USB_OTG_DOEPCTL_CNAK; + + USB_WritePacket(0, 0, 0); + USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK; + break; + case USB_REQ_SET_ADDRESS: + // set now? + USBx_DEVICE->DCFG |= ((setup.b.wValue.w & 0x7f) << 4); + + #ifdef DEBUG_USB + puts(" set address\n"); + #endif + + // TODO: this isn't enumeration complete + // moved here to work better on OS X + usb_cb_enumeration_complete(); + + USB_WritePacket(0, 0, 0); + USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK; + + break; + case USB_REQ_GET_DESCRIPTOR: + switch (setup.b.wValue.bw.lsb) { + case USB_DESC_TYPE_DEVICE: + //puts(" writing device descriptor\n"); + + // setup transfer + USB_WritePacket(device_desc, min(sizeof(device_desc), setup.b.wLength.w), 0); + USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK; + + //puts("D"); + break; + case USB_DESC_TYPE_CONFIGURATION: + USB_WritePacket(configuration_desc, min(sizeof(configuration_desc), setup.b.wLength.w), 0); + USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK; + break; + case USB_DESC_TYPE_DEVICE_QUALIFIER: + USB_WritePacket(device_qualifier, min(sizeof(device_qualifier), setup.b.wLength.w), 0); + USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK; + break; + case USB_DESC_TYPE_STRING: + switch (setup.b.wValue.bw.msb) { + case STRING_OFFSET_LANGID: + USB_WritePacket((uint8_t*)string_language_desc, min(sizeof(string_language_desc), setup.b.wLength.w), 0); + break; + case STRING_OFFSET_IMANUFACTURER: + USB_WritePacket((uint8_t*)string_manufacturer_desc, min(sizeof(string_manufacturer_desc), setup.b.wLength.w), 0); + break; + case STRING_OFFSET_IPRODUCT: + USB_WritePacket((uint8_t*)string_product_desc, min(sizeof(string_product_desc), setup.b.wLength.w), 0); + break; + case STRING_OFFSET_ISERIAL: + #ifdef PANDA + resp[0] = 0x02 + 12*4; + resp[1] = 0x03; + + // 96 bits = 12 bytes + for (int i = 0; i < 12; i++){ + uint8_t cc = ((uint8_t *)UID_BASE)[i]; + resp[2 + i*4 + 0] = to_hex_char((cc>>4)&0xF); + resp[2 + i*4 + 1] = '\0'; + resp[2 + i*4 + 2] = to_hex_char((cc>>0)&0xF); + resp[2 + i*4 + 3] = '\0'; + } + + USB_WritePacket(resp, min(resp[0], setup.b.wLength.w), 0); + #else + USB_WritePacket((const uint8_t *)string_serial_desc, min(sizeof(string_serial_desc), setup.b.wLength.w), 0); + #endif + break; + #ifdef PANDA + case STRING_OFFSET_ICONFIGURATION: + USB_WritePacket((uint8_t*)string_configuration_desc, min(sizeof(string_configuration_desc), setup.b.wLength.w), 0); + break; + case 238: + USB_WritePacket((uint8_t*)string_238_desc, min(sizeof(string_238_desc), setup.b.wLength.w), 0); + break; + #endif + default: + // nothing + USB_WritePacket(0, 0, 0); + break; + } + USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK; + break; + #ifdef PANDA + case USB_DESC_TYPE_BINARY_OBJECT_STORE: + USB_WritePacket(binary_object_store_desc, min(sizeof(binary_object_store_desc), setup.b.wLength.w), 0); + USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK; + break; + #endif + default: + // nothing here? + USB_WritePacket(0, 0, 0); + USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK; + break; + } + break; + case USB_REQ_GET_STATUS: + // empty resp? + resp[0] = 0; + resp[1] = 0; + USB_WritePacket((void*)&resp, 2, 0); + USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK; + break; + case USB_REQ_SET_INTERFACE: + // Store the alt setting number for IN EP behavior. + current_int0_alt_setting = setup.b.wValue.w; + USB_WritePacket(0, 0, 0); + USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK; + break; + #ifdef PANDA + case WEBUSB_VENDOR_CODE: + switch (setup.b.wIndex.w) { + case WEBUSB_REQ_GET_URL: + USB_WritePacket(webusb_url_descriptor, min(sizeof(webusb_url_descriptor), setup.b.wLength.w), 0); + USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK; + break; + default: + // probably asking for allowed origins, which was removed from the spec + USB_WritePacket(0, 0, 0); + USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK; + break; + } + break; + case MS_VENDOR_CODE: + switch (setup.b.wIndex.w) { + // winusb 2.0 descriptor from BOS + case WINUSB_REQ_GET_DESCRIPTOR: + USB_WritePacket_EP0((uint8_t*)winusb_20_desc, min(sizeof(winusb_20_desc), setup.b.wLength.w)); + break; + // Extended Compat ID OS Descriptor + case WINUSB_REQ_GET_COMPATID_DESCRIPTOR: + USB_WritePacket_EP0((uint8_t*)winusb_ext_compatid_os_desc, min(sizeof(winusb_ext_compatid_os_desc), setup.b.wLength.w)); + break; + // Extended Properties OS Descriptor + case WINUSB_REQ_GET_EXT_PROPS_OS: + USB_WritePacket_EP0((uint8_t*)winusb_ext_prop_os_desc, min(sizeof(winusb_ext_prop_os_desc), setup.b.wLength.w)); + break; + default: + USB_WritePacket_EP0(0, 0); + } + break; + #endif + default: + resp_len = usb_cb_control_msg(&setup, resp, 1); + USB_WritePacket(resp, min(resp_len, setup.b.wLength.w), 0); + USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK; + } +} + +void usb_init() { + // full speed PHY, do reset and remove power down + /*puth(USBx->GRSTCTL); + puts(" resetting PHY\n");*/ + while ((USBx->GRSTCTL & USB_OTG_GRSTCTL_AHBIDL) == 0); + //puts("AHB idle\n"); + + // reset PHY here + USBx->GRSTCTL |= USB_OTG_GRSTCTL_CSRST; + while ((USBx->GRSTCTL & USB_OTG_GRSTCTL_CSRST) == USB_OTG_GRSTCTL_CSRST); + //puts("reset done\n"); + + // internal PHY, force device mode + USBx->GUSBCFG = USB_OTG_GUSBCFG_PHYSEL | USB_OTG_GUSBCFG_FDMOD; + + // slowest timings + USBx->GUSBCFG |= (uint32_t)((USBD_FS_TRDT_VALUE << 10) & USB_OTG_GUSBCFG_TRDT); + + // power up the PHY +#ifdef STM32F4 + USBx->GCCFG = USB_OTG_GCCFG_PWRDWN; + + //USBx->GCCFG |= USB_OTG_GCCFG_VBDEN | USB_OTG_GCCFG_SDEN |USB_OTG_GCCFG_PDEN | USB_OTG_GCCFG_DCDEN; + + /* B-peripheral session valid override enable*/ + USBx->GOTGCTL |= USB_OTG_GOTGCTL_BVALOVAL; + USBx->GOTGCTL |= USB_OTG_GOTGCTL_BVALOEN; +#else + USBx->GCCFG = USB_OTG_GCCFG_PWRDWN | USB_OTG_GCCFG_NOVBUSSENS; +#endif + + // be a device, slowest timings + //USBx->GUSBCFG = USB_OTG_GUSBCFG_FDMOD | USB_OTG_GUSBCFG_PHYSEL | USB_OTG_GUSBCFG_TRDT | USB_OTG_GUSBCFG_TOCAL; + //USBx->GUSBCFG |= (uint32_t)((USBD_FS_TRDT_VALUE << 10) & USB_OTG_GUSBCFG_TRDT); + //USBx->GUSBCFG = USB_OTG_GUSBCFG_PHYSEL | USB_OTG_GUSBCFG_TRDT | USB_OTG_GUSBCFG_TOCAL; + + // **** for debugging, doesn't seem to work **** + //USBx->GUSBCFG |= USB_OTG_GUSBCFG_CTXPKT; + + // reset PHY clock + USBx_PCGCCTL = 0; + + // enable the fancy OTG things + // DCFG_FRAME_INTERVAL_80 is 0 + //USBx->GUSBCFG |= USB_OTG_GUSBCFG_HNPCAP | USB_OTG_GUSBCFG_SRPCAP; + USBx_DEVICE->DCFG |= USB_OTG_SPEED_FULL | USB_OTG_DCFG_NZLSOHSK; + + //USBx_DEVICE->DCFG = USB_OTG_DCFG_NZLSOHSK | USB_OTG_DCFG_DSPD; + //USBx_DEVICE->DCFG = USB_OTG_DCFG_DSPD; + + // clear pending interrupts + USBx->GINTSTS = 0xBFFFFFFFU; + + // setup USB interrupts + // all interrupts except TXFIFO EMPTY + //USBx->GINTMSK = 0xFFFFFFFF & ~(USB_OTG_GINTMSK_NPTXFEM | USB_OTG_GINTMSK_PTXFEM | USB_OTG_GINTSTS_SOF | USB_OTG_GINTSTS_EOPF); + //USBx->GINTMSK = 0xFFFFFFFF & ~(USB_OTG_GINTMSK_NPTXFEM | USB_OTG_GINTMSK_PTXFEM); + USBx->GINTMSK = USB_OTG_GINTMSK_USBRST | USB_OTG_GINTMSK_ENUMDNEM | USB_OTG_GINTMSK_OTGINT | + USB_OTG_GINTMSK_RXFLVLM | USB_OTG_GINTMSK_GONAKEFFM | USB_OTG_GINTMSK_GINAKEFFM | + USB_OTG_GINTMSK_OEPINT | USB_OTG_GINTMSK_IEPINT | USB_OTG_GINTMSK_USBSUSPM | + USB_OTG_GINTMSK_CIDSCHGM | USB_OTG_GINTMSK_SRQIM | USB_OTG_GINTMSK_MMISM; + + USBx->GAHBCFG = USB_OTG_GAHBCFG_GINT; + + // DCTL startup value is 2 on new chip, 0 on old chip + // THIS IS FUCKING BULLSHIT + USBx_DEVICE->DCTL = 0; + + // enable the IRQ + NVIC_EnableIRQ(OTG_FS_IRQn); +} + +// ***************************** USB port ***************************** + +void usb_irqhandler(void) { + //USBx->GINTMSK = 0; + + unsigned int gintsts = USBx->GINTSTS; + unsigned int gotgint = USBx->GOTGINT; + unsigned int daint = USBx_DEVICE->DAINT; + + // gintsts SUSPEND? 04008428 + #ifdef DEBUG_USB + puth(gintsts); + puts(" "); + /*puth(USBx->GCCFG); + puts(" ");*/ + puth(gotgint); + puts(" ep "); + puth(daint); + puts(" USB interrupt!\n"); + #endif + + if (gintsts & USB_OTG_GINTSTS_CIDSCHG) { + puts("connector ID status change\n"); + } + + if (gintsts & USB_OTG_GINTSTS_ESUSP) { + puts("ESUSP detected\n"); + } + + if (gintsts & USB_OTG_GINTSTS_USBRST) { + puts("USB reset\n"); + usb_reset(); + } + + if (gintsts & USB_OTG_GINTSTS_ENUMDNE) { + puts("enumeration done"); + // Full speed, ENUMSPD + //puth(USBx_DEVICE->DSTS); + puts("\n"); + } + + if (gintsts & USB_OTG_GINTSTS_OTGINT) { + puts("OTG int:"); + puth(USBx->GOTGINT); + puts("\n"); + + // getting ADTOCHG + //USBx->GOTGINT = USBx->GOTGINT; + } + + // RX FIFO first + if (gintsts & USB_OTG_GINTSTS_RXFLVL) { + // 1. Read the Receive status pop register + volatile unsigned int rxst = USBx->GRXSTSP; + + #ifdef DEBUG_USB + puts(" RX FIFO:"); + puth(rxst); + puts(" status: "); + puth((rxst & USB_OTG_GRXSTSP_PKTSTS) >> 17); + puts(" len: "); + puth((rxst & USB_OTG_GRXSTSP_BCNT) >> 4); + puts("\n"); + #endif + + if (((rxst & USB_OTG_GRXSTSP_PKTSTS) >> 17) == STS_DATA_UPDT) { + int endpoint = (rxst & USB_OTG_GRXSTSP_EPNUM); + int len = (rxst & USB_OTG_GRXSTSP_BCNT) >> 4; + USB_ReadPacket(&usbdata, len); + #ifdef DEBUG_USB + puts(" data "); + puth(len); + puts("\n"); + hexdump(&usbdata, len); + #endif + + if (endpoint == 2) { + usb_cb_ep2_out(usbdata, len, 1); + } + + if (endpoint == 3) { + usb_cb_ep3_out(usbdata, len, 1); + } + } else if (((rxst & USB_OTG_GRXSTSP_PKTSTS) >> 17) == STS_SETUP_UPDT) { + USB_ReadPacket(&setup, 8); + #ifdef DEBUG_USB + puts(" setup "); + hexdump(&setup, 8); + puts("\n"); + #endif + } + } + + /*if (gintsts & USB_OTG_GINTSTS_HPRTINT) { + // host + puts("HPRT:"); + puth(USBx_HOST_PORT->HPRT); + puts("\n"); + if (USBx_HOST_PORT->HPRT & USB_OTG_HPRT_PCDET) { + USBx_HOST_PORT->HPRT |= USB_OTG_HPRT_PRST; + USBx_HOST_PORT->HPRT |= USB_OTG_HPRT_PCDET; + } + + }*/ + + if ((gintsts & USB_OTG_GINTSTS_BOUTNAKEFF) || (gintsts & USB_OTG_GINTSTS_GINAKEFF)) { + // no global NAK, why is this getting set? + #ifdef DEBUG_USB + puts("GLOBAL NAK\n"); + #endif + USBx_DEVICE->DCTL |= USB_OTG_DCTL_CGONAK | USB_OTG_DCTL_CGINAK; + } + + if (gintsts & USB_OTG_GINTSTS_SRQINT) { + // we want to do "A-device host negotiation protocol" since we are the A-device + /*puts("start request\n"); + puth(USBx->GOTGCTL); + puts("\n");*/ + //USBx->GUSBCFG |= USB_OTG_GUSBCFG_FDMOD; + //USBx_HOST_PORT->HPRT = USB_OTG_HPRT_PPWR | USB_OTG_HPRT_PENA; + //USBx->GOTGCTL |= USB_OTG_GOTGCTL_SRQ; + } + + // out endpoint hit + if (gintsts & USB_OTG_GINTSTS_OEPINT) { + #ifdef DEBUG_USB + puts(" 0:"); + puth(USBx_OUTEP(0)->DOEPINT); + puts(" 2:"); + puth(USBx_OUTEP(2)->DOEPINT); + puts(" 3:"); + puth(USBx_OUTEP(3)->DOEPINT); + puts(" "); + puth(USBx_OUTEP(3)->DOEPCTL); + puts(" 4:"); + puth(USBx_OUTEP(4)->DOEPINT); + puts(" OUT ENDPOINT\n"); + #endif + + if (USBx_OUTEP(2)->DOEPINT & USB_OTG_DOEPINT_XFRC) { + #ifdef DEBUG_USB + puts(" OUT2 PACKET XFRC\n"); + #endif + USBx_OUTEP(2)->DOEPTSIZ = (1 << 19) | 0x40; + USBx_OUTEP(2)->DOEPCTL |= USB_OTG_DOEPCTL_EPENA | USB_OTG_DOEPCTL_CNAK; + } + + if (USBx_OUTEP(3)->DOEPINT & USB_OTG_DOEPINT_XFRC) { + #ifdef DEBUG_USB + puts(" OUT3 PACKET XFRC\n"); + #endif + USBx_OUTEP(3)->DOEPTSIZ = (1 << 19) | 0x40; + USBx_OUTEP(3)->DOEPCTL |= USB_OTG_DOEPCTL_EPENA | USB_OTG_DOEPCTL_CNAK; + } else if (USBx_OUTEP(3)->DOEPINT & 0x2000) { + #ifdef DEBUG_USB + puts(" OUT3 PACKET WTF\n"); + #endif + // if NAK was set trigger this, unknown interrupt + USBx_OUTEP(3)->DOEPTSIZ = (1 << 19) | 0x40; + USBx_OUTEP(3)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK; + } else if (USBx_OUTEP(3)->DOEPINT) { + puts("OUTEP3 error "); + puth(USBx_OUTEP(3)->DOEPINT); + puts("\n"); + } + + if (USBx_OUTEP(0)->DOEPINT & USB_OTG_DIEPINT_XFRC) { + // ready for next packet + USBx_OUTEP(0)->DOEPTSIZ = USB_OTG_DOEPTSIZ_STUPCNT | (USB_OTG_DOEPTSIZ_PKTCNT & (1 << 19)) | (1 * 8); + } + + // respond to setup packets + if (USBx_OUTEP(0)->DOEPINT & USB_OTG_DOEPINT_STUP) { + usb_setup(); + } + + USBx_OUTEP(0)->DOEPINT = USBx_OUTEP(0)->DOEPINT; + USBx_OUTEP(2)->DOEPINT = USBx_OUTEP(2)->DOEPINT; + USBx_OUTEP(3)->DOEPINT = USBx_OUTEP(3)->DOEPINT; + } + + // interrupt endpoint hit (Page 1221) + if (gintsts & USB_OTG_GINTSTS_IEPINT) { + #ifdef DEBUG_USB + puts(" "); + puth(USBx_INEP(0)->DIEPINT); + puts(" "); + puth(USBx_INEP(1)->DIEPINT); + puts(" IN ENDPOINT\n"); + #endif + + // Should likely check the EP of the IN request even if there is + // only one IN endpoint. + + // No need to set NAK in OTG_DIEPCTL0 when nothing to send, + // Appears USB core automatically sets NAK. WritePacket clears it. + + // Handle the two interface alternate settings. Setting 0 is has + // EP1 as bulk. Setting 1 has EP1 as interrupt. The code to handle + // these two EP variations are very similar and can be + // restructured for smaller code footprint. Keeping split out for + // now for clarity. + + //TODO add default case. Should it NAK? + switch (current_int0_alt_setting) { + case 0: ////// Bulk config + // *** IN token received when TxFIFO is empty + if (USBx_INEP(1)->DIEPINT & USB_OTG_DIEPMSK_ITTXFEMSK) { + #ifdef DEBUG_USB + puts(" IN PACKET QUEUE\n"); + #endif + // TODO: always assuming max len, can we get the length? + USB_WritePacket((void *)resp, usb_cb_ep1_in(resp, 0x40, 1), 1); + } + break; + + case 1: ////// Interrupt config + // *** IN token received when TxFIFO is empty + if (USBx_INEP(1)->DIEPINT & USB_OTG_DIEPMSK_ITTXFEMSK) { + #ifdef DEBUG_USB + puts(" IN PACKET QUEUE\n"); + #endif + // TODO: always assuming max len, can we get the length? + int len = usb_cb_ep1_in(resp, 0x40, 1); + if (len > 0) { + USB_WritePacket((void *)resp, len, 1); + } + } + break; + } + + if (USBx_INEP(0)->DIEPINT & USB_OTG_DIEPMSK_ITTXFEMSK) { + #ifdef DEBUG_USB + puts(" IN PACKET QUEUE\n"); + #endif + + if (ep0_txlen != 0 && (USBx_INEP(0)->DTXFSTS & USB_OTG_DTXFSTS_INEPTFSAV) >= 0x40) { + uint16_t len = min(ep0_txlen, 0x40); + USB_WritePacket(ep0_txdata, len, 0); + ep0_txdata += len; + ep0_txlen -= len; + if (ep0_txlen == 0) { + ep0_txdata = NULL; + USBx_DEVICE->DIEPEMPMSK &= ~1; + USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK; + } + } + } + + // clear interrupts + USBx_INEP(0)->DIEPINT = USBx_INEP(0)->DIEPINT; // Why ep0? + USBx_INEP(1)->DIEPINT = USBx_INEP(1)->DIEPINT; + } + + // clear all interrupts we handled + USBx_DEVICE->DAINT = daint; + USBx->GOTGINT = gotgint; + USBx->GINTSTS = gintsts; + + //USBx->GINTMSK = 0xFFFFFFFF & ~(USB_OTG_GINTMSK_NPTXFEM | USB_OTG_GINTMSK_PTXFEM | USB_OTG_GINTSTS_SOF | USB_OTG_GINTSTS_EOPF); +} + +void OTG_FS_IRQHandler(void) { + NVIC_DisableIRQ(OTG_FS_IRQn); + //__disable_irq(); + usb_irqhandler(); + //__enable_irq(); + NVIC_EnableIRQ(OTG_FS_IRQn); +} + diff --git a/panda/board/get_sdk.sh b/panda/board/get_sdk.sh new file mode 100755 index 00000000000000..7b8d1f9154c0ac --- /dev/null +++ b/panda/board/get_sdk.sh @@ -0,0 +1,3 @@ +#!/bin/bash +sudo apt-get install gcc-arm-none-eabi python-pip +sudo pip2 install libusb1 pycrypto requests diff --git a/panda/board/get_sdk_mac.sh b/panda/board/get_sdk_mac.sh new file mode 100755 index 00000000000000..a6f641dce12116 --- /dev/null +++ b/panda/board/get_sdk_mac.sh @@ -0,0 +1,5 @@ +#!/bin/bash +# Need formula for gcc +brew tap ArmMbed/homebrew-formulae +brew install python dfu-util arm-none-eabi-gcc +pip2 install libusb1 pycrypto requests diff --git a/panda/board/gpio.h b/panda/board/gpio.h new file mode 100644 index 00000000000000..6112f6f887c703 --- /dev/null +++ b/panda/board/gpio.h @@ -0,0 +1,477 @@ +#ifdef STM32F4 + #include "stm32f4xx_hal_gpio_ex.h" +#else + #include "stm32f2xx_hal_gpio_ex.h" +#endif + +// ********************* dynamic configuration detection ********************* + +#define PANDA_REV_AB 0 +#define PANDA_REV_C 1 + +#define PULL_EFFECTIVE_DELAY 10 + +int has_external_debug_serial = 0; +int is_giant_panda = 0; +int is_entering_bootmode = 0; +int revision = PANDA_REV_AB; +int is_grey_panda = 0; + +int detect_with_pull(GPIO_TypeDef *GPIO, int pin, int mode) { + set_gpio_mode(GPIO, pin, MODE_INPUT); + set_gpio_pullup(GPIO, pin, mode); + for (volatile int i=0; iCR |= RCC_CR_HSEON; + while ((RCC->CR & RCC_CR_HSERDY) == 0); + + // divide shit + RCC->CFGR = RCC_CFGR_HPRE_DIV1 | RCC_CFGR_PPRE2_DIV2 | RCC_CFGR_PPRE1_DIV4; + #ifdef PANDA + RCC->PLLCFGR = RCC_PLLCFGR_PLLQ_2 | RCC_PLLCFGR_PLLM_3 | + RCC_PLLCFGR_PLLN_6 | RCC_PLLCFGR_PLLN_5 | RCC_PLLCFGR_PLLSRC_HSE; + #else + #ifdef PEDAL + // comma pedal has a 16mhz crystal + RCC->PLLCFGR = RCC_PLLCFGR_PLLQ_2 | RCC_PLLCFGR_PLLM_3 | + RCC_PLLCFGR_PLLN_6 | RCC_PLLCFGR_PLLN_5 | RCC_PLLCFGR_PLLSRC_HSE; + #else + // NEO board has a 8mhz crystal + RCC->PLLCFGR = RCC_PLLCFGR_PLLQ_2 | RCC_PLLCFGR_PLLM_3 | + RCC_PLLCFGR_PLLN_7 | RCC_PLLCFGR_PLLN_6 | RCC_PLLCFGR_PLLSRC_HSE; + #endif + #endif + + // start PLL + RCC->CR |= RCC_CR_PLLON; + while ((RCC->CR & RCC_CR_PLLRDY) == 0); + + // Configure Flash prefetch, Instruction cache, Data cache and wait state + // *** without this, it breaks *** + FLASH->ACR = FLASH_ACR_ICEN | FLASH_ACR_DCEN | FLASH_ACR_LATENCY_5WS; + + // switch to PLL + RCC->CFGR |= RCC_CFGR_SW_PLL; + while ((RCC->CFGR & RCC_CFGR_SWS) != RCC_CFGR_SWS_PLL); + + // *** running on PLL *** +} + +void periph_init() { + // enable GPIOB, UART2, CAN, USB clock + RCC->AHB1ENR |= RCC_AHB1ENR_GPIOAEN; + RCC->AHB1ENR |= RCC_AHB1ENR_GPIOBEN; + RCC->AHB1ENR |= RCC_AHB1ENR_GPIOCEN; + RCC->AHB1ENR |= RCC_AHB1ENR_GPIODEN; + + RCC->AHB1ENR |= RCC_AHB1ENR_DMA2EN; + RCC->APB1ENR |= RCC_APB1ENR_USART2EN; + RCC->APB1ENR |= RCC_APB1ENR_USART3EN; + #ifdef PANDA + RCC->APB1ENR |= RCC_APB1ENR_UART5EN; + #endif + RCC->APB1ENR |= RCC_APB1ENR_CAN1EN; + RCC->APB1ENR |= RCC_APB1ENR_CAN2EN; + #ifdef CAN3 + RCC->APB1ENR |= RCC_APB1ENR_CAN3EN; + #endif + RCC->APB1ENR |= RCC_APB1ENR_DACEN; + RCC->APB1ENR |= RCC_APB1ENR_TIM2EN; + RCC->APB1ENR |= RCC_APB1ENR_TIM3EN; + RCC->APB1ENR |= RCC_APB1ENR_TIM4EN; + RCC->APB2ENR |= RCC_APB2ENR_USART1EN; + RCC->AHB2ENR |= RCC_AHB2ENR_OTGFSEN; + RCC->APB2ENR |= RCC_APB2ENR_TIM1EN; + RCC->APB2ENR |= RCC_APB2ENR_ADC1EN; + RCC->APB2ENR |= RCC_APB2ENR_SPI1EN; + + // needed? + RCC->APB2ENR |= RCC_APB2ENR_SYSCFGEN; +} + +// ********************* setters ********************* + +void set_can_enable(CAN_TypeDef *CAN, int enabled) { + // enable CAN busses + if (CAN == CAN1) { + #ifdef PANDA + // CAN1_EN + set_gpio_output(GPIOC, 1, !enabled); + #else + #ifdef PEDAL + // CAN1_EN (not flipped) + set_gpio_output(GPIOB, 3, !enabled); + #else + // CAN1_EN + set_gpio_output(GPIOB, 3, enabled); + #endif + #endif + } else if (CAN == CAN2) { + #ifdef PANDA + // CAN2_EN + set_gpio_output(GPIOC, 13, !enabled); + #else + // CAN2_EN + set_gpio_output(GPIOB, 4, enabled); + #endif + #ifdef CAN3 + } else if (CAN == CAN3) { + // CAN3_EN + set_gpio_output(GPIOA, 0, !enabled); + #endif + } +} + +#ifdef PANDA + #define LED_RED 9 + #define LED_GREEN 7 + #define LED_BLUE 6 +#else + #define LED_RED 10 + #define LED_GREEN 11 + #define LED_BLUE -1 +#endif + +void set_led(int led_num, int on) { + if (led_num == -1) return; + + #ifdef PANDA + set_gpio_output(GPIOC, led_num, !on); + #else + set_gpio_output(GPIOB, led_num, !on); + #endif +} + +void set_can_mode(int can, int use_gmlan) { + // connects to CAN2 xcvr or GMLAN xcvr + if (use_gmlan) { + if (can == 1) { + // B5,B6: disable normal mode + set_gpio_mode(GPIOB, 5, MODE_INPUT); + set_gpio_mode(GPIOB, 6, MODE_INPUT); + + // B12,B13: gmlan mode + set_gpio_alternate(GPIOB, 12, GPIO_AF9_CAN2); + set_gpio_alternate(GPIOB, 13, GPIO_AF9_CAN2); +#ifdef CAN3 + } else if (revision == PANDA_REV_C && can == 2) { + // A8,A15: disable normal mode + set_gpio_mode(GPIOA, 8, MODE_INPUT); + set_gpio_mode(GPIOA, 15, MODE_INPUT); + + // B3,B4: enable gmlan mode + set_gpio_alternate(GPIOB, 3, GPIO_AF11_CAN3); + set_gpio_alternate(GPIOB, 4, GPIO_AF11_CAN3); +#endif + } + } else { + if (can == 1) { + // B12,B13: disable gmlan mode + set_gpio_mode(GPIOB, 12, MODE_INPUT); + set_gpio_mode(GPIOB, 13, MODE_INPUT); + + // B5,B6: normal mode + set_gpio_alternate(GPIOB, 5, GPIO_AF9_CAN2); + set_gpio_alternate(GPIOB, 6, GPIO_AF9_CAN2); +#ifdef CAN3 + } else if (can == 2) { + if(revision == PANDA_REV_C){ + // B3,B4: disable gmlan mode + set_gpio_mode(GPIOB, 3, MODE_INPUT); + set_gpio_mode(GPIOB, 4, MODE_INPUT); + } + // A8,A15: normal mode + set_gpio_alternate(GPIOA, 8, GPIO_AF11_CAN3); + set_gpio_alternate(GPIOA, 15, GPIO_AF11_CAN3); +#endif + } + } +} + +#define USB_POWER_NONE 0 +#define USB_POWER_CLIENT 1 +#define USB_POWER_CDP 2 +#define USB_POWER_DCP 3 + +int usb_power_mode = USB_POWER_NONE; + +void set_usb_power_mode(int mode) { + switch (mode) { + case USB_POWER_CLIENT: + // B2,A13: set client mode + set_gpio_output(GPIOB, 2, 0); + set_gpio_output(GPIOA, 13, 1); + break; + case USB_POWER_CDP: + // B2,A13: set CDP mode + set_gpio_output(GPIOB, 2, 1); + set_gpio_output(GPIOA, 13, 1); + break; + case USB_POWER_DCP: + // B2,A13: set DCP mode on the charger (breaks USB!) + set_gpio_output(GPIOB, 2, 0); + set_gpio_output(GPIOA, 13, 0); + break; + } + usb_power_mode = mode; +} + +#define ESP_DISABLED 0 +#define ESP_ENABLED 1 +#define ESP_BOOTMODE 2 + +void set_esp_mode(int mode) { + switch (mode) { + case ESP_DISABLED: + // ESP OFF + set_gpio_output(GPIOC, 14, 0); + set_gpio_output(GPIOC, 5, 0); + break; + case ESP_ENABLED: + // ESP ON + set_gpio_output(GPIOC, 14, 1); + set_gpio_output(GPIOC, 5, 1); + break; + case ESP_BOOTMODE: + set_gpio_output(GPIOC, 14, 1); + set_gpio_output(GPIOC, 5, 0); + break; + } +} + +// ********************* big init function ********************* + +// board specific +void gpio_init() { + // pull low to hold ESP in reset?? + // enable OTG out tied to ground + GPIOA->ODR = 0; + GPIOB->ODR = 0; + GPIOA->PUPDR = 0; + //GPIOC->ODR = 0; + GPIOB->AFR[0] = 0; + GPIOB->AFR[1] = 0; + + // C2,C3: analog mode, voltage and current sense + set_gpio_mode(GPIOC, 2, MODE_ANALOG); + set_gpio_mode(GPIOC, 3, MODE_ANALOG); + +#ifdef PEDAL + // comma pedal has inputs on C0 and C1 + set_gpio_mode(GPIOC, 0, MODE_ANALOG); + set_gpio_mode(GPIOC, 1, MODE_ANALOG); + // DAC outputs on A4 and A5 + // apparently they don't need GPIO setup +#endif + + // C8: FAN aka TIM3_CH4 + set_gpio_alternate(GPIOC, 8, GPIO_AF2_TIM3); + + // turn off LEDs and set mode + set_led(LED_RED, 0); + set_led(LED_GREEN, 0); + set_led(LED_BLUE, 0); + + // A11,A12: USB + set_gpio_alternate(GPIOA, 11, GPIO_AF10_OTG_FS); + set_gpio_alternate(GPIOA, 12, GPIO_AF10_OTG_FS); + GPIOA->OSPEEDR = GPIO_OSPEEDER_OSPEEDR11 | GPIO_OSPEEDER_OSPEEDR12; + +#ifdef PANDA + // enable started_alt on the panda + set_gpio_pullup(GPIOA, 1, PULL_UP); + + // A2,A3: USART 2 for debugging + set_gpio_alternate(GPIOA, 2, GPIO_AF7_USART2); + set_gpio_alternate(GPIOA, 3, GPIO_AF7_USART2); + + // A9,A10: USART 1 for talking to the ESP + set_gpio_alternate(GPIOA, 9, GPIO_AF7_USART1); + set_gpio_alternate(GPIOA, 10, GPIO_AF7_USART1); + + // B12: GMLAN, ignition sense, pull up + set_gpio_pullup(GPIOB, 12, PULL_UP); + + // A4,A5,A6,A7: setup SPI + set_gpio_alternate(GPIOA, 4, GPIO_AF5_SPI1); + set_gpio_alternate(GPIOA, 5, GPIO_AF5_SPI1); + set_gpio_alternate(GPIOA, 6, GPIO_AF5_SPI1); + set_gpio_alternate(GPIOA, 7, GPIO_AF5_SPI1); +#endif + + // B8,B9: CAN 1 +#ifdef STM32F4 + set_gpio_alternate(GPIOB, 8, GPIO_AF8_CAN1); + set_gpio_alternate(GPIOB, 9, GPIO_AF8_CAN1); +#else + set_gpio_alternate(GPIOB, 8, GPIO_AF9_CAN1); + set_gpio_alternate(GPIOB, 9, GPIO_AF9_CAN1); +#endif + set_can_enable(CAN1, 1); + + // B5,B6: CAN 2 + set_can_mode(1, 0); + set_can_enable(CAN2, 1); + + // A8,A15: CAN 3 + #ifdef CAN3 + set_can_mode(2, 0); + set_can_enable(CAN3, 1); + #endif + + /* GMLAN mode pins: + M0(B15) M1(B14) mode + ======================= + 0 0 sleep + 1 0 100kbit + 0 1 high voltage wakeup + 1 1 33kbit (normal) + */ + + // put gmlan transceiver in normal mode + set_gpio_output(GPIOB, 14, 1); + set_gpio_output(GPIOB, 15, 1); + + #ifdef PANDA + // K-line enable moved from B4->B7 to make room for GMLAN on CAN3 + if (revision == PANDA_REV_C) { + set_gpio_output(GPIOB, 7, 1); // REV C + } else { + set_gpio_output(GPIOB, 4, 1); // REV AB + } + + // C12,D2: K-Line setup on UART 5 + set_gpio_alternate(GPIOC, 12, GPIO_AF8_UART5); + set_gpio_alternate(GPIOD, 2, GPIO_AF8_UART5); + set_gpio_pullup(GPIOD, 2, PULL_UP); + + // L-line enable + set_gpio_output(GPIOA, 14, 1); + + // C10,C11: L-Line setup on USART 3 + set_gpio_alternate(GPIOC, 10, GPIO_AF7_USART3); + set_gpio_alternate(GPIOC, 11, GPIO_AF7_USART3); + set_gpio_pullup(GPIOC, 11, PULL_UP); + #endif + + if (revision == PANDA_REV_C) { + set_usb_power_mode(USB_POWER_CLIENT); + } +} + +// ********************* early bringup ********************* + +#define ENTER_BOOTLOADER_MAGIC 0xdeadbeef +#define ENTER_SOFTLOADER_MAGIC 0xdeadc0de +#define BOOT_NORMAL 0xdeadb111 + +extern void *g_pfnVectors; +extern uint32_t enter_bootloader_mode; + +void jump_to_bootloader() { + // do enter bootloader + enter_bootloader_mode = 0; + void (*bootloader)(void) = (void (*)(void)) (*((uint32_t *)0x1fff0004)); + + // jump to bootloader + bootloader(); + + // reset on exit + enter_bootloader_mode = BOOT_NORMAL; + NVIC_SystemReset(); +} + +void early() { + // after it's been in the bootloader, things are initted differently, so we reset + if (enter_bootloader_mode != BOOT_NORMAL && + enter_bootloader_mode != ENTER_BOOTLOADER_MAGIC && + enter_bootloader_mode != ENTER_SOFTLOADER_MAGIC) { + enter_bootloader_mode = BOOT_NORMAL; + NVIC_SystemReset(); + } + + // if wrong chip, reboot + volatile unsigned int id = DBGMCU->IDCODE; + #ifdef STM32F4 + if ((id&0xFFF) != 0x463) enter_bootloader_mode = ENTER_BOOTLOADER_MAGIC; + #else + if ((id&0xFFF) != 0x411) enter_bootloader_mode = ENTER_BOOTLOADER_MAGIC; + #endif + + // setup interrupt table + SCB->VTOR = (uint32_t)&g_pfnVectors; + + // early GPIOs float everything + RCC->AHB1ENR = RCC_AHB1ENR_GPIOAEN | RCC_AHB1ENR_GPIOBEN | RCC_AHB1ENR_GPIOCEN; + + GPIOA->MODER = 0; GPIOB->MODER = 0; GPIOC->MODER = 0; + GPIOA->ODR = 0; GPIOB->ODR = 0; GPIOC->ODR = 0; + GPIOA->PUPDR = 0; GPIOB->PUPDR = 0; GPIOC->PUPDR = 0; + + detect(); + + #ifdef PANDA + // enable the ESP, disable ESP boot mode + // unless we are on a giant panda, then there's no ESP + if (is_giant_panda) { + set_esp_mode(ESP_DISABLED); + } else { + set_esp_mode(ESP_ENABLED); + } + #endif + + + if (enter_bootloader_mode == ENTER_BOOTLOADER_MAGIC) { + #ifdef PANDA + set_esp_mode(ESP_DISABLED); + #endif + set_led(LED_GREEN, 1); + jump_to_bootloader(); + } + + if (is_entering_bootmode) { + enter_bootloader_mode = ENTER_SOFTLOADER_MAGIC; + } +} + diff --git a/panda/board/inc/cmsis_gcc.h b/panda/board/inc/cmsis_gcc.h new file mode 100644 index 00000000000000..bb89fbba9e4000 --- /dev/null +++ b/panda/board/inc/cmsis_gcc.h @@ -0,0 +1,1373 @@ +/**************************************************************************//** + * @file cmsis_gcc.h + * @brief CMSIS Cortex-M Core Function/Instruction Header File + * @version V4.30 + * @date 20. October 2015 + ******************************************************************************/ +/* Copyright (c) 2009 - 2015 ARM LIMITED + + All rights reserved. + Redistribution and use in source and binary forms, with or without + modification, are permitted provided that the following conditions are met: + - Redistributions of source code must retain the above copyright + notice, this list of conditions and the following disclaimer. + - Redistributions in binary form must reproduce the above copyright + notice, this list of conditions and the following disclaimer in the + documentation and/or other materials provided with the distribution. + - Neither the name of ARM nor the names of its contributors may be used + to endorse or promote products derived from this software without + specific prior written permission. + * + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE + LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + POSSIBILITY OF SUCH DAMAGE. + ---------------------------------------------------------------------------*/ + + +#ifndef __CMSIS_GCC_H +#define __CMSIS_GCC_H + +/* ignore some GCC warnings */ +#if defined ( __GNUC__ ) +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wsign-conversion" +#pragma GCC diagnostic ignored "-Wconversion" +#pragma GCC diagnostic ignored "-Wunused-parameter" +#endif + + +/* ########################### Core Function Access ########################### */ +/** \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_RegAccFunctions CMSIS Core Register Access Functions + @{ + */ + +/** + \brief Enable IRQ Interrupts + \details Enables IRQ interrupts by clearing the I-bit in the CPSR. + Can only be executed in Privileged modes. + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE void __enable_irq(void) +{ + __ASM volatile ("cpsie i" : : : "memory"); +} + + +/** + \brief Disable IRQ Interrupts + \details Disables IRQ interrupts by setting the I-bit in the CPSR. + Can only be executed in Privileged modes. + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE void __disable_irq(void) +{ + __ASM volatile ("cpsid i" : : : "memory"); +} + + +/** + \brief Get Control Register + \details Returns the content of the Control Register. + \return Control Register value + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_CONTROL(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, control" : "=r" (result) ); + return(result); +} + + +/** + \brief Set Control Register + \details Writes the given value to the Control Register. + \param [in] control Control Register value to set + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE void __set_CONTROL(uint32_t control) +{ + __ASM volatile ("MSR control, %0" : : "r" (control) : "memory"); +} + + +/** + \brief Get IPSR Register + \details Returns the content of the IPSR Register. + \return IPSR Register value + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_IPSR(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, ipsr" : "=r" (result) ); + return(result); +} + + +/** + \brief Get APSR Register + \details Returns the content of the APSR Register. + \return APSR Register value + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_APSR(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, apsr" : "=r" (result) ); + return(result); +} + + +/** + \brief Get xPSR Register + \details Returns the content of the xPSR Register. + + \return xPSR Register value + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_xPSR(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, xpsr" : "=r" (result) ); + return(result); +} + + +/** + \brief Get Process Stack Pointer + \details Returns the current value of the Process Stack Pointer (PSP). + \return PSP Register value + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_PSP(void) +{ + register uint32_t result; + + __ASM volatile ("MRS %0, psp\n" : "=r" (result) ); + return(result); +} + + +/** + \brief Set Process Stack Pointer + \details Assigns the given value to the Process Stack Pointer (PSP). + \param [in] topOfProcStack Process Stack Pointer value to set + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE void __set_PSP(uint32_t topOfProcStack) +{ + __ASM volatile ("MSR psp, %0\n" : : "r" (topOfProcStack) : "sp"); +} + + +/** + \brief Get Main Stack Pointer + \details Returns the current value of the Main Stack Pointer (MSP). + \return MSP Register value + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_MSP(void) +{ + register uint32_t result; + + __ASM volatile ("MRS %0, msp\n" : "=r" (result) ); + return(result); +} + + +/** + \brief Set Main Stack Pointer + \details Assigns the given value to the Main Stack Pointer (MSP). + + \param [in] topOfMainStack Main Stack Pointer value to set + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE void __set_MSP(uint32_t topOfMainStack) +{ + __ASM volatile ("MSR msp, %0\n" : : "r" (topOfMainStack) : "sp"); +} + + +/** + \brief Get Priority Mask + \details Returns the current state of the priority mask bit from the Priority Mask Register. + \return Priority Mask value + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_PRIMASK(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, primask" : "=r" (result) ); + return(result); +} + + +/** + \brief Set Priority Mask + \details Assigns the given value to the Priority Mask Register. + \param [in] priMask Priority Mask + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE void __set_PRIMASK(uint32_t priMask) +{ + __ASM volatile ("MSR primask, %0" : : "r" (priMask) : "memory"); +} + + +#if (__CORTEX_M >= 0x03U) + +/** + \brief Enable FIQ + \details Enables FIQ interrupts by clearing the F-bit in the CPSR. + Can only be executed in Privileged modes. + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE void __enable_fault_irq(void) +{ + __ASM volatile ("cpsie f" : : : "memory"); +} + + +/** + \brief Disable FIQ + \details Disables FIQ interrupts by setting the F-bit in the CPSR. + Can only be executed in Privileged modes. + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE void __disable_fault_irq(void) +{ + __ASM volatile ("cpsid f" : : : "memory"); +} + + +/** + \brief Get Base Priority + \details Returns the current value of the Base Priority register. + \return Base Priority register value + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_BASEPRI(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, basepri" : "=r" (result) ); + return(result); +} + + +/** + \brief Set Base Priority + \details Assigns the given value to the Base Priority register. + \param [in] basePri Base Priority value to set + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE void __set_BASEPRI(uint32_t value) +{ + __ASM volatile ("MSR basepri, %0" : : "r" (value) : "memory"); +} + + +/** + \brief Set Base Priority with condition + \details Assigns the given value to the Base Priority register only if BASEPRI masking is disabled, + or the new value increases the BASEPRI priority level. + \param [in] basePri Base Priority value to set + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE void __set_BASEPRI_MAX(uint32_t value) +{ + __ASM volatile ("MSR basepri_max, %0" : : "r" (value) : "memory"); +} + + +/** + \brief Get Fault Mask + \details Returns the current value of the Fault Mask register. + \return Fault Mask register value + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_FAULTMASK(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, faultmask" : "=r" (result) ); + return(result); +} + + +/** + \brief Set Fault Mask + \details Assigns the given value to the Fault Mask register. + \param [in] faultMask Fault Mask value to set + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE void __set_FAULTMASK(uint32_t faultMask) +{ + __ASM volatile ("MSR faultmask, %0" : : "r" (faultMask) : "memory"); +} + +#endif /* (__CORTEX_M >= 0x03U) */ + + +#if (__CORTEX_M == 0x04U) || (__CORTEX_M == 0x07U) + +/** + \brief Get FPSCR + \details Returns the current value of the Floating Point Status/Control register. + \return Floating Point Status/Control register value + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_FPSCR(void) +{ +#if (__FPU_PRESENT == 1U) && (__FPU_USED == 1U) + uint32_t result; + + /* Empty asm statement works as a scheduling barrier */ + __ASM volatile (""); + __ASM volatile ("VMRS %0, fpscr" : "=r" (result) ); + __ASM volatile (""); + return(result); +#else + return(0); +#endif +} + + +/** + \brief Set FPSCR + \details Assigns the given value to the Floating Point Status/Control register. + \param [in] fpscr Floating Point Status/Control value to set + */ +__attribute__( ( always_inline ) ) __STATIC_INLINE void __set_FPSCR(uint32_t fpscr) +{ +#if (__FPU_PRESENT == 1U) && (__FPU_USED == 1U) + /* Empty asm statement works as a scheduling barrier */ + __ASM volatile (""); + __ASM volatile ("VMSR fpscr, %0" : : "r" (fpscr) : "vfpcc"); + __ASM volatile (""); +#endif +} + +#endif /* (__CORTEX_M == 0x04U) || (__CORTEX_M == 0x07U) */ + + + +/*@} end of CMSIS_Core_RegAccFunctions */ + + +/* ########################## Core Instruction Access ######################### */ +/** \defgroup CMSIS_Core_InstructionInterface CMSIS Core Instruction Interface + Access to dedicated instructions + @{ +*/ + +/* Define macros for porting to both thumb1 and thumb2. + * For thumb1, use low register (r0-r7), specified by constraint "l" + * Otherwise, use general registers, specified by constraint "r" */ +#if defined (__thumb__) && !defined (__thumb2__) +#define __CMSIS_GCC_OUT_REG(r) "=l" (r) +#define __CMSIS_GCC_USE_REG(r) "l" (r) +#else +#define __CMSIS_GCC_OUT_REG(r) "=r" (r) +#define __CMSIS_GCC_USE_REG(r) "r" (r) +#endif + +/** + \brief No Operation + \details No Operation does nothing. This instruction can be used for code alignment purposes. + */ +__attribute__((always_inline)) __STATIC_INLINE void __NOP(void) +{ + __ASM volatile ("nop"); +} + + +/** + \brief Wait For Interrupt + \details Wait For Interrupt is a hint instruction that suspends execution until one of a number of events occurs. + */ +__attribute__((always_inline)) __STATIC_INLINE void __WFI(void) +{ + __ASM volatile ("wfi"); +} + + +/** + \brief Wait For Event + \details Wait For Event is a hint instruction that permits the processor to enter + a low-power state until one of a number of events occurs. + */ +__attribute__((always_inline)) __STATIC_INLINE void __WFE(void) +{ + __ASM volatile ("wfe"); +} + + +/** + \brief Send Event + \details Send Event is a hint instruction. It causes an event to be signaled to the CPU. + */ +__attribute__((always_inline)) __STATIC_INLINE void __SEV(void) +{ + __ASM volatile ("sev"); +} + + +/** + \brief Instruction Synchronization Barrier + \details Instruction Synchronization Barrier flushes the pipeline in the processor, + so that all instructions following the ISB are fetched from cache or memory, + after the instruction has been completed. + */ +__attribute__((always_inline)) __STATIC_INLINE void __ISB(void) +{ + __ASM volatile ("isb 0xF":::"memory"); +} + + +/** + \brief Data Synchronization Barrier + \details Acts as a special kind of Data Memory Barrier. + It completes when all explicit memory accesses before this instruction complete. + */ +__attribute__((always_inline)) __STATIC_INLINE void __DSB(void) +{ + __ASM volatile ("dsb 0xF":::"memory"); +} + + +/** + \brief Data Memory Barrier + \details Ensures the apparent order of the explicit memory operations before + and after the instruction, without ensuring their completion. + */ +__attribute__((always_inline)) __STATIC_INLINE void __DMB(void) +{ + __ASM volatile ("dmb 0xF":::"memory"); +} + + +/** + \brief Reverse byte order (32 bit) + \details Reverses the byte order in integer value. + \param [in] value Value to reverse + \return Reversed value + */ +__attribute__((always_inline)) __STATIC_INLINE uint32_t __REV(uint32_t value) +{ +#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 5) + return __builtin_bswap32(value); +#else + uint32_t result; + + __ASM volatile ("rev %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); + return(result); +#endif +} + + +/** + \brief Reverse byte order (16 bit) + \details Reverses the byte order in two unsigned short values. + \param [in] value Value to reverse + \return Reversed value + */ +__attribute__((always_inline)) __STATIC_INLINE uint32_t __REV16(uint32_t value) +{ + uint32_t result; + + __ASM volatile ("rev16 %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); + return(result); +} + + +/** + \brief Reverse byte order in signed short value + \details Reverses the byte order in a signed short value with sign extension to integer. + \param [in] value Value to reverse + \return Reversed value + */ +__attribute__((always_inline)) __STATIC_INLINE int32_t __REVSH(int32_t value) +{ +#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) + return (short)__builtin_bswap16(value); +#else + int32_t result; + + __ASM volatile ("revsh %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); + return(result); +#endif +} + + +/** + \brief Rotate Right in unsigned value (32 bit) + \details Rotate Right (immediate) provides the value of the contents of a register rotated by a variable number of bits. + \param [in] value Value to rotate + \param [in] value Number of Bits to rotate + \return Rotated value + */ +__attribute__((always_inline)) __STATIC_INLINE uint32_t __ROR(uint32_t op1, uint32_t op2) +{ + return (op1 >> op2) | (op1 << (32U - op2)); +} + + +/** + \brief Breakpoint + \details Causes the processor to enter Debug state. + Debug tools can use this to investigate system state when the instruction at a particular address is reached. + \param [in] value is ignored by the processor. + If required, a debugger can use it to store additional information about the breakpoint. + */ +#define __BKPT(value) __ASM volatile ("bkpt "#value) + + +/** + \brief Reverse bit order of value + \details Reverses the bit order of the given value. + \param [in] value Value to reverse + \return Reversed value + */ +__attribute__((always_inline)) __STATIC_INLINE uint32_t __RBIT(uint32_t value) +{ + uint32_t result; + +#if (__CORTEX_M >= 0x03U) || (__CORTEX_SC >= 300U) + __ASM volatile ("rbit %0, %1" : "=r" (result) : "r" (value) ); +#else + int32_t s = 4 /*sizeof(v)*/ * 8 - 1; /* extra shift needed at end */ + + result = value; /* r will be reversed bits of v; first get LSB of v */ + for (value >>= 1U; value; value >>= 1U) + { + result <<= 1U; + result |= value & 1U; + s--; + } + result <<= s; /* shift when v's highest bits are zero */ +#endif + return(result); +} + + +/** + \brief Count leading zeros + \details Counts the number of leading zeros of a data value. + \param [in] value Value to count the leading zeros + \return number of leading zeros in value + */ +#define __CLZ __builtin_clz + + +#if (__CORTEX_M >= 0x03U) || (__CORTEX_SC >= 300U) + +/** + \brief LDR Exclusive (8 bit) + \details Executes a exclusive LDR instruction for 8 bit value. + \param [in] ptr Pointer to data + \return value of type uint8_t at (*ptr) + */ +__attribute__((always_inline)) __STATIC_INLINE uint8_t __LDREXB(volatile uint8_t *addr) +{ + uint32_t result; + +#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) + __ASM volatile ("ldrexb %0, %1" : "=r" (result) : "Q" (*addr) ); +#else + /* Prior to GCC 4.8, "Q" will be expanded to [rx, #0] which is not + accepted by assembler. So has to use following less efficient pattern. + */ + __ASM volatile ("ldrexb %0, [%1]" : "=r" (result) : "r" (addr) : "memory" ); +#endif + return ((uint8_t) result); /* Add explicit type cast here */ +} + + +/** + \brief LDR Exclusive (16 bit) + \details Executes a exclusive LDR instruction for 16 bit values. + \param [in] ptr Pointer to data + \return value of type uint16_t at (*ptr) + */ +__attribute__((always_inline)) __STATIC_INLINE uint16_t __LDREXH(volatile uint16_t *addr) +{ + uint32_t result; + +#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) + __ASM volatile ("ldrexh %0, %1" : "=r" (result) : "Q" (*addr) ); +#else + /* Prior to GCC 4.8, "Q" will be expanded to [rx, #0] which is not + accepted by assembler. So has to use following less efficient pattern. + */ + __ASM volatile ("ldrexh %0, [%1]" : "=r" (result) : "r" (addr) : "memory" ); +#endif + return ((uint16_t) result); /* Add explicit type cast here */ +} + + +/** + \brief LDR Exclusive (32 bit) + \details Executes a exclusive LDR instruction for 32 bit values. + \param [in] ptr Pointer to data + \return value of type uint32_t at (*ptr) + */ +__attribute__((always_inline)) __STATIC_INLINE uint32_t __LDREXW(volatile uint32_t *addr) +{ + uint32_t result; + + __ASM volatile ("ldrex %0, %1" : "=r" (result) : "Q" (*addr) ); + return(result); +} + + +/** + \brief STR Exclusive (8 bit) + \details Executes a exclusive STR instruction for 8 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +__attribute__((always_inline)) __STATIC_INLINE uint32_t __STREXB(uint8_t value, volatile uint8_t *addr) +{ + uint32_t result; + + __ASM volatile ("strexb %0, %2, %1" : "=&r" (result), "=Q" (*addr) : "r" ((uint32_t)value) ); + return(result); +} + + +/** + \brief STR Exclusive (16 bit) + \details Executes a exclusive STR instruction for 16 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +__attribute__((always_inline)) __STATIC_INLINE uint32_t __STREXH(uint16_t value, volatile uint16_t *addr) +{ + uint32_t result; + + __ASM volatile ("strexh %0, %2, %1" : "=&r" (result), "=Q" (*addr) : "r" ((uint32_t)value) ); + return(result); +} + + +/** + \brief STR Exclusive (32 bit) + \details Executes a exclusive STR instruction for 32 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +__attribute__((always_inline)) __STATIC_INLINE uint32_t __STREXW(uint32_t value, volatile uint32_t *addr) +{ + uint32_t result; + + __ASM volatile ("strex %0, %2, %1" : "=&r" (result), "=Q" (*addr) : "r" (value) ); + return(result); +} + + +/** + \brief Remove the exclusive lock + \details Removes the exclusive lock which is created by LDREX. + */ +__attribute__((always_inline)) __STATIC_INLINE void __CLREX(void) +{ + __ASM volatile ("clrex" ::: "memory"); +} + + +/** + \brief Signed Saturate + \details Saturates a signed value. + \param [in] value Value to be saturated + \param [in] sat Bit position to saturate to (1..32) + \return Saturated value + */ +#define __SSAT(ARG1,ARG2) \ +({ \ + uint32_t __RES, __ARG1 = (ARG1); \ + __ASM ("ssat %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ + __RES; \ + }) + + +/** + \brief Unsigned Saturate + \details Saturates an unsigned value. + \param [in] value Value to be saturated + \param [in] sat Bit position to saturate to (0..31) + \return Saturated value + */ +#define __USAT(ARG1,ARG2) \ +({ \ + uint32_t __RES, __ARG1 = (ARG1); \ + __ASM ("usat %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ + __RES; \ + }) + + +/** + \brief Rotate Right with Extend (32 bit) + \details Moves each bit of a bitstring right by one bit. + The carry input is shifted in at the left end of the bitstring. + \param [in] value Value to rotate + \return Rotated value + */ +__attribute__((always_inline)) __STATIC_INLINE uint32_t __RRX(uint32_t value) +{ + uint32_t result; + + __ASM volatile ("rrx %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); + return(result); +} + + +/** + \brief LDRT Unprivileged (8 bit) + \details Executes a Unprivileged LDRT instruction for 8 bit value. + \param [in] ptr Pointer to data + \return value of type uint8_t at (*ptr) + */ +__attribute__((always_inline)) __STATIC_INLINE uint8_t __LDRBT(volatile uint8_t *addr) +{ + uint32_t result; + +#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) + __ASM volatile ("ldrbt %0, %1" : "=r" (result) : "Q" (*addr) ); +#else + /* Prior to GCC 4.8, "Q" will be expanded to [rx, #0] which is not + accepted by assembler. So has to use following less efficient pattern. + */ + __ASM volatile ("ldrbt %0, [%1]" : "=r" (result) : "r" (addr) : "memory" ); +#endif + return ((uint8_t) result); /* Add explicit type cast here */ +} + + +/** + \brief LDRT Unprivileged (16 bit) + \details Executes a Unprivileged LDRT instruction for 16 bit values. + \param [in] ptr Pointer to data + \return value of type uint16_t at (*ptr) + */ +__attribute__((always_inline)) __STATIC_INLINE uint16_t __LDRHT(volatile uint16_t *addr) +{ + uint32_t result; + +#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) + __ASM volatile ("ldrht %0, %1" : "=r" (result) : "Q" (*addr) ); +#else + /* Prior to GCC 4.8, "Q" will be expanded to [rx, #0] which is not + accepted by assembler. So has to use following less efficient pattern. + */ + __ASM volatile ("ldrht %0, [%1]" : "=r" (result) : "r" (addr) : "memory" ); +#endif + return ((uint16_t) result); /* Add explicit type cast here */ +} + + +/** + \brief LDRT Unprivileged (32 bit) + \details Executes a Unprivileged LDRT instruction for 32 bit values. + \param [in] ptr Pointer to data + \return value of type uint32_t at (*ptr) + */ +__attribute__((always_inline)) __STATIC_INLINE uint32_t __LDRT(volatile uint32_t *addr) +{ + uint32_t result; + + __ASM volatile ("ldrt %0, %1" : "=r" (result) : "Q" (*addr) ); + return(result); +} + + +/** + \brief STRT Unprivileged (8 bit) + \details Executes a Unprivileged STRT instruction for 8 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + */ +__attribute__((always_inline)) __STATIC_INLINE void __STRBT(uint8_t value, volatile uint8_t *addr) +{ + __ASM volatile ("strbt %1, %0" : "=Q" (*addr) : "r" ((uint32_t)value) ); +} + + +/** + \brief STRT Unprivileged (16 bit) + \details Executes a Unprivileged STRT instruction for 16 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + */ +__attribute__((always_inline)) __STATIC_INLINE void __STRHT(uint16_t value, volatile uint16_t *addr) +{ + __ASM volatile ("strht %1, %0" : "=Q" (*addr) : "r" ((uint32_t)value) ); +} + + +/** + \brief STRT Unprivileged (32 bit) + \details Executes a Unprivileged STRT instruction for 32 bit values. + \param [in] value Value to store + \param [in] ptr Pointer to location + */ +__attribute__((always_inline)) __STATIC_INLINE void __STRT(uint32_t value, volatile uint32_t *addr) +{ + __ASM volatile ("strt %1, %0" : "=Q" (*addr) : "r" (value) ); +} + +#endif /* (__CORTEX_M >= 0x03U) || (__CORTEX_SC >= 300U) */ + +/*@}*/ /* end of group CMSIS_Core_InstructionInterface */ + + +/* ################### Compiler specific Intrinsics ########################### */ +/** \defgroup CMSIS_SIMD_intrinsics CMSIS SIMD Intrinsics + Access to dedicated SIMD instructions + @{ +*/ + +#if (__CORTEX_M >= 0x04U) /* only for Cortex-M4 and above */ + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SADD8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("sadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __QADD8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("qadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SHADD8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("shadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UADD8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UQADD8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uqadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UHADD8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uhadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SSUB8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("ssub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __QSUB8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("qsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SHSUB8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("shsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __USUB8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("usub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UQSUB8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uqsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UHSUB8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uhsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SADD16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("sadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __QADD16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("qadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SHADD16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("shadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UADD16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UQADD16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uqadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UHADD16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uhadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SSUB16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("ssub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __QSUB16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("qsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SHSUB16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("shsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __USUB16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("usub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UQSUB16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uqsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UHSUB16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uhsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SASX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("sasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __QASX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("qasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SHASX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("shasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UASX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UQASX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uqasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UHASX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uhasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SSAX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("ssax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __QSAX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("qsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SHSAX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("shsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __USAX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("usax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UQSAX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uqsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UHSAX(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uhsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __USAD8(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("usad8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __USADA8(uint32_t op1, uint32_t op2, uint32_t op3) +{ + uint32_t result; + + __ASM volatile ("usada8 %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); + return(result); +} + +#define __SSAT16(ARG1,ARG2) \ +({ \ + int32_t __RES, __ARG1 = (ARG1); \ + __ASM ("ssat16 %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ + __RES; \ + }) + +#define __USAT16(ARG1,ARG2) \ +({ \ + uint32_t __RES, __ARG1 = (ARG1); \ + __ASM ("usat16 %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ + __RES; \ + }) + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UXTB16(uint32_t op1) +{ + uint32_t result; + + __ASM volatile ("uxtb16 %0, %1" : "=r" (result) : "r" (op1)); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UXTAB16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("uxtab16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SXTB16(uint32_t op1) +{ + uint32_t result; + + __ASM volatile ("sxtb16 %0, %1" : "=r" (result) : "r" (op1)); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SXTAB16(uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("sxtab16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SMUAD (uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("smuad %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SMUADX (uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("smuadx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SMLAD (uint32_t op1, uint32_t op2, uint32_t op3) +{ + uint32_t result; + + __ASM volatile ("smlad %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SMLADX (uint32_t op1, uint32_t op2, uint32_t op3) +{ + uint32_t result; + + __ASM volatile ("smladx %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint64_t __SMLALD (uint32_t op1, uint32_t op2, uint64_t acc) +{ + union llreg_u{ + uint32_t w32[2]; + uint64_t w64; + } llr; + llr.w64 = acc; + +#ifndef __ARMEB__ /* Little endian */ + __ASM volatile ("smlald %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); +#else /* Big endian */ + __ASM volatile ("smlald %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); +#endif + + return(llr.w64); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint64_t __SMLALDX (uint32_t op1, uint32_t op2, uint64_t acc) +{ + union llreg_u{ + uint32_t w32[2]; + uint64_t w64; + } llr; + llr.w64 = acc; + +#ifndef __ARMEB__ /* Little endian */ + __ASM volatile ("smlaldx %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); +#else /* Big endian */ + __ASM volatile ("smlaldx %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); +#endif + + return(llr.w64); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SMUSD (uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("smusd %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SMUSDX (uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("smusdx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SMLSD (uint32_t op1, uint32_t op2, uint32_t op3) +{ + uint32_t result; + + __ASM volatile ("smlsd %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SMLSDX (uint32_t op1, uint32_t op2, uint32_t op3) +{ + uint32_t result; + + __ASM volatile ("smlsdx %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint64_t __SMLSLD (uint32_t op1, uint32_t op2, uint64_t acc) +{ + union llreg_u{ + uint32_t w32[2]; + uint64_t w64; + } llr; + llr.w64 = acc; + +#ifndef __ARMEB__ /* Little endian */ + __ASM volatile ("smlsld %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); +#else /* Big endian */ + __ASM volatile ("smlsld %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); +#endif + + return(llr.w64); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint64_t __SMLSLDX (uint32_t op1, uint32_t op2, uint64_t acc) +{ + union llreg_u{ + uint32_t w32[2]; + uint64_t w64; + } llr; + llr.w64 = acc; + +#ifndef __ARMEB__ /* Little endian */ + __ASM volatile ("smlsldx %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); +#else /* Big endian */ + __ASM volatile ("smlsldx %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); +#endif + + return(llr.w64); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SEL (uint32_t op1, uint32_t op2) +{ + uint32_t result; + + __ASM volatile ("sel %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE int32_t __QADD( int32_t op1, int32_t op2) +{ + int32_t result; + + __ASM volatile ("qadd %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +__attribute__( ( always_inline ) ) __STATIC_INLINE int32_t __QSUB( int32_t op1, int32_t op2) +{ + int32_t result; + + __ASM volatile ("qsub %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); + return(result); +} + +#define __PKHBT(ARG1,ARG2,ARG3) \ +({ \ + uint32_t __RES, __ARG1 = (ARG1), __ARG2 = (ARG2); \ + __ASM ("pkhbt %0, %1, %2, lsl %3" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2), "I" (ARG3) ); \ + __RES; \ + }) + +#define __PKHTB(ARG1,ARG2,ARG3) \ +({ \ + uint32_t __RES, __ARG1 = (ARG1), __ARG2 = (ARG2); \ + if (ARG3 == 0) \ + __ASM ("pkhtb %0, %1, %2" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2) ); \ + else \ + __ASM ("pkhtb %0, %1, %2, asr %3" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2), "I" (ARG3) ); \ + __RES; \ + }) + +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SMMLA (int32_t op1, int32_t op2, int32_t op3) +{ + int32_t result; + + __ASM volatile ("smmla %0, %1, %2, %3" : "=r" (result): "r" (op1), "r" (op2), "r" (op3) ); + return(result); +} + +#endif /* (__CORTEX_M >= 0x04) */ +/*@} end of group CMSIS_SIMD_intrinsics */ + + +#if defined ( __GNUC__ ) +#pragma GCC diagnostic pop +#endif + +#endif /* __CMSIS_GCC_H */ diff --git a/panda/board/inc/core_cm3.h b/panda/board/inc/core_cm3.h new file mode 100644 index 00000000000000..b4ac4c7b05a799 --- /dev/null +++ b/panda/board/inc/core_cm3.h @@ -0,0 +1,1763 @@ +/**************************************************************************//** + * @file core_cm3.h + * @brief CMSIS Cortex-M3 Core Peripheral Access Layer Header File + * @version V4.30 + * @date 20. October 2015 + ******************************************************************************/ +/* Copyright (c) 2009 - 2015 ARM LIMITED + + All rights reserved. + Redistribution and use in source and binary forms, with or without + modification, are permitted provided that the following conditions are met: + - Redistributions of source code must retain the above copyright + notice, this list of conditions and the following disclaimer. + - Redistributions in binary form must reproduce the above copyright + notice, this list of conditions and the following disclaimer in the + documentation and/or other materials provided with the distribution. + - Neither the name of ARM nor the names of its contributors may be used + to endorse or promote products derived from this software without + specific prior written permission. + * + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE + LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + POSSIBILITY OF SUCH DAMAGE. + ---------------------------------------------------------------------------*/ + + +#if defined ( __ICCARM__ ) + #pragma system_include /* treat file as system include file for MISRA check */ +#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) + #pragma clang system_header /* treat file as system include file */ +#endif + +#ifndef __CORE_CM3_H_GENERIC +#define __CORE_CM3_H_GENERIC + +#include + +#ifdef __cplusplus + extern "C" { +#endif + +/** + \page CMSIS_MISRA_Exceptions MISRA-C:2004 Compliance Exceptions + CMSIS violates the following MISRA-C:2004 rules: + + \li Required Rule 8.5, object/function definition in header file.
+ Function definitions in header files are used to allow 'inlining'. + + \li Required Rule 18.4, declaration of union type or object of union type: '{...}'.
+ Unions are used for effective representation of core registers. + + \li Advisory Rule 19.7, Function-like macro defined.
+ Function-like macros are used to allow more efficient code. + */ + + +/******************************************************************************* + * CMSIS definitions + ******************************************************************************/ +/** + \ingroup Cortex_M3 + @{ + */ + +/* CMSIS CM3 definitions */ +#define __CM3_CMSIS_VERSION_MAIN (0x04U) /*!< [31:16] CMSIS HAL main version */ +#define __CM3_CMSIS_VERSION_SUB (0x1EU) /*!< [15:0] CMSIS HAL sub version */ +#define __CM3_CMSIS_VERSION ((__CM3_CMSIS_VERSION_MAIN << 16U) | \ + __CM3_CMSIS_VERSION_SUB ) /*!< CMSIS HAL version number */ + +#define __CORTEX_M (0x03U) /*!< Cortex-M Core */ + + +#if defined ( __CC_ARM ) + #define __ASM __asm /*!< asm keyword for ARM Compiler */ + #define __INLINE __inline /*!< inline keyword for ARM Compiler */ + #define __STATIC_INLINE static __inline + +#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) + #define __ASM __asm /*!< asm keyword for ARM Compiler */ + #define __INLINE __inline /*!< inline keyword for ARM Compiler */ + #define __STATIC_INLINE static __inline + +#elif defined ( __GNUC__ ) + #define __ASM __asm /*!< asm keyword for GNU Compiler */ + #define __INLINE inline /*!< inline keyword for GNU Compiler */ + #define __STATIC_INLINE static inline + +#elif defined ( __ICCARM__ ) + #define __ASM __asm /*!< asm keyword for IAR Compiler */ + #define __INLINE inline /*!< inline keyword for IAR Compiler. Only available in High optimization mode! */ + #define __STATIC_INLINE static inline + +#elif defined ( __TMS470__ ) + #define __ASM __asm /*!< asm keyword for TI CCS Compiler */ + #define __STATIC_INLINE static inline + +#elif defined ( __TASKING__ ) + #define __ASM __asm /*!< asm keyword for TASKING Compiler */ + #define __INLINE inline /*!< inline keyword for TASKING Compiler */ + #define __STATIC_INLINE static inline + +#elif defined ( __CSMC__ ) + #define __packed + #define __ASM _asm /*!< asm keyword for COSMIC Compiler */ + #define __INLINE inline /*!< inline keyword for COSMIC Compiler. Use -pc99 on compile line */ + #define __STATIC_INLINE static inline + +#else + #error Unknown compiler +#endif + +/** __FPU_USED indicates whether an FPU is used or not. + This core does not support an FPU at all +*/ +#define __FPU_USED 0U + +#if defined ( __CC_ARM ) + #if defined __TARGET_FPU_VFP + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) + #if defined __ARM_PCS_VFP + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#elif defined ( __GNUC__ ) + #if defined (__VFP_FP__) && !defined(__SOFTFP__) + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#elif defined ( __ICCARM__ ) + #if defined __ARMVFP__ + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#elif defined ( __TMS470__ ) + #if defined __TI_VFP_SUPPORT__ + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#elif defined ( __TASKING__ ) + #if defined __FPU_VFP__ + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#elif defined ( __CSMC__ ) + #if ( __CSMC__ & 0x400U) + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#endif + +#include "core_cmInstr.h" /* Core Instruction Access */ +#include "core_cmFunc.h" /* Core Function Access */ + +#ifdef __cplusplus +} +#endif + +#endif /* __CORE_CM3_H_GENERIC */ + +#ifndef __CMSIS_GENERIC + +#ifndef __CORE_CM3_H_DEPENDANT +#define __CORE_CM3_H_DEPENDANT + +#ifdef __cplusplus + extern "C" { +#endif + +/* check device defines and use defaults */ +#if defined __CHECK_DEVICE_DEFINES + #ifndef __CM3_REV + #define __CM3_REV 0x0200U + #warning "__CM3_REV not defined in device header file; using default!" + #endif + + #ifndef __MPU_PRESENT + #define __MPU_PRESENT 0U + #warning "__MPU_PRESENT not defined in device header file; using default!" + #endif + + #ifndef __NVIC_PRIO_BITS + #define __NVIC_PRIO_BITS 4U + #warning "__NVIC_PRIO_BITS not defined in device header file; using default!" + #endif + + #ifndef __Vendor_SysTickConfig + #define __Vendor_SysTickConfig 0U + #warning "__Vendor_SysTickConfig not defined in device header file; using default!" + #endif +#endif + +/* IO definitions (access restrictions to peripheral registers) */ +/** + \defgroup CMSIS_glob_defs CMSIS Global Defines + + IO Type Qualifiers are used + \li to specify the access to peripheral variables. + \li for automatic generation of peripheral register debug information. +*/ +#ifdef __cplusplus + #define __I volatile /*!< Defines 'read only' permissions */ +#else + #define __I volatile const /*!< Defines 'read only' permissions */ +#endif +#define __O volatile /*!< Defines 'write only' permissions */ +#define __IO volatile /*!< Defines 'read / write' permissions */ + +/* following defines should be used for structure members */ +#define __IM volatile const /*! Defines 'read only' structure member permissions */ +#define __OM volatile /*! Defines 'write only' structure member permissions */ +#define __IOM volatile /*! Defines 'read / write' structure member permissions */ + +/*@} end of group Cortex_M3 */ + + + +/******************************************************************************* + * Register Abstraction + Core Register contain: + - Core Register + - Core NVIC Register + - Core SCB Register + - Core SysTick Register + - Core Debug Register + - Core MPU Register + ******************************************************************************/ +/** + \defgroup CMSIS_core_register Defines and Type Definitions + \brief Type definitions and defines for Cortex-M processor based devices. +*/ + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_CORE Status and Control Registers + \brief Core Register type definitions. + @{ + */ + +/** + \brief Union type to access the Application Program Status Register (APSR). + */ +typedef union +{ + struct + { + uint32_t _reserved0:27; /*!< bit: 0..26 Reserved */ + uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ + uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ + uint32_t C:1; /*!< bit: 29 Carry condition code flag */ + uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ + uint32_t N:1; /*!< bit: 31 Negative condition code flag */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} APSR_Type; + +/* APSR Register Definitions */ +#define APSR_N_Pos 31U /*!< APSR: N Position */ +#define APSR_N_Msk (1UL << APSR_N_Pos) /*!< APSR: N Mask */ + +#define APSR_Z_Pos 30U /*!< APSR: Z Position */ +#define APSR_Z_Msk (1UL << APSR_Z_Pos) /*!< APSR: Z Mask */ + +#define APSR_C_Pos 29U /*!< APSR: C Position */ +#define APSR_C_Msk (1UL << APSR_C_Pos) /*!< APSR: C Mask */ + +#define APSR_V_Pos 28U /*!< APSR: V Position */ +#define APSR_V_Msk (1UL << APSR_V_Pos) /*!< APSR: V Mask */ + +#define APSR_Q_Pos 27U /*!< APSR: Q Position */ +#define APSR_Q_Msk (1UL << APSR_Q_Pos) /*!< APSR: Q Mask */ + + +/** + \brief Union type to access the Interrupt Program Status Register (IPSR). + */ +typedef union +{ + struct + { + uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ + uint32_t _reserved0:23; /*!< bit: 9..31 Reserved */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} IPSR_Type; + +/* IPSR Register Definitions */ +#define IPSR_ISR_Pos 0U /*!< IPSR: ISR Position */ +#define IPSR_ISR_Msk (0x1FFUL /*<< IPSR_ISR_Pos*/) /*!< IPSR: ISR Mask */ + + +/** + \brief Union type to access the Special-Purpose Program Status Registers (xPSR). + */ +typedef union +{ + struct + { + uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ + uint32_t _reserved0:15; /*!< bit: 9..23 Reserved */ + uint32_t T:1; /*!< bit: 24 Thumb bit (read 0) */ + uint32_t IT:2; /*!< bit: 25..26 saved IT state (read 0) */ + uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ + uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ + uint32_t C:1; /*!< bit: 29 Carry condition code flag */ + uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ + uint32_t N:1; /*!< bit: 31 Negative condition code flag */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} xPSR_Type; + +/* xPSR Register Definitions */ +#define xPSR_N_Pos 31U /*!< xPSR: N Position */ +#define xPSR_N_Msk (1UL << xPSR_N_Pos) /*!< xPSR: N Mask */ + +#define xPSR_Z_Pos 30U /*!< xPSR: Z Position */ +#define xPSR_Z_Msk (1UL << xPSR_Z_Pos) /*!< xPSR: Z Mask */ + +#define xPSR_C_Pos 29U /*!< xPSR: C Position */ +#define xPSR_C_Msk (1UL << xPSR_C_Pos) /*!< xPSR: C Mask */ + +#define xPSR_V_Pos 28U /*!< xPSR: V Position */ +#define xPSR_V_Msk (1UL << xPSR_V_Pos) /*!< xPSR: V Mask */ + +#define xPSR_Q_Pos 27U /*!< xPSR: Q Position */ +#define xPSR_Q_Msk (1UL << xPSR_Q_Pos) /*!< xPSR: Q Mask */ + +#define xPSR_IT_Pos 25U /*!< xPSR: IT Position */ +#define xPSR_IT_Msk (3UL << xPSR_IT_Pos) /*!< xPSR: IT Mask */ + +#define xPSR_T_Pos 24U /*!< xPSR: T Position */ +#define xPSR_T_Msk (1UL << xPSR_T_Pos) /*!< xPSR: T Mask */ + +#define xPSR_ISR_Pos 0U /*!< xPSR: ISR Position */ +#define xPSR_ISR_Msk (0x1FFUL /*<< xPSR_ISR_Pos*/) /*!< xPSR: ISR Mask */ + + +/** + \brief Union type to access the Control Registers (CONTROL). + */ +typedef union +{ + struct + { + uint32_t nPRIV:1; /*!< bit: 0 Execution privilege in Thread mode */ + uint32_t SPSEL:1; /*!< bit: 1 Stack to be used */ + uint32_t _reserved1:30; /*!< bit: 2..31 Reserved */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} CONTROL_Type; + +/* CONTROL Register Definitions */ +#define CONTROL_SPSEL_Pos 1U /*!< CONTROL: SPSEL Position */ +#define CONTROL_SPSEL_Msk (1UL << CONTROL_SPSEL_Pos) /*!< CONTROL: SPSEL Mask */ + +#define CONTROL_nPRIV_Pos 0U /*!< CONTROL: nPRIV Position */ +#define CONTROL_nPRIV_Msk (1UL /*<< CONTROL_nPRIV_Pos*/) /*!< CONTROL: nPRIV Mask */ + +/*@} end of group CMSIS_CORE */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_NVIC Nested Vectored Interrupt Controller (NVIC) + \brief Type definitions for the NVIC Registers + @{ + */ + +/** + \brief Structure type to access the Nested Vectored Interrupt Controller (NVIC). + */ +typedef struct +{ + __IOM uint32_t ISER[8U]; /*!< Offset: 0x000 (R/W) Interrupt Set Enable Register */ + uint32_t RESERVED0[24U]; + __IOM uint32_t ICER[8U]; /*!< Offset: 0x080 (R/W) Interrupt Clear Enable Register */ + uint32_t RSERVED1[24U]; + __IOM uint32_t ISPR[8U]; /*!< Offset: 0x100 (R/W) Interrupt Set Pending Register */ + uint32_t RESERVED2[24U]; + __IOM uint32_t ICPR[8U]; /*!< Offset: 0x180 (R/W) Interrupt Clear Pending Register */ + uint32_t RESERVED3[24U]; + __IOM uint32_t IABR[8U]; /*!< Offset: 0x200 (R/W) Interrupt Active bit Register */ + uint32_t RESERVED4[56U]; + __IOM uint8_t IP[240U]; /*!< Offset: 0x300 (R/W) Interrupt Priority Register (8Bit wide) */ + uint32_t RESERVED5[644U]; + __OM uint32_t STIR; /*!< Offset: 0xE00 ( /W) Software Trigger Interrupt Register */ +} NVIC_Type; + +/* Software Triggered Interrupt Register Definitions */ +#define NVIC_STIR_INTID_Pos 0U /*!< STIR: INTLINESNUM Position */ +#define NVIC_STIR_INTID_Msk (0x1FFUL /*<< NVIC_STIR_INTID_Pos*/) /*!< STIR: INTLINESNUM Mask */ + +/*@} end of group CMSIS_NVIC */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_SCB System Control Block (SCB) + \brief Type definitions for the System Control Block Registers + @{ + */ + +/** + \brief Structure type to access the System Control Block (SCB). + */ +typedef struct +{ + __IM uint32_t CPUID; /*!< Offset: 0x000 (R/ ) CPUID Base Register */ + __IOM uint32_t ICSR; /*!< Offset: 0x004 (R/W) Interrupt Control and State Register */ + __IOM uint32_t VTOR; /*!< Offset: 0x008 (R/W) Vector Table Offset Register */ + __IOM uint32_t AIRCR; /*!< Offset: 0x00C (R/W) Application Interrupt and Reset Control Register */ + __IOM uint32_t SCR; /*!< Offset: 0x010 (R/W) System Control Register */ + __IOM uint32_t CCR; /*!< Offset: 0x014 (R/W) Configuration Control Register */ + __IOM uint8_t SHP[12U]; /*!< Offset: 0x018 (R/W) System Handlers Priority Registers (4-7, 8-11, 12-15) */ + __IOM uint32_t SHCSR; /*!< Offset: 0x024 (R/W) System Handler Control and State Register */ + __IOM uint32_t CFSR; /*!< Offset: 0x028 (R/W) Configurable Fault Status Register */ + __IOM uint32_t HFSR; /*!< Offset: 0x02C (R/W) HardFault Status Register */ + __IOM uint32_t DFSR; /*!< Offset: 0x030 (R/W) Debug Fault Status Register */ + __IOM uint32_t MMFAR; /*!< Offset: 0x034 (R/W) MemManage Fault Address Register */ + __IOM uint32_t BFAR; /*!< Offset: 0x038 (R/W) BusFault Address Register */ + __IOM uint32_t AFSR; /*!< Offset: 0x03C (R/W) Auxiliary Fault Status Register */ + __IM uint32_t PFR[2U]; /*!< Offset: 0x040 (R/ ) Processor Feature Register */ + __IM uint32_t DFR; /*!< Offset: 0x048 (R/ ) Debug Feature Register */ + __IM uint32_t ADR; /*!< Offset: 0x04C (R/ ) Auxiliary Feature Register */ + __IM uint32_t MMFR[4U]; /*!< Offset: 0x050 (R/ ) Memory Model Feature Register */ + __IM uint32_t ISAR[5U]; /*!< Offset: 0x060 (R/ ) Instruction Set Attributes Register */ + uint32_t RESERVED0[5U]; + __IOM uint32_t CPACR; /*!< Offset: 0x088 (R/W) Coprocessor Access Control Register */ +} SCB_Type; + +/* SCB CPUID Register Definitions */ +#define SCB_CPUID_IMPLEMENTER_Pos 24U /*!< SCB CPUID: IMPLEMENTER Position */ +#define SCB_CPUID_IMPLEMENTER_Msk (0xFFUL << SCB_CPUID_IMPLEMENTER_Pos) /*!< SCB CPUID: IMPLEMENTER Mask */ + +#define SCB_CPUID_VARIANT_Pos 20U /*!< SCB CPUID: VARIANT Position */ +#define SCB_CPUID_VARIANT_Msk (0xFUL << SCB_CPUID_VARIANT_Pos) /*!< SCB CPUID: VARIANT Mask */ + +#define SCB_CPUID_ARCHITECTURE_Pos 16U /*!< SCB CPUID: ARCHITECTURE Position */ +#define SCB_CPUID_ARCHITECTURE_Msk (0xFUL << SCB_CPUID_ARCHITECTURE_Pos) /*!< SCB CPUID: ARCHITECTURE Mask */ + +#define SCB_CPUID_PARTNO_Pos 4U /*!< SCB CPUID: PARTNO Position */ +#define SCB_CPUID_PARTNO_Msk (0xFFFUL << SCB_CPUID_PARTNO_Pos) /*!< SCB CPUID: PARTNO Mask */ + +#define SCB_CPUID_REVISION_Pos 0U /*!< SCB CPUID: REVISION Position */ +#define SCB_CPUID_REVISION_Msk (0xFUL /*<< SCB_CPUID_REVISION_Pos*/) /*!< SCB CPUID: REVISION Mask */ + +/* SCB Interrupt Control State Register Definitions */ +#define SCB_ICSR_NMIPENDSET_Pos 31U /*!< SCB ICSR: NMIPENDSET Position */ +#define SCB_ICSR_NMIPENDSET_Msk (1UL << SCB_ICSR_NMIPENDSET_Pos) /*!< SCB ICSR: NMIPENDSET Mask */ + +#define SCB_ICSR_PENDSVSET_Pos 28U /*!< SCB ICSR: PENDSVSET Position */ +#define SCB_ICSR_PENDSVSET_Msk (1UL << SCB_ICSR_PENDSVSET_Pos) /*!< SCB ICSR: PENDSVSET Mask */ + +#define SCB_ICSR_PENDSVCLR_Pos 27U /*!< SCB ICSR: PENDSVCLR Position */ +#define SCB_ICSR_PENDSVCLR_Msk (1UL << SCB_ICSR_PENDSVCLR_Pos) /*!< SCB ICSR: PENDSVCLR Mask */ + +#define SCB_ICSR_PENDSTSET_Pos 26U /*!< SCB ICSR: PENDSTSET Position */ +#define SCB_ICSR_PENDSTSET_Msk (1UL << SCB_ICSR_PENDSTSET_Pos) /*!< SCB ICSR: PENDSTSET Mask */ + +#define SCB_ICSR_PENDSTCLR_Pos 25U /*!< SCB ICSR: PENDSTCLR Position */ +#define SCB_ICSR_PENDSTCLR_Msk (1UL << SCB_ICSR_PENDSTCLR_Pos) /*!< SCB ICSR: PENDSTCLR Mask */ + +#define SCB_ICSR_ISRPREEMPT_Pos 23U /*!< SCB ICSR: ISRPREEMPT Position */ +#define SCB_ICSR_ISRPREEMPT_Msk (1UL << SCB_ICSR_ISRPREEMPT_Pos) /*!< SCB ICSR: ISRPREEMPT Mask */ + +#define SCB_ICSR_ISRPENDING_Pos 22U /*!< SCB ICSR: ISRPENDING Position */ +#define SCB_ICSR_ISRPENDING_Msk (1UL << SCB_ICSR_ISRPENDING_Pos) /*!< SCB ICSR: ISRPENDING Mask */ + +#define SCB_ICSR_VECTPENDING_Pos 12U /*!< SCB ICSR: VECTPENDING Position */ +#define SCB_ICSR_VECTPENDING_Msk (0x1FFUL << SCB_ICSR_VECTPENDING_Pos) /*!< SCB ICSR: VECTPENDING Mask */ + +#define SCB_ICSR_RETTOBASE_Pos 11U /*!< SCB ICSR: RETTOBASE Position */ +#define SCB_ICSR_RETTOBASE_Msk (1UL << SCB_ICSR_RETTOBASE_Pos) /*!< SCB ICSR: RETTOBASE Mask */ + +#define SCB_ICSR_VECTACTIVE_Pos 0U /*!< SCB ICSR: VECTACTIVE Position */ +#define SCB_ICSR_VECTACTIVE_Msk (0x1FFUL /*<< SCB_ICSR_VECTACTIVE_Pos*/) /*!< SCB ICSR: VECTACTIVE Mask */ + +/* SCB Vector Table Offset Register Definitions */ +#if (__CM3_REV < 0x0201U) /* core r2p1 */ +#define SCB_VTOR_TBLBASE_Pos 29U /*!< SCB VTOR: TBLBASE Position */ +#define SCB_VTOR_TBLBASE_Msk (1UL << SCB_VTOR_TBLBASE_Pos) /*!< SCB VTOR: TBLBASE Mask */ + +#define SCB_VTOR_TBLOFF_Pos 7U /*!< SCB VTOR: TBLOFF Position */ +#define SCB_VTOR_TBLOFF_Msk (0x3FFFFFUL << SCB_VTOR_TBLOFF_Pos) /*!< SCB VTOR: TBLOFF Mask */ +#else +#define SCB_VTOR_TBLOFF_Pos 7U /*!< SCB VTOR: TBLOFF Position */ +#define SCB_VTOR_TBLOFF_Msk (0x1FFFFFFUL << SCB_VTOR_TBLOFF_Pos) /*!< SCB VTOR: TBLOFF Mask */ +#endif + +/* SCB Application Interrupt and Reset Control Register Definitions */ +#define SCB_AIRCR_VECTKEY_Pos 16U /*!< SCB AIRCR: VECTKEY Position */ +#define SCB_AIRCR_VECTKEY_Msk (0xFFFFUL << SCB_AIRCR_VECTKEY_Pos) /*!< SCB AIRCR: VECTKEY Mask */ + +#define SCB_AIRCR_VECTKEYSTAT_Pos 16U /*!< SCB AIRCR: VECTKEYSTAT Position */ +#define SCB_AIRCR_VECTKEYSTAT_Msk (0xFFFFUL << SCB_AIRCR_VECTKEYSTAT_Pos) /*!< SCB AIRCR: VECTKEYSTAT Mask */ + +#define SCB_AIRCR_ENDIANESS_Pos 15U /*!< SCB AIRCR: ENDIANESS Position */ +#define SCB_AIRCR_ENDIANESS_Msk (1UL << SCB_AIRCR_ENDIANESS_Pos) /*!< SCB AIRCR: ENDIANESS Mask */ + +#define SCB_AIRCR_PRIGROUP_Pos 8U /*!< SCB AIRCR: PRIGROUP Position */ +#define SCB_AIRCR_PRIGROUP_Msk (7UL << SCB_AIRCR_PRIGROUP_Pos) /*!< SCB AIRCR: PRIGROUP Mask */ + +#define SCB_AIRCR_SYSRESETREQ_Pos 2U /*!< SCB AIRCR: SYSRESETREQ Position */ +#define SCB_AIRCR_SYSRESETREQ_Msk (1UL << SCB_AIRCR_SYSRESETREQ_Pos) /*!< SCB AIRCR: SYSRESETREQ Mask */ + +#define SCB_AIRCR_VECTCLRACTIVE_Pos 1U /*!< SCB AIRCR: VECTCLRACTIVE Position */ +#define SCB_AIRCR_VECTCLRACTIVE_Msk (1UL << SCB_AIRCR_VECTCLRACTIVE_Pos) /*!< SCB AIRCR: VECTCLRACTIVE Mask */ + +#define SCB_AIRCR_VECTRESET_Pos 0U /*!< SCB AIRCR: VECTRESET Position */ +#define SCB_AIRCR_VECTRESET_Msk (1UL /*<< SCB_AIRCR_VECTRESET_Pos*/) /*!< SCB AIRCR: VECTRESET Mask */ + +/* SCB System Control Register Definitions */ +#define SCB_SCR_SEVONPEND_Pos 4U /*!< SCB SCR: SEVONPEND Position */ +#define SCB_SCR_SEVONPEND_Msk (1UL << SCB_SCR_SEVONPEND_Pos) /*!< SCB SCR: SEVONPEND Mask */ + +#define SCB_SCR_SLEEPDEEP_Pos 2U /*!< SCB SCR: SLEEPDEEP Position */ +#define SCB_SCR_SLEEPDEEP_Msk (1UL << SCB_SCR_SLEEPDEEP_Pos) /*!< SCB SCR: SLEEPDEEP Mask */ + +#define SCB_SCR_SLEEPONEXIT_Pos 1U /*!< SCB SCR: SLEEPONEXIT Position */ +#define SCB_SCR_SLEEPONEXIT_Msk (1UL << SCB_SCR_SLEEPONEXIT_Pos) /*!< SCB SCR: SLEEPONEXIT Mask */ + +/* SCB Configuration Control Register Definitions */ +#define SCB_CCR_STKALIGN_Pos 9U /*!< SCB CCR: STKALIGN Position */ +#define SCB_CCR_STKALIGN_Msk (1UL << SCB_CCR_STKALIGN_Pos) /*!< SCB CCR: STKALIGN Mask */ + +#define SCB_CCR_BFHFNMIGN_Pos 8U /*!< SCB CCR: BFHFNMIGN Position */ +#define SCB_CCR_BFHFNMIGN_Msk (1UL << SCB_CCR_BFHFNMIGN_Pos) /*!< SCB CCR: BFHFNMIGN Mask */ + +#define SCB_CCR_DIV_0_TRP_Pos 4U /*!< SCB CCR: DIV_0_TRP Position */ +#define SCB_CCR_DIV_0_TRP_Msk (1UL << SCB_CCR_DIV_0_TRP_Pos) /*!< SCB CCR: DIV_0_TRP Mask */ + +#define SCB_CCR_UNALIGN_TRP_Pos 3U /*!< SCB CCR: UNALIGN_TRP Position */ +#define SCB_CCR_UNALIGN_TRP_Msk (1UL << SCB_CCR_UNALIGN_TRP_Pos) /*!< SCB CCR: UNALIGN_TRP Mask */ + +#define SCB_CCR_USERSETMPEND_Pos 1U /*!< SCB CCR: USERSETMPEND Position */ +#define SCB_CCR_USERSETMPEND_Msk (1UL << SCB_CCR_USERSETMPEND_Pos) /*!< SCB CCR: USERSETMPEND Mask */ + +#define SCB_CCR_NONBASETHRDENA_Pos 0U /*!< SCB CCR: NONBASETHRDENA Position */ +#define SCB_CCR_NONBASETHRDENA_Msk (1UL /*<< SCB_CCR_NONBASETHRDENA_Pos*/) /*!< SCB CCR: NONBASETHRDENA Mask */ + +/* SCB System Handler Control and State Register Definitions */ +#define SCB_SHCSR_USGFAULTENA_Pos 18U /*!< SCB SHCSR: USGFAULTENA Position */ +#define SCB_SHCSR_USGFAULTENA_Msk (1UL << SCB_SHCSR_USGFAULTENA_Pos) /*!< SCB SHCSR: USGFAULTENA Mask */ + +#define SCB_SHCSR_BUSFAULTENA_Pos 17U /*!< SCB SHCSR: BUSFAULTENA Position */ +#define SCB_SHCSR_BUSFAULTENA_Msk (1UL << SCB_SHCSR_BUSFAULTENA_Pos) /*!< SCB SHCSR: BUSFAULTENA Mask */ + +#define SCB_SHCSR_MEMFAULTENA_Pos 16U /*!< SCB SHCSR: MEMFAULTENA Position */ +#define SCB_SHCSR_MEMFAULTENA_Msk (1UL << SCB_SHCSR_MEMFAULTENA_Pos) /*!< SCB SHCSR: MEMFAULTENA Mask */ + +#define SCB_SHCSR_SVCALLPENDED_Pos 15U /*!< SCB SHCSR: SVCALLPENDED Position */ +#define SCB_SHCSR_SVCALLPENDED_Msk (1UL << SCB_SHCSR_SVCALLPENDED_Pos) /*!< SCB SHCSR: SVCALLPENDED Mask */ + +#define SCB_SHCSR_BUSFAULTPENDED_Pos 14U /*!< SCB SHCSR: BUSFAULTPENDED Position */ +#define SCB_SHCSR_BUSFAULTPENDED_Msk (1UL << SCB_SHCSR_BUSFAULTPENDED_Pos) /*!< SCB SHCSR: BUSFAULTPENDED Mask */ + +#define SCB_SHCSR_MEMFAULTPENDED_Pos 13U /*!< SCB SHCSR: MEMFAULTPENDED Position */ +#define SCB_SHCSR_MEMFAULTPENDED_Msk (1UL << SCB_SHCSR_MEMFAULTPENDED_Pos) /*!< SCB SHCSR: MEMFAULTPENDED Mask */ + +#define SCB_SHCSR_USGFAULTPENDED_Pos 12U /*!< SCB SHCSR: USGFAULTPENDED Position */ +#define SCB_SHCSR_USGFAULTPENDED_Msk (1UL << SCB_SHCSR_USGFAULTPENDED_Pos) /*!< SCB SHCSR: USGFAULTPENDED Mask */ + +#define SCB_SHCSR_SYSTICKACT_Pos 11U /*!< SCB SHCSR: SYSTICKACT Position */ +#define SCB_SHCSR_SYSTICKACT_Msk (1UL << SCB_SHCSR_SYSTICKACT_Pos) /*!< SCB SHCSR: SYSTICKACT Mask */ + +#define SCB_SHCSR_PENDSVACT_Pos 10U /*!< SCB SHCSR: PENDSVACT Position */ +#define SCB_SHCSR_PENDSVACT_Msk (1UL << SCB_SHCSR_PENDSVACT_Pos) /*!< SCB SHCSR: PENDSVACT Mask */ + +#define SCB_SHCSR_MONITORACT_Pos 8U /*!< SCB SHCSR: MONITORACT Position */ +#define SCB_SHCSR_MONITORACT_Msk (1UL << SCB_SHCSR_MONITORACT_Pos) /*!< SCB SHCSR: MONITORACT Mask */ + +#define SCB_SHCSR_SVCALLACT_Pos 7U /*!< SCB SHCSR: SVCALLACT Position */ +#define SCB_SHCSR_SVCALLACT_Msk (1UL << SCB_SHCSR_SVCALLACT_Pos) /*!< SCB SHCSR: SVCALLACT Mask */ + +#define SCB_SHCSR_USGFAULTACT_Pos 3U /*!< SCB SHCSR: USGFAULTACT Position */ +#define SCB_SHCSR_USGFAULTACT_Msk (1UL << SCB_SHCSR_USGFAULTACT_Pos) /*!< SCB SHCSR: USGFAULTACT Mask */ + +#define SCB_SHCSR_BUSFAULTACT_Pos 1U /*!< SCB SHCSR: BUSFAULTACT Position */ +#define SCB_SHCSR_BUSFAULTACT_Msk (1UL << SCB_SHCSR_BUSFAULTACT_Pos) /*!< SCB SHCSR: BUSFAULTACT Mask */ + +#define SCB_SHCSR_MEMFAULTACT_Pos 0U /*!< SCB SHCSR: MEMFAULTACT Position */ +#define SCB_SHCSR_MEMFAULTACT_Msk (1UL /*<< SCB_SHCSR_MEMFAULTACT_Pos*/) /*!< SCB SHCSR: MEMFAULTACT Mask */ + +/* SCB Configurable Fault Status Register Definitions */ +#define SCB_CFSR_USGFAULTSR_Pos 16U /*!< SCB CFSR: Usage Fault Status Register Position */ +#define SCB_CFSR_USGFAULTSR_Msk (0xFFFFUL << SCB_CFSR_USGFAULTSR_Pos) /*!< SCB CFSR: Usage Fault Status Register Mask */ + +#define SCB_CFSR_BUSFAULTSR_Pos 8U /*!< SCB CFSR: Bus Fault Status Register Position */ +#define SCB_CFSR_BUSFAULTSR_Msk (0xFFUL << SCB_CFSR_BUSFAULTSR_Pos) /*!< SCB CFSR: Bus Fault Status Register Mask */ + +#define SCB_CFSR_MEMFAULTSR_Pos 0U /*!< SCB CFSR: Memory Manage Fault Status Register Position */ +#define SCB_CFSR_MEMFAULTSR_Msk (0xFFUL /*<< SCB_CFSR_MEMFAULTSR_Pos*/) /*!< SCB CFSR: Memory Manage Fault Status Register Mask */ + +/* SCB Hard Fault Status Register Definitions */ +#define SCB_HFSR_DEBUGEVT_Pos 31U /*!< SCB HFSR: DEBUGEVT Position */ +#define SCB_HFSR_DEBUGEVT_Msk (1UL << SCB_HFSR_DEBUGEVT_Pos) /*!< SCB HFSR: DEBUGEVT Mask */ + +#define SCB_HFSR_FORCED_Pos 30U /*!< SCB HFSR: FORCED Position */ +#define SCB_HFSR_FORCED_Msk (1UL << SCB_HFSR_FORCED_Pos) /*!< SCB HFSR: FORCED Mask */ + +#define SCB_HFSR_VECTTBL_Pos 1U /*!< SCB HFSR: VECTTBL Position */ +#define SCB_HFSR_VECTTBL_Msk (1UL << SCB_HFSR_VECTTBL_Pos) /*!< SCB HFSR: VECTTBL Mask */ + +/* SCB Debug Fault Status Register Definitions */ +#define SCB_DFSR_EXTERNAL_Pos 4U /*!< SCB DFSR: EXTERNAL Position */ +#define SCB_DFSR_EXTERNAL_Msk (1UL << SCB_DFSR_EXTERNAL_Pos) /*!< SCB DFSR: EXTERNAL Mask */ + +#define SCB_DFSR_VCATCH_Pos 3U /*!< SCB DFSR: VCATCH Position */ +#define SCB_DFSR_VCATCH_Msk (1UL << SCB_DFSR_VCATCH_Pos) /*!< SCB DFSR: VCATCH Mask */ + +#define SCB_DFSR_DWTTRAP_Pos 2U /*!< SCB DFSR: DWTTRAP Position */ +#define SCB_DFSR_DWTTRAP_Msk (1UL << SCB_DFSR_DWTTRAP_Pos) /*!< SCB DFSR: DWTTRAP Mask */ + +#define SCB_DFSR_BKPT_Pos 1U /*!< SCB DFSR: BKPT Position */ +#define SCB_DFSR_BKPT_Msk (1UL << SCB_DFSR_BKPT_Pos) /*!< SCB DFSR: BKPT Mask */ + +#define SCB_DFSR_HALTED_Pos 0U /*!< SCB DFSR: HALTED Position */ +#define SCB_DFSR_HALTED_Msk (1UL /*<< SCB_DFSR_HALTED_Pos*/) /*!< SCB DFSR: HALTED Mask */ + +/*@} end of group CMSIS_SCB */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_SCnSCB System Controls not in SCB (SCnSCB) + \brief Type definitions for the System Control and ID Register not in the SCB + @{ + */ + +/** + \brief Structure type to access the System Control and ID Register not in the SCB. + */ +typedef struct +{ + uint32_t RESERVED0[1U]; + __IM uint32_t ICTR; /*!< Offset: 0x004 (R/ ) Interrupt Controller Type Register */ +#if ((defined __CM3_REV) && (__CM3_REV >= 0x200U)) + __IOM uint32_t ACTLR; /*!< Offset: 0x008 (R/W) Auxiliary Control Register */ +#else + uint32_t RESERVED1[1U]; +#endif +} SCnSCB_Type; + +/* Interrupt Controller Type Register Definitions */ +#define SCnSCB_ICTR_INTLINESNUM_Pos 0U /*!< ICTR: INTLINESNUM Position */ +#define SCnSCB_ICTR_INTLINESNUM_Msk (0xFUL /*<< SCnSCB_ICTR_INTLINESNUM_Pos*/) /*!< ICTR: INTLINESNUM Mask */ + +/* Auxiliary Control Register Definitions */ + +#define SCnSCB_ACTLR_DISFOLD_Pos 2U /*!< ACTLR: DISFOLD Position */ +#define SCnSCB_ACTLR_DISFOLD_Msk (1UL << SCnSCB_ACTLR_DISFOLD_Pos) /*!< ACTLR: DISFOLD Mask */ + +#define SCnSCB_ACTLR_DISDEFWBUF_Pos 1U /*!< ACTLR: DISDEFWBUF Position */ +#define SCnSCB_ACTLR_DISDEFWBUF_Msk (1UL << SCnSCB_ACTLR_DISDEFWBUF_Pos) /*!< ACTLR: DISDEFWBUF Mask */ + +#define SCnSCB_ACTLR_DISMCYCINT_Pos 0U /*!< ACTLR: DISMCYCINT Position */ +#define SCnSCB_ACTLR_DISMCYCINT_Msk (1UL /*<< SCnSCB_ACTLR_DISMCYCINT_Pos*/) /*!< ACTLR: DISMCYCINT Mask */ + +/*@} end of group CMSIS_SCnotSCB */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_SysTick System Tick Timer (SysTick) + \brief Type definitions for the System Timer Registers. + @{ + */ + +/** + \brief Structure type to access the System Timer (SysTick). + */ +typedef struct +{ + __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) SysTick Control and Status Register */ + __IOM uint32_t LOAD; /*!< Offset: 0x004 (R/W) SysTick Reload Value Register */ + __IOM uint32_t VAL; /*!< Offset: 0x008 (R/W) SysTick Current Value Register */ + __IM uint32_t CALIB; /*!< Offset: 0x00C (R/ ) SysTick Calibration Register */ +} SysTick_Type; + +/* SysTick Control / Status Register Definitions */ +#define SysTick_CTRL_COUNTFLAG_Pos 16U /*!< SysTick CTRL: COUNTFLAG Position */ +#define SysTick_CTRL_COUNTFLAG_Msk (1UL << SysTick_CTRL_COUNTFLAG_Pos) /*!< SysTick CTRL: COUNTFLAG Mask */ + +#define SysTick_CTRL_CLKSOURCE_Pos 2U /*!< SysTick CTRL: CLKSOURCE Position */ +#define SysTick_CTRL_CLKSOURCE_Msk (1UL << SysTick_CTRL_CLKSOURCE_Pos) /*!< SysTick CTRL: CLKSOURCE Mask */ + +#define SysTick_CTRL_TICKINT_Pos 1U /*!< SysTick CTRL: TICKINT Position */ +#define SysTick_CTRL_TICKINT_Msk (1UL << SysTick_CTRL_TICKINT_Pos) /*!< SysTick CTRL: TICKINT Mask */ + +#define SysTick_CTRL_ENABLE_Pos 0U /*!< SysTick CTRL: ENABLE Position */ +#define SysTick_CTRL_ENABLE_Msk (1UL /*<< SysTick_CTRL_ENABLE_Pos*/) /*!< SysTick CTRL: ENABLE Mask */ + +/* SysTick Reload Register Definitions */ +#define SysTick_LOAD_RELOAD_Pos 0U /*!< SysTick LOAD: RELOAD Position */ +#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFUL /*<< SysTick_LOAD_RELOAD_Pos*/) /*!< SysTick LOAD: RELOAD Mask */ + +/* SysTick Current Register Definitions */ +#define SysTick_VAL_CURRENT_Pos 0U /*!< SysTick VAL: CURRENT Position */ +#define SysTick_VAL_CURRENT_Msk (0xFFFFFFUL /*<< SysTick_VAL_CURRENT_Pos*/) /*!< SysTick VAL: CURRENT Mask */ + +/* SysTick Calibration Register Definitions */ +#define SysTick_CALIB_NOREF_Pos 31U /*!< SysTick CALIB: NOREF Position */ +#define SysTick_CALIB_NOREF_Msk (1UL << SysTick_CALIB_NOREF_Pos) /*!< SysTick CALIB: NOREF Mask */ + +#define SysTick_CALIB_SKEW_Pos 30U /*!< SysTick CALIB: SKEW Position */ +#define SysTick_CALIB_SKEW_Msk (1UL << SysTick_CALIB_SKEW_Pos) /*!< SysTick CALIB: SKEW Mask */ + +#define SysTick_CALIB_TENMS_Pos 0U /*!< SysTick CALIB: TENMS Position */ +#define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL /*<< SysTick_CALIB_TENMS_Pos*/) /*!< SysTick CALIB: TENMS Mask */ + +/*@} end of group CMSIS_SysTick */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_ITM Instrumentation Trace Macrocell (ITM) + \brief Type definitions for the Instrumentation Trace Macrocell (ITM) + @{ + */ + +/** + \brief Structure type to access the Instrumentation Trace Macrocell Register (ITM). + */ +typedef struct +{ + __OM union + { + __OM uint8_t u8; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 8-bit */ + __OM uint16_t u16; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 16-bit */ + __OM uint32_t u32; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 32-bit */ + } PORT [32U]; /*!< Offset: 0x000 ( /W) ITM Stimulus Port Registers */ + uint32_t RESERVED0[864U]; + __IOM uint32_t TER; /*!< Offset: 0xE00 (R/W) ITM Trace Enable Register */ + uint32_t RESERVED1[15U]; + __IOM uint32_t TPR; /*!< Offset: 0xE40 (R/W) ITM Trace Privilege Register */ + uint32_t RESERVED2[15U]; + __IOM uint32_t TCR; /*!< Offset: 0xE80 (R/W) ITM Trace Control Register */ + uint32_t RESERVED3[29U]; + __OM uint32_t IWR; /*!< Offset: 0xEF8 ( /W) ITM Integration Write Register */ + __IM uint32_t IRR; /*!< Offset: 0xEFC (R/ ) ITM Integration Read Register */ + __IOM uint32_t IMCR; /*!< Offset: 0xF00 (R/W) ITM Integration Mode Control Register */ + uint32_t RESERVED4[43U]; + __OM uint32_t LAR; /*!< Offset: 0xFB0 ( /W) ITM Lock Access Register */ + __IM uint32_t LSR; /*!< Offset: 0xFB4 (R/ ) ITM Lock Status Register */ + uint32_t RESERVED5[6U]; + __IM uint32_t PID4; /*!< Offset: 0xFD0 (R/ ) ITM Peripheral Identification Register #4 */ + __IM uint32_t PID5; /*!< Offset: 0xFD4 (R/ ) ITM Peripheral Identification Register #5 */ + __IM uint32_t PID6; /*!< Offset: 0xFD8 (R/ ) ITM Peripheral Identification Register #6 */ + __IM uint32_t PID7; /*!< Offset: 0xFDC (R/ ) ITM Peripheral Identification Register #7 */ + __IM uint32_t PID0; /*!< Offset: 0xFE0 (R/ ) ITM Peripheral Identification Register #0 */ + __IM uint32_t PID1; /*!< Offset: 0xFE4 (R/ ) ITM Peripheral Identification Register #1 */ + __IM uint32_t PID2; /*!< Offset: 0xFE8 (R/ ) ITM Peripheral Identification Register #2 */ + __IM uint32_t PID3; /*!< Offset: 0xFEC (R/ ) ITM Peripheral Identification Register #3 */ + __IM uint32_t CID0; /*!< Offset: 0xFF0 (R/ ) ITM Component Identification Register #0 */ + __IM uint32_t CID1; /*!< Offset: 0xFF4 (R/ ) ITM Component Identification Register #1 */ + __IM uint32_t CID2; /*!< Offset: 0xFF8 (R/ ) ITM Component Identification Register #2 */ + __IM uint32_t CID3; /*!< Offset: 0xFFC (R/ ) ITM Component Identification Register #3 */ +} ITM_Type; + +/* ITM Trace Privilege Register Definitions */ +#define ITM_TPR_PRIVMASK_Pos 0U /*!< ITM TPR: PRIVMASK Position */ +#define ITM_TPR_PRIVMASK_Msk (0xFUL /*<< ITM_TPR_PRIVMASK_Pos*/) /*!< ITM TPR: PRIVMASK Mask */ + +/* ITM Trace Control Register Definitions */ +#define ITM_TCR_BUSY_Pos 23U /*!< ITM TCR: BUSY Position */ +#define ITM_TCR_BUSY_Msk (1UL << ITM_TCR_BUSY_Pos) /*!< ITM TCR: BUSY Mask */ + +#define ITM_TCR_TraceBusID_Pos 16U /*!< ITM TCR: ATBID Position */ +#define ITM_TCR_TraceBusID_Msk (0x7FUL << ITM_TCR_TraceBusID_Pos) /*!< ITM TCR: ATBID Mask */ + +#define ITM_TCR_GTSFREQ_Pos 10U /*!< ITM TCR: Global timestamp frequency Position */ +#define ITM_TCR_GTSFREQ_Msk (3UL << ITM_TCR_GTSFREQ_Pos) /*!< ITM TCR: Global timestamp frequency Mask */ + +#define ITM_TCR_TSPrescale_Pos 8U /*!< ITM TCR: TSPrescale Position */ +#define ITM_TCR_TSPrescale_Msk (3UL << ITM_TCR_TSPrescale_Pos) /*!< ITM TCR: TSPrescale Mask */ + +#define ITM_TCR_SWOENA_Pos 4U /*!< ITM TCR: SWOENA Position */ +#define ITM_TCR_SWOENA_Msk (1UL << ITM_TCR_SWOENA_Pos) /*!< ITM TCR: SWOENA Mask */ + +#define ITM_TCR_DWTENA_Pos 3U /*!< ITM TCR: DWTENA Position */ +#define ITM_TCR_DWTENA_Msk (1UL << ITM_TCR_DWTENA_Pos) /*!< ITM TCR: DWTENA Mask */ + +#define ITM_TCR_SYNCENA_Pos 2U /*!< ITM TCR: SYNCENA Position */ +#define ITM_TCR_SYNCENA_Msk (1UL << ITM_TCR_SYNCENA_Pos) /*!< ITM TCR: SYNCENA Mask */ + +#define ITM_TCR_TSENA_Pos 1U /*!< ITM TCR: TSENA Position */ +#define ITM_TCR_TSENA_Msk (1UL << ITM_TCR_TSENA_Pos) /*!< ITM TCR: TSENA Mask */ + +#define ITM_TCR_ITMENA_Pos 0U /*!< ITM TCR: ITM Enable bit Position */ +#define ITM_TCR_ITMENA_Msk (1UL /*<< ITM_TCR_ITMENA_Pos*/) /*!< ITM TCR: ITM Enable bit Mask */ + +/* ITM Integration Write Register Definitions */ +#define ITM_IWR_ATVALIDM_Pos 0U /*!< ITM IWR: ATVALIDM Position */ +#define ITM_IWR_ATVALIDM_Msk (1UL /*<< ITM_IWR_ATVALIDM_Pos*/) /*!< ITM IWR: ATVALIDM Mask */ + +/* ITM Integration Read Register Definitions */ +#define ITM_IRR_ATREADYM_Pos 0U /*!< ITM IRR: ATREADYM Position */ +#define ITM_IRR_ATREADYM_Msk (1UL /*<< ITM_IRR_ATREADYM_Pos*/) /*!< ITM IRR: ATREADYM Mask */ + +/* ITM Integration Mode Control Register Definitions */ +#define ITM_IMCR_INTEGRATION_Pos 0U /*!< ITM IMCR: INTEGRATION Position */ +#define ITM_IMCR_INTEGRATION_Msk (1UL /*<< ITM_IMCR_INTEGRATION_Pos*/) /*!< ITM IMCR: INTEGRATION Mask */ + +/* ITM Lock Status Register Definitions */ +#define ITM_LSR_ByteAcc_Pos 2U /*!< ITM LSR: ByteAcc Position */ +#define ITM_LSR_ByteAcc_Msk (1UL << ITM_LSR_ByteAcc_Pos) /*!< ITM LSR: ByteAcc Mask */ + +#define ITM_LSR_Access_Pos 1U /*!< ITM LSR: Access Position */ +#define ITM_LSR_Access_Msk (1UL << ITM_LSR_Access_Pos) /*!< ITM LSR: Access Mask */ + +#define ITM_LSR_Present_Pos 0U /*!< ITM LSR: Present Position */ +#define ITM_LSR_Present_Msk (1UL /*<< ITM_LSR_Present_Pos*/) /*!< ITM LSR: Present Mask */ + +/*@}*/ /* end of group CMSIS_ITM */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_DWT Data Watchpoint and Trace (DWT) + \brief Type definitions for the Data Watchpoint and Trace (DWT) + @{ + */ + +/** + \brief Structure type to access the Data Watchpoint and Trace Register (DWT). + */ +typedef struct +{ + __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) Control Register */ + __IOM uint32_t CYCCNT; /*!< Offset: 0x004 (R/W) Cycle Count Register */ + __IOM uint32_t CPICNT; /*!< Offset: 0x008 (R/W) CPI Count Register */ + __IOM uint32_t EXCCNT; /*!< Offset: 0x00C (R/W) Exception Overhead Count Register */ + __IOM uint32_t SLEEPCNT; /*!< Offset: 0x010 (R/W) Sleep Count Register */ + __IOM uint32_t LSUCNT; /*!< Offset: 0x014 (R/W) LSU Count Register */ + __IOM uint32_t FOLDCNT; /*!< Offset: 0x018 (R/W) Folded-instruction Count Register */ + __IM uint32_t PCSR; /*!< Offset: 0x01C (R/ ) Program Counter Sample Register */ + __IOM uint32_t COMP0; /*!< Offset: 0x020 (R/W) Comparator Register 0 */ + __IOM uint32_t MASK0; /*!< Offset: 0x024 (R/W) Mask Register 0 */ + __IOM uint32_t FUNCTION0; /*!< Offset: 0x028 (R/W) Function Register 0 */ + uint32_t RESERVED0[1U]; + __IOM uint32_t COMP1; /*!< Offset: 0x030 (R/W) Comparator Register 1 */ + __IOM uint32_t MASK1; /*!< Offset: 0x034 (R/W) Mask Register 1 */ + __IOM uint32_t FUNCTION1; /*!< Offset: 0x038 (R/W) Function Register 1 */ + uint32_t RESERVED1[1U]; + __IOM uint32_t COMP2; /*!< Offset: 0x040 (R/W) Comparator Register 2 */ + __IOM uint32_t MASK2; /*!< Offset: 0x044 (R/W) Mask Register 2 */ + __IOM uint32_t FUNCTION2; /*!< Offset: 0x048 (R/W) Function Register 2 */ + uint32_t RESERVED2[1U]; + __IOM uint32_t COMP3; /*!< Offset: 0x050 (R/W) Comparator Register 3 */ + __IOM uint32_t MASK3; /*!< Offset: 0x054 (R/W) Mask Register 3 */ + __IOM uint32_t FUNCTION3; /*!< Offset: 0x058 (R/W) Function Register 3 */ +} DWT_Type; + +/* DWT Control Register Definitions */ +#define DWT_CTRL_NUMCOMP_Pos 28U /*!< DWT CTRL: NUMCOMP Position */ +#define DWT_CTRL_NUMCOMP_Msk (0xFUL << DWT_CTRL_NUMCOMP_Pos) /*!< DWT CTRL: NUMCOMP Mask */ + +#define DWT_CTRL_NOTRCPKT_Pos 27U /*!< DWT CTRL: NOTRCPKT Position */ +#define DWT_CTRL_NOTRCPKT_Msk (0x1UL << DWT_CTRL_NOTRCPKT_Pos) /*!< DWT CTRL: NOTRCPKT Mask */ + +#define DWT_CTRL_NOEXTTRIG_Pos 26U /*!< DWT CTRL: NOEXTTRIG Position */ +#define DWT_CTRL_NOEXTTRIG_Msk (0x1UL << DWT_CTRL_NOEXTTRIG_Pos) /*!< DWT CTRL: NOEXTTRIG Mask */ + +#define DWT_CTRL_NOCYCCNT_Pos 25U /*!< DWT CTRL: NOCYCCNT Position */ +#define DWT_CTRL_NOCYCCNT_Msk (0x1UL << DWT_CTRL_NOCYCCNT_Pos) /*!< DWT CTRL: NOCYCCNT Mask */ + +#define DWT_CTRL_NOPRFCNT_Pos 24U /*!< DWT CTRL: NOPRFCNT Position */ +#define DWT_CTRL_NOPRFCNT_Msk (0x1UL << DWT_CTRL_NOPRFCNT_Pos) /*!< DWT CTRL: NOPRFCNT Mask */ + +#define DWT_CTRL_CYCEVTENA_Pos 22U /*!< DWT CTRL: CYCEVTENA Position */ +#define DWT_CTRL_CYCEVTENA_Msk (0x1UL << DWT_CTRL_CYCEVTENA_Pos) /*!< DWT CTRL: CYCEVTENA Mask */ + +#define DWT_CTRL_FOLDEVTENA_Pos 21U /*!< DWT CTRL: FOLDEVTENA Position */ +#define DWT_CTRL_FOLDEVTENA_Msk (0x1UL << DWT_CTRL_FOLDEVTENA_Pos) /*!< DWT CTRL: FOLDEVTENA Mask */ + +#define DWT_CTRL_LSUEVTENA_Pos 20U /*!< DWT CTRL: LSUEVTENA Position */ +#define DWT_CTRL_LSUEVTENA_Msk (0x1UL << DWT_CTRL_LSUEVTENA_Pos) /*!< DWT CTRL: LSUEVTENA Mask */ + +#define DWT_CTRL_SLEEPEVTENA_Pos 19U /*!< DWT CTRL: SLEEPEVTENA Position */ +#define DWT_CTRL_SLEEPEVTENA_Msk (0x1UL << DWT_CTRL_SLEEPEVTENA_Pos) /*!< DWT CTRL: SLEEPEVTENA Mask */ + +#define DWT_CTRL_EXCEVTENA_Pos 18U /*!< DWT CTRL: EXCEVTENA Position */ +#define DWT_CTRL_EXCEVTENA_Msk (0x1UL << DWT_CTRL_EXCEVTENA_Pos) /*!< DWT CTRL: EXCEVTENA Mask */ + +#define DWT_CTRL_CPIEVTENA_Pos 17U /*!< DWT CTRL: CPIEVTENA Position */ +#define DWT_CTRL_CPIEVTENA_Msk (0x1UL << DWT_CTRL_CPIEVTENA_Pos) /*!< DWT CTRL: CPIEVTENA Mask */ + +#define DWT_CTRL_EXCTRCENA_Pos 16U /*!< DWT CTRL: EXCTRCENA Position */ +#define DWT_CTRL_EXCTRCENA_Msk (0x1UL << DWT_CTRL_EXCTRCENA_Pos) /*!< DWT CTRL: EXCTRCENA Mask */ + +#define DWT_CTRL_PCSAMPLENA_Pos 12U /*!< DWT CTRL: PCSAMPLENA Position */ +#define DWT_CTRL_PCSAMPLENA_Msk (0x1UL << DWT_CTRL_PCSAMPLENA_Pos) /*!< DWT CTRL: PCSAMPLENA Mask */ + +#define DWT_CTRL_SYNCTAP_Pos 10U /*!< DWT CTRL: SYNCTAP Position */ +#define DWT_CTRL_SYNCTAP_Msk (0x3UL << DWT_CTRL_SYNCTAP_Pos) /*!< DWT CTRL: SYNCTAP Mask */ + +#define DWT_CTRL_CYCTAP_Pos 9U /*!< DWT CTRL: CYCTAP Position */ +#define DWT_CTRL_CYCTAP_Msk (0x1UL << DWT_CTRL_CYCTAP_Pos) /*!< DWT CTRL: CYCTAP Mask */ + +#define DWT_CTRL_POSTINIT_Pos 5U /*!< DWT CTRL: POSTINIT Position */ +#define DWT_CTRL_POSTINIT_Msk (0xFUL << DWT_CTRL_POSTINIT_Pos) /*!< DWT CTRL: POSTINIT Mask */ + +#define DWT_CTRL_POSTPRESET_Pos 1U /*!< DWT CTRL: POSTPRESET Position */ +#define DWT_CTRL_POSTPRESET_Msk (0xFUL << DWT_CTRL_POSTPRESET_Pos) /*!< DWT CTRL: POSTPRESET Mask */ + +#define DWT_CTRL_CYCCNTENA_Pos 0U /*!< DWT CTRL: CYCCNTENA Position */ +#define DWT_CTRL_CYCCNTENA_Msk (0x1UL /*<< DWT_CTRL_CYCCNTENA_Pos*/) /*!< DWT CTRL: CYCCNTENA Mask */ + +/* DWT CPI Count Register Definitions */ +#define DWT_CPICNT_CPICNT_Pos 0U /*!< DWT CPICNT: CPICNT Position */ +#define DWT_CPICNT_CPICNT_Msk (0xFFUL /*<< DWT_CPICNT_CPICNT_Pos*/) /*!< DWT CPICNT: CPICNT Mask */ + +/* DWT Exception Overhead Count Register Definitions */ +#define DWT_EXCCNT_EXCCNT_Pos 0U /*!< DWT EXCCNT: EXCCNT Position */ +#define DWT_EXCCNT_EXCCNT_Msk (0xFFUL /*<< DWT_EXCCNT_EXCCNT_Pos*/) /*!< DWT EXCCNT: EXCCNT Mask */ + +/* DWT Sleep Count Register Definitions */ +#define DWT_SLEEPCNT_SLEEPCNT_Pos 0U /*!< DWT SLEEPCNT: SLEEPCNT Position */ +#define DWT_SLEEPCNT_SLEEPCNT_Msk (0xFFUL /*<< DWT_SLEEPCNT_SLEEPCNT_Pos*/) /*!< DWT SLEEPCNT: SLEEPCNT Mask */ + +/* DWT LSU Count Register Definitions */ +#define DWT_LSUCNT_LSUCNT_Pos 0U /*!< DWT LSUCNT: LSUCNT Position */ +#define DWT_LSUCNT_LSUCNT_Msk (0xFFUL /*<< DWT_LSUCNT_LSUCNT_Pos*/) /*!< DWT LSUCNT: LSUCNT Mask */ + +/* DWT Folded-instruction Count Register Definitions */ +#define DWT_FOLDCNT_FOLDCNT_Pos 0U /*!< DWT FOLDCNT: FOLDCNT Position */ +#define DWT_FOLDCNT_FOLDCNT_Msk (0xFFUL /*<< DWT_FOLDCNT_FOLDCNT_Pos*/) /*!< DWT FOLDCNT: FOLDCNT Mask */ + +/* DWT Comparator Mask Register Definitions */ +#define DWT_MASK_MASK_Pos 0U /*!< DWT MASK: MASK Position */ +#define DWT_MASK_MASK_Msk (0x1FUL /*<< DWT_MASK_MASK_Pos*/) /*!< DWT MASK: MASK Mask */ + +/* DWT Comparator Function Register Definitions */ +#define DWT_FUNCTION_MATCHED_Pos 24U /*!< DWT FUNCTION: MATCHED Position */ +#define DWT_FUNCTION_MATCHED_Msk (0x1UL << DWT_FUNCTION_MATCHED_Pos) /*!< DWT FUNCTION: MATCHED Mask */ + +#define DWT_FUNCTION_DATAVADDR1_Pos 16U /*!< DWT FUNCTION: DATAVADDR1 Position */ +#define DWT_FUNCTION_DATAVADDR1_Msk (0xFUL << DWT_FUNCTION_DATAVADDR1_Pos) /*!< DWT FUNCTION: DATAVADDR1 Mask */ + +#define DWT_FUNCTION_DATAVADDR0_Pos 12U /*!< DWT FUNCTION: DATAVADDR0 Position */ +#define DWT_FUNCTION_DATAVADDR0_Msk (0xFUL << DWT_FUNCTION_DATAVADDR0_Pos) /*!< DWT FUNCTION: DATAVADDR0 Mask */ + +#define DWT_FUNCTION_DATAVSIZE_Pos 10U /*!< DWT FUNCTION: DATAVSIZE Position */ +#define DWT_FUNCTION_DATAVSIZE_Msk (0x3UL << DWT_FUNCTION_DATAVSIZE_Pos) /*!< DWT FUNCTION: DATAVSIZE Mask */ + +#define DWT_FUNCTION_LNK1ENA_Pos 9U /*!< DWT FUNCTION: LNK1ENA Position */ +#define DWT_FUNCTION_LNK1ENA_Msk (0x1UL << DWT_FUNCTION_LNK1ENA_Pos) /*!< DWT FUNCTION: LNK1ENA Mask */ + +#define DWT_FUNCTION_DATAVMATCH_Pos 8U /*!< DWT FUNCTION: DATAVMATCH Position */ +#define DWT_FUNCTION_DATAVMATCH_Msk (0x1UL << DWT_FUNCTION_DATAVMATCH_Pos) /*!< DWT FUNCTION: DATAVMATCH Mask */ + +#define DWT_FUNCTION_CYCMATCH_Pos 7U /*!< DWT FUNCTION: CYCMATCH Position */ +#define DWT_FUNCTION_CYCMATCH_Msk (0x1UL << DWT_FUNCTION_CYCMATCH_Pos) /*!< DWT FUNCTION: CYCMATCH Mask */ + +#define DWT_FUNCTION_EMITRANGE_Pos 5U /*!< DWT FUNCTION: EMITRANGE Position */ +#define DWT_FUNCTION_EMITRANGE_Msk (0x1UL << DWT_FUNCTION_EMITRANGE_Pos) /*!< DWT FUNCTION: EMITRANGE Mask */ + +#define DWT_FUNCTION_FUNCTION_Pos 0U /*!< DWT FUNCTION: FUNCTION Position */ +#define DWT_FUNCTION_FUNCTION_Msk (0xFUL /*<< DWT_FUNCTION_FUNCTION_Pos*/) /*!< DWT FUNCTION: FUNCTION Mask */ + +/*@}*/ /* end of group CMSIS_DWT */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_TPI Trace Port Interface (TPI) + \brief Type definitions for the Trace Port Interface (TPI) + @{ + */ + +/** + \brief Structure type to access the Trace Port Interface Register (TPI). + */ +typedef struct +{ + __IOM uint32_t SSPSR; /*!< Offset: 0x000 (R/ ) Supported Parallel Port Size Register */ + __IOM uint32_t CSPSR; /*!< Offset: 0x004 (R/W) Current Parallel Port Size Register */ + uint32_t RESERVED0[2U]; + __IOM uint32_t ACPR; /*!< Offset: 0x010 (R/W) Asynchronous Clock Prescaler Register */ + uint32_t RESERVED1[55U]; + __IOM uint32_t SPPR; /*!< Offset: 0x0F0 (R/W) Selected Pin Protocol Register */ + uint32_t RESERVED2[131U]; + __IM uint32_t FFSR; /*!< Offset: 0x300 (R/ ) Formatter and Flush Status Register */ + __IOM uint32_t FFCR; /*!< Offset: 0x304 (R/W) Formatter and Flush Control Register */ + __IM uint32_t FSCR; /*!< Offset: 0x308 (R/ ) Formatter Synchronization Counter Register */ + uint32_t RESERVED3[759U]; + __IM uint32_t TRIGGER; /*!< Offset: 0xEE8 (R/ ) TRIGGER */ + __IM uint32_t FIFO0; /*!< Offset: 0xEEC (R/ ) Integration ETM Data */ + __IM uint32_t ITATBCTR2; /*!< Offset: 0xEF0 (R/ ) ITATBCTR2 */ + uint32_t RESERVED4[1U]; + __IM uint32_t ITATBCTR0; /*!< Offset: 0xEF8 (R/ ) ITATBCTR0 */ + __IM uint32_t FIFO1; /*!< Offset: 0xEFC (R/ ) Integration ITM Data */ + __IOM uint32_t ITCTRL; /*!< Offset: 0xF00 (R/W) Integration Mode Control */ + uint32_t RESERVED5[39U]; + __IOM uint32_t CLAIMSET; /*!< Offset: 0xFA0 (R/W) Claim tag set */ + __IOM uint32_t CLAIMCLR; /*!< Offset: 0xFA4 (R/W) Claim tag clear */ + uint32_t RESERVED7[8U]; + __IM uint32_t DEVID; /*!< Offset: 0xFC8 (R/ ) TPIU_DEVID */ + __IM uint32_t DEVTYPE; /*!< Offset: 0xFCC (R/ ) TPIU_DEVTYPE */ +} TPI_Type; + +/* TPI Asynchronous Clock Prescaler Register Definitions */ +#define TPI_ACPR_PRESCALER_Pos 0U /*!< TPI ACPR: PRESCALER Position */ +#define TPI_ACPR_PRESCALER_Msk (0x1FFFUL /*<< TPI_ACPR_PRESCALER_Pos*/) /*!< TPI ACPR: PRESCALER Mask */ + +/* TPI Selected Pin Protocol Register Definitions */ +#define TPI_SPPR_TXMODE_Pos 0U /*!< TPI SPPR: TXMODE Position */ +#define TPI_SPPR_TXMODE_Msk (0x3UL /*<< TPI_SPPR_TXMODE_Pos*/) /*!< TPI SPPR: TXMODE Mask */ + +/* TPI Formatter and Flush Status Register Definitions */ +#define TPI_FFSR_FtNonStop_Pos 3U /*!< TPI FFSR: FtNonStop Position */ +#define TPI_FFSR_FtNonStop_Msk (0x1UL << TPI_FFSR_FtNonStop_Pos) /*!< TPI FFSR: FtNonStop Mask */ + +#define TPI_FFSR_TCPresent_Pos 2U /*!< TPI FFSR: TCPresent Position */ +#define TPI_FFSR_TCPresent_Msk (0x1UL << TPI_FFSR_TCPresent_Pos) /*!< TPI FFSR: TCPresent Mask */ + +#define TPI_FFSR_FtStopped_Pos 1U /*!< TPI FFSR: FtStopped Position */ +#define TPI_FFSR_FtStopped_Msk (0x1UL << TPI_FFSR_FtStopped_Pos) /*!< TPI FFSR: FtStopped Mask */ + +#define TPI_FFSR_FlInProg_Pos 0U /*!< TPI FFSR: FlInProg Position */ +#define TPI_FFSR_FlInProg_Msk (0x1UL /*<< TPI_FFSR_FlInProg_Pos*/) /*!< TPI FFSR: FlInProg Mask */ + +/* TPI Formatter and Flush Control Register Definitions */ +#define TPI_FFCR_TrigIn_Pos 8U /*!< TPI FFCR: TrigIn Position */ +#define TPI_FFCR_TrigIn_Msk (0x1UL << TPI_FFCR_TrigIn_Pos) /*!< TPI FFCR: TrigIn Mask */ + +#define TPI_FFCR_EnFCont_Pos 1U /*!< TPI FFCR: EnFCont Position */ +#define TPI_FFCR_EnFCont_Msk (0x1UL << TPI_FFCR_EnFCont_Pos) /*!< TPI FFCR: EnFCont Mask */ + +/* TPI TRIGGER Register Definitions */ +#define TPI_TRIGGER_TRIGGER_Pos 0U /*!< TPI TRIGGER: TRIGGER Position */ +#define TPI_TRIGGER_TRIGGER_Msk (0x1UL /*<< TPI_TRIGGER_TRIGGER_Pos*/) /*!< TPI TRIGGER: TRIGGER Mask */ + +/* TPI Integration ETM Data Register Definitions (FIFO0) */ +#define TPI_FIFO0_ITM_ATVALID_Pos 29U /*!< TPI FIFO0: ITM_ATVALID Position */ +#define TPI_FIFO0_ITM_ATVALID_Msk (0x3UL << TPI_FIFO0_ITM_ATVALID_Pos) /*!< TPI FIFO0: ITM_ATVALID Mask */ + +#define TPI_FIFO0_ITM_bytecount_Pos 27U /*!< TPI FIFO0: ITM_bytecount Position */ +#define TPI_FIFO0_ITM_bytecount_Msk (0x3UL << TPI_FIFO0_ITM_bytecount_Pos) /*!< TPI FIFO0: ITM_bytecount Mask */ + +#define TPI_FIFO0_ETM_ATVALID_Pos 26U /*!< TPI FIFO0: ETM_ATVALID Position */ +#define TPI_FIFO0_ETM_ATVALID_Msk (0x3UL << TPI_FIFO0_ETM_ATVALID_Pos) /*!< TPI FIFO0: ETM_ATVALID Mask */ + +#define TPI_FIFO0_ETM_bytecount_Pos 24U /*!< TPI FIFO0: ETM_bytecount Position */ +#define TPI_FIFO0_ETM_bytecount_Msk (0x3UL << TPI_FIFO0_ETM_bytecount_Pos) /*!< TPI FIFO0: ETM_bytecount Mask */ + +#define TPI_FIFO0_ETM2_Pos 16U /*!< TPI FIFO0: ETM2 Position */ +#define TPI_FIFO0_ETM2_Msk (0xFFUL << TPI_FIFO0_ETM2_Pos) /*!< TPI FIFO0: ETM2 Mask */ + +#define TPI_FIFO0_ETM1_Pos 8U /*!< TPI FIFO0: ETM1 Position */ +#define TPI_FIFO0_ETM1_Msk (0xFFUL << TPI_FIFO0_ETM1_Pos) /*!< TPI FIFO0: ETM1 Mask */ + +#define TPI_FIFO0_ETM0_Pos 0U /*!< TPI FIFO0: ETM0 Position */ +#define TPI_FIFO0_ETM0_Msk (0xFFUL /*<< TPI_FIFO0_ETM0_Pos*/) /*!< TPI FIFO0: ETM0 Mask */ + +/* TPI ITATBCTR2 Register Definitions */ +#define TPI_ITATBCTR2_ATREADY_Pos 0U /*!< TPI ITATBCTR2: ATREADY Position */ +#define TPI_ITATBCTR2_ATREADY_Msk (0x1UL /*<< TPI_ITATBCTR2_ATREADY_Pos*/) /*!< TPI ITATBCTR2: ATREADY Mask */ + +/* TPI Integration ITM Data Register Definitions (FIFO1) */ +#define TPI_FIFO1_ITM_ATVALID_Pos 29U /*!< TPI FIFO1: ITM_ATVALID Position */ +#define TPI_FIFO1_ITM_ATVALID_Msk (0x3UL << TPI_FIFO1_ITM_ATVALID_Pos) /*!< TPI FIFO1: ITM_ATVALID Mask */ + +#define TPI_FIFO1_ITM_bytecount_Pos 27U /*!< TPI FIFO1: ITM_bytecount Position */ +#define TPI_FIFO1_ITM_bytecount_Msk (0x3UL << TPI_FIFO1_ITM_bytecount_Pos) /*!< TPI FIFO1: ITM_bytecount Mask */ + +#define TPI_FIFO1_ETM_ATVALID_Pos 26U /*!< TPI FIFO1: ETM_ATVALID Position */ +#define TPI_FIFO1_ETM_ATVALID_Msk (0x3UL << TPI_FIFO1_ETM_ATVALID_Pos) /*!< TPI FIFO1: ETM_ATVALID Mask */ + +#define TPI_FIFO1_ETM_bytecount_Pos 24U /*!< TPI FIFO1: ETM_bytecount Position */ +#define TPI_FIFO1_ETM_bytecount_Msk (0x3UL << TPI_FIFO1_ETM_bytecount_Pos) /*!< TPI FIFO1: ETM_bytecount Mask */ + +#define TPI_FIFO1_ITM2_Pos 16U /*!< TPI FIFO1: ITM2 Position */ +#define TPI_FIFO1_ITM2_Msk (0xFFUL << TPI_FIFO1_ITM2_Pos) /*!< TPI FIFO1: ITM2 Mask */ + +#define TPI_FIFO1_ITM1_Pos 8U /*!< TPI FIFO1: ITM1 Position */ +#define TPI_FIFO1_ITM1_Msk (0xFFUL << TPI_FIFO1_ITM1_Pos) /*!< TPI FIFO1: ITM1 Mask */ + +#define TPI_FIFO1_ITM0_Pos 0U /*!< TPI FIFO1: ITM0 Position */ +#define TPI_FIFO1_ITM0_Msk (0xFFUL /*<< TPI_FIFO1_ITM0_Pos*/) /*!< TPI FIFO1: ITM0 Mask */ + +/* TPI ITATBCTR0 Register Definitions */ +#define TPI_ITATBCTR0_ATREADY_Pos 0U /*!< TPI ITATBCTR0: ATREADY Position */ +#define TPI_ITATBCTR0_ATREADY_Msk (0x1UL /*<< TPI_ITATBCTR0_ATREADY_Pos*/) /*!< TPI ITATBCTR0: ATREADY Mask */ + +/* TPI Integration Mode Control Register Definitions */ +#define TPI_ITCTRL_Mode_Pos 0U /*!< TPI ITCTRL: Mode Position */ +#define TPI_ITCTRL_Mode_Msk (0x1UL /*<< TPI_ITCTRL_Mode_Pos*/) /*!< TPI ITCTRL: Mode Mask */ + +/* TPI DEVID Register Definitions */ +#define TPI_DEVID_NRZVALID_Pos 11U /*!< TPI DEVID: NRZVALID Position */ +#define TPI_DEVID_NRZVALID_Msk (0x1UL << TPI_DEVID_NRZVALID_Pos) /*!< TPI DEVID: NRZVALID Mask */ + +#define TPI_DEVID_MANCVALID_Pos 10U /*!< TPI DEVID: MANCVALID Position */ +#define TPI_DEVID_MANCVALID_Msk (0x1UL << TPI_DEVID_MANCVALID_Pos) /*!< TPI DEVID: MANCVALID Mask */ + +#define TPI_DEVID_PTINVALID_Pos 9U /*!< TPI DEVID: PTINVALID Position */ +#define TPI_DEVID_PTINVALID_Msk (0x1UL << TPI_DEVID_PTINVALID_Pos) /*!< TPI DEVID: PTINVALID Mask */ + +#define TPI_DEVID_MinBufSz_Pos 6U /*!< TPI DEVID: MinBufSz Position */ +#define TPI_DEVID_MinBufSz_Msk (0x7UL << TPI_DEVID_MinBufSz_Pos) /*!< TPI DEVID: MinBufSz Mask */ + +#define TPI_DEVID_AsynClkIn_Pos 5U /*!< TPI DEVID: AsynClkIn Position */ +#define TPI_DEVID_AsynClkIn_Msk (0x1UL << TPI_DEVID_AsynClkIn_Pos) /*!< TPI DEVID: AsynClkIn Mask */ + +#define TPI_DEVID_NrTraceInput_Pos 0U /*!< TPI DEVID: NrTraceInput Position */ +#define TPI_DEVID_NrTraceInput_Msk (0x1FUL /*<< TPI_DEVID_NrTraceInput_Pos*/) /*!< TPI DEVID: NrTraceInput Mask */ + +/* TPI DEVTYPE Register Definitions */ +#define TPI_DEVTYPE_MajorType_Pos 4U /*!< TPI DEVTYPE: MajorType Position */ +#define TPI_DEVTYPE_MajorType_Msk (0xFUL << TPI_DEVTYPE_MajorType_Pos) /*!< TPI DEVTYPE: MajorType Mask */ + +#define TPI_DEVTYPE_SubType_Pos 0U /*!< TPI DEVTYPE: SubType Position */ +#define TPI_DEVTYPE_SubType_Msk (0xFUL /*<< TPI_DEVTYPE_SubType_Pos*/) /*!< TPI DEVTYPE: SubType Mask */ + +/*@}*/ /* end of group CMSIS_TPI */ + + +#if (__MPU_PRESENT == 1U) +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_MPU Memory Protection Unit (MPU) + \brief Type definitions for the Memory Protection Unit (MPU) + @{ + */ + +/** + \brief Structure type to access the Memory Protection Unit (MPU). + */ +typedef struct +{ + __IM uint32_t TYPE; /*!< Offset: 0x000 (R/ ) MPU Type Register */ + __IOM uint32_t CTRL; /*!< Offset: 0x004 (R/W) MPU Control Register */ + __IOM uint32_t RNR; /*!< Offset: 0x008 (R/W) MPU Region RNRber Register */ + __IOM uint32_t RBAR; /*!< Offset: 0x00C (R/W) MPU Region Base Address Register */ + __IOM uint32_t RASR; /*!< Offset: 0x010 (R/W) MPU Region Attribute and Size Register */ + __IOM uint32_t RBAR_A1; /*!< Offset: 0x014 (R/W) MPU Alias 1 Region Base Address Register */ + __IOM uint32_t RASR_A1; /*!< Offset: 0x018 (R/W) MPU Alias 1 Region Attribute and Size Register */ + __IOM uint32_t RBAR_A2; /*!< Offset: 0x01C (R/W) MPU Alias 2 Region Base Address Register */ + __IOM uint32_t RASR_A2; /*!< Offset: 0x020 (R/W) MPU Alias 2 Region Attribute and Size Register */ + __IOM uint32_t RBAR_A3; /*!< Offset: 0x024 (R/W) MPU Alias 3 Region Base Address Register */ + __IOM uint32_t RASR_A3; /*!< Offset: 0x028 (R/W) MPU Alias 3 Region Attribute and Size Register */ +} MPU_Type; + +/* MPU Type Register Definitions */ +#define MPU_TYPE_IREGION_Pos 16U /*!< MPU TYPE: IREGION Position */ +#define MPU_TYPE_IREGION_Msk (0xFFUL << MPU_TYPE_IREGION_Pos) /*!< MPU TYPE: IREGION Mask */ + +#define MPU_TYPE_DREGION_Pos 8U /*!< MPU TYPE: DREGION Position */ +#define MPU_TYPE_DREGION_Msk (0xFFUL << MPU_TYPE_DREGION_Pos) /*!< MPU TYPE: DREGION Mask */ + +#define MPU_TYPE_SEPARATE_Pos 0U /*!< MPU TYPE: SEPARATE Position */ +#define MPU_TYPE_SEPARATE_Msk (1UL /*<< MPU_TYPE_SEPARATE_Pos*/) /*!< MPU TYPE: SEPARATE Mask */ + +/* MPU Control Register Definitions */ +#define MPU_CTRL_PRIVDEFENA_Pos 2U /*!< MPU CTRL: PRIVDEFENA Position */ +#define MPU_CTRL_PRIVDEFENA_Msk (1UL << MPU_CTRL_PRIVDEFENA_Pos) /*!< MPU CTRL: PRIVDEFENA Mask */ + +#define MPU_CTRL_HFNMIENA_Pos 1U /*!< MPU CTRL: HFNMIENA Position */ +#define MPU_CTRL_HFNMIENA_Msk (1UL << MPU_CTRL_HFNMIENA_Pos) /*!< MPU CTRL: HFNMIENA Mask */ + +#define MPU_CTRL_ENABLE_Pos 0U /*!< MPU CTRL: ENABLE Position */ +#define MPU_CTRL_ENABLE_Msk (1UL /*<< MPU_CTRL_ENABLE_Pos*/) /*!< MPU CTRL: ENABLE Mask */ + +/* MPU Region Number Register Definitions */ +#define MPU_RNR_REGION_Pos 0U /*!< MPU RNR: REGION Position */ +#define MPU_RNR_REGION_Msk (0xFFUL /*<< MPU_RNR_REGION_Pos*/) /*!< MPU RNR: REGION Mask */ + +/* MPU Region Base Address Register Definitions */ +#define MPU_RBAR_ADDR_Pos 5U /*!< MPU RBAR: ADDR Position */ +#define MPU_RBAR_ADDR_Msk (0x7FFFFFFUL << MPU_RBAR_ADDR_Pos) /*!< MPU RBAR: ADDR Mask */ + +#define MPU_RBAR_VALID_Pos 4U /*!< MPU RBAR: VALID Position */ +#define MPU_RBAR_VALID_Msk (1UL << MPU_RBAR_VALID_Pos) /*!< MPU RBAR: VALID Mask */ + +#define MPU_RBAR_REGION_Pos 0U /*!< MPU RBAR: REGION Position */ +#define MPU_RBAR_REGION_Msk (0xFUL /*<< MPU_RBAR_REGION_Pos*/) /*!< MPU RBAR: REGION Mask */ + +/* MPU Region Attribute and Size Register Definitions */ +#define MPU_RASR_ATTRS_Pos 16U /*!< MPU RASR: MPU Region Attribute field Position */ +#define MPU_RASR_ATTRS_Msk (0xFFFFUL << MPU_RASR_ATTRS_Pos) /*!< MPU RASR: MPU Region Attribute field Mask */ + +#define MPU_RASR_XN_Pos 28U /*!< MPU RASR: ATTRS.XN Position */ +#define MPU_RASR_XN_Msk (1UL << MPU_RASR_XN_Pos) /*!< MPU RASR: ATTRS.XN Mask */ + +#define MPU_RASR_AP_Pos 24U /*!< MPU RASR: ATTRS.AP Position */ +#define MPU_RASR_AP_Msk (0x7UL << MPU_RASR_AP_Pos) /*!< MPU RASR: ATTRS.AP Mask */ + +#define MPU_RASR_TEX_Pos 19U /*!< MPU RASR: ATTRS.TEX Position */ +#define MPU_RASR_TEX_Msk (0x7UL << MPU_RASR_TEX_Pos) /*!< MPU RASR: ATTRS.TEX Mask */ + +#define MPU_RASR_S_Pos 18U /*!< MPU RASR: ATTRS.S Position */ +#define MPU_RASR_S_Msk (1UL << MPU_RASR_S_Pos) /*!< MPU RASR: ATTRS.S Mask */ + +#define MPU_RASR_C_Pos 17U /*!< MPU RASR: ATTRS.C Position */ +#define MPU_RASR_C_Msk (1UL << MPU_RASR_C_Pos) /*!< MPU RASR: ATTRS.C Mask */ + +#define MPU_RASR_B_Pos 16U /*!< MPU RASR: ATTRS.B Position */ +#define MPU_RASR_B_Msk (1UL << MPU_RASR_B_Pos) /*!< MPU RASR: ATTRS.B Mask */ + +#define MPU_RASR_SRD_Pos 8U /*!< MPU RASR: Sub-Region Disable Position */ +#define MPU_RASR_SRD_Msk (0xFFUL << MPU_RASR_SRD_Pos) /*!< MPU RASR: Sub-Region Disable Mask */ + +#define MPU_RASR_SIZE_Pos 1U /*!< MPU RASR: Region Size Field Position */ +#define MPU_RASR_SIZE_Msk (0x1FUL << MPU_RASR_SIZE_Pos) /*!< MPU RASR: Region Size Field Mask */ + +#define MPU_RASR_ENABLE_Pos 0U /*!< MPU RASR: Region enable bit Position */ +#define MPU_RASR_ENABLE_Msk (1UL /*<< MPU_RASR_ENABLE_Pos*/) /*!< MPU RASR: Region enable bit Disable Mask */ + +/*@} end of group CMSIS_MPU */ +#endif + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_CoreDebug Core Debug Registers (CoreDebug) + \brief Type definitions for the Core Debug Registers + @{ + */ + +/** + \brief Structure type to access the Core Debug Register (CoreDebug). + */ +typedef struct +{ + __IOM uint32_t DHCSR; /*!< Offset: 0x000 (R/W) Debug Halting Control and Status Register */ + __OM uint32_t DCRSR; /*!< Offset: 0x004 ( /W) Debug Core Register Selector Register */ + __IOM uint32_t DCRDR; /*!< Offset: 0x008 (R/W) Debug Core Register Data Register */ + __IOM uint32_t DEMCR; /*!< Offset: 0x00C (R/W) Debug Exception and Monitor Control Register */ +} CoreDebug_Type; + +/* Debug Halting Control and Status Register Definitions */ +#define CoreDebug_DHCSR_DBGKEY_Pos 16U /*!< CoreDebug DHCSR: DBGKEY Position */ +#define CoreDebug_DHCSR_DBGKEY_Msk (0xFFFFUL << CoreDebug_DHCSR_DBGKEY_Pos) /*!< CoreDebug DHCSR: DBGKEY Mask */ + +#define CoreDebug_DHCSR_S_RESET_ST_Pos 25U /*!< CoreDebug DHCSR: S_RESET_ST Position */ +#define CoreDebug_DHCSR_S_RESET_ST_Msk (1UL << CoreDebug_DHCSR_S_RESET_ST_Pos) /*!< CoreDebug DHCSR: S_RESET_ST Mask */ + +#define CoreDebug_DHCSR_S_RETIRE_ST_Pos 24U /*!< CoreDebug DHCSR: S_RETIRE_ST Position */ +#define CoreDebug_DHCSR_S_RETIRE_ST_Msk (1UL << CoreDebug_DHCSR_S_RETIRE_ST_Pos) /*!< CoreDebug DHCSR: S_RETIRE_ST Mask */ + +#define CoreDebug_DHCSR_S_LOCKUP_Pos 19U /*!< CoreDebug DHCSR: S_LOCKUP Position */ +#define CoreDebug_DHCSR_S_LOCKUP_Msk (1UL << CoreDebug_DHCSR_S_LOCKUP_Pos) /*!< CoreDebug DHCSR: S_LOCKUP Mask */ + +#define CoreDebug_DHCSR_S_SLEEP_Pos 18U /*!< CoreDebug DHCSR: S_SLEEP Position */ +#define CoreDebug_DHCSR_S_SLEEP_Msk (1UL << CoreDebug_DHCSR_S_SLEEP_Pos) /*!< CoreDebug DHCSR: S_SLEEP Mask */ + +#define CoreDebug_DHCSR_S_HALT_Pos 17U /*!< CoreDebug DHCSR: S_HALT Position */ +#define CoreDebug_DHCSR_S_HALT_Msk (1UL << CoreDebug_DHCSR_S_HALT_Pos) /*!< CoreDebug DHCSR: S_HALT Mask */ + +#define CoreDebug_DHCSR_S_REGRDY_Pos 16U /*!< CoreDebug DHCSR: S_REGRDY Position */ +#define CoreDebug_DHCSR_S_REGRDY_Msk (1UL << CoreDebug_DHCSR_S_REGRDY_Pos) /*!< CoreDebug DHCSR: S_REGRDY Mask */ + +#define CoreDebug_DHCSR_C_SNAPSTALL_Pos 5U /*!< CoreDebug DHCSR: C_SNAPSTALL Position */ +#define CoreDebug_DHCSR_C_SNAPSTALL_Msk (1UL << CoreDebug_DHCSR_C_SNAPSTALL_Pos) /*!< CoreDebug DHCSR: C_SNAPSTALL Mask */ + +#define CoreDebug_DHCSR_C_MASKINTS_Pos 3U /*!< CoreDebug DHCSR: C_MASKINTS Position */ +#define CoreDebug_DHCSR_C_MASKINTS_Msk (1UL << CoreDebug_DHCSR_C_MASKINTS_Pos) /*!< CoreDebug DHCSR: C_MASKINTS Mask */ + +#define CoreDebug_DHCSR_C_STEP_Pos 2U /*!< CoreDebug DHCSR: C_STEP Position */ +#define CoreDebug_DHCSR_C_STEP_Msk (1UL << CoreDebug_DHCSR_C_STEP_Pos) /*!< CoreDebug DHCSR: C_STEP Mask */ + +#define CoreDebug_DHCSR_C_HALT_Pos 1U /*!< CoreDebug DHCSR: C_HALT Position */ +#define CoreDebug_DHCSR_C_HALT_Msk (1UL << CoreDebug_DHCSR_C_HALT_Pos) /*!< CoreDebug DHCSR: C_HALT Mask */ + +#define CoreDebug_DHCSR_C_DEBUGEN_Pos 0U /*!< CoreDebug DHCSR: C_DEBUGEN Position */ +#define CoreDebug_DHCSR_C_DEBUGEN_Msk (1UL /*<< CoreDebug_DHCSR_C_DEBUGEN_Pos*/) /*!< CoreDebug DHCSR: C_DEBUGEN Mask */ + +/* Debug Core Register Selector Register Definitions */ +#define CoreDebug_DCRSR_REGWnR_Pos 16U /*!< CoreDebug DCRSR: REGWnR Position */ +#define CoreDebug_DCRSR_REGWnR_Msk (1UL << CoreDebug_DCRSR_REGWnR_Pos) /*!< CoreDebug DCRSR: REGWnR Mask */ + +#define CoreDebug_DCRSR_REGSEL_Pos 0U /*!< CoreDebug DCRSR: REGSEL Position */ +#define CoreDebug_DCRSR_REGSEL_Msk (0x1FUL /*<< CoreDebug_DCRSR_REGSEL_Pos*/) /*!< CoreDebug DCRSR: REGSEL Mask */ + +/* Debug Exception and Monitor Control Register Definitions */ +#define CoreDebug_DEMCR_TRCENA_Pos 24U /*!< CoreDebug DEMCR: TRCENA Position */ +#define CoreDebug_DEMCR_TRCENA_Msk (1UL << CoreDebug_DEMCR_TRCENA_Pos) /*!< CoreDebug DEMCR: TRCENA Mask */ + +#define CoreDebug_DEMCR_MON_REQ_Pos 19U /*!< CoreDebug DEMCR: MON_REQ Position */ +#define CoreDebug_DEMCR_MON_REQ_Msk (1UL << CoreDebug_DEMCR_MON_REQ_Pos) /*!< CoreDebug DEMCR: MON_REQ Mask */ + +#define CoreDebug_DEMCR_MON_STEP_Pos 18U /*!< CoreDebug DEMCR: MON_STEP Position */ +#define CoreDebug_DEMCR_MON_STEP_Msk (1UL << CoreDebug_DEMCR_MON_STEP_Pos) /*!< CoreDebug DEMCR: MON_STEP Mask */ + +#define CoreDebug_DEMCR_MON_PEND_Pos 17U /*!< CoreDebug DEMCR: MON_PEND Position */ +#define CoreDebug_DEMCR_MON_PEND_Msk (1UL << CoreDebug_DEMCR_MON_PEND_Pos) /*!< CoreDebug DEMCR: MON_PEND Mask */ + +#define CoreDebug_DEMCR_MON_EN_Pos 16U /*!< CoreDebug DEMCR: MON_EN Position */ +#define CoreDebug_DEMCR_MON_EN_Msk (1UL << CoreDebug_DEMCR_MON_EN_Pos) /*!< CoreDebug DEMCR: MON_EN Mask */ + +#define CoreDebug_DEMCR_VC_HARDERR_Pos 10U /*!< CoreDebug DEMCR: VC_HARDERR Position */ +#define CoreDebug_DEMCR_VC_HARDERR_Msk (1UL << CoreDebug_DEMCR_VC_HARDERR_Pos) /*!< CoreDebug DEMCR: VC_HARDERR Mask */ + +#define CoreDebug_DEMCR_VC_INTERR_Pos 9U /*!< CoreDebug DEMCR: VC_INTERR Position */ +#define CoreDebug_DEMCR_VC_INTERR_Msk (1UL << CoreDebug_DEMCR_VC_INTERR_Pos) /*!< CoreDebug DEMCR: VC_INTERR Mask */ + +#define CoreDebug_DEMCR_VC_BUSERR_Pos 8U /*!< CoreDebug DEMCR: VC_BUSERR Position */ +#define CoreDebug_DEMCR_VC_BUSERR_Msk (1UL << CoreDebug_DEMCR_VC_BUSERR_Pos) /*!< CoreDebug DEMCR: VC_BUSERR Mask */ + +#define CoreDebug_DEMCR_VC_STATERR_Pos 7U /*!< CoreDebug DEMCR: VC_STATERR Position */ +#define CoreDebug_DEMCR_VC_STATERR_Msk (1UL << CoreDebug_DEMCR_VC_STATERR_Pos) /*!< CoreDebug DEMCR: VC_STATERR Mask */ + +#define CoreDebug_DEMCR_VC_CHKERR_Pos 6U /*!< CoreDebug DEMCR: VC_CHKERR Position */ +#define CoreDebug_DEMCR_VC_CHKERR_Msk (1UL << CoreDebug_DEMCR_VC_CHKERR_Pos) /*!< CoreDebug DEMCR: VC_CHKERR Mask */ + +#define CoreDebug_DEMCR_VC_NOCPERR_Pos 5U /*!< CoreDebug DEMCR: VC_NOCPERR Position */ +#define CoreDebug_DEMCR_VC_NOCPERR_Msk (1UL << CoreDebug_DEMCR_VC_NOCPERR_Pos) /*!< CoreDebug DEMCR: VC_NOCPERR Mask */ + +#define CoreDebug_DEMCR_VC_MMERR_Pos 4U /*!< CoreDebug DEMCR: VC_MMERR Position */ +#define CoreDebug_DEMCR_VC_MMERR_Msk (1UL << CoreDebug_DEMCR_VC_MMERR_Pos) /*!< CoreDebug DEMCR: VC_MMERR Mask */ + +#define CoreDebug_DEMCR_VC_CORERESET_Pos 0U /*!< CoreDebug DEMCR: VC_CORERESET Position */ +#define CoreDebug_DEMCR_VC_CORERESET_Msk (1UL /*<< CoreDebug_DEMCR_VC_CORERESET_Pos*/) /*!< CoreDebug DEMCR: VC_CORERESET Mask */ + +/*@} end of group CMSIS_CoreDebug */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_core_bitfield Core register bit field macros + \brief Macros for use with bit field definitions (xxx_Pos, xxx_Msk). + @{ + */ + +/** + \brief Mask and shift a bit field value for use in a register bit range. + \param[in] field Name of the register bit field. + \param[in] value Value of the bit field. + \return Masked and shifted value. +*/ +#define _VAL2FLD(field, value) ((value << field ## _Pos) & field ## _Msk) + +/** + \brief Mask and shift a register value to extract a bit filed value. + \param[in] field Name of the register bit field. + \param[in] value Value of register. + \return Masked and shifted bit field value. +*/ +#define _FLD2VAL(field, value) ((value & field ## _Msk) >> field ## _Pos) + +/*@} end of group CMSIS_core_bitfield */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_core_base Core Definitions + \brief Definitions for base addresses, unions, and structures. + @{ + */ + +/* Memory mapping of Cortex-M3 Hardware */ +#define SCS_BASE (0xE000E000UL) /*!< System Control Space Base Address */ +#define ITM_BASE (0xE0000000UL) /*!< ITM Base Address */ +#define DWT_BASE (0xE0001000UL) /*!< DWT Base Address */ +#define TPI_BASE (0xE0040000UL) /*!< TPI Base Address */ +#define CoreDebug_BASE (0xE000EDF0UL) /*!< Core Debug Base Address */ +#define SysTick_BASE (SCS_BASE + 0x0010UL) /*!< SysTick Base Address */ +#define NVIC_BASE (SCS_BASE + 0x0100UL) /*!< NVIC Base Address */ +#define SCB_BASE (SCS_BASE + 0x0D00UL) /*!< System Control Block Base Address */ + +#define SCnSCB ((SCnSCB_Type *) SCS_BASE ) /*!< System control Register not in SCB */ +#define SCB ((SCB_Type *) SCB_BASE ) /*!< SCB configuration struct */ +#define SysTick ((SysTick_Type *) SysTick_BASE ) /*!< SysTick configuration struct */ +#define NVIC ((NVIC_Type *) NVIC_BASE ) /*!< NVIC configuration struct */ +#define ITM ((ITM_Type *) ITM_BASE ) /*!< ITM configuration struct */ +#define DWT ((DWT_Type *) DWT_BASE ) /*!< DWT configuration struct */ +#define TPI ((TPI_Type *) TPI_BASE ) /*!< TPI configuration struct */ +#define CoreDebug ((CoreDebug_Type *) CoreDebug_BASE) /*!< Core Debug configuration struct */ + +#if (__MPU_PRESENT == 1U) + #define MPU_BASE (SCS_BASE + 0x0D90UL) /*!< Memory Protection Unit */ + #define MPU ((MPU_Type *) MPU_BASE ) /*!< Memory Protection Unit */ +#endif + +/*@} */ + + + +/******************************************************************************* + * Hardware Abstraction Layer + Core Function Interface contains: + - Core NVIC Functions + - Core SysTick Functions + - Core Debug Functions + - Core Register Access Functions + ******************************************************************************/ +/** + \defgroup CMSIS_Core_FunctionInterface Functions and Instructions Reference +*/ + + + +/* ########################## NVIC functions #################################### */ +/** + \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_NVICFunctions NVIC Functions + \brief Functions that manage interrupts and exceptions via the NVIC. + @{ + */ + +/** + \brief Set Priority Grouping + \details Sets the priority grouping field using the required unlock sequence. + The parameter PriorityGroup is assigned to the field SCB->AIRCR [10:8] PRIGROUP field. + Only values from 0..7 are used. + In case of a conflict between priority grouping and available + priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. + \param [in] PriorityGroup Priority grouping field. + */ +__STATIC_INLINE void NVIC_SetPriorityGrouping(uint32_t PriorityGroup) +{ + uint32_t reg_value; + uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ + + reg_value = SCB->AIRCR; /* read old register configuration */ + reg_value &= ~((uint32_t)(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk)); /* clear bits to change */ + reg_value = (reg_value | + ((uint32_t)0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | + (PriorityGroupTmp << 8U) ); /* Insert write key and priorty group */ + SCB->AIRCR = reg_value; +} + + +/** + \brief Get Priority Grouping + \details Reads the priority grouping field from the NVIC Interrupt Controller. + \return Priority grouping field (SCB->AIRCR [10:8] PRIGROUP field). + */ +__STATIC_INLINE uint32_t NVIC_GetPriorityGrouping(void) +{ + return ((uint32_t)((SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) >> SCB_AIRCR_PRIGROUP_Pos)); +} + + +/** + \brief Enable External Interrupt + \details Enables a device-specific interrupt in the NVIC interrupt controller. + \param [in] IRQn External interrupt number. Value cannot be negative. + */ +__STATIC_INLINE void NVIC_EnableIRQ(IRQn_Type IRQn) +{ + NVIC->ISER[(((uint32_t)(int32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)(int32_t)IRQn) & 0x1FUL)); +} + + +/** + \brief Disable External Interrupt + \details Disables a device-specific interrupt in the NVIC interrupt controller. + \param [in] IRQn External interrupt number. Value cannot be negative. + */ +__STATIC_INLINE void NVIC_DisableIRQ(IRQn_Type IRQn) +{ + NVIC->ICER[(((uint32_t)(int32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)(int32_t)IRQn) & 0x1FUL)); +} + + +/** + \brief Get Pending Interrupt + \details Reads the pending register in the NVIC and returns the pending bit for the specified interrupt. + \param [in] IRQn Interrupt number. + \return 0 Interrupt status is not pending. + \return 1 Interrupt status is pending. + */ +__STATIC_INLINE uint32_t NVIC_GetPendingIRQ(IRQn_Type IRQn) +{ + return((uint32_t)(((NVIC->ISPR[(((uint32_t)(int32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)(int32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); +} + + +/** + \brief Set Pending Interrupt + \details Sets the pending bit of an external interrupt. + \param [in] IRQn Interrupt number. Value cannot be negative. + */ +__STATIC_INLINE void NVIC_SetPendingIRQ(IRQn_Type IRQn) +{ + NVIC->ISPR[(((uint32_t)(int32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)(int32_t)IRQn) & 0x1FUL)); +} + + +/** + \brief Clear Pending Interrupt + \details Clears the pending bit of an external interrupt. + \param [in] IRQn External interrupt number. Value cannot be negative. + */ +__STATIC_INLINE void NVIC_ClearPendingIRQ(IRQn_Type IRQn) +{ + NVIC->ICPR[(((uint32_t)(int32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)(int32_t)IRQn) & 0x1FUL)); +} + + +/** + \brief Get Active Interrupt + \details Reads the active register in NVIC and returns the active bit. + \param [in] IRQn Interrupt number. + \return 0 Interrupt status is not active. + \return 1 Interrupt status is active. + */ +__STATIC_INLINE uint32_t NVIC_GetActive(IRQn_Type IRQn) +{ + return((uint32_t)(((NVIC->IABR[(((uint32_t)(int32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)(int32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); +} + + +/** + \brief Set Interrupt Priority + \details Sets the priority of an interrupt. + \note The priority cannot be set for every core interrupt. + \param [in] IRQn Interrupt number. + \param [in] priority Priority to set. + */ +__STATIC_INLINE void NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority) +{ + if ((int32_t)(IRQn) < 0) + { + SCB->SHP[(((uint32_t)(int32_t)IRQn) & 0xFUL)-4UL] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); + } + else + { + NVIC->IP[((uint32_t)(int32_t)IRQn)] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); + } +} + + +/** + \brief Get Interrupt Priority + \details Reads the priority of an interrupt. + The interrupt number can be positive to specify an external (device specific) interrupt, + or negative to specify an internal (core) interrupt. + \param [in] IRQn Interrupt number. + \return Interrupt Priority. + Value is aligned automatically to the implemented priority bits of the microcontroller. + */ +__STATIC_INLINE uint32_t NVIC_GetPriority(IRQn_Type IRQn) +{ + + if ((int32_t)(IRQn) < 0) + { + return(((uint32_t)SCB->SHP[(((uint32_t)(int32_t)IRQn) & 0xFUL)-4UL] >> (8U - __NVIC_PRIO_BITS))); + } + else + { + return(((uint32_t)NVIC->IP[((uint32_t)(int32_t)IRQn)] >> (8U - __NVIC_PRIO_BITS))); + } +} + + +/** + \brief Encode Priority + \details Encodes the priority for an interrupt with the given priority group, + preemptive priority value, and subpriority value. + In case of a conflict between priority grouping and available + priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. + \param [in] PriorityGroup Used priority group. + \param [in] PreemptPriority Preemptive priority value (starting from 0). + \param [in] SubPriority Subpriority value (starting from 0). + \return Encoded priority. Value can be used in the function \ref NVIC_SetPriority(). + */ +__STATIC_INLINE uint32_t NVIC_EncodePriority (uint32_t PriorityGroup, uint32_t PreemptPriority, uint32_t SubPriority) +{ + uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ + uint32_t PreemptPriorityBits; + uint32_t SubPriorityBits; + + PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); + SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); + + return ( + ((PreemptPriority & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL)) << SubPriorityBits) | + ((SubPriority & (uint32_t)((1UL << (SubPriorityBits )) - 1UL))) + ); +} + + +/** + \brief Decode Priority + \details Decodes an interrupt priority value with a given priority group to + preemptive priority value and subpriority value. + In case of a conflict between priority grouping and available + priority bits (__NVIC_PRIO_BITS) the smallest possible priority group is set. + \param [in] Priority Priority value, which can be retrieved with the function \ref NVIC_GetPriority(). + \param [in] PriorityGroup Used priority group. + \param [out] pPreemptPriority Preemptive priority value (starting from 0). + \param [out] pSubPriority Subpriority value (starting from 0). + */ +__STATIC_INLINE void NVIC_DecodePriority (uint32_t Priority, uint32_t PriorityGroup, uint32_t* const pPreemptPriority, uint32_t* const pSubPriority) +{ + uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ + uint32_t PreemptPriorityBits; + uint32_t SubPriorityBits; + + PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); + SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); + + *pPreemptPriority = (Priority >> SubPriorityBits) & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL); + *pSubPriority = (Priority ) & (uint32_t)((1UL << (SubPriorityBits )) - 1UL); +} + + +/** + \brief System Reset + \details Initiates a system reset request to reset the MCU. + */ +__STATIC_INLINE void NVIC_SystemReset(void) +{ + __DSB(); /* Ensure all outstanding memory accesses included + buffered write are completed before reset */ + SCB->AIRCR = (uint32_t)((0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | + (SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) | + SCB_AIRCR_SYSRESETREQ_Msk ); /* Keep priority group unchanged */ + __DSB(); /* Ensure completion of memory access */ + + for(;;) /* wait until reset */ + { + __NOP(); + } +} + +/*@} end of CMSIS_Core_NVICFunctions */ + + + +/* ################################## SysTick function ############################################ */ +/** + \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_SysTickFunctions SysTick Functions + \brief Functions that configure the System. + @{ + */ + +#if (__Vendor_SysTickConfig == 0U) + +/** + \brief System Tick Configuration + \details Initializes the System Timer and its interrupt, and starts the System Tick Timer. + Counter is in free running mode to generate periodic interrupts. + \param [in] ticks Number of ticks between two interrupts. + \return 0 Function succeeded. + \return 1 Function failed. + \note When the variable __Vendor_SysTickConfig is set to 1, then the + function SysTick_Config is not included. In this case, the file device.h + must contain a vendor-specific implementation of this function. + */ +__STATIC_INLINE uint32_t SysTick_Config(uint32_t ticks) +{ + if ((ticks - 1UL) > SysTick_LOAD_RELOAD_Msk) + { + return (1UL); /* Reload value impossible */ + } + + SysTick->LOAD = (uint32_t)(ticks - 1UL); /* set reload register */ + NVIC_SetPriority (SysTick_IRQn, (1UL << __NVIC_PRIO_BITS) - 1UL); /* set Priority for Systick Interrupt */ + SysTick->VAL = 0UL; /* Load the SysTick Counter Value */ + SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk | + SysTick_CTRL_TICKINT_Msk | + SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ + return (0UL); /* Function successful */ +} + +#endif + +/*@} end of CMSIS_Core_SysTickFunctions */ + + + +/* ##################################### Debug In/Output function ########################################### */ +/** + \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_core_DebugFunctions ITM Functions + \brief Functions that access the ITM debug interface. + @{ + */ + +extern volatile int32_t ITM_RxBuffer; /*!< External variable to receive characters. */ +#define ITM_RXBUFFER_EMPTY 0x5AA55AA5U /*!< Value identifying \ref ITM_RxBuffer is ready for next character. */ + + +/** + \brief ITM Send Character + \details Transmits a character via the ITM channel 0, and + \li Just returns when no debugger is connected that has booked the output. + \li Is blocking when a debugger is connected, but the previous character sent has not been transmitted. + \param [in] ch Character to transmit. + \returns Character to transmit. + */ +__STATIC_INLINE uint32_t ITM_SendChar (uint32_t ch) +{ + if (((ITM->TCR & ITM_TCR_ITMENA_Msk) != 0UL) && /* ITM enabled */ + ((ITM->TER & 1UL ) != 0UL) ) /* ITM Port #0 enabled */ + { + while (ITM->PORT[0U].u32 == 0UL) + { + __NOP(); + } + ITM->PORT[0U].u8 = (uint8_t)ch; + } + return (ch); +} + + +/** + \brief ITM Receive Character + \details Inputs a character via the external variable \ref ITM_RxBuffer. + \return Received character. + \return -1 No character pending. + */ +__STATIC_INLINE int32_t ITM_ReceiveChar (void) +{ + int32_t ch = -1; /* no character available */ + + if (ITM_RxBuffer != ITM_RXBUFFER_EMPTY) + { + ch = ITM_RxBuffer; + ITM_RxBuffer = ITM_RXBUFFER_EMPTY; /* ready for next character */ + } + + return (ch); +} + + +/** + \brief ITM Check Character + \details Checks whether a character is pending for reading in the variable \ref ITM_RxBuffer. + \return 0 No character available. + \return 1 Character available. + */ +__STATIC_INLINE int32_t ITM_CheckChar (void) +{ + + if (ITM_RxBuffer == ITM_RXBUFFER_EMPTY) + { + return (0); /* no character available */ + } + else + { + return (1); /* character available */ + } +} + +/*@} end of CMSIS_core_DebugFunctions */ + + + + +#ifdef __cplusplus +} +#endif + +#endif /* __CORE_CM3_H_DEPENDANT */ + +#endif /* __CMSIS_GENERIC */ diff --git a/panda/board/inc/core_cm4.h b/panda/board/inc/core_cm4.h new file mode 100644 index 00000000000000..dc840ebf222138 --- /dev/null +++ b/panda/board/inc/core_cm4.h @@ -0,0 +1,1937 @@ +/**************************************************************************//** + * @file core_cm4.h + * @brief CMSIS Cortex-M4 Core Peripheral Access Layer Header File + * @version V4.30 + * @date 20. October 2015 + ******************************************************************************/ +/* Copyright (c) 2009 - 2015 ARM LIMITED + + All rights reserved. + Redistribution and use in source and binary forms, with or without + modification, are permitted provided that the following conditions are met: + - Redistributions of source code must retain the above copyright + notice, this list of conditions and the following disclaimer. + - Redistributions in binary form must reproduce the above copyright + notice, this list of conditions and the following disclaimer in the + documentation and/or other materials provided with the distribution. + - Neither the name of ARM nor the names of its contributors may be used + to endorse or promote products derived from this software without + specific prior written permission. + * + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE + LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + POSSIBILITY OF SUCH DAMAGE. + ---------------------------------------------------------------------------*/ + + +#if defined ( __ICCARM__ ) + #pragma system_include /* treat file as system include file for MISRA check */ +#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) + #pragma clang system_header /* treat file as system include file */ +#endif + +#ifndef __CORE_CM4_H_GENERIC +#define __CORE_CM4_H_GENERIC + +#include + +#ifdef __cplusplus + extern "C" { +#endif + +/** + \page CMSIS_MISRA_Exceptions MISRA-C:2004 Compliance Exceptions + CMSIS violates the following MISRA-C:2004 rules: + + \li Required Rule 8.5, object/function definition in header file.
+ Function definitions in header files are used to allow 'inlining'. + + \li Required Rule 18.4, declaration of union type or object of union type: '{...}'.
+ Unions are used for effective representation of core registers. + + \li Advisory Rule 19.7, Function-like macro defined.
+ Function-like macros are used to allow more efficient code. + */ + + +/******************************************************************************* + * CMSIS definitions + ******************************************************************************/ +/** + \ingroup Cortex_M4 + @{ + */ + +/* CMSIS CM4 definitions */ +#define __CM4_CMSIS_VERSION_MAIN (0x04U) /*!< [31:16] CMSIS HAL main version */ +#define __CM4_CMSIS_VERSION_SUB (0x1EU) /*!< [15:0] CMSIS HAL sub version */ +#define __CM4_CMSIS_VERSION ((__CM4_CMSIS_VERSION_MAIN << 16U) | \ + __CM4_CMSIS_VERSION_SUB ) /*!< CMSIS HAL version number */ + +#define __CORTEX_M (0x04U) /*!< Cortex-M Core */ + + +#if defined ( __CC_ARM ) + #define __ASM __asm /*!< asm keyword for ARM Compiler */ + #define __INLINE __inline /*!< inline keyword for ARM Compiler */ + #define __STATIC_INLINE static __inline + +#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) + #define __ASM __asm /*!< asm keyword for ARM Compiler */ + #define __INLINE __inline /*!< inline keyword for ARM Compiler */ + #define __STATIC_INLINE static __inline + +#elif defined ( __GNUC__ ) + #define __ASM __asm /*!< asm keyword for GNU Compiler */ + #define __INLINE inline /*!< inline keyword for GNU Compiler */ + #define __STATIC_INLINE static inline + +#elif defined ( __ICCARM__ ) + #define __ASM __asm /*!< asm keyword for IAR Compiler */ + #define __INLINE inline /*!< inline keyword for IAR Compiler. Only available in High optimization mode! */ + #define __STATIC_INLINE static inline + +#elif defined ( __TMS470__ ) + #define __ASM __asm /*!< asm keyword for TI CCS Compiler */ + #define __STATIC_INLINE static inline + +#elif defined ( __TASKING__ ) + #define __ASM __asm /*!< asm keyword for TASKING Compiler */ + #define __INLINE inline /*!< inline keyword for TASKING Compiler */ + #define __STATIC_INLINE static inline + +#elif defined ( __CSMC__ ) + #define __packed + #define __ASM _asm /*!< asm keyword for COSMIC Compiler */ + #define __INLINE inline /*!< inline keyword for COSMIC Compiler. Use -pc99 on compile line */ + #define __STATIC_INLINE static inline + +#else + #error Unknown compiler +#endif + +/** __FPU_USED indicates whether an FPU is used or not. + For this, __FPU_PRESENT has to be checked prior to making use of FPU specific registers and functions. +*/ +#if defined ( __CC_ARM ) + #if defined __TARGET_FPU_VFP + #if (__FPU_PRESENT == 1U) + #define __FPU_USED 1U + #else + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #define __FPU_USED 0U + #endif + #else + #define __FPU_USED 0U + #endif + +#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) + #if defined __ARM_PCS_VFP + #if (__FPU_PRESENT == 1) + #define __FPU_USED 1U + #else + #warning "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #define __FPU_USED 0U + #endif + #else + #define __FPU_USED 0U + #endif + +#elif defined ( __GNUC__ ) + #if defined (__VFP_FP__) && !defined(__SOFTFP__) + #if (__FPU_PRESENT == 1U) + #define __FPU_USED 1U + #else + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #define __FPU_USED 0U + #endif + #else + #define __FPU_USED 0U + #endif + +#elif defined ( __ICCARM__ ) + #if defined __ARMVFP__ + #if (__FPU_PRESENT == 1U) + #define __FPU_USED 1U + #else + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #define __FPU_USED 0U + #endif + #else + #define __FPU_USED 0U + #endif + +#elif defined ( __TMS470__ ) + #if defined __TI_VFP_SUPPORT__ + #if (__FPU_PRESENT == 1U) + #define __FPU_USED 1U + #else + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #define __FPU_USED 0U + #endif + #else + #define __FPU_USED 0U + #endif + +#elif defined ( __TASKING__ ) + #if defined __FPU_VFP__ + #if (__FPU_PRESENT == 1U) + #define __FPU_USED 1U + #else + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #define __FPU_USED 0U + #endif + #else + #define __FPU_USED 0U + #endif + +#elif defined ( __CSMC__ ) + #if ( __CSMC__ & 0x400U) + #if (__FPU_PRESENT == 1U) + #define __FPU_USED 1U + #else + #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #define __FPU_USED 0U + #endif + #else + #define __FPU_USED 0U + #endif + +#endif + +#include "core_cmInstr.h" /* Core Instruction Access */ +#include "core_cmFunc.h" /* Core Function Access */ +#include "core_cmSimd.h" /* Compiler specific SIMD Intrinsics */ + +#ifdef __cplusplus +} +#endif + +#endif /* __CORE_CM4_H_GENERIC */ + +#ifndef __CMSIS_GENERIC + +#ifndef __CORE_CM4_H_DEPENDANT +#define __CORE_CM4_H_DEPENDANT + +#ifdef __cplusplus + extern "C" { +#endif + +/* check device defines and use defaults */ +#if defined __CHECK_DEVICE_DEFINES + #ifndef __CM4_REV + #define __CM4_REV 0x0000U + #warning "__CM4_REV not defined in device header file; using default!" + #endif + + #ifndef __FPU_PRESENT + #define __FPU_PRESENT 0U + #warning "__FPU_PRESENT not defined in device header file; using default!" + #endif + + #ifndef __MPU_PRESENT + #define __MPU_PRESENT 0U + #warning "__MPU_PRESENT not defined in device header file; using default!" + #endif + + #ifndef __NVIC_PRIO_BITS + #define __NVIC_PRIO_BITS 4U + #warning "__NVIC_PRIO_BITS not defined in device header file; using default!" + #endif + + #ifndef __Vendor_SysTickConfig + #define __Vendor_SysTickConfig 0U + #warning "__Vendor_SysTickConfig not defined in device header file; using default!" + #endif +#endif + +/* IO definitions (access restrictions to peripheral registers) */ +/** + \defgroup CMSIS_glob_defs CMSIS Global Defines + + IO Type Qualifiers are used + \li to specify the access to peripheral variables. + \li for automatic generation of peripheral register debug information. +*/ +#ifdef __cplusplus + #define __I volatile /*!< Defines 'read only' permissions */ +#else + #define __I volatile const /*!< Defines 'read only' permissions */ +#endif +#define __O volatile /*!< Defines 'write only' permissions */ +#define __IO volatile /*!< Defines 'read / write' permissions */ + +/* following defines should be used for structure members */ +#define __IM volatile const /*! Defines 'read only' structure member permissions */ +#define __OM volatile /*! Defines 'write only' structure member permissions */ +#define __IOM volatile /*! Defines 'read / write' structure member permissions */ + +/*@} end of group Cortex_M4 */ + + + +/******************************************************************************* + * Register Abstraction + Core Register contain: + - Core Register + - Core NVIC Register + - Core SCB Register + - Core SysTick Register + - Core Debug Register + - Core MPU Register + - Core FPU Register + ******************************************************************************/ +/** + \defgroup CMSIS_core_register Defines and Type Definitions + \brief Type definitions and defines for Cortex-M processor based devices. +*/ + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_CORE Status and Control Registers + \brief Core Register type definitions. + @{ + */ + +/** + \brief Union type to access the Application Program Status Register (APSR). + */ +typedef union +{ + struct + { + uint32_t _reserved0:16; /*!< bit: 0..15 Reserved */ + uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */ + uint32_t _reserved1:7; /*!< bit: 20..26 Reserved */ + uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ + uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ + uint32_t C:1; /*!< bit: 29 Carry condition code flag */ + uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ + uint32_t N:1; /*!< bit: 31 Negative condition code flag */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} APSR_Type; + +/* APSR Register Definitions */ +#define APSR_N_Pos 31U /*!< APSR: N Position */ +#define APSR_N_Msk (1UL << APSR_N_Pos) /*!< APSR: N Mask */ + +#define APSR_Z_Pos 30U /*!< APSR: Z Position */ +#define APSR_Z_Msk (1UL << APSR_Z_Pos) /*!< APSR: Z Mask */ + +#define APSR_C_Pos 29U /*!< APSR: C Position */ +#define APSR_C_Msk (1UL << APSR_C_Pos) /*!< APSR: C Mask */ + +#define APSR_V_Pos 28U /*!< APSR: V Position */ +#define APSR_V_Msk (1UL << APSR_V_Pos) /*!< APSR: V Mask */ + +#define APSR_Q_Pos 27U /*!< APSR: Q Position */ +#define APSR_Q_Msk (1UL << APSR_Q_Pos) /*!< APSR: Q Mask */ + +#define APSR_GE_Pos 16U /*!< APSR: GE Position */ +#define APSR_GE_Msk (0xFUL << APSR_GE_Pos) /*!< APSR: GE Mask */ + + +/** + \brief Union type to access the Interrupt Program Status Register (IPSR). + */ +typedef union +{ + struct + { + uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ + uint32_t _reserved0:23; /*!< bit: 9..31 Reserved */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} IPSR_Type; + +/* IPSR Register Definitions */ +#define IPSR_ISR_Pos 0U /*!< IPSR: ISR Position */ +#define IPSR_ISR_Msk (0x1FFUL /*<< IPSR_ISR_Pos*/) /*!< IPSR: ISR Mask */ + + +/** + \brief Union type to access the Special-Purpose Program Status Registers (xPSR). + */ +typedef union +{ + struct + { + uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ + uint32_t _reserved0:7; /*!< bit: 9..15 Reserved */ + uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */ + uint32_t _reserved1:4; /*!< bit: 20..23 Reserved */ + uint32_t T:1; /*!< bit: 24 Thumb bit (read 0) */ + uint32_t IT:2; /*!< bit: 25..26 saved IT state (read 0) */ + uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ + uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ + uint32_t C:1; /*!< bit: 29 Carry condition code flag */ + uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ + uint32_t N:1; /*!< bit: 31 Negative condition code flag */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} xPSR_Type; + +/* xPSR Register Definitions */ +#define xPSR_N_Pos 31U /*!< xPSR: N Position */ +#define xPSR_N_Msk (1UL << xPSR_N_Pos) /*!< xPSR: N Mask */ + +#define xPSR_Z_Pos 30U /*!< xPSR: Z Position */ +#define xPSR_Z_Msk (1UL << xPSR_Z_Pos) /*!< xPSR: Z Mask */ + +#define xPSR_C_Pos 29U /*!< xPSR: C Position */ +#define xPSR_C_Msk (1UL << xPSR_C_Pos) /*!< xPSR: C Mask */ + +#define xPSR_V_Pos 28U /*!< xPSR: V Position */ +#define xPSR_V_Msk (1UL << xPSR_V_Pos) /*!< xPSR: V Mask */ + +#define xPSR_Q_Pos 27U /*!< xPSR: Q Position */ +#define xPSR_Q_Msk (1UL << xPSR_Q_Pos) /*!< xPSR: Q Mask */ + +#define xPSR_IT_Pos 25U /*!< xPSR: IT Position */ +#define xPSR_IT_Msk (3UL << xPSR_IT_Pos) /*!< xPSR: IT Mask */ + +#define xPSR_T_Pos 24U /*!< xPSR: T Position */ +#define xPSR_T_Msk (1UL << xPSR_T_Pos) /*!< xPSR: T Mask */ + +#define xPSR_GE_Pos 16U /*!< xPSR: GE Position */ +#define xPSR_GE_Msk (0xFUL << xPSR_GE_Pos) /*!< xPSR: GE Mask */ + +#define xPSR_ISR_Pos 0U /*!< xPSR: ISR Position */ +#define xPSR_ISR_Msk (0x1FFUL /*<< xPSR_ISR_Pos*/) /*!< xPSR: ISR Mask */ + + +/** + \brief Union type to access the Control Registers (CONTROL). + */ +typedef union +{ + struct + { + uint32_t nPRIV:1; /*!< bit: 0 Execution privilege in Thread mode */ + uint32_t SPSEL:1; /*!< bit: 1 Stack to be used */ + uint32_t FPCA:1; /*!< bit: 2 FP extension active flag */ + uint32_t _reserved0:29; /*!< bit: 3..31 Reserved */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} CONTROL_Type; + +/* CONTROL Register Definitions */ +#define CONTROL_FPCA_Pos 2U /*!< CONTROL: FPCA Position */ +#define CONTROL_FPCA_Msk (1UL << CONTROL_FPCA_Pos) /*!< CONTROL: FPCA Mask */ + +#define CONTROL_SPSEL_Pos 1U /*!< CONTROL: SPSEL Position */ +#define CONTROL_SPSEL_Msk (1UL << CONTROL_SPSEL_Pos) /*!< CONTROL: SPSEL Mask */ + +#define CONTROL_nPRIV_Pos 0U /*!< CONTROL: nPRIV Position */ +#define CONTROL_nPRIV_Msk (1UL /*<< CONTROL_nPRIV_Pos*/) /*!< CONTROL: nPRIV Mask */ + +/*@} end of group CMSIS_CORE */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_NVIC Nested Vectored Interrupt Controller (NVIC) + \brief Type definitions for the NVIC Registers + @{ + */ + +/** + \brief Structure type to access the Nested Vectored Interrupt Controller (NVIC). + */ +typedef struct +{ + __IOM uint32_t ISER[8U]; /*!< Offset: 0x000 (R/W) Interrupt Set Enable Register */ + uint32_t RESERVED0[24U]; + __IOM uint32_t ICER[8U]; /*!< Offset: 0x080 (R/W) Interrupt Clear Enable Register */ + uint32_t RSERVED1[24U]; + __IOM uint32_t ISPR[8U]; /*!< Offset: 0x100 (R/W) Interrupt Set Pending Register */ + uint32_t RESERVED2[24U]; + __IOM uint32_t ICPR[8U]; /*!< Offset: 0x180 (R/W) Interrupt Clear Pending Register */ + uint32_t RESERVED3[24U]; + __IOM uint32_t IABR[8U]; /*!< Offset: 0x200 (R/W) Interrupt Active bit Register */ + uint32_t RESERVED4[56U]; + __IOM uint8_t IP[240U]; /*!< Offset: 0x300 (R/W) Interrupt Priority Register (8Bit wide) */ + uint32_t RESERVED5[644U]; + __OM uint32_t STIR; /*!< Offset: 0xE00 ( /W) Software Trigger Interrupt Register */ +} NVIC_Type; + +/* Software Triggered Interrupt Register Definitions */ +#define NVIC_STIR_INTID_Pos 0U /*!< STIR: INTLINESNUM Position */ +#define NVIC_STIR_INTID_Msk (0x1FFUL /*<< NVIC_STIR_INTID_Pos*/) /*!< STIR: INTLINESNUM Mask */ + +/*@} end of group CMSIS_NVIC */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_SCB System Control Block (SCB) + \brief Type definitions for the System Control Block Registers + @{ + */ + +/** + \brief Structure type to access the System Control Block (SCB). + */ +typedef struct +{ + __IM uint32_t CPUID; /*!< Offset: 0x000 (R/ ) CPUID Base Register */ + __IOM uint32_t ICSR; /*!< Offset: 0x004 (R/W) Interrupt Control and State Register */ + __IOM uint32_t VTOR; /*!< Offset: 0x008 (R/W) Vector Table Offset Register */ + __IOM uint32_t AIRCR; /*!< Offset: 0x00C (R/W) Application Interrupt and Reset Control Register */ + __IOM uint32_t SCR; /*!< Offset: 0x010 (R/W) System Control Register */ + __IOM uint32_t CCR; /*!< Offset: 0x014 (R/W) Configuration Control Register */ + __IOM uint8_t SHP[12U]; /*!< Offset: 0x018 (R/W) System Handlers Priority Registers (4-7, 8-11, 12-15) */ + __IOM uint32_t SHCSR; /*!< Offset: 0x024 (R/W) System Handler Control and State Register */ + __IOM uint32_t CFSR; /*!< Offset: 0x028 (R/W) Configurable Fault Status Register */ + __IOM uint32_t HFSR; /*!< Offset: 0x02C (R/W) HardFault Status Register */ + __IOM uint32_t DFSR; /*!< Offset: 0x030 (R/W) Debug Fault Status Register */ + __IOM uint32_t MMFAR; /*!< Offset: 0x034 (R/W) MemManage Fault Address Register */ + __IOM uint32_t BFAR; /*!< Offset: 0x038 (R/W) BusFault Address Register */ + __IOM uint32_t AFSR; /*!< Offset: 0x03C (R/W) Auxiliary Fault Status Register */ + __IM uint32_t PFR[2U]; /*!< Offset: 0x040 (R/ ) Processor Feature Register */ + __IM uint32_t DFR; /*!< Offset: 0x048 (R/ ) Debug Feature Register */ + __IM uint32_t ADR; /*!< Offset: 0x04C (R/ ) Auxiliary Feature Register */ + __IM uint32_t MMFR[4U]; /*!< Offset: 0x050 (R/ ) Memory Model Feature Register */ + __IM uint32_t ISAR[5U]; /*!< Offset: 0x060 (R/ ) Instruction Set Attributes Register */ + uint32_t RESERVED0[5U]; + __IOM uint32_t CPACR; /*!< Offset: 0x088 (R/W) Coprocessor Access Control Register */ +} SCB_Type; + +/* SCB CPUID Register Definitions */ +#define SCB_CPUID_IMPLEMENTER_Pos 24U /*!< SCB CPUID: IMPLEMENTER Position */ +#define SCB_CPUID_IMPLEMENTER_Msk (0xFFUL << SCB_CPUID_IMPLEMENTER_Pos) /*!< SCB CPUID: IMPLEMENTER Mask */ + +#define SCB_CPUID_VARIANT_Pos 20U /*!< SCB CPUID: VARIANT Position */ +#define SCB_CPUID_VARIANT_Msk (0xFUL << SCB_CPUID_VARIANT_Pos) /*!< SCB CPUID: VARIANT Mask */ + +#define SCB_CPUID_ARCHITECTURE_Pos 16U /*!< SCB CPUID: ARCHITECTURE Position */ +#define SCB_CPUID_ARCHITECTURE_Msk (0xFUL << SCB_CPUID_ARCHITECTURE_Pos) /*!< SCB CPUID: ARCHITECTURE Mask */ + +#define SCB_CPUID_PARTNO_Pos 4U /*!< SCB CPUID: PARTNO Position */ +#define SCB_CPUID_PARTNO_Msk (0xFFFUL << SCB_CPUID_PARTNO_Pos) /*!< SCB CPUID: PARTNO Mask */ + +#define SCB_CPUID_REVISION_Pos 0U /*!< SCB CPUID: REVISION Position */ +#define SCB_CPUID_REVISION_Msk (0xFUL /*<< SCB_CPUID_REVISION_Pos*/) /*!< SCB CPUID: REVISION Mask */ + +/* SCB Interrupt Control State Register Definitions */ +#define SCB_ICSR_NMIPENDSET_Pos 31U /*!< SCB ICSR: NMIPENDSET Position */ +#define SCB_ICSR_NMIPENDSET_Msk (1UL << SCB_ICSR_NMIPENDSET_Pos) /*!< SCB ICSR: NMIPENDSET Mask */ + +#define SCB_ICSR_PENDSVSET_Pos 28U /*!< SCB ICSR: PENDSVSET Position */ +#define SCB_ICSR_PENDSVSET_Msk (1UL << SCB_ICSR_PENDSVSET_Pos) /*!< SCB ICSR: PENDSVSET Mask */ + +#define SCB_ICSR_PENDSVCLR_Pos 27U /*!< SCB ICSR: PENDSVCLR Position */ +#define SCB_ICSR_PENDSVCLR_Msk (1UL << SCB_ICSR_PENDSVCLR_Pos) /*!< SCB ICSR: PENDSVCLR Mask */ + +#define SCB_ICSR_PENDSTSET_Pos 26U /*!< SCB ICSR: PENDSTSET Position */ +#define SCB_ICSR_PENDSTSET_Msk (1UL << SCB_ICSR_PENDSTSET_Pos) /*!< SCB ICSR: PENDSTSET Mask */ + +#define SCB_ICSR_PENDSTCLR_Pos 25U /*!< SCB ICSR: PENDSTCLR Position */ +#define SCB_ICSR_PENDSTCLR_Msk (1UL << SCB_ICSR_PENDSTCLR_Pos) /*!< SCB ICSR: PENDSTCLR Mask */ + +#define SCB_ICSR_ISRPREEMPT_Pos 23U /*!< SCB ICSR: ISRPREEMPT Position */ +#define SCB_ICSR_ISRPREEMPT_Msk (1UL << SCB_ICSR_ISRPREEMPT_Pos) /*!< SCB ICSR: ISRPREEMPT Mask */ + +#define SCB_ICSR_ISRPENDING_Pos 22U /*!< SCB ICSR: ISRPENDING Position */ +#define SCB_ICSR_ISRPENDING_Msk (1UL << SCB_ICSR_ISRPENDING_Pos) /*!< SCB ICSR: ISRPENDING Mask */ + +#define SCB_ICSR_VECTPENDING_Pos 12U /*!< SCB ICSR: VECTPENDING Position */ +#define SCB_ICSR_VECTPENDING_Msk (0x1FFUL << SCB_ICSR_VECTPENDING_Pos) /*!< SCB ICSR: VECTPENDING Mask */ + +#define SCB_ICSR_RETTOBASE_Pos 11U /*!< SCB ICSR: RETTOBASE Position */ +#define SCB_ICSR_RETTOBASE_Msk (1UL << SCB_ICSR_RETTOBASE_Pos) /*!< SCB ICSR: RETTOBASE Mask */ + +#define SCB_ICSR_VECTACTIVE_Pos 0U /*!< SCB ICSR: VECTACTIVE Position */ +#define SCB_ICSR_VECTACTIVE_Msk (0x1FFUL /*<< SCB_ICSR_VECTACTIVE_Pos*/) /*!< SCB ICSR: VECTACTIVE Mask */ + +/* SCB Vector Table Offset Register Definitions */ +#define SCB_VTOR_TBLOFF_Pos 7U /*!< SCB VTOR: TBLOFF Position */ +#define SCB_VTOR_TBLOFF_Msk (0x1FFFFFFUL << SCB_VTOR_TBLOFF_Pos) /*!< SCB VTOR: TBLOFF Mask */ + +/* SCB Application Interrupt and Reset Control Register Definitions */ +#define SCB_AIRCR_VECTKEY_Pos 16U /*!< SCB AIRCR: VECTKEY Position */ +#define SCB_AIRCR_VECTKEY_Msk (0xFFFFUL << SCB_AIRCR_VECTKEY_Pos) /*!< SCB AIRCR: VECTKEY Mask */ + +#define SCB_AIRCR_VECTKEYSTAT_Pos 16U /*!< SCB AIRCR: VECTKEYSTAT Position */ +#define SCB_AIRCR_VECTKEYSTAT_Msk (0xFFFFUL << SCB_AIRCR_VECTKEYSTAT_Pos) /*!< SCB AIRCR: VECTKEYSTAT Mask */ + +#define SCB_AIRCR_ENDIANESS_Pos 15U /*!< SCB AIRCR: ENDIANESS Position */ +#define SCB_AIRCR_ENDIANESS_Msk (1UL << SCB_AIRCR_ENDIANESS_Pos) /*!< SCB AIRCR: ENDIANESS Mask */ + +#define SCB_AIRCR_PRIGROUP_Pos 8U /*!< SCB AIRCR: PRIGROUP Position */ +#define SCB_AIRCR_PRIGROUP_Msk (7UL << SCB_AIRCR_PRIGROUP_Pos) /*!< SCB AIRCR: PRIGROUP Mask */ + +#define SCB_AIRCR_SYSRESETREQ_Pos 2U /*!< SCB AIRCR: SYSRESETREQ Position */ +#define SCB_AIRCR_SYSRESETREQ_Msk (1UL << SCB_AIRCR_SYSRESETREQ_Pos) /*!< SCB AIRCR: SYSRESETREQ Mask */ + +#define SCB_AIRCR_VECTCLRACTIVE_Pos 1U /*!< SCB AIRCR: VECTCLRACTIVE Position */ +#define SCB_AIRCR_VECTCLRACTIVE_Msk (1UL << SCB_AIRCR_VECTCLRACTIVE_Pos) /*!< SCB AIRCR: VECTCLRACTIVE Mask */ + +#define SCB_AIRCR_VECTRESET_Pos 0U /*!< SCB AIRCR: VECTRESET Position */ +#define SCB_AIRCR_VECTRESET_Msk (1UL /*<< SCB_AIRCR_VECTRESET_Pos*/) /*!< SCB AIRCR: VECTRESET Mask */ + +/* SCB System Control Register Definitions */ +#define SCB_SCR_SEVONPEND_Pos 4U /*!< SCB SCR: SEVONPEND Position */ +#define SCB_SCR_SEVONPEND_Msk (1UL << SCB_SCR_SEVONPEND_Pos) /*!< SCB SCR: SEVONPEND Mask */ + +#define SCB_SCR_SLEEPDEEP_Pos 2U /*!< SCB SCR: SLEEPDEEP Position */ +#define SCB_SCR_SLEEPDEEP_Msk (1UL << SCB_SCR_SLEEPDEEP_Pos) /*!< SCB SCR: SLEEPDEEP Mask */ + +#define SCB_SCR_SLEEPONEXIT_Pos 1U /*!< SCB SCR: SLEEPONEXIT Position */ +#define SCB_SCR_SLEEPONEXIT_Msk (1UL << SCB_SCR_SLEEPONEXIT_Pos) /*!< SCB SCR: SLEEPONEXIT Mask */ + +/* SCB Configuration Control Register Definitions */ +#define SCB_CCR_STKALIGN_Pos 9U /*!< SCB CCR: STKALIGN Position */ +#define SCB_CCR_STKALIGN_Msk (1UL << SCB_CCR_STKALIGN_Pos) /*!< SCB CCR: STKALIGN Mask */ + +#define SCB_CCR_BFHFNMIGN_Pos 8U /*!< SCB CCR: BFHFNMIGN Position */ +#define SCB_CCR_BFHFNMIGN_Msk (1UL << SCB_CCR_BFHFNMIGN_Pos) /*!< SCB CCR: BFHFNMIGN Mask */ + +#define SCB_CCR_DIV_0_TRP_Pos 4U /*!< SCB CCR: DIV_0_TRP Position */ +#define SCB_CCR_DIV_0_TRP_Msk (1UL << SCB_CCR_DIV_0_TRP_Pos) /*!< SCB CCR: DIV_0_TRP Mask */ + +#define SCB_CCR_UNALIGN_TRP_Pos 3U /*!< SCB CCR: UNALIGN_TRP Position */ +#define SCB_CCR_UNALIGN_TRP_Msk (1UL << SCB_CCR_UNALIGN_TRP_Pos) /*!< SCB CCR: UNALIGN_TRP Mask */ + +#define SCB_CCR_USERSETMPEND_Pos 1U /*!< SCB CCR: USERSETMPEND Position */ +#define SCB_CCR_USERSETMPEND_Msk (1UL << SCB_CCR_USERSETMPEND_Pos) /*!< SCB CCR: USERSETMPEND Mask */ + +#define SCB_CCR_NONBASETHRDENA_Pos 0U /*!< SCB CCR: NONBASETHRDENA Position */ +#define SCB_CCR_NONBASETHRDENA_Msk (1UL /*<< SCB_CCR_NONBASETHRDENA_Pos*/) /*!< SCB CCR: NONBASETHRDENA Mask */ + +/* SCB System Handler Control and State Register Definitions */ +#define SCB_SHCSR_USGFAULTENA_Pos 18U /*!< SCB SHCSR: USGFAULTENA Position */ +#define SCB_SHCSR_USGFAULTENA_Msk (1UL << SCB_SHCSR_USGFAULTENA_Pos) /*!< SCB SHCSR: USGFAULTENA Mask */ + +#define SCB_SHCSR_BUSFAULTENA_Pos 17U /*!< SCB SHCSR: BUSFAULTENA Position */ +#define SCB_SHCSR_BUSFAULTENA_Msk (1UL << SCB_SHCSR_BUSFAULTENA_Pos) /*!< SCB SHCSR: BUSFAULTENA Mask */ + +#define SCB_SHCSR_MEMFAULTENA_Pos 16U /*!< SCB SHCSR: MEMFAULTENA Position */ +#define SCB_SHCSR_MEMFAULTENA_Msk (1UL << SCB_SHCSR_MEMFAULTENA_Pos) /*!< SCB SHCSR: MEMFAULTENA Mask */ + +#define SCB_SHCSR_SVCALLPENDED_Pos 15U /*!< SCB SHCSR: SVCALLPENDED Position */ +#define SCB_SHCSR_SVCALLPENDED_Msk (1UL << SCB_SHCSR_SVCALLPENDED_Pos) /*!< SCB SHCSR: SVCALLPENDED Mask */ + +#define SCB_SHCSR_BUSFAULTPENDED_Pos 14U /*!< SCB SHCSR: BUSFAULTPENDED Position */ +#define SCB_SHCSR_BUSFAULTPENDED_Msk (1UL << SCB_SHCSR_BUSFAULTPENDED_Pos) /*!< SCB SHCSR: BUSFAULTPENDED Mask */ + +#define SCB_SHCSR_MEMFAULTPENDED_Pos 13U /*!< SCB SHCSR: MEMFAULTPENDED Position */ +#define SCB_SHCSR_MEMFAULTPENDED_Msk (1UL << SCB_SHCSR_MEMFAULTPENDED_Pos) /*!< SCB SHCSR: MEMFAULTPENDED Mask */ + +#define SCB_SHCSR_USGFAULTPENDED_Pos 12U /*!< SCB SHCSR: USGFAULTPENDED Position */ +#define SCB_SHCSR_USGFAULTPENDED_Msk (1UL << SCB_SHCSR_USGFAULTPENDED_Pos) /*!< SCB SHCSR: USGFAULTPENDED Mask */ + +#define SCB_SHCSR_SYSTICKACT_Pos 11U /*!< SCB SHCSR: SYSTICKACT Position */ +#define SCB_SHCSR_SYSTICKACT_Msk (1UL << SCB_SHCSR_SYSTICKACT_Pos) /*!< SCB SHCSR: SYSTICKACT Mask */ + +#define SCB_SHCSR_PENDSVACT_Pos 10U /*!< SCB SHCSR: PENDSVACT Position */ +#define SCB_SHCSR_PENDSVACT_Msk (1UL << SCB_SHCSR_PENDSVACT_Pos) /*!< SCB SHCSR: PENDSVACT Mask */ + +#define SCB_SHCSR_MONITORACT_Pos 8U /*!< SCB SHCSR: MONITORACT Position */ +#define SCB_SHCSR_MONITORACT_Msk (1UL << SCB_SHCSR_MONITORACT_Pos) /*!< SCB SHCSR: MONITORACT Mask */ + +#define SCB_SHCSR_SVCALLACT_Pos 7U /*!< SCB SHCSR: SVCALLACT Position */ +#define SCB_SHCSR_SVCALLACT_Msk (1UL << SCB_SHCSR_SVCALLACT_Pos) /*!< SCB SHCSR: SVCALLACT Mask */ + +#define SCB_SHCSR_USGFAULTACT_Pos 3U /*!< SCB SHCSR: USGFAULTACT Position */ +#define SCB_SHCSR_USGFAULTACT_Msk (1UL << SCB_SHCSR_USGFAULTACT_Pos) /*!< SCB SHCSR: USGFAULTACT Mask */ + +#define SCB_SHCSR_BUSFAULTACT_Pos 1U /*!< SCB SHCSR: BUSFAULTACT Position */ +#define SCB_SHCSR_BUSFAULTACT_Msk (1UL << SCB_SHCSR_BUSFAULTACT_Pos) /*!< SCB SHCSR: BUSFAULTACT Mask */ + +#define SCB_SHCSR_MEMFAULTACT_Pos 0U /*!< SCB SHCSR: MEMFAULTACT Position */ +#define SCB_SHCSR_MEMFAULTACT_Msk (1UL /*<< SCB_SHCSR_MEMFAULTACT_Pos*/) /*!< SCB SHCSR: MEMFAULTACT Mask */ + +/* SCB Configurable Fault Status Register Definitions */ +#define SCB_CFSR_USGFAULTSR_Pos 16U /*!< SCB CFSR: Usage Fault Status Register Position */ +#define SCB_CFSR_USGFAULTSR_Msk (0xFFFFUL << SCB_CFSR_USGFAULTSR_Pos) /*!< SCB CFSR: Usage Fault Status Register Mask */ + +#define SCB_CFSR_BUSFAULTSR_Pos 8U /*!< SCB CFSR: Bus Fault Status Register Position */ +#define SCB_CFSR_BUSFAULTSR_Msk (0xFFUL << SCB_CFSR_BUSFAULTSR_Pos) /*!< SCB CFSR: Bus Fault Status Register Mask */ + +#define SCB_CFSR_MEMFAULTSR_Pos 0U /*!< SCB CFSR: Memory Manage Fault Status Register Position */ +#define SCB_CFSR_MEMFAULTSR_Msk (0xFFUL /*<< SCB_CFSR_MEMFAULTSR_Pos*/) /*!< SCB CFSR: Memory Manage Fault Status Register Mask */ + +/* SCB Hard Fault Status Register Definitions */ +#define SCB_HFSR_DEBUGEVT_Pos 31U /*!< SCB HFSR: DEBUGEVT Position */ +#define SCB_HFSR_DEBUGEVT_Msk (1UL << SCB_HFSR_DEBUGEVT_Pos) /*!< SCB HFSR: DEBUGEVT Mask */ + +#define SCB_HFSR_FORCED_Pos 30U /*!< SCB HFSR: FORCED Position */ +#define SCB_HFSR_FORCED_Msk (1UL << SCB_HFSR_FORCED_Pos) /*!< SCB HFSR: FORCED Mask */ + +#define SCB_HFSR_VECTTBL_Pos 1U /*!< SCB HFSR: VECTTBL Position */ +#define SCB_HFSR_VECTTBL_Msk (1UL << SCB_HFSR_VECTTBL_Pos) /*!< SCB HFSR: VECTTBL Mask */ + +/* SCB Debug Fault Status Register Definitions */ +#define SCB_DFSR_EXTERNAL_Pos 4U /*!< SCB DFSR: EXTERNAL Position */ +#define SCB_DFSR_EXTERNAL_Msk (1UL << SCB_DFSR_EXTERNAL_Pos) /*!< SCB DFSR: EXTERNAL Mask */ + +#define SCB_DFSR_VCATCH_Pos 3U /*!< SCB DFSR: VCATCH Position */ +#define SCB_DFSR_VCATCH_Msk (1UL << SCB_DFSR_VCATCH_Pos) /*!< SCB DFSR: VCATCH Mask */ + +#define SCB_DFSR_DWTTRAP_Pos 2U /*!< SCB DFSR: DWTTRAP Position */ +#define SCB_DFSR_DWTTRAP_Msk (1UL << SCB_DFSR_DWTTRAP_Pos) /*!< SCB DFSR: DWTTRAP Mask */ + +#define SCB_DFSR_BKPT_Pos 1U /*!< SCB DFSR: BKPT Position */ +#define SCB_DFSR_BKPT_Msk (1UL << SCB_DFSR_BKPT_Pos) /*!< SCB DFSR: BKPT Mask */ + +#define SCB_DFSR_HALTED_Pos 0U /*!< SCB DFSR: HALTED Position */ +#define SCB_DFSR_HALTED_Msk (1UL /*<< SCB_DFSR_HALTED_Pos*/) /*!< SCB DFSR: HALTED Mask */ + +/*@} end of group CMSIS_SCB */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_SCnSCB System Controls not in SCB (SCnSCB) + \brief Type definitions for the System Control and ID Register not in the SCB + @{ + */ + +/** + \brief Structure type to access the System Control and ID Register not in the SCB. + */ +typedef struct +{ + uint32_t RESERVED0[1U]; + __IM uint32_t ICTR; /*!< Offset: 0x004 (R/ ) Interrupt Controller Type Register */ + __IOM uint32_t ACTLR; /*!< Offset: 0x008 (R/W) Auxiliary Control Register */ +} SCnSCB_Type; + +/* Interrupt Controller Type Register Definitions */ +#define SCnSCB_ICTR_INTLINESNUM_Pos 0U /*!< ICTR: INTLINESNUM Position */ +#define SCnSCB_ICTR_INTLINESNUM_Msk (0xFUL /*<< SCnSCB_ICTR_INTLINESNUM_Pos*/) /*!< ICTR: INTLINESNUM Mask */ + +/* Auxiliary Control Register Definitions */ +#define SCnSCB_ACTLR_DISOOFP_Pos 9U /*!< ACTLR: DISOOFP Position */ +#define SCnSCB_ACTLR_DISOOFP_Msk (1UL << SCnSCB_ACTLR_DISOOFP_Pos) /*!< ACTLR: DISOOFP Mask */ + +#define SCnSCB_ACTLR_DISFPCA_Pos 8U /*!< ACTLR: DISFPCA Position */ +#define SCnSCB_ACTLR_DISFPCA_Msk (1UL << SCnSCB_ACTLR_DISFPCA_Pos) /*!< ACTLR: DISFPCA Mask */ + +#define SCnSCB_ACTLR_DISFOLD_Pos 2U /*!< ACTLR: DISFOLD Position */ +#define SCnSCB_ACTLR_DISFOLD_Msk (1UL << SCnSCB_ACTLR_DISFOLD_Pos) /*!< ACTLR: DISFOLD Mask */ + +#define SCnSCB_ACTLR_DISDEFWBUF_Pos 1U /*!< ACTLR: DISDEFWBUF Position */ +#define SCnSCB_ACTLR_DISDEFWBUF_Msk (1UL << SCnSCB_ACTLR_DISDEFWBUF_Pos) /*!< ACTLR: DISDEFWBUF Mask */ + +#define SCnSCB_ACTLR_DISMCYCINT_Pos 0U /*!< ACTLR: DISMCYCINT Position */ +#define SCnSCB_ACTLR_DISMCYCINT_Msk (1UL /*<< SCnSCB_ACTLR_DISMCYCINT_Pos*/) /*!< ACTLR: DISMCYCINT Mask */ + +/*@} end of group CMSIS_SCnotSCB */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_SysTick System Tick Timer (SysTick) + \brief Type definitions for the System Timer Registers. + @{ + */ + +/** + \brief Structure type to access the System Timer (SysTick). + */ +typedef struct +{ + __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) SysTick Control and Status Register */ + __IOM uint32_t LOAD; /*!< Offset: 0x004 (R/W) SysTick Reload Value Register */ + __IOM uint32_t VAL; /*!< Offset: 0x008 (R/W) SysTick Current Value Register */ + __IM uint32_t CALIB; /*!< Offset: 0x00C (R/ ) SysTick Calibration Register */ +} SysTick_Type; + +/* SysTick Control / Status Register Definitions */ +#define SysTick_CTRL_COUNTFLAG_Pos 16U /*!< SysTick CTRL: COUNTFLAG Position */ +#define SysTick_CTRL_COUNTFLAG_Msk (1UL << SysTick_CTRL_COUNTFLAG_Pos) /*!< SysTick CTRL: COUNTFLAG Mask */ + +#define SysTick_CTRL_CLKSOURCE_Pos 2U /*!< SysTick CTRL: CLKSOURCE Position */ +#define SysTick_CTRL_CLKSOURCE_Msk (1UL << SysTick_CTRL_CLKSOURCE_Pos) /*!< SysTick CTRL: CLKSOURCE Mask */ + +#define SysTick_CTRL_TICKINT_Pos 1U /*!< SysTick CTRL: TICKINT Position */ +#define SysTick_CTRL_TICKINT_Msk (1UL << SysTick_CTRL_TICKINT_Pos) /*!< SysTick CTRL: TICKINT Mask */ + +#define SysTick_CTRL_ENABLE_Pos 0U /*!< SysTick CTRL: ENABLE Position */ +#define SysTick_CTRL_ENABLE_Msk (1UL /*<< SysTick_CTRL_ENABLE_Pos*/) /*!< SysTick CTRL: ENABLE Mask */ + +/* SysTick Reload Register Definitions */ +#define SysTick_LOAD_RELOAD_Pos 0U /*!< SysTick LOAD: RELOAD Position */ +#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFUL /*<< SysTick_LOAD_RELOAD_Pos*/) /*!< SysTick LOAD: RELOAD Mask */ + +/* SysTick Current Register Definitions */ +#define SysTick_VAL_CURRENT_Pos 0U /*!< SysTick VAL: CURRENT Position */ +#define SysTick_VAL_CURRENT_Msk (0xFFFFFFUL /*<< SysTick_VAL_CURRENT_Pos*/) /*!< SysTick VAL: CURRENT Mask */ + +/* SysTick Calibration Register Definitions */ +#define SysTick_CALIB_NOREF_Pos 31U /*!< SysTick CALIB: NOREF Position */ +#define SysTick_CALIB_NOREF_Msk (1UL << SysTick_CALIB_NOREF_Pos) /*!< SysTick CALIB: NOREF Mask */ + +#define SysTick_CALIB_SKEW_Pos 30U /*!< SysTick CALIB: SKEW Position */ +#define SysTick_CALIB_SKEW_Msk (1UL << SysTick_CALIB_SKEW_Pos) /*!< SysTick CALIB: SKEW Mask */ + +#define SysTick_CALIB_TENMS_Pos 0U /*!< SysTick CALIB: TENMS Position */ +#define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL /*<< SysTick_CALIB_TENMS_Pos*/) /*!< SysTick CALIB: TENMS Mask */ + +/*@} end of group CMSIS_SysTick */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_ITM Instrumentation Trace Macrocell (ITM) + \brief Type definitions for the Instrumentation Trace Macrocell (ITM) + @{ + */ + +/** + \brief Structure type to access the Instrumentation Trace Macrocell Register (ITM). + */ +typedef struct +{ + __OM union + { + __OM uint8_t u8; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 8-bit */ + __OM uint16_t u16; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 16-bit */ + __OM uint32_t u32; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 32-bit */ + } PORT [32U]; /*!< Offset: 0x000 ( /W) ITM Stimulus Port Registers */ + uint32_t RESERVED0[864U]; + __IOM uint32_t TER; /*!< Offset: 0xE00 (R/W) ITM Trace Enable Register */ + uint32_t RESERVED1[15U]; + __IOM uint32_t TPR; /*!< Offset: 0xE40 (R/W) ITM Trace Privilege Register */ + uint32_t RESERVED2[15U]; + __IOM uint32_t TCR; /*!< Offset: 0xE80 (R/W) ITM Trace Control Register */ + uint32_t RESERVED3[29U]; + __OM uint32_t IWR; /*!< Offset: 0xEF8 ( /W) ITM Integration Write Register */ + __IM uint32_t IRR; /*!< Offset: 0xEFC (R/ ) ITM Integration Read Register */ + __IOM uint32_t IMCR; /*!< Offset: 0xF00 (R/W) ITM Integration Mode Control Register */ + uint32_t RESERVED4[43U]; + __OM uint32_t LAR; /*!< Offset: 0xFB0 ( /W) ITM Lock Access Register */ + __IM uint32_t LSR; /*!< Offset: 0xFB4 (R/ ) ITM Lock Status Register */ + uint32_t RESERVED5[6U]; + __IM uint32_t PID4; /*!< Offset: 0xFD0 (R/ ) ITM Peripheral Identification Register #4 */ + __IM uint32_t PID5; /*!< Offset: 0xFD4 (R/ ) ITM Peripheral Identification Register #5 */ + __IM uint32_t PID6; /*!< Offset: 0xFD8 (R/ ) ITM Peripheral Identification Register #6 */ + __IM uint32_t PID7; /*!< Offset: 0xFDC (R/ ) ITM Peripheral Identification Register #7 */ + __IM uint32_t PID0; /*!< Offset: 0xFE0 (R/ ) ITM Peripheral Identification Register #0 */ + __IM uint32_t PID1; /*!< Offset: 0xFE4 (R/ ) ITM Peripheral Identification Register #1 */ + __IM uint32_t PID2; /*!< Offset: 0xFE8 (R/ ) ITM Peripheral Identification Register #2 */ + __IM uint32_t PID3; /*!< Offset: 0xFEC (R/ ) ITM Peripheral Identification Register #3 */ + __IM uint32_t CID0; /*!< Offset: 0xFF0 (R/ ) ITM Component Identification Register #0 */ + __IM uint32_t CID1; /*!< Offset: 0xFF4 (R/ ) ITM Component Identification Register #1 */ + __IM uint32_t CID2; /*!< Offset: 0xFF8 (R/ ) ITM Component Identification Register #2 */ + __IM uint32_t CID3; /*!< Offset: 0xFFC (R/ ) ITM Component Identification Register #3 */ +} ITM_Type; + +/* ITM Trace Privilege Register Definitions */ +#define ITM_TPR_PRIVMASK_Pos 0U /*!< ITM TPR: PRIVMASK Position */ +#define ITM_TPR_PRIVMASK_Msk (0xFUL /*<< ITM_TPR_PRIVMASK_Pos*/) /*!< ITM TPR: PRIVMASK Mask */ + +/* ITM Trace Control Register Definitions */ +#define ITM_TCR_BUSY_Pos 23U /*!< ITM TCR: BUSY Position */ +#define ITM_TCR_BUSY_Msk (1UL << ITM_TCR_BUSY_Pos) /*!< ITM TCR: BUSY Mask */ + +#define ITM_TCR_TraceBusID_Pos 16U /*!< ITM TCR: ATBID Position */ +#define ITM_TCR_TraceBusID_Msk (0x7FUL << ITM_TCR_TraceBusID_Pos) /*!< ITM TCR: ATBID Mask */ + +#define ITM_TCR_GTSFREQ_Pos 10U /*!< ITM TCR: Global timestamp frequency Position */ +#define ITM_TCR_GTSFREQ_Msk (3UL << ITM_TCR_GTSFREQ_Pos) /*!< ITM TCR: Global timestamp frequency Mask */ + +#define ITM_TCR_TSPrescale_Pos 8U /*!< ITM TCR: TSPrescale Position */ +#define ITM_TCR_TSPrescale_Msk (3UL << ITM_TCR_TSPrescale_Pos) /*!< ITM TCR: TSPrescale Mask */ + +#define ITM_TCR_SWOENA_Pos 4U /*!< ITM TCR: SWOENA Position */ +#define ITM_TCR_SWOENA_Msk (1UL << ITM_TCR_SWOENA_Pos) /*!< ITM TCR: SWOENA Mask */ + +#define ITM_TCR_DWTENA_Pos 3U /*!< ITM TCR: DWTENA Position */ +#define ITM_TCR_DWTENA_Msk (1UL << ITM_TCR_DWTENA_Pos) /*!< ITM TCR: DWTENA Mask */ + +#define ITM_TCR_SYNCENA_Pos 2U /*!< ITM TCR: SYNCENA Position */ +#define ITM_TCR_SYNCENA_Msk (1UL << ITM_TCR_SYNCENA_Pos) /*!< ITM TCR: SYNCENA Mask */ + +#define ITM_TCR_TSENA_Pos 1U /*!< ITM TCR: TSENA Position */ +#define ITM_TCR_TSENA_Msk (1UL << ITM_TCR_TSENA_Pos) /*!< ITM TCR: TSENA Mask */ + +#define ITM_TCR_ITMENA_Pos 0U /*!< ITM TCR: ITM Enable bit Position */ +#define ITM_TCR_ITMENA_Msk (1UL /*<< ITM_TCR_ITMENA_Pos*/) /*!< ITM TCR: ITM Enable bit Mask */ + +/* ITM Integration Write Register Definitions */ +#define ITM_IWR_ATVALIDM_Pos 0U /*!< ITM IWR: ATVALIDM Position */ +#define ITM_IWR_ATVALIDM_Msk (1UL /*<< ITM_IWR_ATVALIDM_Pos*/) /*!< ITM IWR: ATVALIDM Mask */ + +/* ITM Integration Read Register Definitions */ +#define ITM_IRR_ATREADYM_Pos 0U /*!< ITM IRR: ATREADYM Position */ +#define ITM_IRR_ATREADYM_Msk (1UL /*<< ITM_IRR_ATREADYM_Pos*/) /*!< ITM IRR: ATREADYM Mask */ + +/* ITM Integration Mode Control Register Definitions */ +#define ITM_IMCR_INTEGRATION_Pos 0U /*!< ITM IMCR: INTEGRATION Position */ +#define ITM_IMCR_INTEGRATION_Msk (1UL /*<< ITM_IMCR_INTEGRATION_Pos*/) /*!< ITM IMCR: INTEGRATION Mask */ + +/* ITM Lock Status Register Definitions */ +#define ITM_LSR_ByteAcc_Pos 2U /*!< ITM LSR: ByteAcc Position */ +#define ITM_LSR_ByteAcc_Msk (1UL << ITM_LSR_ByteAcc_Pos) /*!< ITM LSR: ByteAcc Mask */ + +#define ITM_LSR_Access_Pos 1U /*!< ITM LSR: Access Position */ +#define ITM_LSR_Access_Msk (1UL << ITM_LSR_Access_Pos) /*!< ITM LSR: Access Mask */ + +#define ITM_LSR_Present_Pos 0U /*!< ITM LSR: Present Position */ +#define ITM_LSR_Present_Msk (1UL /*<< ITM_LSR_Present_Pos*/) /*!< ITM LSR: Present Mask */ + +/*@}*/ /* end of group CMSIS_ITM */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_DWT Data Watchpoint and Trace (DWT) + \brief Type definitions for the Data Watchpoint and Trace (DWT) + @{ + */ + +/** + \brief Structure type to access the Data Watchpoint and Trace Register (DWT). + */ +typedef struct +{ + __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) Control Register */ + __IOM uint32_t CYCCNT; /*!< Offset: 0x004 (R/W) Cycle Count Register */ + __IOM uint32_t CPICNT; /*!< Offset: 0x008 (R/W) CPI Count Register */ + __IOM uint32_t EXCCNT; /*!< Offset: 0x00C (R/W) Exception Overhead Count Register */ + __IOM uint32_t SLEEPCNT; /*!< Offset: 0x010 (R/W) Sleep Count Register */ + __IOM uint32_t LSUCNT; /*!< Offset: 0x014 (R/W) LSU Count Register */ + __IOM uint32_t FOLDCNT; /*!< Offset: 0x018 (R/W) Folded-instruction Count Register */ + __IM uint32_t PCSR; /*!< Offset: 0x01C (R/ ) Program Counter Sample Register */ + __IOM uint32_t COMP0; /*!< Offset: 0x020 (R/W) Comparator Register 0 */ + __IOM uint32_t MASK0; /*!< Offset: 0x024 (R/W) Mask Register 0 */ + __IOM uint32_t FUNCTION0; /*!< Offset: 0x028 (R/W) Function Register 0 */ + uint32_t RESERVED0[1U]; + __IOM uint32_t COMP1; /*!< Offset: 0x030 (R/W) Comparator Register 1 */ + __IOM uint32_t MASK1; /*!< Offset: 0x034 (R/W) Mask Register 1 */ + __IOM uint32_t FUNCTION1; /*!< Offset: 0x038 (R/W) Function Register 1 */ + uint32_t RESERVED1[1U]; + __IOM uint32_t COMP2; /*!< Offset: 0x040 (R/W) Comparator Register 2 */ + __IOM uint32_t MASK2; /*!< Offset: 0x044 (R/W) Mask Register 2 */ + __IOM uint32_t FUNCTION2; /*!< Offset: 0x048 (R/W) Function Register 2 */ + uint32_t RESERVED2[1U]; + __IOM uint32_t COMP3; /*!< Offset: 0x050 (R/W) Comparator Register 3 */ + __IOM uint32_t MASK3; /*!< Offset: 0x054 (R/W) Mask Register 3 */ + __IOM uint32_t FUNCTION3; /*!< Offset: 0x058 (R/W) Function Register 3 */ +} DWT_Type; + +/* DWT Control Register Definitions */ +#define DWT_CTRL_NUMCOMP_Pos 28U /*!< DWT CTRL: NUMCOMP Position */ +#define DWT_CTRL_NUMCOMP_Msk (0xFUL << DWT_CTRL_NUMCOMP_Pos) /*!< DWT CTRL: NUMCOMP Mask */ + +#define DWT_CTRL_NOTRCPKT_Pos 27U /*!< DWT CTRL: NOTRCPKT Position */ +#define DWT_CTRL_NOTRCPKT_Msk (0x1UL << DWT_CTRL_NOTRCPKT_Pos) /*!< DWT CTRL: NOTRCPKT Mask */ + +#define DWT_CTRL_NOEXTTRIG_Pos 26U /*!< DWT CTRL: NOEXTTRIG Position */ +#define DWT_CTRL_NOEXTTRIG_Msk (0x1UL << DWT_CTRL_NOEXTTRIG_Pos) /*!< DWT CTRL: NOEXTTRIG Mask */ + +#define DWT_CTRL_NOCYCCNT_Pos 25U /*!< DWT CTRL: NOCYCCNT Position */ +#define DWT_CTRL_NOCYCCNT_Msk (0x1UL << DWT_CTRL_NOCYCCNT_Pos) /*!< DWT CTRL: NOCYCCNT Mask */ + +#define DWT_CTRL_NOPRFCNT_Pos 24U /*!< DWT CTRL: NOPRFCNT Position */ +#define DWT_CTRL_NOPRFCNT_Msk (0x1UL << DWT_CTRL_NOPRFCNT_Pos) /*!< DWT CTRL: NOPRFCNT Mask */ + +#define DWT_CTRL_CYCEVTENA_Pos 22U /*!< DWT CTRL: CYCEVTENA Position */ +#define DWT_CTRL_CYCEVTENA_Msk (0x1UL << DWT_CTRL_CYCEVTENA_Pos) /*!< DWT CTRL: CYCEVTENA Mask */ + +#define DWT_CTRL_FOLDEVTENA_Pos 21U /*!< DWT CTRL: FOLDEVTENA Position */ +#define DWT_CTRL_FOLDEVTENA_Msk (0x1UL << DWT_CTRL_FOLDEVTENA_Pos) /*!< DWT CTRL: FOLDEVTENA Mask */ + +#define DWT_CTRL_LSUEVTENA_Pos 20U /*!< DWT CTRL: LSUEVTENA Position */ +#define DWT_CTRL_LSUEVTENA_Msk (0x1UL << DWT_CTRL_LSUEVTENA_Pos) /*!< DWT CTRL: LSUEVTENA Mask */ + +#define DWT_CTRL_SLEEPEVTENA_Pos 19U /*!< DWT CTRL: SLEEPEVTENA Position */ +#define DWT_CTRL_SLEEPEVTENA_Msk (0x1UL << DWT_CTRL_SLEEPEVTENA_Pos) /*!< DWT CTRL: SLEEPEVTENA Mask */ + +#define DWT_CTRL_EXCEVTENA_Pos 18U /*!< DWT CTRL: EXCEVTENA Position */ +#define DWT_CTRL_EXCEVTENA_Msk (0x1UL << DWT_CTRL_EXCEVTENA_Pos) /*!< DWT CTRL: EXCEVTENA Mask */ + +#define DWT_CTRL_CPIEVTENA_Pos 17U /*!< DWT CTRL: CPIEVTENA Position */ +#define DWT_CTRL_CPIEVTENA_Msk (0x1UL << DWT_CTRL_CPIEVTENA_Pos) /*!< DWT CTRL: CPIEVTENA Mask */ + +#define DWT_CTRL_EXCTRCENA_Pos 16U /*!< DWT CTRL: EXCTRCENA Position */ +#define DWT_CTRL_EXCTRCENA_Msk (0x1UL << DWT_CTRL_EXCTRCENA_Pos) /*!< DWT CTRL: EXCTRCENA Mask */ + +#define DWT_CTRL_PCSAMPLENA_Pos 12U /*!< DWT CTRL: PCSAMPLENA Position */ +#define DWT_CTRL_PCSAMPLENA_Msk (0x1UL << DWT_CTRL_PCSAMPLENA_Pos) /*!< DWT CTRL: PCSAMPLENA Mask */ + +#define DWT_CTRL_SYNCTAP_Pos 10U /*!< DWT CTRL: SYNCTAP Position */ +#define DWT_CTRL_SYNCTAP_Msk (0x3UL << DWT_CTRL_SYNCTAP_Pos) /*!< DWT CTRL: SYNCTAP Mask */ + +#define DWT_CTRL_CYCTAP_Pos 9U /*!< DWT CTRL: CYCTAP Position */ +#define DWT_CTRL_CYCTAP_Msk (0x1UL << DWT_CTRL_CYCTAP_Pos) /*!< DWT CTRL: CYCTAP Mask */ + +#define DWT_CTRL_POSTINIT_Pos 5U /*!< DWT CTRL: POSTINIT Position */ +#define DWT_CTRL_POSTINIT_Msk (0xFUL << DWT_CTRL_POSTINIT_Pos) /*!< DWT CTRL: POSTINIT Mask */ + +#define DWT_CTRL_POSTPRESET_Pos 1U /*!< DWT CTRL: POSTPRESET Position */ +#define DWT_CTRL_POSTPRESET_Msk (0xFUL << DWT_CTRL_POSTPRESET_Pos) /*!< DWT CTRL: POSTPRESET Mask */ + +#define DWT_CTRL_CYCCNTENA_Pos 0U /*!< DWT CTRL: CYCCNTENA Position */ +#define DWT_CTRL_CYCCNTENA_Msk (0x1UL /*<< DWT_CTRL_CYCCNTENA_Pos*/) /*!< DWT CTRL: CYCCNTENA Mask */ + +/* DWT CPI Count Register Definitions */ +#define DWT_CPICNT_CPICNT_Pos 0U /*!< DWT CPICNT: CPICNT Position */ +#define DWT_CPICNT_CPICNT_Msk (0xFFUL /*<< DWT_CPICNT_CPICNT_Pos*/) /*!< DWT CPICNT: CPICNT Mask */ + +/* DWT Exception Overhead Count Register Definitions */ +#define DWT_EXCCNT_EXCCNT_Pos 0U /*!< DWT EXCCNT: EXCCNT Position */ +#define DWT_EXCCNT_EXCCNT_Msk (0xFFUL /*<< DWT_EXCCNT_EXCCNT_Pos*/) /*!< DWT EXCCNT: EXCCNT Mask */ + +/* DWT Sleep Count Register Definitions */ +#define DWT_SLEEPCNT_SLEEPCNT_Pos 0U /*!< DWT SLEEPCNT: SLEEPCNT Position */ +#define DWT_SLEEPCNT_SLEEPCNT_Msk (0xFFUL /*<< DWT_SLEEPCNT_SLEEPCNT_Pos*/) /*!< DWT SLEEPCNT: SLEEPCNT Mask */ + +/* DWT LSU Count Register Definitions */ +#define DWT_LSUCNT_LSUCNT_Pos 0U /*!< DWT LSUCNT: LSUCNT Position */ +#define DWT_LSUCNT_LSUCNT_Msk (0xFFUL /*<< DWT_LSUCNT_LSUCNT_Pos*/) /*!< DWT LSUCNT: LSUCNT Mask */ + +/* DWT Folded-instruction Count Register Definitions */ +#define DWT_FOLDCNT_FOLDCNT_Pos 0U /*!< DWT FOLDCNT: FOLDCNT Position */ +#define DWT_FOLDCNT_FOLDCNT_Msk (0xFFUL /*<< DWT_FOLDCNT_FOLDCNT_Pos*/) /*!< DWT FOLDCNT: FOLDCNT Mask */ + +/* DWT Comparator Mask Register Definitions */ +#define DWT_MASK_MASK_Pos 0U /*!< DWT MASK: MASK Position */ +#define DWT_MASK_MASK_Msk (0x1FUL /*<< DWT_MASK_MASK_Pos*/) /*!< DWT MASK: MASK Mask */ + +/* DWT Comparator Function Register Definitions */ +#define DWT_FUNCTION_MATCHED_Pos 24U /*!< DWT FUNCTION: MATCHED Position */ +#define DWT_FUNCTION_MATCHED_Msk (0x1UL << DWT_FUNCTION_MATCHED_Pos) /*!< DWT FUNCTION: MATCHED Mask */ + +#define DWT_FUNCTION_DATAVADDR1_Pos 16U /*!< DWT FUNCTION: DATAVADDR1 Position */ +#define DWT_FUNCTION_DATAVADDR1_Msk (0xFUL << DWT_FUNCTION_DATAVADDR1_Pos) /*!< DWT FUNCTION: DATAVADDR1 Mask */ + +#define DWT_FUNCTION_DATAVADDR0_Pos 12U /*!< DWT FUNCTION: DATAVADDR0 Position */ +#define DWT_FUNCTION_DATAVADDR0_Msk (0xFUL << DWT_FUNCTION_DATAVADDR0_Pos) /*!< DWT FUNCTION: DATAVADDR0 Mask */ + +#define DWT_FUNCTION_DATAVSIZE_Pos 10U /*!< DWT FUNCTION: DATAVSIZE Position */ +#define DWT_FUNCTION_DATAVSIZE_Msk (0x3UL << DWT_FUNCTION_DATAVSIZE_Pos) /*!< DWT FUNCTION: DATAVSIZE Mask */ + +#define DWT_FUNCTION_LNK1ENA_Pos 9U /*!< DWT FUNCTION: LNK1ENA Position */ +#define DWT_FUNCTION_LNK1ENA_Msk (0x1UL << DWT_FUNCTION_LNK1ENA_Pos) /*!< DWT FUNCTION: LNK1ENA Mask */ + +#define DWT_FUNCTION_DATAVMATCH_Pos 8U /*!< DWT FUNCTION: DATAVMATCH Position */ +#define DWT_FUNCTION_DATAVMATCH_Msk (0x1UL << DWT_FUNCTION_DATAVMATCH_Pos) /*!< DWT FUNCTION: DATAVMATCH Mask */ + +#define DWT_FUNCTION_CYCMATCH_Pos 7U /*!< DWT FUNCTION: CYCMATCH Position */ +#define DWT_FUNCTION_CYCMATCH_Msk (0x1UL << DWT_FUNCTION_CYCMATCH_Pos) /*!< DWT FUNCTION: CYCMATCH Mask */ + +#define DWT_FUNCTION_EMITRANGE_Pos 5U /*!< DWT FUNCTION: EMITRANGE Position */ +#define DWT_FUNCTION_EMITRANGE_Msk (0x1UL << DWT_FUNCTION_EMITRANGE_Pos) /*!< DWT FUNCTION: EMITRANGE Mask */ + +#define DWT_FUNCTION_FUNCTION_Pos 0U /*!< DWT FUNCTION: FUNCTION Position */ +#define DWT_FUNCTION_FUNCTION_Msk (0xFUL /*<< DWT_FUNCTION_FUNCTION_Pos*/) /*!< DWT FUNCTION: FUNCTION Mask */ + +/*@}*/ /* end of group CMSIS_DWT */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_TPI Trace Port Interface (TPI) + \brief Type definitions for the Trace Port Interface (TPI) + @{ + */ + +/** + \brief Structure type to access the Trace Port Interface Register (TPI). + */ +typedef struct +{ + __IOM uint32_t SSPSR; /*!< Offset: 0x000 (R/ ) Supported Parallel Port Size Register */ + __IOM uint32_t CSPSR; /*!< Offset: 0x004 (R/W) Current Parallel Port Size Register */ + uint32_t RESERVED0[2U]; + __IOM uint32_t ACPR; /*!< Offset: 0x010 (R/W) Asynchronous Clock Prescaler Register */ + uint32_t RESERVED1[55U]; + __IOM uint32_t SPPR; /*!< Offset: 0x0F0 (R/W) Selected Pin Protocol Register */ + uint32_t RESERVED2[131U]; + __IM uint32_t FFSR; /*!< Offset: 0x300 (R/ ) Formatter and Flush Status Register */ + __IOM uint32_t FFCR; /*!< Offset: 0x304 (R/W) Formatter and Flush Control Register */ + __IM uint32_t FSCR; /*!< Offset: 0x308 (R/ ) Formatter Synchronization Counter Register */ + uint32_t RESERVED3[759U]; + __IM uint32_t TRIGGER; /*!< Offset: 0xEE8 (R/ ) TRIGGER */ + __IM uint32_t FIFO0; /*!< Offset: 0xEEC (R/ ) Integration ETM Data */ + __IM uint32_t ITATBCTR2; /*!< Offset: 0xEF0 (R/ ) ITATBCTR2 */ + uint32_t RESERVED4[1U]; + __IM uint32_t ITATBCTR0; /*!< Offset: 0xEF8 (R/ ) ITATBCTR0 */ + __IM uint32_t FIFO1; /*!< Offset: 0xEFC (R/ ) Integration ITM Data */ + __IOM uint32_t ITCTRL; /*!< Offset: 0xF00 (R/W) Integration Mode Control */ + uint32_t RESERVED5[39U]; + __IOM uint32_t CLAIMSET; /*!< Offset: 0xFA0 (R/W) Claim tag set */ + __IOM uint32_t CLAIMCLR; /*!< Offset: 0xFA4 (R/W) Claim tag clear */ + uint32_t RESERVED7[8U]; + __IM uint32_t DEVID; /*!< Offset: 0xFC8 (R/ ) TPIU_DEVID */ + __IM uint32_t DEVTYPE; /*!< Offset: 0xFCC (R/ ) TPIU_DEVTYPE */ +} TPI_Type; + +/* TPI Asynchronous Clock Prescaler Register Definitions */ +#define TPI_ACPR_PRESCALER_Pos 0U /*!< TPI ACPR: PRESCALER Position */ +#define TPI_ACPR_PRESCALER_Msk (0x1FFFUL /*<< TPI_ACPR_PRESCALER_Pos*/) /*!< TPI ACPR: PRESCALER Mask */ + +/* TPI Selected Pin Protocol Register Definitions */ +#define TPI_SPPR_TXMODE_Pos 0U /*!< TPI SPPR: TXMODE Position */ +#define TPI_SPPR_TXMODE_Msk (0x3UL /*<< TPI_SPPR_TXMODE_Pos*/) /*!< TPI SPPR: TXMODE Mask */ + +/* TPI Formatter and Flush Status Register Definitions */ +#define TPI_FFSR_FtNonStop_Pos 3U /*!< TPI FFSR: FtNonStop Position */ +#define TPI_FFSR_FtNonStop_Msk (0x1UL << TPI_FFSR_FtNonStop_Pos) /*!< TPI FFSR: FtNonStop Mask */ + +#define TPI_FFSR_TCPresent_Pos 2U /*!< TPI FFSR: TCPresent Position */ +#define TPI_FFSR_TCPresent_Msk (0x1UL << TPI_FFSR_TCPresent_Pos) /*!< TPI FFSR: TCPresent Mask */ + +#define TPI_FFSR_FtStopped_Pos 1U /*!< TPI FFSR: FtStopped Position */ +#define TPI_FFSR_FtStopped_Msk (0x1UL << TPI_FFSR_FtStopped_Pos) /*!< TPI FFSR: FtStopped Mask */ + +#define TPI_FFSR_FlInProg_Pos 0U /*!< TPI FFSR: FlInProg Position */ +#define TPI_FFSR_FlInProg_Msk (0x1UL /*<< TPI_FFSR_FlInProg_Pos*/) /*!< TPI FFSR: FlInProg Mask */ + +/* TPI Formatter and Flush Control Register Definitions */ +#define TPI_FFCR_TrigIn_Pos 8U /*!< TPI FFCR: TrigIn Position */ +#define TPI_FFCR_TrigIn_Msk (0x1UL << TPI_FFCR_TrigIn_Pos) /*!< TPI FFCR: TrigIn Mask */ + +#define TPI_FFCR_EnFCont_Pos 1U /*!< TPI FFCR: EnFCont Position */ +#define TPI_FFCR_EnFCont_Msk (0x1UL << TPI_FFCR_EnFCont_Pos) /*!< TPI FFCR: EnFCont Mask */ + +/* TPI TRIGGER Register Definitions */ +#define TPI_TRIGGER_TRIGGER_Pos 0U /*!< TPI TRIGGER: TRIGGER Position */ +#define TPI_TRIGGER_TRIGGER_Msk (0x1UL /*<< TPI_TRIGGER_TRIGGER_Pos*/) /*!< TPI TRIGGER: TRIGGER Mask */ + +/* TPI Integration ETM Data Register Definitions (FIFO0) */ +#define TPI_FIFO0_ITM_ATVALID_Pos 29U /*!< TPI FIFO0: ITM_ATVALID Position */ +#define TPI_FIFO0_ITM_ATVALID_Msk (0x3UL << TPI_FIFO0_ITM_ATVALID_Pos) /*!< TPI FIFO0: ITM_ATVALID Mask */ + +#define TPI_FIFO0_ITM_bytecount_Pos 27U /*!< TPI FIFO0: ITM_bytecount Position */ +#define TPI_FIFO0_ITM_bytecount_Msk (0x3UL << TPI_FIFO0_ITM_bytecount_Pos) /*!< TPI FIFO0: ITM_bytecount Mask */ + +#define TPI_FIFO0_ETM_ATVALID_Pos 26U /*!< TPI FIFO0: ETM_ATVALID Position */ +#define TPI_FIFO0_ETM_ATVALID_Msk (0x3UL << TPI_FIFO0_ETM_ATVALID_Pos) /*!< TPI FIFO0: ETM_ATVALID Mask */ + +#define TPI_FIFO0_ETM_bytecount_Pos 24U /*!< TPI FIFO0: ETM_bytecount Position */ +#define TPI_FIFO0_ETM_bytecount_Msk (0x3UL << TPI_FIFO0_ETM_bytecount_Pos) /*!< TPI FIFO0: ETM_bytecount Mask */ + +#define TPI_FIFO0_ETM2_Pos 16U /*!< TPI FIFO0: ETM2 Position */ +#define TPI_FIFO0_ETM2_Msk (0xFFUL << TPI_FIFO0_ETM2_Pos) /*!< TPI FIFO0: ETM2 Mask */ + +#define TPI_FIFO0_ETM1_Pos 8U /*!< TPI FIFO0: ETM1 Position */ +#define TPI_FIFO0_ETM1_Msk (0xFFUL << TPI_FIFO0_ETM1_Pos) /*!< TPI FIFO0: ETM1 Mask */ + +#define TPI_FIFO0_ETM0_Pos 0U /*!< TPI FIFO0: ETM0 Position */ +#define TPI_FIFO0_ETM0_Msk (0xFFUL /*<< TPI_FIFO0_ETM0_Pos*/) /*!< TPI FIFO0: ETM0 Mask */ + +/* TPI ITATBCTR2 Register Definitions */ +#define TPI_ITATBCTR2_ATREADY_Pos 0U /*!< TPI ITATBCTR2: ATREADY Position */ +#define TPI_ITATBCTR2_ATREADY_Msk (0x1UL /*<< TPI_ITATBCTR2_ATREADY_Pos*/) /*!< TPI ITATBCTR2: ATREADY Mask */ + +/* TPI Integration ITM Data Register Definitions (FIFO1) */ +#define TPI_FIFO1_ITM_ATVALID_Pos 29U /*!< TPI FIFO1: ITM_ATVALID Position */ +#define TPI_FIFO1_ITM_ATVALID_Msk (0x3UL << TPI_FIFO1_ITM_ATVALID_Pos) /*!< TPI FIFO1: ITM_ATVALID Mask */ + +#define TPI_FIFO1_ITM_bytecount_Pos 27U /*!< TPI FIFO1: ITM_bytecount Position */ +#define TPI_FIFO1_ITM_bytecount_Msk (0x3UL << TPI_FIFO1_ITM_bytecount_Pos) /*!< TPI FIFO1: ITM_bytecount Mask */ + +#define TPI_FIFO1_ETM_ATVALID_Pos 26U /*!< TPI FIFO1: ETM_ATVALID Position */ +#define TPI_FIFO1_ETM_ATVALID_Msk (0x3UL << TPI_FIFO1_ETM_ATVALID_Pos) /*!< TPI FIFO1: ETM_ATVALID Mask */ + +#define TPI_FIFO1_ETM_bytecount_Pos 24U /*!< TPI FIFO1: ETM_bytecount Position */ +#define TPI_FIFO1_ETM_bytecount_Msk (0x3UL << TPI_FIFO1_ETM_bytecount_Pos) /*!< TPI FIFO1: ETM_bytecount Mask */ + +#define TPI_FIFO1_ITM2_Pos 16U /*!< TPI FIFO1: ITM2 Position */ +#define TPI_FIFO1_ITM2_Msk (0xFFUL << TPI_FIFO1_ITM2_Pos) /*!< TPI FIFO1: ITM2 Mask */ + +#define TPI_FIFO1_ITM1_Pos 8U /*!< TPI FIFO1: ITM1 Position */ +#define TPI_FIFO1_ITM1_Msk (0xFFUL << TPI_FIFO1_ITM1_Pos) /*!< TPI FIFO1: ITM1 Mask */ + +#define TPI_FIFO1_ITM0_Pos 0U /*!< TPI FIFO1: ITM0 Position */ +#define TPI_FIFO1_ITM0_Msk (0xFFUL /*<< TPI_FIFO1_ITM0_Pos*/) /*!< TPI FIFO1: ITM0 Mask */ + +/* TPI ITATBCTR0 Register Definitions */ +#define TPI_ITATBCTR0_ATREADY_Pos 0U /*!< TPI ITATBCTR0: ATREADY Position */ +#define TPI_ITATBCTR0_ATREADY_Msk (0x1UL /*<< TPI_ITATBCTR0_ATREADY_Pos*/) /*!< TPI ITATBCTR0: ATREADY Mask */ + +/* TPI Integration Mode Control Register Definitions */ +#define TPI_ITCTRL_Mode_Pos 0U /*!< TPI ITCTRL: Mode Position */ +#define TPI_ITCTRL_Mode_Msk (0x1UL /*<< TPI_ITCTRL_Mode_Pos*/) /*!< TPI ITCTRL: Mode Mask */ + +/* TPI DEVID Register Definitions */ +#define TPI_DEVID_NRZVALID_Pos 11U /*!< TPI DEVID: NRZVALID Position */ +#define TPI_DEVID_NRZVALID_Msk (0x1UL << TPI_DEVID_NRZVALID_Pos) /*!< TPI DEVID: NRZVALID Mask */ + +#define TPI_DEVID_MANCVALID_Pos 10U /*!< TPI DEVID: MANCVALID Position */ +#define TPI_DEVID_MANCVALID_Msk (0x1UL << TPI_DEVID_MANCVALID_Pos) /*!< TPI DEVID: MANCVALID Mask */ + +#define TPI_DEVID_PTINVALID_Pos 9U /*!< TPI DEVID: PTINVALID Position */ +#define TPI_DEVID_PTINVALID_Msk (0x1UL << TPI_DEVID_PTINVALID_Pos) /*!< TPI DEVID: PTINVALID Mask */ + +#define TPI_DEVID_MinBufSz_Pos 6U /*!< TPI DEVID: MinBufSz Position */ +#define TPI_DEVID_MinBufSz_Msk (0x7UL << TPI_DEVID_MinBufSz_Pos) /*!< TPI DEVID: MinBufSz Mask */ + +#define TPI_DEVID_AsynClkIn_Pos 5U /*!< TPI DEVID: AsynClkIn Position */ +#define TPI_DEVID_AsynClkIn_Msk (0x1UL << TPI_DEVID_AsynClkIn_Pos) /*!< TPI DEVID: AsynClkIn Mask */ + +#define TPI_DEVID_NrTraceInput_Pos 0U /*!< TPI DEVID: NrTraceInput Position */ +#define TPI_DEVID_NrTraceInput_Msk (0x1FUL /*<< TPI_DEVID_NrTraceInput_Pos*/) /*!< TPI DEVID: NrTraceInput Mask */ + +/* TPI DEVTYPE Register Definitions */ +#define TPI_DEVTYPE_MajorType_Pos 4U /*!< TPI DEVTYPE: MajorType Position */ +#define TPI_DEVTYPE_MajorType_Msk (0xFUL << TPI_DEVTYPE_MajorType_Pos) /*!< TPI DEVTYPE: MajorType Mask */ + +#define TPI_DEVTYPE_SubType_Pos 0U /*!< TPI DEVTYPE: SubType Position */ +#define TPI_DEVTYPE_SubType_Msk (0xFUL /*<< TPI_DEVTYPE_SubType_Pos*/) /*!< TPI DEVTYPE: SubType Mask */ + +/*@}*/ /* end of group CMSIS_TPI */ + + +#if (__MPU_PRESENT == 1U) +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_MPU Memory Protection Unit (MPU) + \brief Type definitions for the Memory Protection Unit (MPU) + @{ + */ + +/** + \brief Structure type to access the Memory Protection Unit (MPU). + */ +typedef struct +{ + __IM uint32_t TYPE; /*!< Offset: 0x000 (R/ ) MPU Type Register */ + __IOM uint32_t CTRL; /*!< Offset: 0x004 (R/W) MPU Control Register */ + __IOM uint32_t RNR; /*!< Offset: 0x008 (R/W) MPU Region RNRber Register */ + __IOM uint32_t RBAR; /*!< Offset: 0x00C (R/W) MPU Region Base Address Register */ + __IOM uint32_t RASR; /*!< Offset: 0x010 (R/W) MPU Region Attribute and Size Register */ + __IOM uint32_t RBAR_A1; /*!< Offset: 0x014 (R/W) MPU Alias 1 Region Base Address Register */ + __IOM uint32_t RASR_A1; /*!< Offset: 0x018 (R/W) MPU Alias 1 Region Attribute and Size Register */ + __IOM uint32_t RBAR_A2; /*!< Offset: 0x01C (R/W) MPU Alias 2 Region Base Address Register */ + __IOM uint32_t RASR_A2; /*!< Offset: 0x020 (R/W) MPU Alias 2 Region Attribute and Size Register */ + __IOM uint32_t RBAR_A3; /*!< Offset: 0x024 (R/W) MPU Alias 3 Region Base Address Register */ + __IOM uint32_t RASR_A3; /*!< Offset: 0x028 (R/W) MPU Alias 3 Region Attribute and Size Register */ +} MPU_Type; + +/* MPU Type Register Definitions */ +#define MPU_TYPE_IREGION_Pos 16U /*!< MPU TYPE: IREGION Position */ +#define MPU_TYPE_IREGION_Msk (0xFFUL << MPU_TYPE_IREGION_Pos) /*!< MPU TYPE: IREGION Mask */ + +#define MPU_TYPE_DREGION_Pos 8U /*!< MPU TYPE: DREGION Position */ +#define MPU_TYPE_DREGION_Msk (0xFFUL << MPU_TYPE_DREGION_Pos) /*!< MPU TYPE: DREGION Mask */ + +#define MPU_TYPE_SEPARATE_Pos 0U /*!< MPU TYPE: SEPARATE Position */ +#define MPU_TYPE_SEPARATE_Msk (1UL /*<< MPU_TYPE_SEPARATE_Pos*/) /*!< MPU TYPE: SEPARATE Mask */ + +/* MPU Control Register Definitions */ +#define MPU_CTRL_PRIVDEFENA_Pos 2U /*!< MPU CTRL: PRIVDEFENA Position */ +#define MPU_CTRL_PRIVDEFENA_Msk (1UL << MPU_CTRL_PRIVDEFENA_Pos) /*!< MPU CTRL: PRIVDEFENA Mask */ + +#define MPU_CTRL_HFNMIENA_Pos 1U /*!< MPU CTRL: HFNMIENA Position */ +#define MPU_CTRL_HFNMIENA_Msk (1UL << MPU_CTRL_HFNMIENA_Pos) /*!< MPU CTRL: HFNMIENA Mask */ + +#define MPU_CTRL_ENABLE_Pos 0U /*!< MPU CTRL: ENABLE Position */ +#define MPU_CTRL_ENABLE_Msk (1UL /*<< MPU_CTRL_ENABLE_Pos*/) /*!< MPU CTRL: ENABLE Mask */ + +/* MPU Region Number Register Definitions */ +#define MPU_RNR_REGION_Pos 0U /*!< MPU RNR: REGION Position */ +#define MPU_RNR_REGION_Msk (0xFFUL /*<< MPU_RNR_REGION_Pos*/) /*!< MPU RNR: REGION Mask */ + +/* MPU Region Base Address Register Definitions */ +#define MPU_RBAR_ADDR_Pos 5U /*!< MPU RBAR: ADDR Position */ +#define MPU_RBAR_ADDR_Msk (0x7FFFFFFUL << MPU_RBAR_ADDR_Pos) /*!< MPU RBAR: ADDR Mask */ + +#define MPU_RBAR_VALID_Pos 4U /*!< MPU RBAR: VALID Position */ +#define MPU_RBAR_VALID_Msk (1UL << MPU_RBAR_VALID_Pos) /*!< MPU RBAR: VALID Mask */ + +#define MPU_RBAR_REGION_Pos 0U /*!< MPU RBAR: REGION Position */ +#define MPU_RBAR_REGION_Msk (0xFUL /*<< MPU_RBAR_REGION_Pos*/) /*!< MPU RBAR: REGION Mask */ + +/* MPU Region Attribute and Size Register Definitions */ +#define MPU_RASR_ATTRS_Pos 16U /*!< MPU RASR: MPU Region Attribute field Position */ +#define MPU_RASR_ATTRS_Msk (0xFFFFUL << MPU_RASR_ATTRS_Pos) /*!< MPU RASR: MPU Region Attribute field Mask */ + +#define MPU_RASR_XN_Pos 28U /*!< MPU RASR: ATTRS.XN Position */ +#define MPU_RASR_XN_Msk (1UL << MPU_RASR_XN_Pos) /*!< MPU RASR: ATTRS.XN Mask */ + +#define MPU_RASR_AP_Pos 24U /*!< MPU RASR: ATTRS.AP Position */ +#define MPU_RASR_AP_Msk (0x7UL << MPU_RASR_AP_Pos) /*!< MPU RASR: ATTRS.AP Mask */ + +#define MPU_RASR_TEX_Pos 19U /*!< MPU RASR: ATTRS.TEX Position */ +#define MPU_RASR_TEX_Msk (0x7UL << MPU_RASR_TEX_Pos) /*!< MPU RASR: ATTRS.TEX Mask */ + +#define MPU_RASR_S_Pos 18U /*!< MPU RASR: ATTRS.S Position */ +#define MPU_RASR_S_Msk (1UL << MPU_RASR_S_Pos) /*!< MPU RASR: ATTRS.S Mask */ + +#define MPU_RASR_C_Pos 17U /*!< MPU RASR: ATTRS.C Position */ +#define MPU_RASR_C_Msk (1UL << MPU_RASR_C_Pos) /*!< MPU RASR: ATTRS.C Mask */ + +#define MPU_RASR_B_Pos 16U /*!< MPU RASR: ATTRS.B Position */ +#define MPU_RASR_B_Msk (1UL << MPU_RASR_B_Pos) /*!< MPU RASR: ATTRS.B Mask */ + +#define MPU_RASR_SRD_Pos 8U /*!< MPU RASR: Sub-Region Disable Position */ +#define MPU_RASR_SRD_Msk (0xFFUL << MPU_RASR_SRD_Pos) /*!< MPU RASR: Sub-Region Disable Mask */ + +#define MPU_RASR_SIZE_Pos 1U /*!< MPU RASR: Region Size Field Position */ +#define MPU_RASR_SIZE_Msk (0x1FUL << MPU_RASR_SIZE_Pos) /*!< MPU RASR: Region Size Field Mask */ + +#define MPU_RASR_ENABLE_Pos 0U /*!< MPU RASR: Region enable bit Position */ +#define MPU_RASR_ENABLE_Msk (1UL /*<< MPU_RASR_ENABLE_Pos*/) /*!< MPU RASR: Region enable bit Disable Mask */ + +/*@} end of group CMSIS_MPU */ +#endif + + +#if (__FPU_PRESENT == 1U) +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_FPU Floating Point Unit (FPU) + \brief Type definitions for the Floating Point Unit (FPU) + @{ + */ + +/** + \brief Structure type to access the Floating Point Unit (FPU). + */ +typedef struct +{ + uint32_t RESERVED0[1U]; + __IOM uint32_t FPCCR; /*!< Offset: 0x004 (R/W) Floating-Point Context Control Register */ + __IOM uint32_t FPCAR; /*!< Offset: 0x008 (R/W) Floating-Point Context Address Register */ + __IOM uint32_t FPDSCR; /*!< Offset: 0x00C (R/W) Floating-Point Default Status Control Register */ + __IM uint32_t MVFR0; /*!< Offset: 0x010 (R/ ) Media and FP Feature Register 0 */ + __IM uint32_t MVFR1; /*!< Offset: 0x014 (R/ ) Media and FP Feature Register 1 */ +} FPU_Type; + +/* Floating-Point Context Control Register Definitions */ +#define FPU_FPCCR_ASPEN_Pos 31U /*!< FPCCR: ASPEN bit Position */ +#define FPU_FPCCR_ASPEN_Msk (1UL << FPU_FPCCR_ASPEN_Pos) /*!< FPCCR: ASPEN bit Mask */ + +#define FPU_FPCCR_LSPEN_Pos 30U /*!< FPCCR: LSPEN Position */ +#define FPU_FPCCR_LSPEN_Msk (1UL << FPU_FPCCR_LSPEN_Pos) /*!< FPCCR: LSPEN bit Mask */ + +#define FPU_FPCCR_MONRDY_Pos 8U /*!< FPCCR: MONRDY Position */ +#define FPU_FPCCR_MONRDY_Msk (1UL << FPU_FPCCR_MONRDY_Pos) /*!< FPCCR: MONRDY bit Mask */ + +#define FPU_FPCCR_BFRDY_Pos 6U /*!< FPCCR: BFRDY Position */ +#define FPU_FPCCR_BFRDY_Msk (1UL << FPU_FPCCR_BFRDY_Pos) /*!< FPCCR: BFRDY bit Mask */ + +#define FPU_FPCCR_MMRDY_Pos 5U /*!< FPCCR: MMRDY Position */ +#define FPU_FPCCR_MMRDY_Msk (1UL << FPU_FPCCR_MMRDY_Pos) /*!< FPCCR: MMRDY bit Mask */ + +#define FPU_FPCCR_HFRDY_Pos 4U /*!< FPCCR: HFRDY Position */ +#define FPU_FPCCR_HFRDY_Msk (1UL << FPU_FPCCR_HFRDY_Pos) /*!< FPCCR: HFRDY bit Mask */ + +#define FPU_FPCCR_THREAD_Pos 3U /*!< FPCCR: processor mode bit Position */ +#define FPU_FPCCR_THREAD_Msk (1UL << FPU_FPCCR_THREAD_Pos) /*!< FPCCR: processor mode active bit Mask */ + +#define FPU_FPCCR_USER_Pos 1U /*!< FPCCR: privilege level bit Position */ +#define FPU_FPCCR_USER_Msk (1UL << FPU_FPCCR_USER_Pos) /*!< FPCCR: privilege level bit Mask */ + +#define FPU_FPCCR_LSPACT_Pos 0U /*!< FPCCR: Lazy state preservation active bit Position */ +#define FPU_FPCCR_LSPACT_Msk (1UL /*<< FPU_FPCCR_LSPACT_Pos*/) /*!< FPCCR: Lazy state preservation active bit Mask */ + +/* Floating-Point Context Address Register Definitions */ +#define FPU_FPCAR_ADDRESS_Pos 3U /*!< FPCAR: ADDRESS bit Position */ +#define FPU_FPCAR_ADDRESS_Msk (0x1FFFFFFFUL << FPU_FPCAR_ADDRESS_Pos) /*!< FPCAR: ADDRESS bit Mask */ + +/* Floating-Point Default Status Control Register Definitions */ +#define FPU_FPDSCR_AHP_Pos 26U /*!< FPDSCR: AHP bit Position */ +#define FPU_FPDSCR_AHP_Msk (1UL << FPU_FPDSCR_AHP_Pos) /*!< FPDSCR: AHP bit Mask */ + +#define FPU_FPDSCR_DN_Pos 25U /*!< FPDSCR: DN bit Position */ +#define FPU_FPDSCR_DN_Msk (1UL << FPU_FPDSCR_DN_Pos) /*!< FPDSCR: DN bit Mask */ + +#define FPU_FPDSCR_FZ_Pos 24U /*!< FPDSCR: FZ bit Position */ +#define FPU_FPDSCR_FZ_Msk (1UL << FPU_FPDSCR_FZ_Pos) /*!< FPDSCR: FZ bit Mask */ + +#define FPU_FPDSCR_RMode_Pos 22U /*!< FPDSCR: RMode bit Position */ +#define FPU_FPDSCR_RMode_Msk (3UL << FPU_FPDSCR_RMode_Pos) /*!< FPDSCR: RMode bit Mask */ + +/* Media and FP Feature Register 0 Definitions */ +#define FPU_MVFR0_FP_rounding_modes_Pos 28U /*!< MVFR0: FP rounding modes bits Position */ +#define FPU_MVFR0_FP_rounding_modes_Msk (0xFUL << FPU_MVFR0_FP_rounding_modes_Pos) /*!< MVFR0: FP rounding modes bits Mask */ + +#define FPU_MVFR0_Short_vectors_Pos 24U /*!< MVFR0: Short vectors bits Position */ +#define FPU_MVFR0_Short_vectors_Msk (0xFUL << FPU_MVFR0_Short_vectors_Pos) /*!< MVFR0: Short vectors bits Mask */ + +#define FPU_MVFR0_Square_root_Pos 20U /*!< MVFR0: Square root bits Position */ +#define FPU_MVFR0_Square_root_Msk (0xFUL << FPU_MVFR0_Square_root_Pos) /*!< MVFR0: Square root bits Mask */ + +#define FPU_MVFR0_Divide_Pos 16U /*!< MVFR0: Divide bits Position */ +#define FPU_MVFR0_Divide_Msk (0xFUL << FPU_MVFR0_Divide_Pos) /*!< MVFR0: Divide bits Mask */ + +#define FPU_MVFR0_FP_excep_trapping_Pos 12U /*!< MVFR0: FP exception trapping bits Position */ +#define FPU_MVFR0_FP_excep_trapping_Msk (0xFUL << FPU_MVFR0_FP_excep_trapping_Pos) /*!< MVFR0: FP exception trapping bits Mask */ + +#define FPU_MVFR0_Double_precision_Pos 8U /*!< MVFR0: Double-precision bits Position */ +#define FPU_MVFR0_Double_precision_Msk (0xFUL << FPU_MVFR0_Double_precision_Pos) /*!< MVFR0: Double-precision bits Mask */ + +#define FPU_MVFR0_Single_precision_Pos 4U /*!< MVFR0: Single-precision bits Position */ +#define FPU_MVFR0_Single_precision_Msk (0xFUL << FPU_MVFR0_Single_precision_Pos) /*!< MVFR0: Single-precision bits Mask */ + +#define FPU_MVFR0_A_SIMD_registers_Pos 0U /*!< MVFR0: A_SIMD registers bits Position */ +#define FPU_MVFR0_A_SIMD_registers_Msk (0xFUL /*<< FPU_MVFR0_A_SIMD_registers_Pos*/) /*!< MVFR0: A_SIMD registers bits Mask */ + +/* Media and FP Feature Register 1 Definitions */ +#define FPU_MVFR1_FP_fused_MAC_Pos 28U /*!< MVFR1: FP fused MAC bits Position */ +#define FPU_MVFR1_FP_fused_MAC_Msk (0xFUL << FPU_MVFR1_FP_fused_MAC_Pos) /*!< MVFR1: FP fused MAC bits Mask */ + +#define FPU_MVFR1_FP_HPFP_Pos 24U /*!< MVFR1: FP HPFP bits Position */ +#define FPU_MVFR1_FP_HPFP_Msk (0xFUL << FPU_MVFR1_FP_HPFP_Pos) /*!< MVFR1: FP HPFP bits Mask */ + +#define FPU_MVFR1_D_NaN_mode_Pos 4U /*!< MVFR1: D_NaN mode bits Position */ +#define FPU_MVFR1_D_NaN_mode_Msk (0xFUL << FPU_MVFR1_D_NaN_mode_Pos) /*!< MVFR1: D_NaN mode bits Mask */ + +#define FPU_MVFR1_FtZ_mode_Pos 0U /*!< MVFR1: FtZ mode bits Position */ +#define FPU_MVFR1_FtZ_mode_Msk (0xFUL /*<< FPU_MVFR1_FtZ_mode_Pos*/) /*!< MVFR1: FtZ mode bits Mask */ + +/*@} end of group CMSIS_FPU */ +#endif + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_CoreDebug Core Debug Registers (CoreDebug) + \brief Type definitions for the Core Debug Registers + @{ + */ + +/** + \brief Structure type to access the Core Debug Register (CoreDebug). + */ +typedef struct +{ + __IOM uint32_t DHCSR; /*!< Offset: 0x000 (R/W) Debug Halting Control and Status Register */ + __OM uint32_t DCRSR; /*!< Offset: 0x004 ( /W) Debug Core Register Selector Register */ + __IOM uint32_t DCRDR; /*!< Offset: 0x008 (R/W) Debug Core Register Data Register */ + __IOM uint32_t DEMCR; /*!< Offset: 0x00C (R/W) Debug Exception and Monitor Control Register */ +} CoreDebug_Type; + +/* Debug Halting Control and Status Register Definitions */ +#define CoreDebug_DHCSR_DBGKEY_Pos 16U /*!< CoreDebug DHCSR: DBGKEY Position */ +#define CoreDebug_DHCSR_DBGKEY_Msk (0xFFFFUL << CoreDebug_DHCSR_DBGKEY_Pos) /*!< CoreDebug DHCSR: DBGKEY Mask */ + +#define CoreDebug_DHCSR_S_RESET_ST_Pos 25U /*!< CoreDebug DHCSR: S_RESET_ST Position */ +#define CoreDebug_DHCSR_S_RESET_ST_Msk (1UL << CoreDebug_DHCSR_S_RESET_ST_Pos) /*!< CoreDebug DHCSR: S_RESET_ST Mask */ + +#define CoreDebug_DHCSR_S_RETIRE_ST_Pos 24U /*!< CoreDebug DHCSR: S_RETIRE_ST Position */ +#define CoreDebug_DHCSR_S_RETIRE_ST_Msk (1UL << CoreDebug_DHCSR_S_RETIRE_ST_Pos) /*!< CoreDebug DHCSR: S_RETIRE_ST Mask */ + +#define CoreDebug_DHCSR_S_LOCKUP_Pos 19U /*!< CoreDebug DHCSR: S_LOCKUP Position */ +#define CoreDebug_DHCSR_S_LOCKUP_Msk (1UL << CoreDebug_DHCSR_S_LOCKUP_Pos) /*!< CoreDebug DHCSR: S_LOCKUP Mask */ + +#define CoreDebug_DHCSR_S_SLEEP_Pos 18U /*!< CoreDebug DHCSR: S_SLEEP Position */ +#define CoreDebug_DHCSR_S_SLEEP_Msk (1UL << CoreDebug_DHCSR_S_SLEEP_Pos) /*!< CoreDebug DHCSR: S_SLEEP Mask */ + +#define CoreDebug_DHCSR_S_HALT_Pos 17U /*!< CoreDebug DHCSR: S_HALT Position */ +#define CoreDebug_DHCSR_S_HALT_Msk (1UL << CoreDebug_DHCSR_S_HALT_Pos) /*!< CoreDebug DHCSR: S_HALT Mask */ + +#define CoreDebug_DHCSR_S_REGRDY_Pos 16U /*!< CoreDebug DHCSR: S_REGRDY Position */ +#define CoreDebug_DHCSR_S_REGRDY_Msk (1UL << CoreDebug_DHCSR_S_REGRDY_Pos) /*!< CoreDebug DHCSR: S_REGRDY Mask */ + +#define CoreDebug_DHCSR_C_SNAPSTALL_Pos 5U /*!< CoreDebug DHCSR: C_SNAPSTALL Position */ +#define CoreDebug_DHCSR_C_SNAPSTALL_Msk (1UL << CoreDebug_DHCSR_C_SNAPSTALL_Pos) /*!< CoreDebug DHCSR: C_SNAPSTALL Mask */ + +#define CoreDebug_DHCSR_C_MASKINTS_Pos 3U /*!< CoreDebug DHCSR: C_MASKINTS Position */ +#define CoreDebug_DHCSR_C_MASKINTS_Msk (1UL << CoreDebug_DHCSR_C_MASKINTS_Pos) /*!< CoreDebug DHCSR: C_MASKINTS Mask */ + +#define CoreDebug_DHCSR_C_STEP_Pos 2U /*!< CoreDebug DHCSR: C_STEP Position */ +#define CoreDebug_DHCSR_C_STEP_Msk (1UL << CoreDebug_DHCSR_C_STEP_Pos) /*!< CoreDebug DHCSR: C_STEP Mask */ + +#define CoreDebug_DHCSR_C_HALT_Pos 1U /*!< CoreDebug DHCSR: C_HALT Position */ +#define CoreDebug_DHCSR_C_HALT_Msk (1UL << CoreDebug_DHCSR_C_HALT_Pos) /*!< CoreDebug DHCSR: C_HALT Mask */ + +#define CoreDebug_DHCSR_C_DEBUGEN_Pos 0U /*!< CoreDebug DHCSR: C_DEBUGEN Position */ +#define CoreDebug_DHCSR_C_DEBUGEN_Msk (1UL /*<< CoreDebug_DHCSR_C_DEBUGEN_Pos*/) /*!< CoreDebug DHCSR: C_DEBUGEN Mask */ + +/* Debug Core Register Selector Register Definitions */ +#define CoreDebug_DCRSR_REGWnR_Pos 16U /*!< CoreDebug DCRSR: REGWnR Position */ +#define CoreDebug_DCRSR_REGWnR_Msk (1UL << CoreDebug_DCRSR_REGWnR_Pos) /*!< CoreDebug DCRSR: REGWnR Mask */ + +#define CoreDebug_DCRSR_REGSEL_Pos 0U /*!< CoreDebug DCRSR: REGSEL Position */ +#define CoreDebug_DCRSR_REGSEL_Msk (0x1FUL /*<< CoreDebug_DCRSR_REGSEL_Pos*/) /*!< CoreDebug DCRSR: REGSEL Mask */ + +/* Debug Exception and Monitor Control Register Definitions */ +#define CoreDebug_DEMCR_TRCENA_Pos 24U /*!< CoreDebug DEMCR: TRCENA Position */ +#define CoreDebug_DEMCR_TRCENA_Msk (1UL << CoreDebug_DEMCR_TRCENA_Pos) /*!< CoreDebug DEMCR: TRCENA Mask */ + +#define CoreDebug_DEMCR_MON_REQ_Pos 19U /*!< CoreDebug DEMCR: MON_REQ Position */ +#define CoreDebug_DEMCR_MON_REQ_Msk (1UL << CoreDebug_DEMCR_MON_REQ_Pos) /*!< CoreDebug DEMCR: MON_REQ Mask */ + +#define CoreDebug_DEMCR_MON_STEP_Pos 18U /*!< CoreDebug DEMCR: MON_STEP Position */ +#define CoreDebug_DEMCR_MON_STEP_Msk (1UL << CoreDebug_DEMCR_MON_STEP_Pos) /*!< CoreDebug DEMCR: MON_STEP Mask */ + +#define CoreDebug_DEMCR_MON_PEND_Pos 17U /*!< CoreDebug DEMCR: MON_PEND Position */ +#define CoreDebug_DEMCR_MON_PEND_Msk (1UL << CoreDebug_DEMCR_MON_PEND_Pos) /*!< CoreDebug DEMCR: MON_PEND Mask */ + +#define CoreDebug_DEMCR_MON_EN_Pos 16U /*!< CoreDebug DEMCR: MON_EN Position */ +#define CoreDebug_DEMCR_MON_EN_Msk (1UL << CoreDebug_DEMCR_MON_EN_Pos) /*!< CoreDebug DEMCR: MON_EN Mask */ + +#define CoreDebug_DEMCR_VC_HARDERR_Pos 10U /*!< CoreDebug DEMCR: VC_HARDERR Position */ +#define CoreDebug_DEMCR_VC_HARDERR_Msk (1UL << CoreDebug_DEMCR_VC_HARDERR_Pos) /*!< CoreDebug DEMCR: VC_HARDERR Mask */ + +#define CoreDebug_DEMCR_VC_INTERR_Pos 9U /*!< CoreDebug DEMCR: VC_INTERR Position */ +#define CoreDebug_DEMCR_VC_INTERR_Msk (1UL << CoreDebug_DEMCR_VC_INTERR_Pos) /*!< CoreDebug DEMCR: VC_INTERR Mask */ + +#define CoreDebug_DEMCR_VC_BUSERR_Pos 8U /*!< CoreDebug DEMCR: VC_BUSERR Position */ +#define CoreDebug_DEMCR_VC_BUSERR_Msk (1UL << CoreDebug_DEMCR_VC_BUSERR_Pos) /*!< CoreDebug DEMCR: VC_BUSERR Mask */ + +#define CoreDebug_DEMCR_VC_STATERR_Pos 7U /*!< CoreDebug DEMCR: VC_STATERR Position */ +#define CoreDebug_DEMCR_VC_STATERR_Msk (1UL << CoreDebug_DEMCR_VC_STATERR_Pos) /*!< CoreDebug DEMCR: VC_STATERR Mask */ + +#define CoreDebug_DEMCR_VC_CHKERR_Pos 6U /*!< CoreDebug DEMCR: VC_CHKERR Position */ +#define CoreDebug_DEMCR_VC_CHKERR_Msk (1UL << CoreDebug_DEMCR_VC_CHKERR_Pos) /*!< CoreDebug DEMCR: VC_CHKERR Mask */ + +#define CoreDebug_DEMCR_VC_NOCPERR_Pos 5U /*!< CoreDebug DEMCR: VC_NOCPERR Position */ +#define CoreDebug_DEMCR_VC_NOCPERR_Msk (1UL << CoreDebug_DEMCR_VC_NOCPERR_Pos) /*!< CoreDebug DEMCR: VC_NOCPERR Mask */ + +#define CoreDebug_DEMCR_VC_MMERR_Pos 4U /*!< CoreDebug DEMCR: VC_MMERR Position */ +#define CoreDebug_DEMCR_VC_MMERR_Msk (1UL << CoreDebug_DEMCR_VC_MMERR_Pos) /*!< CoreDebug DEMCR: VC_MMERR Mask */ + +#define CoreDebug_DEMCR_VC_CORERESET_Pos 0U /*!< CoreDebug DEMCR: VC_CORERESET Position */ +#define CoreDebug_DEMCR_VC_CORERESET_Msk (1UL /*<< CoreDebug_DEMCR_VC_CORERESET_Pos*/) /*!< CoreDebug DEMCR: VC_CORERESET Mask */ + +/*@} end of group CMSIS_CoreDebug */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_core_bitfield Core register bit field macros + \brief Macros for use with bit field definitions (xxx_Pos, xxx_Msk). + @{ + */ + +/** + \brief Mask and shift a bit field value for use in a register bit range. + \param[in] field Name of the register bit field. + \param[in] value Value of the bit field. + \return Masked and shifted value. +*/ +#define _VAL2FLD(field, value) ((value << field ## _Pos) & field ## _Msk) + +/** + \brief Mask and shift a register value to extract a bit filed value. + \param[in] field Name of the register bit field. + \param[in] value Value of register. + \return Masked and shifted bit field value. +*/ +#define _FLD2VAL(field, value) ((value & field ## _Msk) >> field ## _Pos) + +/*@} end of group CMSIS_core_bitfield */ + + +/** + \ingroup CMSIS_core_register + \defgroup CMSIS_core_base Core Definitions + \brief Definitions for base addresses, unions, and structures. + @{ + */ + +/* Memory mapping of Cortex-M4 Hardware */ +#define SCS_BASE (0xE000E000UL) /*!< System Control Space Base Address */ +#define ITM_BASE (0xE0000000UL) /*!< ITM Base Address */ +#define DWT_BASE (0xE0001000UL) /*!< DWT Base Address */ +#define TPI_BASE (0xE0040000UL) /*!< TPI Base Address */ +#define CoreDebug_BASE (0xE000EDF0UL) /*!< Core Debug Base Address */ +#define SysTick_BASE (SCS_BASE + 0x0010UL) /*!< SysTick Base Address */ +#define NVIC_BASE (SCS_BASE + 0x0100UL) /*!< NVIC Base Address */ +#define SCB_BASE (SCS_BASE + 0x0D00UL) /*!< System Control Block Base Address */ + +#define SCnSCB ((SCnSCB_Type *) SCS_BASE ) /*!< System control Register not in SCB */ +#define SCB ((SCB_Type *) SCB_BASE ) /*!< SCB configuration struct */ +#define SysTick ((SysTick_Type *) SysTick_BASE ) /*!< SysTick configuration struct */ +#define NVIC ((NVIC_Type *) NVIC_BASE ) /*!< NVIC configuration struct */ +#define ITM ((ITM_Type *) ITM_BASE ) /*!< ITM configuration struct */ +#define DWT ((DWT_Type *) DWT_BASE ) /*!< DWT configuration struct */ +#define TPI ((TPI_Type *) TPI_BASE ) /*!< TPI configuration struct */ +#define CoreDebug ((CoreDebug_Type *) CoreDebug_BASE) /*!< Core Debug configuration struct */ + +#if (__MPU_PRESENT == 1U) + #define MPU_BASE (SCS_BASE + 0x0D90UL) /*!< Memory Protection Unit */ + #define MPU ((MPU_Type *) MPU_BASE ) /*!< Memory Protection Unit */ +#endif + +#if (__FPU_PRESENT == 1U) + #define FPU_BASE (SCS_BASE + 0x0F30UL) /*!< Floating Point Unit */ + #define FPU ((FPU_Type *) FPU_BASE ) /*!< Floating Point Unit */ +#endif + +/*@} */ + + + +/******************************************************************************* + * Hardware Abstraction Layer + Core Function Interface contains: + - Core NVIC Functions + - Core SysTick Functions + - Core Debug Functions + - Core Register Access Functions + ******************************************************************************/ +/** + \defgroup CMSIS_Core_FunctionInterface Functions and Instructions Reference +*/ + + + +/* ########################## NVIC functions #################################### */ +/** + \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_NVICFunctions NVIC Functions + \brief Functions that manage interrupts and exceptions via the NVIC. + @{ + */ + +/** + \brief Set Priority Grouping + \details Sets the priority grouping field using the required unlock sequence. + The parameter PriorityGroup is assigned to the field SCB->AIRCR [10:8] PRIGROUP field. + Only values from 0..7 are used. + In case of a conflict between priority grouping and available + priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. + \param [in] PriorityGroup Priority grouping field. + */ +__STATIC_INLINE void NVIC_SetPriorityGrouping(uint32_t PriorityGroup) +{ + uint32_t reg_value; + uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ + + reg_value = SCB->AIRCR; /* read old register configuration */ + reg_value &= ~((uint32_t)(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk)); /* clear bits to change */ + reg_value = (reg_value | + ((uint32_t)0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | + (PriorityGroupTmp << 8U) ); /* Insert write key and priorty group */ + SCB->AIRCR = reg_value; +} + + +/** + \brief Get Priority Grouping + \details Reads the priority grouping field from the NVIC Interrupt Controller. + \return Priority grouping field (SCB->AIRCR [10:8] PRIGROUP field). + */ +__STATIC_INLINE uint32_t NVIC_GetPriorityGrouping(void) +{ + return ((uint32_t)((SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) >> SCB_AIRCR_PRIGROUP_Pos)); +} + + +/** + \brief Enable External Interrupt + \details Enables a device-specific interrupt in the NVIC interrupt controller. + \param [in] IRQn External interrupt number. Value cannot be negative. + */ +__STATIC_INLINE void NVIC_EnableIRQ(IRQn_Type IRQn) +{ + NVIC->ISER[(((uint32_t)(int32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)(int32_t)IRQn) & 0x1FUL)); +} + + +/** + \brief Disable External Interrupt + \details Disables a device-specific interrupt in the NVIC interrupt controller. + \param [in] IRQn External interrupt number. Value cannot be negative. + */ +__STATIC_INLINE void NVIC_DisableIRQ(IRQn_Type IRQn) +{ + NVIC->ICER[(((uint32_t)(int32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)(int32_t)IRQn) & 0x1FUL)); +} + + +/** + \brief Get Pending Interrupt + \details Reads the pending register in the NVIC and returns the pending bit for the specified interrupt. + \param [in] IRQn Interrupt number. + \return 0 Interrupt status is not pending. + \return 1 Interrupt status is pending. + */ +__STATIC_INLINE uint32_t NVIC_GetPendingIRQ(IRQn_Type IRQn) +{ + return((uint32_t)(((NVIC->ISPR[(((uint32_t)(int32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)(int32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); +} + + +/** + \brief Set Pending Interrupt + \details Sets the pending bit of an external interrupt. + \param [in] IRQn Interrupt number. Value cannot be negative. + */ +__STATIC_INLINE void NVIC_SetPendingIRQ(IRQn_Type IRQn) +{ + NVIC->ISPR[(((uint32_t)(int32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)(int32_t)IRQn) & 0x1FUL)); +} + + +/** + \brief Clear Pending Interrupt + \details Clears the pending bit of an external interrupt. + \param [in] IRQn External interrupt number. Value cannot be negative. + */ +__STATIC_INLINE void NVIC_ClearPendingIRQ(IRQn_Type IRQn) +{ + NVIC->ICPR[(((uint32_t)(int32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)(int32_t)IRQn) & 0x1FUL)); +} + + +/** + \brief Get Active Interrupt + \details Reads the active register in NVIC and returns the active bit. + \param [in] IRQn Interrupt number. + \return 0 Interrupt status is not active. + \return 1 Interrupt status is active. + */ +__STATIC_INLINE uint32_t NVIC_GetActive(IRQn_Type IRQn) +{ + return((uint32_t)(((NVIC->IABR[(((uint32_t)(int32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)(int32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); +} + + +/** + \brief Set Interrupt Priority + \details Sets the priority of an interrupt. + \note The priority cannot be set for every core interrupt. + \param [in] IRQn Interrupt number. + \param [in] priority Priority to set. + */ +__STATIC_INLINE void NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority) +{ + if ((int32_t)(IRQn) < 0) + { + SCB->SHP[(((uint32_t)(int32_t)IRQn) & 0xFUL)-4UL] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); + } + else + { + NVIC->IP[((uint32_t)(int32_t)IRQn)] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); + } +} + + +/** + \brief Get Interrupt Priority + \details Reads the priority of an interrupt. + The interrupt number can be positive to specify an external (device specific) interrupt, + or negative to specify an internal (core) interrupt. + \param [in] IRQn Interrupt number. + \return Interrupt Priority. + Value is aligned automatically to the implemented priority bits of the microcontroller. + */ +__STATIC_INLINE uint32_t NVIC_GetPriority(IRQn_Type IRQn) +{ + + if ((int32_t)(IRQn) < 0) + { + return(((uint32_t)SCB->SHP[(((uint32_t)(int32_t)IRQn) & 0xFUL)-4UL] >> (8U - __NVIC_PRIO_BITS))); + } + else + { + return(((uint32_t)NVIC->IP[((uint32_t)(int32_t)IRQn)] >> (8U - __NVIC_PRIO_BITS))); + } +} + + +/** + \brief Encode Priority + \details Encodes the priority for an interrupt with the given priority group, + preemptive priority value, and subpriority value. + In case of a conflict between priority grouping and available + priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. + \param [in] PriorityGroup Used priority group. + \param [in] PreemptPriority Preemptive priority value (starting from 0). + \param [in] SubPriority Subpriority value (starting from 0). + \return Encoded priority. Value can be used in the function \ref NVIC_SetPriority(). + */ +__STATIC_INLINE uint32_t NVIC_EncodePriority (uint32_t PriorityGroup, uint32_t PreemptPriority, uint32_t SubPriority) +{ + uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ + uint32_t PreemptPriorityBits; + uint32_t SubPriorityBits; + + PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); + SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); + + return ( + ((PreemptPriority & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL)) << SubPriorityBits) | + ((SubPriority & (uint32_t)((1UL << (SubPriorityBits )) - 1UL))) + ); +} + + +/** + \brief Decode Priority + \details Decodes an interrupt priority value with a given priority group to + preemptive priority value and subpriority value. + In case of a conflict between priority grouping and available + priority bits (__NVIC_PRIO_BITS) the smallest possible priority group is set. + \param [in] Priority Priority value, which can be retrieved with the function \ref NVIC_GetPriority(). + \param [in] PriorityGroup Used priority group. + \param [out] pPreemptPriority Preemptive priority value (starting from 0). + \param [out] pSubPriority Subpriority value (starting from 0). + */ +__STATIC_INLINE void NVIC_DecodePriority (uint32_t Priority, uint32_t PriorityGroup, uint32_t* const pPreemptPriority, uint32_t* const pSubPriority) +{ + uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ + uint32_t PreemptPriorityBits; + uint32_t SubPriorityBits; + + PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); + SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); + + *pPreemptPriority = (Priority >> SubPriorityBits) & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL); + *pSubPriority = (Priority ) & (uint32_t)((1UL << (SubPriorityBits )) - 1UL); +} + + +/** + \brief System Reset + \details Initiates a system reset request to reset the MCU. + */ +__STATIC_INLINE void NVIC_SystemReset(void) +{ + __DSB(); /* Ensure all outstanding memory accesses included + buffered write are completed before reset */ + SCB->AIRCR = (uint32_t)((0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | + (SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) | + SCB_AIRCR_SYSRESETREQ_Msk ); /* Keep priority group unchanged */ + __DSB(); /* Ensure completion of memory access */ + + for(;;) /* wait until reset */ + { + __NOP(); + } +} + +/*@} end of CMSIS_Core_NVICFunctions */ + + + +/* ################################## SysTick function ############################################ */ +/** + \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_SysTickFunctions SysTick Functions + \brief Functions that configure the System. + @{ + */ + +#if (__Vendor_SysTickConfig == 0U) + +/** + \brief System Tick Configuration + \details Initializes the System Timer and its interrupt, and starts the System Tick Timer. + Counter is in free running mode to generate periodic interrupts. + \param [in] ticks Number of ticks between two interrupts. + \return 0 Function succeeded. + \return 1 Function failed. + \note When the variable __Vendor_SysTickConfig is set to 1, then the + function SysTick_Config is not included. In this case, the file device.h + must contain a vendor-specific implementation of this function. + */ +__STATIC_INLINE uint32_t SysTick_Config(uint32_t ticks) +{ + if ((ticks - 1UL) > SysTick_LOAD_RELOAD_Msk) + { + return (1UL); /* Reload value impossible */ + } + + SysTick->LOAD = (uint32_t)(ticks - 1UL); /* set reload register */ + NVIC_SetPriority (SysTick_IRQn, (1UL << __NVIC_PRIO_BITS) - 1UL); /* set Priority for Systick Interrupt */ + SysTick->VAL = 0UL; /* Load the SysTick Counter Value */ + SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk | + SysTick_CTRL_TICKINT_Msk | + SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ + return (0UL); /* Function successful */ +} + +#endif + +/*@} end of CMSIS_Core_SysTickFunctions */ + + + +/* ##################################### Debug In/Output function ########################################### */ +/** + \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_core_DebugFunctions ITM Functions + \brief Functions that access the ITM debug interface. + @{ + */ + +extern volatile int32_t ITM_RxBuffer; /*!< External variable to receive characters. */ +#define ITM_RXBUFFER_EMPTY 0x5AA55AA5U /*!< Value identifying \ref ITM_RxBuffer is ready for next character. */ + + +/** + \brief ITM Send Character + \details Transmits a character via the ITM channel 0, and + \li Just returns when no debugger is connected that has booked the output. + \li Is blocking when a debugger is connected, but the previous character sent has not been transmitted. + \param [in] ch Character to transmit. + \returns Character to transmit. + */ +__STATIC_INLINE uint32_t ITM_SendChar (uint32_t ch) +{ + if (((ITM->TCR & ITM_TCR_ITMENA_Msk) != 0UL) && /* ITM enabled */ + ((ITM->TER & 1UL ) != 0UL) ) /* ITM Port #0 enabled */ + { + while (ITM->PORT[0U].u32 == 0UL) + { + __NOP(); + } + ITM->PORT[0U].u8 = (uint8_t)ch; + } + return (ch); +} + + +/** + \brief ITM Receive Character + \details Inputs a character via the external variable \ref ITM_RxBuffer. + \return Received character. + \return -1 No character pending. + */ +__STATIC_INLINE int32_t ITM_ReceiveChar (void) +{ + int32_t ch = -1; /* no character available */ + + if (ITM_RxBuffer != ITM_RXBUFFER_EMPTY) + { + ch = ITM_RxBuffer; + ITM_RxBuffer = ITM_RXBUFFER_EMPTY; /* ready for next character */ + } + + return (ch); +} + + +/** + \brief ITM Check Character + \details Checks whether a character is pending for reading in the variable \ref ITM_RxBuffer. + \return 0 No character available. + \return 1 Character available. + */ +__STATIC_INLINE int32_t ITM_CheckChar (void) +{ + + if (ITM_RxBuffer == ITM_RXBUFFER_EMPTY) + { + return (0); /* no character available */ + } + else + { + return (1); /* character available */ + } +} + +/*@} end of CMSIS_core_DebugFunctions */ + + + + +#ifdef __cplusplus +} +#endif + +#endif /* __CORE_CM4_H_DEPENDANT */ + +#endif /* __CMSIS_GENERIC */ diff --git a/panda/board/inc/core_cmFunc.h b/panda/board/inc/core_cmFunc.h new file mode 100644 index 00000000000000..652a48af07a93d --- /dev/null +++ b/panda/board/inc/core_cmFunc.h @@ -0,0 +1,87 @@ +/**************************************************************************//** + * @file core_cmFunc.h + * @brief CMSIS Cortex-M Core Function Access Header File + * @version V4.30 + * @date 20. October 2015 + ******************************************************************************/ +/* Copyright (c) 2009 - 2015 ARM LIMITED + + All rights reserved. + Redistribution and use in source and binary forms, with or without + modification, are permitted provided that the following conditions are met: + - Redistributions of source code must retain the above copyright + notice, this list of conditions and the following disclaimer. + - Redistributions in binary form must reproduce the above copyright + notice, this list of conditions and the following disclaimer in the + documentation and/or other materials provided with the distribution. + - Neither the name of ARM nor the names of its contributors may be used + to endorse or promote products derived from this software without + specific prior written permission. + * + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE + LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + POSSIBILITY OF SUCH DAMAGE. + ---------------------------------------------------------------------------*/ + + +#if defined ( __ICCARM__ ) + #pragma system_include /* treat file as system include file for MISRA check */ +#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) + #pragma clang system_header /* treat file as system include file */ +#endif + +#ifndef __CORE_CMFUNC_H +#define __CORE_CMFUNC_H + + +/* ########################### Core Function Access ########################### */ +/** \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_RegAccFunctions CMSIS Core Register Access Functions + @{ +*/ + +/*------------------ RealView Compiler -----------------*/ +#if defined ( __CC_ARM ) + #include "cmsis_armcc.h" + +/*------------------ ARM Compiler V6 -------------------*/ +#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) + #include "cmsis_armcc_V6.h" + +/*------------------ GNU Compiler ----------------------*/ +#elif defined ( __GNUC__ ) + #include "cmsis_gcc.h" + +/*------------------ ICC Compiler ----------------------*/ +#elif defined ( __ICCARM__ ) + #include + +/*------------------ TI CCS Compiler -------------------*/ +#elif defined ( __TMS470__ ) + #include + +/*------------------ TASKING Compiler ------------------*/ +#elif defined ( __TASKING__ ) + /* + * The CMSIS functions have been implemented as intrinsics in the compiler. + * Please use "carm -?i" to get an up to date list of all intrinsics, + * Including the CMSIS ones. + */ + +/*------------------ COSMIC Compiler -------------------*/ +#elif defined ( __CSMC__ ) + #include + +#endif + +/*@} end of CMSIS_Core_RegAccFunctions */ + +#endif /* __CORE_CMFUNC_H */ diff --git a/panda/board/inc/core_cmInstr.h b/panda/board/inc/core_cmInstr.h new file mode 100644 index 00000000000000..f474b0e6f362c7 --- /dev/null +++ b/panda/board/inc/core_cmInstr.h @@ -0,0 +1,87 @@ +/**************************************************************************//** + * @file core_cmInstr.h + * @brief CMSIS Cortex-M Core Instruction Access Header File + * @version V4.30 + * @date 20. October 2015 + ******************************************************************************/ +/* Copyright (c) 2009 - 2015 ARM LIMITED + + All rights reserved. + Redistribution and use in source and binary forms, with or without + modification, are permitted provided that the following conditions are met: + - Redistributions of source code must retain the above copyright + notice, this list of conditions and the following disclaimer. + - Redistributions in binary form must reproduce the above copyright + notice, this list of conditions and the following disclaimer in the + documentation and/or other materials provided with the distribution. + - Neither the name of ARM nor the names of its contributors may be used + to endorse or promote products derived from this software without + specific prior written permission. + * + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE + LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + POSSIBILITY OF SUCH DAMAGE. + ---------------------------------------------------------------------------*/ + + +#if defined ( __ICCARM__ ) + #pragma system_include /* treat file as system include file for MISRA check */ +#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) + #pragma clang system_header /* treat file as system include file */ +#endif + +#ifndef __CORE_CMINSTR_H +#define __CORE_CMINSTR_H + + +/* ########################## Core Instruction Access ######################### */ +/** \defgroup CMSIS_Core_InstructionInterface CMSIS Core Instruction Interface + Access to dedicated instructions + @{ +*/ + +/*------------------ RealView Compiler -----------------*/ +#if defined ( __CC_ARM ) + #include "cmsis_armcc.h" + +/*------------------ ARM Compiler V6 -------------------*/ +#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) + #include "cmsis_armcc_V6.h" + +/*------------------ GNU Compiler ----------------------*/ +#elif defined ( __GNUC__ ) + #include "cmsis_gcc.h" + +/*------------------ ICC Compiler ----------------------*/ +#elif defined ( __ICCARM__ ) + #include + +/*------------------ TI CCS Compiler -------------------*/ +#elif defined ( __TMS470__ ) + #include + +/*------------------ TASKING Compiler ------------------*/ +#elif defined ( __TASKING__ ) + /* + * The CMSIS functions have been implemented as intrinsics in the compiler. + * Please use "carm -?i" to get an up to date list of all intrinsics, + * Including the CMSIS ones. + */ + +/*------------------ COSMIC Compiler -------------------*/ +#elif defined ( __CSMC__ ) + #include + +#endif + +/*@}*/ /* end of group CMSIS_Core_InstructionInterface */ + +#endif /* __CORE_CMINSTR_H */ diff --git a/panda/board/inc/core_cmSimd.h b/panda/board/inc/core_cmSimd.h new file mode 100644 index 00000000000000..66bf5c2a725b6d --- /dev/null +++ b/panda/board/inc/core_cmSimd.h @@ -0,0 +1,96 @@ +/**************************************************************************//** + * @file core_cmSimd.h + * @brief CMSIS Cortex-M SIMD Header File + * @version V4.30 + * @date 20. October 2015 + ******************************************************************************/ +/* Copyright (c) 2009 - 2015 ARM LIMITED + + All rights reserved. + Redistribution and use in source and binary forms, with or without + modification, are permitted provided that the following conditions are met: + - Redistributions of source code must retain the above copyright + notice, this list of conditions and the following disclaimer. + - Redistributions in binary form must reproduce the above copyright + notice, this list of conditions and the following disclaimer in the + documentation and/or other materials provided with the distribution. + - Neither the name of ARM nor the names of its contributors may be used + to endorse or promote products derived from this software without + specific prior written permission. + * + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE + LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + POSSIBILITY OF SUCH DAMAGE. + ---------------------------------------------------------------------------*/ + + +#if defined ( __ICCARM__ ) + #pragma system_include /* treat file as system include file for MISRA check */ +#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) + #pragma clang system_header /* treat file as system include file */ +#endif + +#ifndef __CORE_CMSIMD_H +#define __CORE_CMSIMD_H + +#ifdef __cplusplus + extern "C" { +#endif + + +/* ################### Compiler specific Intrinsics ########################### */ +/** \defgroup CMSIS_SIMD_intrinsics CMSIS SIMD Intrinsics + Access to dedicated SIMD instructions + @{ +*/ + +/*------------------ RealView Compiler -----------------*/ +#if defined ( __CC_ARM ) + #include "cmsis_armcc.h" + +/*------------------ ARM Compiler V6 -------------------*/ +#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) + #include "cmsis_armcc_V6.h" + +/*------------------ GNU Compiler ----------------------*/ +#elif defined ( __GNUC__ ) + #include "cmsis_gcc.h" + +/*------------------ ICC Compiler ----------------------*/ +#elif defined ( __ICCARM__ ) + #include + +/*------------------ TI CCS Compiler -------------------*/ +#elif defined ( __TMS470__ ) + #include + +/*------------------ TASKING Compiler ------------------*/ +#elif defined ( __TASKING__ ) + /* + * The CMSIS functions have been implemented as intrinsics in the compiler. + * Please use "carm -?i" to get an up to date list of all intrinsics, + * Including the CMSIS ones. + */ + +/*------------------ COSMIC Compiler -------------------*/ +#elif defined ( __CSMC__ ) + #include + +#endif + +/*@} end of group CMSIS_SIMD_intrinsics */ + + +#ifdef __cplusplus +} +#endif + +#endif /* __CORE_CMSIMD_H */ diff --git a/panda/board/inc/stm32f205xx.h b/panda/board/inc/stm32f205xx.h new file mode 100644 index 00000000000000..ba825d1970327c --- /dev/null +++ b/panda/board/inc/stm32f205xx.h @@ -0,0 +1,7666 @@ +/** + ****************************************************************************** + * @file stm32f205xx.h + * @author MCD Application Team + * @version V2.1.2 + * @date 29-June-2016 + * @brief CMSIS STM32F205xx Device Peripheral Access Layer Header File. + * This file contains : + * - Data structures and the address mapping for all peripherals + * - Peripherals registers declarations and bits definition + * - Macros to access peripheral’s registers hardware + * + ****************************************************************************** + * @attention + * + *

© COPYRIGHT(c) 2016 STMicroelectronics

+ * + * Redistribution and use in source and binary forms, with or without modification, + * are permitted provided that the following conditions are met: + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * 3. Neither the name of STMicroelectronics nor the names of its contributors + * may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************** + */ + +/** @addtogroup CMSIS + * @{ + */ + +/** @addtogroup stm32f205xx + * @{ + */ + +#ifndef __STM32F205xx_H +#define __STM32F205xx_H + +#ifdef __cplusplus + extern "C" { +#endif /* __cplusplus */ + + +/** @addtogroup Configuration_section_for_CMSIS + * @{ + */ + +/** + * @brief Configuration of the Cortex-M3 Processor and Core Peripherals + */ +#define __CM3_REV 0x0200U /*!< Core revision r0p1 */ +#define __MPU_PRESENT 1U /*!< STM32F2XX provides an MPU */ +#define __NVIC_PRIO_BITS 4U /*!< STM32F2XX uses 4 Bits for the Priority Levels */ +#define __Vendor_SysTickConfig 0U /*!< Set to 1 if different SysTick Config is used */ + +/** + * @} + */ + +/** @addtogroup Peripheral_interrupt_number_definition + * @{ + */ + +/** + * @brief STM32F2XX Interrupt Number Definition, according to the selected device + * in @ref Library_configuration_section + */ +typedef enum +{ +/****** Cortex-M3 Processor Exceptions Numbers ****************************************************************/ + NonMaskableInt_IRQn = -14, /*!< 2 Non Maskable Interrupt */ + MemoryManagement_IRQn = -12, /*!< 4 Cortex-M3 Memory Management Interrupt */ + BusFault_IRQn = -11, /*!< 5 Cortex-M3 Bus Fault Interrupt */ + UsageFault_IRQn = -10, /*!< 6 Cortex-M3 Usage Fault Interrupt */ + SVCall_IRQn = -5, /*!< 11 Cortex-M3 SV Call Interrupt */ + DebugMonitor_IRQn = -4, /*!< 12 Cortex-M3 Debug Monitor Interrupt */ + PendSV_IRQn = -2, /*!< 14 Cortex-M3 Pend SV Interrupt */ + SysTick_IRQn = -1, /*!< 15 Cortex-M3 System Tick Interrupt */ +/****** STM32 specific Interrupt Numbers **********************************************************************/ + WWDG_IRQn = 0, /*!< Window WatchDog Interrupt */ + PVD_IRQn = 1, /*!< PVD through EXTI Line detection Interrupt */ + TAMP_STAMP_IRQn = 2, /*!< Tamper and TimeStamp interrupts through the EXTI line */ + RTC_WKUP_IRQn = 3, /*!< RTC Wakeup interrupt through the EXTI line */ + FLASH_IRQn = 4, /*!< FLASH global Interrupt */ + RCC_IRQn = 5, /*!< RCC global Interrupt */ + EXTI0_IRQn = 6, /*!< EXTI Line0 Interrupt */ + EXTI1_IRQn = 7, /*!< EXTI Line1 Interrupt */ + EXTI2_IRQn = 8, /*!< EXTI Line2 Interrupt */ + EXTI3_IRQn = 9, /*!< EXTI Line3 Interrupt */ + EXTI4_IRQn = 10, /*!< EXTI Line4 Interrupt */ + DMA1_Stream0_IRQn = 11, /*!< DMA1 Stream 0 global Interrupt */ + DMA1_Stream1_IRQn = 12, /*!< DMA1 Stream 1 global Interrupt */ + DMA1_Stream2_IRQn = 13, /*!< DMA1 Stream 2 global Interrupt */ + DMA1_Stream3_IRQn = 14, /*!< DMA1 Stream 3 global Interrupt */ + DMA1_Stream4_IRQn = 15, /*!< DMA1 Stream 4 global Interrupt */ + DMA1_Stream5_IRQn = 16, /*!< DMA1 Stream 5 global Interrupt */ + DMA1_Stream6_IRQn = 17, /*!< DMA1 Stream 6 global Interrupt */ + ADC_IRQn = 18, /*!< ADC1, ADC2 and ADC3 global Interrupts */ + CAN1_TX_IRQn = 19, /*!< CAN1 TX Interrupt */ + CAN1_RX0_IRQn = 20, /*!< CAN1 RX0 Interrupt */ + CAN1_RX1_IRQn = 21, /*!< CAN1 RX1 Interrupt */ + CAN1_SCE_IRQn = 22, /*!< CAN1 SCE Interrupt */ + EXTI9_5_IRQn = 23, /*!< External Line[9:5] Interrupts */ + TIM1_BRK_TIM9_IRQn = 24, /*!< TIM1 Break interrupt and TIM9 global interrupt */ + TIM1_UP_TIM10_IRQn = 25, /*!< TIM1 Update Interrupt and TIM10 global interrupt */ + TIM1_TRG_COM_TIM11_IRQn = 26, /*!< TIM1 Trigger and Commutation Interrupt and TIM11 global interrupt */ + TIM1_CC_IRQn = 27, /*!< TIM1 Capture Compare Interrupt */ + TIM2_IRQn = 28, /*!< TIM2 global Interrupt */ + TIM3_IRQn = 29, /*!< TIM3 global Interrupt */ + TIM4_IRQn = 30, /*!< TIM4 global Interrupt */ + I2C1_EV_IRQn = 31, /*!< I2C1 Event Interrupt */ + I2C1_ER_IRQn = 32, /*!< I2C1 Error Interrupt */ + I2C2_EV_IRQn = 33, /*!< I2C2 Event Interrupt */ + I2C2_ER_IRQn = 34, /*!< I2C2 Error Interrupt */ + SPI1_IRQn = 35, /*!< SPI1 global Interrupt */ + SPI2_IRQn = 36, /*!< SPI2 global Interrupt */ + USART1_IRQn = 37, /*!< USART1 global Interrupt */ + USART2_IRQn = 38, /*!< USART2 global Interrupt */ + USART3_IRQn = 39, /*!< USART3 global Interrupt */ + EXTI15_10_IRQn = 40, /*!< External Line[15:10] Interrupts */ + RTC_Alarm_IRQn = 41, /*!< RTC Alarm (A and B) through EXTI Line Interrupt */ + OTG_FS_WKUP_IRQn = 42, /*!< USB OTG FS Wakeup through EXTI line interrupt */ + TIM8_BRK_TIM12_IRQn = 43, /*!< TIM8 Break Interrupt and TIM12 global interrupt */ + TIM8_UP_TIM13_IRQn = 44, /*!< TIM8 Update Interrupt and TIM13 global interrupt */ + TIM8_TRG_COM_TIM14_IRQn = 45, /*!< TIM8 Trigger and Commutation Interrupt and TIM14 global interrupt */ + TIM8_CC_IRQn = 46, /*!< TIM8 Capture Compare Interrupt */ + DMA1_Stream7_IRQn = 47, /*!< DMA1 Stream7 Interrupt */ + FSMC_IRQn = 48, /*!< FSMC global Interrupt */ + SDIO_IRQn = 49, /*!< SDIO global Interrupt */ + TIM5_IRQn = 50, /*!< TIM5 global Interrupt */ + SPI3_IRQn = 51, /*!< SPI3 global Interrupt */ + UART4_IRQn = 52, /*!< UART4 global Interrupt */ + UART5_IRQn = 53, /*!< UART5 global Interrupt */ + TIM6_DAC_IRQn = 54, /*!< TIM6 global and DAC1&2 underrun error interrupts */ + TIM7_IRQn = 55, /*!< TIM7 global interrupt */ + DMA2_Stream0_IRQn = 56, /*!< DMA2 Stream 0 global Interrupt */ + DMA2_Stream1_IRQn = 57, /*!< DMA2 Stream 1 global Interrupt */ + DMA2_Stream2_IRQn = 58, /*!< DMA2 Stream 2 global Interrupt */ + DMA2_Stream3_IRQn = 59, /*!< DMA2 Stream 3 global Interrupt */ + DMA2_Stream4_IRQn = 60, /*!< DMA2 Stream 4 global Interrupt */ + CAN2_TX_IRQn = 63, /*!< CAN2 TX Interrupt */ + CAN2_RX0_IRQn = 64, /*!< CAN2 RX0 Interrupt */ + CAN2_RX1_IRQn = 65, /*!< CAN2 RX1 Interrupt */ + CAN2_SCE_IRQn = 66, /*!< CAN2 SCE Interrupt */ + OTG_FS_IRQn = 67, /*!< USB OTG FS global Interrupt */ + DMA2_Stream5_IRQn = 68, /*!< DMA2 Stream 5 global interrupt */ + DMA2_Stream6_IRQn = 69, /*!< DMA2 Stream 6 global interrupt */ + DMA2_Stream7_IRQn = 70, /*!< DMA2 Stream 7 global interrupt */ + USART6_IRQn = 71, /*!< USART6 global interrupt */ + I2C3_EV_IRQn = 72, /*!< I2C3 event interrupt */ + I2C3_ER_IRQn = 73, /*!< I2C3 error interrupt */ + OTG_HS_EP1_OUT_IRQn = 74, /*!< USB OTG HS End Point 1 Out global interrupt */ + OTG_HS_EP1_IN_IRQn = 75, /*!< USB OTG HS End Point 1 In global interrupt */ + OTG_HS_WKUP_IRQn = 76, /*!< USB OTG HS Wakeup through EXTI interrupt */ + OTG_HS_IRQn = 77, /*!< USB OTG HS global interrupt */ + HASH_RNG_IRQn = 80 /*!< Hash and RNG global interrupt */ +} IRQn_Type; + +/** + * @} + */ + +#include "core_cm3.h" +#include "system_stm32f2xx.h" +#include + +/** @addtogroup Peripheral_registers_structures + * @{ + */ + +/** + * @brief Analog to Digital Converter + */ + +typedef struct +{ + __IO uint32_t SR; /*!< ADC status register, Address offset: 0x00 */ + __IO uint32_t CR1; /*!< ADC control register 1, Address offset: 0x04 */ + __IO uint32_t CR2; /*!< ADC control register 2, Address offset: 0x08 */ + __IO uint32_t SMPR1; /*!< ADC sample time register 1, Address offset: 0x0C */ + __IO uint32_t SMPR2; /*!< ADC sample time register 2, Address offset: 0x10 */ + __IO uint32_t JOFR1; /*!< ADC injected channel data offset register 1, Address offset: 0x14 */ + __IO uint32_t JOFR2; /*!< ADC injected channel data offset register 2, Address offset: 0x18 */ + __IO uint32_t JOFR3; /*!< ADC injected channel data offset register 3, Address offset: 0x1C */ + __IO uint32_t JOFR4; /*!< ADC injected channel data offset register 4, Address offset: 0x20 */ + __IO uint32_t HTR; /*!< ADC watchdog higher threshold register, Address offset: 0x24 */ + __IO uint32_t LTR; /*!< ADC watchdog lower threshold register, Address offset: 0x28 */ + __IO uint32_t SQR1; /*!< ADC regular sequence register 1, Address offset: 0x2C */ + __IO uint32_t SQR2; /*!< ADC regular sequence register 2, Address offset: 0x30 */ + __IO uint32_t SQR3; /*!< ADC regular sequence register 3, Address offset: 0x34 */ + __IO uint32_t JSQR; /*!< ADC injected sequence register, Address offset: 0x38*/ + __IO uint32_t JDR1; /*!< ADC injected data register 1, Address offset: 0x3C */ + __IO uint32_t JDR2; /*!< ADC injected data register 2, Address offset: 0x40 */ + __IO uint32_t JDR3; /*!< ADC injected data register 3, Address offset: 0x44 */ + __IO uint32_t JDR4; /*!< ADC injected data register 4, Address offset: 0x48 */ + __IO uint32_t DR; /*!< ADC regular data register, Address offset: 0x4C */ +} ADC_TypeDef; + +typedef struct +{ + __IO uint32_t CSR; /*!< ADC Common status register, Address offset: ADC1 base address + 0x300 */ + __IO uint32_t CCR; /*!< ADC common control register, Address offset: ADC1 base address + 0x304 */ + __IO uint32_t CDR; /*!< ADC common regular data register for dual + AND triple modes, Address offset: ADC1 base address + 0x308 */ +} ADC_Common_TypeDef; + + +/** + * @brief Controller Area Network TxMailBox + */ + +typedef struct +{ + __IO uint32_t TIR; /*!< CAN TX mailbox identifier register */ + __IO uint32_t TDTR; /*!< CAN mailbox data length control and time stamp register */ + __IO uint32_t TDLR; /*!< CAN mailbox data low register */ + __IO uint32_t TDHR; /*!< CAN mailbox data high register */ +} CAN_TxMailBox_TypeDef; + +/** + * @brief Controller Area Network FIFOMailBox + */ + +typedef struct +{ + __IO uint32_t RIR; /*!< CAN receive FIFO mailbox identifier register */ + __IO uint32_t RDTR; /*!< CAN receive FIFO mailbox data length control and time stamp register */ + __IO uint32_t RDLR; /*!< CAN receive FIFO mailbox data low register */ + __IO uint32_t RDHR; /*!< CAN receive FIFO mailbox data high register */ +} CAN_FIFOMailBox_TypeDef; + +/** + * @brief Controller Area Network FilterRegister + */ + +typedef struct +{ + __IO uint32_t FR1; /*!< CAN Filter bank register 1 */ + __IO uint32_t FR2; /*!< CAN Filter bank register 1 */ +} CAN_FilterRegister_TypeDef; + +/** + * @brief Controller Area Network + */ + +typedef struct +{ + __IO uint32_t MCR; /*!< CAN master control register, Address offset: 0x00 */ + __IO uint32_t MSR; /*!< CAN master status register, Address offset: 0x04 */ + __IO uint32_t TSR; /*!< CAN transmit status register, Address offset: 0x08 */ + __IO uint32_t RF0R; /*!< CAN receive FIFO 0 register, Address offset: 0x0C */ + __IO uint32_t RF1R; /*!< CAN receive FIFO 1 register, Address offset: 0x10 */ + __IO uint32_t IER; /*!< CAN interrupt enable register, Address offset: 0x14 */ + __IO uint32_t ESR; /*!< CAN error status register, Address offset: 0x18 */ + __IO uint32_t BTR; /*!< CAN bit timing register, Address offset: 0x1C */ + uint32_t RESERVED0[88]; /*!< Reserved, 0x020 - 0x17F */ + CAN_TxMailBox_TypeDef sTxMailBox[3]; /*!< CAN Tx MailBox, Address offset: 0x180 - 0x1AC */ + CAN_FIFOMailBox_TypeDef sFIFOMailBox[2]; /*!< CAN FIFO MailBox, Address offset: 0x1B0 - 0x1CC */ + uint32_t RESERVED1[12]; /*!< Reserved, 0x1D0 - 0x1FF */ + __IO uint32_t FMR; /*!< CAN filter master register, Address offset: 0x200 */ + __IO uint32_t FM1R; /*!< CAN filter mode register, Address offset: 0x204 */ + uint32_t RESERVED2; /*!< Reserved, 0x208 */ + __IO uint32_t FS1R; /*!< CAN filter scale register, Address offset: 0x20C */ + uint32_t RESERVED3; /*!< Reserved, 0x210 */ + __IO uint32_t FFA1R; /*!< CAN filter FIFO assignment register, Address offset: 0x214 */ + uint32_t RESERVED4; /*!< Reserved, 0x218 */ + __IO uint32_t FA1R; /*!< CAN filter activation register, Address offset: 0x21C */ + uint32_t RESERVED5[8]; /*!< Reserved, 0x220-0x23F */ + CAN_FilterRegister_TypeDef sFilterRegister[28]; /*!< CAN Filter Register, Address offset: 0x240-0x31C */ +} CAN_TypeDef; + +/** + * @brief CRC calculation unit + */ + +typedef struct +{ + __IO uint32_t DR; /*!< CRC Data register, Address offset: 0x00 */ + __IO uint8_t IDR; /*!< CRC Independent data register, Address offset: 0x04 */ + uint8_t RESERVED0; /*!< Reserved, 0x05 */ + uint16_t RESERVED1; /*!< Reserved, 0x06 */ + __IO uint32_t CR; /*!< CRC Control register, Address offset: 0x08 */ +} CRC_TypeDef; + +/** + * @brief Digital to Analog Converter + */ + +typedef struct +{ + __IO uint32_t CR; /*!< DAC control register, Address offset: 0x00 */ + __IO uint32_t SWTRIGR; /*!< DAC software trigger register, Address offset: 0x04 */ + __IO uint32_t DHR12R1; /*!< DAC channel1 12-bit right-aligned data holding register, Address offset: 0x08 */ + __IO uint32_t DHR12L1; /*!< DAC channel1 12-bit left aligned data holding register, Address offset: 0x0C */ + __IO uint32_t DHR8R1; /*!< DAC channel1 8-bit right aligned data holding register, Address offset: 0x10 */ + __IO uint32_t DHR12R2; /*!< DAC channel2 12-bit right aligned data holding register, Address offset: 0x14 */ + __IO uint32_t DHR12L2; /*!< DAC channel2 12-bit left aligned data holding register, Address offset: 0x18 */ + __IO uint32_t DHR8R2; /*!< DAC channel2 8-bit right-aligned data holding register, Address offset: 0x1C */ + __IO uint32_t DHR12RD; /*!< Dual DAC 12-bit right-aligned data holding register, Address offset: 0x20 */ + __IO uint32_t DHR12LD; /*!< DUAL DAC 12-bit left aligned data holding register, Address offset: 0x24 */ + __IO uint32_t DHR8RD; /*!< DUAL DAC 8-bit right aligned data holding register, Address offset: 0x28 */ + __IO uint32_t DOR1; /*!< DAC channel1 data output register, Address offset: 0x2C */ + __IO uint32_t DOR2; /*!< DAC channel2 data output register, Address offset: 0x30 */ + __IO uint32_t SR; /*!< DAC status register, Address offset: 0x34 */ +} DAC_TypeDef; + +/** + * @brief Debug MCU + */ + +typedef struct +{ + __IO uint32_t IDCODE; /*!< MCU device ID code, Address offset: 0x00 */ + __IO uint32_t CR; /*!< Debug MCU configuration register, Address offset: 0x04 */ + __IO uint32_t APB1FZ; /*!< Debug MCU APB1 freeze register, Address offset: 0x08 */ + __IO uint32_t APB2FZ; /*!< Debug MCU APB2 freeze register, Address offset: 0x0C */ +}DBGMCU_TypeDef; + + +/** + * @brief DMA Controller + */ + +typedef struct +{ + __IO uint32_t CR; /*!< DMA stream x configuration register */ + __IO uint32_t NDTR; /*!< DMA stream x number of data register */ + __IO uint32_t PAR; /*!< DMA stream x peripheral address register */ + __IO uint32_t M0AR; /*!< DMA stream x memory 0 address register */ + __IO uint32_t M1AR; /*!< DMA stream x memory 1 address register */ + __IO uint32_t FCR; /*!< DMA stream x FIFO control register */ +} DMA_Stream_TypeDef; + +typedef struct +{ + __IO uint32_t LISR; /*!< DMA low interrupt status register, Address offset: 0x00 */ + __IO uint32_t HISR; /*!< DMA high interrupt status register, Address offset: 0x04 */ + __IO uint32_t LIFCR; /*!< DMA low interrupt flag clear register, Address offset: 0x08 */ + __IO uint32_t HIFCR; /*!< DMA high interrupt flag clear register, Address offset: 0x0C */ +} DMA_TypeDef; + + +/** + * @brief External Interrupt/Event Controller + */ + +typedef struct +{ + __IO uint32_t IMR; /*!< EXTI Interrupt mask register, Address offset: 0x00 */ + __IO uint32_t EMR; /*!< EXTI Event mask register, Address offset: 0x04 */ + __IO uint32_t RTSR; /*!< EXTI Rising trigger selection register, Address offset: 0x08 */ + __IO uint32_t FTSR; /*!< EXTI Falling trigger selection register, Address offset: 0x0C */ + __IO uint32_t SWIER; /*!< EXTI Software interrupt event register, Address offset: 0x10 */ + __IO uint32_t PR; /*!< EXTI Pending register, Address offset: 0x14 */ +} EXTI_TypeDef; + +/** + * @brief FLASH Registers + */ + +typedef struct +{ + __IO uint32_t ACR; /*!< FLASH access control register, Address offset: 0x00 */ + __IO uint32_t KEYR; /*!< FLASH key register, Address offset: 0x04 */ + __IO uint32_t OPTKEYR; /*!< FLASH option key register, Address offset: 0x08 */ + __IO uint32_t SR; /*!< FLASH status register, Address offset: 0x0C */ + __IO uint32_t CR; /*!< FLASH control register, Address offset: 0x10 */ + __IO uint32_t OPTCR; /*!< FLASH option control register, Address offset: 0x14 */ +} FLASH_TypeDef; + + +/** + * @brief Flexible Static Memory Controller + */ + +typedef struct +{ + __IO uint32_t BTCR[8]; /*!< NOR/PSRAM chip-select control register(BCR) and chip-select timing register(BTR), Address offset: 0x00-1C */ +} FSMC_Bank1_TypeDef; + +/** + * @brief Flexible Static Memory Controller Bank1E + */ + +typedef struct +{ + __IO uint32_t BWTR[7]; /*!< NOR/PSRAM write timing registers, Address offset: 0x104-0x11C */ +} FSMC_Bank1E_TypeDef; + +/** + * @brief Flexible Static Memory Controller Bank2 + */ + +typedef struct +{ + __IO uint32_t PCR2; /*!< NAND Flash control register 2, Address offset: 0x60 */ + __IO uint32_t SR2; /*!< NAND Flash FIFO status and interrupt register 2, Address offset: 0x64 */ + __IO uint32_t PMEM2; /*!< NAND Flash Common memory space timing register 2, Address offset: 0x68 */ + __IO uint32_t PATT2; /*!< NAND Flash Attribute memory space timing register 2, Address offset: 0x6C */ + uint32_t RESERVED0; /*!< Reserved, 0x70 */ + __IO uint32_t ECCR2; /*!< NAND Flash ECC result registers 2, Address offset: 0x74 */ + uint32_t RESERVED1; /*!< Reserved, 0x78 */ + uint32_t RESERVED2; /*!< Reserved, 0x7C */ + __IO uint32_t PCR3; /*!< NAND Flash control register 3, Address offset: 0x80 */ + __IO uint32_t SR3; /*!< NAND Flash FIFO status and interrupt register 3, Address offset: 0x84 */ + __IO uint32_t PMEM3; /*!< NAND Flash Common memory space timing register 3, Address offset: 0x88 */ + __IO uint32_t PATT3; /*!< NAND Flash Attribute memory space timing register 3, Address offset: 0x8C */ + uint32_t RESERVED3; /*!< Reserved, 0x90 */ + __IO uint32_t ECCR3; /*!< NAND Flash ECC result registers 3, Address offset: 0x94 */ +} FSMC_Bank2_3_TypeDef; + +/** + * @brief Flexible Static Memory Controller Bank4 + */ + +typedef struct +{ + __IO uint32_t PCR4; /*!< PC Card control register 4, Address offset: 0xA0 */ + __IO uint32_t SR4; /*!< PC Card FIFO status and interrupt register 4, Address offset: 0xA4 */ + __IO uint32_t PMEM4; /*!< PC Card Common memory space timing register 4, Address offset: 0xA8 */ + __IO uint32_t PATT4; /*!< PC Card Attribute memory space timing register 4, Address offset: 0xAC */ + __IO uint32_t PIO4; /*!< PC Card I/O space timing register 4, Address offset: 0xB0 */ +} FSMC_Bank4_TypeDef; + + +/** + * @brief General Purpose I/O + */ + +typedef struct +{ + __IO uint32_t MODER; /*!< GPIO port mode register, Address offset: 0x00 */ + __IO uint32_t OTYPER; /*!< GPIO port output type register, Address offset: 0x04 */ + __IO uint32_t OSPEEDR; /*!< GPIO port output speed register, Address offset: 0x08 */ + __IO uint32_t PUPDR; /*!< GPIO port pull-up/pull-down register, Address offset: 0x0C */ + __IO uint32_t IDR; /*!< GPIO port input data register, Address offset: 0x10 */ + __IO uint32_t ODR; /*!< GPIO port output data register, Address offset: 0x14 */ + __IO uint32_t BSRR; /*!< GPIO port bit set/reset register, Address offset: 0x18 */ + __IO uint32_t LCKR; /*!< GPIO port configuration lock register, Address offset: 0x1C */ + __IO uint32_t AFR[2]; /*!< GPIO alternate function registers, Address offset: 0x20-0x24 */ +} GPIO_TypeDef; + +/** + * @brief System configuration controller + */ + +typedef struct +{ + __IO uint32_t MEMRMP; /*!< SYSCFG memory remap register, Address offset: 0x00 */ + __IO uint32_t PMC; /*!< SYSCFG peripheral mode configuration register, Address offset: 0x04 */ + __IO uint32_t EXTICR[4]; /*!< SYSCFG external interrupt configuration registers, Address offset: 0x08-0x14 */ + uint32_t RESERVED[2]; /*!< Reserved, 0x18-0x1C */ + __IO uint32_t CMPCR; /*!< SYSCFG Compensation cell control register, Address offset: 0x20 */ +} SYSCFG_TypeDef; + +/** + * @brief Inter-integrated Circuit Interface + */ + +typedef struct +{ + __IO uint32_t CR1; /*!< I2C Control register 1, Address offset: 0x00 */ + __IO uint32_t CR2; /*!< I2C Control register 2, Address offset: 0x04 */ + __IO uint32_t OAR1; /*!< I2C Own address register 1, Address offset: 0x08 */ + __IO uint32_t OAR2; /*!< I2C Own address register 2, Address offset: 0x0C */ + __IO uint32_t DR; /*!< I2C Data register, Address offset: 0x10 */ + __IO uint32_t SR1; /*!< I2C Status register 1, Address offset: 0x14 */ + __IO uint32_t SR2; /*!< I2C Status register 2, Address offset: 0x18 */ + __IO uint32_t CCR; /*!< I2C Clock control register, Address offset: 0x1C */ + __IO uint32_t TRISE; /*!< I2C TRISE register, Address offset: 0x20 */ +} I2C_TypeDef; + +/** + * @brief Independent WATCHDOG + */ + +typedef struct +{ + __IO uint32_t KR; /*!< IWDG Key register, Address offset: 0x00 */ + __IO uint32_t PR; /*!< IWDG Prescaler register, Address offset: 0x04 */ + __IO uint32_t RLR; /*!< IWDG Reload register, Address offset: 0x08 */ + __IO uint32_t SR; /*!< IWDG Status register, Address offset: 0x0C */ +} IWDG_TypeDef; + +/** + * @brief Power Control + */ + +typedef struct +{ + __IO uint32_t CR; /*!< PWR power control register, Address offset: 0x00 */ + __IO uint32_t CSR; /*!< PWR power control/status register, Address offset: 0x04 */ +} PWR_TypeDef; + +/** + * @brief Reset and Clock Control + */ + +typedef struct +{ + __IO uint32_t CR; /*!< RCC clock control register, Address offset: 0x00 */ + __IO uint32_t PLLCFGR; /*!< RCC PLL configuration register, Address offset: 0x04 */ + __IO uint32_t CFGR; /*!< RCC clock configuration register, Address offset: 0x08 */ + __IO uint32_t CIR; /*!< RCC clock interrupt register, Address offset: 0x0C */ + __IO uint32_t AHB1RSTR; /*!< RCC AHB1 peripheral reset register, Address offset: 0x10 */ + __IO uint32_t AHB2RSTR; /*!< RCC AHB2 peripheral reset register, Address offset: 0x14 */ + __IO uint32_t AHB3RSTR; /*!< RCC AHB3 peripheral reset register, Address offset: 0x18 */ + uint32_t RESERVED0; /*!< Reserved, 0x1C */ + __IO uint32_t APB1RSTR; /*!< RCC APB1 peripheral reset register, Address offset: 0x20 */ + __IO uint32_t APB2RSTR; /*!< RCC APB2 peripheral reset register, Address offset: 0x24 */ + uint32_t RESERVED1[2]; /*!< Reserved, 0x28-0x2C */ + __IO uint32_t AHB1ENR; /*!< RCC AHB1 peripheral clock register, Address offset: 0x30 */ + __IO uint32_t AHB2ENR; /*!< RCC AHB2 peripheral clock register, Address offset: 0x34 */ + __IO uint32_t AHB3ENR; /*!< RCC AHB3 peripheral clock register, Address offset: 0x38 */ + uint32_t RESERVED2; /*!< Reserved, 0x3C */ + __IO uint32_t APB1ENR; /*!< RCC APB1 peripheral clock enable register, Address offset: 0x40 */ + __IO uint32_t APB2ENR; /*!< RCC APB2 peripheral clock enable register, Address offset: 0x44 */ + uint32_t RESERVED3[2]; /*!< Reserved, 0x48-0x4C */ + __IO uint32_t AHB1LPENR; /*!< RCC AHB1 peripheral clock enable in low power mode register, Address offset: 0x50 */ + __IO uint32_t AHB2LPENR; /*!< RCC AHB2 peripheral clock enable in low power mode register, Address offset: 0x54 */ + __IO uint32_t AHB3LPENR; /*!< RCC AHB3 peripheral clock enable in low power mode register, Address offset: 0x58 */ + uint32_t RESERVED4; /*!< Reserved, 0x5C */ + __IO uint32_t APB1LPENR; /*!< RCC APB1 peripheral clock enable in low power mode register, Address offset: 0x60 */ + __IO uint32_t APB2LPENR; /*!< RCC APB2 peripheral clock enable in low power mode register, Address offset: 0x64 */ + uint32_t RESERVED5[2]; /*!< Reserved, 0x68-0x6C */ + __IO uint32_t BDCR; /*!< RCC Backup domain control register, Address offset: 0x70 */ + __IO uint32_t CSR; /*!< RCC clock control & status register, Address offset: 0x74 */ + uint32_t RESERVED6[2]; /*!< Reserved, 0x78-0x7C */ + __IO uint32_t SSCGR; /*!< RCC spread spectrum clock generation register, Address offset: 0x80 */ + __IO uint32_t PLLI2SCFGR; /*!< RCC PLLI2S configuration register, Address offset: 0x84 */ + +} RCC_TypeDef; + +/** + * @brief Real-Time Clock + */ + +typedef struct +{ + __IO uint32_t TR; /*!< RTC time register, Address offset: 0x00 */ + __IO uint32_t DR; /*!< RTC date register, Address offset: 0x04 */ + __IO uint32_t CR; /*!< RTC control register, Address offset: 0x08 */ + __IO uint32_t ISR; /*!< RTC initialization and status register, Address offset: 0x0C */ + __IO uint32_t PRER; /*!< RTC prescaler register, Address offset: 0x10 */ + __IO uint32_t WUTR; /*!< RTC wakeup timer register, Address offset: 0x14 */ + __IO uint32_t CALIBR; /*!< RTC calibration register, Address offset: 0x18 */ + __IO uint32_t ALRMAR; /*!< RTC alarm A register, Address offset: 0x1C */ + __IO uint32_t ALRMBR; /*!< RTC alarm B register, Address offset: 0x20 */ + __IO uint32_t WPR; /*!< RTC write protection register, Address offset: 0x24 */ + uint32_t RESERVED1; /*!< Reserved, 0x28 */ + uint32_t RESERVED2; /*!< Reserved, 0x2C */ + __IO uint32_t TSTR; /*!< RTC time stamp time register, Address offset: 0x30 */ + __IO uint32_t TSDR; /*!< RTC time stamp date register, Address offset: 0x34 */ + uint32_t RESERVED3; /*!< Reserved, 0x38 */ + uint32_t RESERVED4; /*!< Reserved, 0x3C */ + __IO uint32_t TAFCR; /*!< RTC tamper and alternate function configuration register, Address offset: 0x40 */ + uint32_t RESERVED5; /*!< Reserved, 0x44 */ + uint32_t RESERVED6; /*!< Reserved, 0x48 */ + uint32_t RESERVED7; /*!< Reserved, 0x4C */ + __IO uint32_t BKP0R; /*!< RTC backup register 1, Address offset: 0x50 */ + __IO uint32_t BKP1R; /*!< RTC backup register 1, Address offset: 0x54 */ + __IO uint32_t BKP2R; /*!< RTC backup register 2, Address offset: 0x58 */ + __IO uint32_t BKP3R; /*!< RTC backup register 3, Address offset: 0x5C */ + __IO uint32_t BKP4R; /*!< RTC backup register 4, Address offset: 0x60 */ + __IO uint32_t BKP5R; /*!< RTC backup register 5, Address offset: 0x64 */ + __IO uint32_t BKP6R; /*!< RTC backup register 6, Address offset: 0x68 */ + __IO uint32_t BKP7R; /*!< RTC backup register 7, Address offset: 0x6C */ + __IO uint32_t BKP8R; /*!< RTC backup register 8, Address offset: 0x70 */ + __IO uint32_t BKP9R; /*!< RTC backup register 9, Address offset: 0x74 */ + __IO uint32_t BKP10R; /*!< RTC backup register 10, Address offset: 0x78 */ + __IO uint32_t BKP11R; /*!< RTC backup register 11, Address offset: 0x7C */ + __IO uint32_t BKP12R; /*!< RTC backup register 12, Address offset: 0x80 */ + __IO uint32_t BKP13R; /*!< RTC backup register 13, Address offset: 0x84 */ + __IO uint32_t BKP14R; /*!< RTC backup register 14, Address offset: 0x88 */ + __IO uint32_t BKP15R; /*!< RTC backup register 15, Address offset: 0x8C */ + __IO uint32_t BKP16R; /*!< RTC backup register 16, Address offset: 0x90 */ + __IO uint32_t BKP17R; /*!< RTC backup register 17, Address offset: 0x94 */ + __IO uint32_t BKP18R; /*!< RTC backup register 18, Address offset: 0x98 */ + __IO uint32_t BKP19R; /*!< RTC backup register 19, Address offset: 0x9C */ +} RTC_TypeDef; + + +/** + * @brief SD host Interface + */ + +typedef struct +{ + __IO uint32_t POWER; /*!< SDIO power control register, Address offset: 0x00 */ + __IO uint32_t CLKCR; /*!< SDI clock control register, Address offset: 0x04 */ + __IO uint32_t ARG; /*!< SDIO argument register, Address offset: 0x08 */ + __IO uint32_t CMD; /*!< SDIO command register, Address offset: 0x0C */ + __IO const uint32_t RESPCMD; /*!< SDIO command response register, Address offset: 0x10 */ + __IO const uint32_t RESP1; /*!< SDIO response 1 register, Address offset: 0x14 */ + __IO const uint32_t RESP2; /*!< SDIO response 2 register, Address offset: 0x18 */ + __IO const uint32_t RESP3; /*!< SDIO response 3 register, Address offset: 0x1C */ + __IO const uint32_t RESP4; /*!< SDIO response 4 register, Address offset: 0x20 */ + __IO uint32_t DTIMER; /*!< SDIO data timer register, Address offset: 0x24 */ + __IO uint32_t DLEN; /*!< SDIO data length register, Address offset: 0x28 */ + __IO uint32_t DCTRL; /*!< SDIO data control register, Address offset: 0x2C */ + __IO const uint32_t DCOUNT; /*!< SDIO data counter register, Address offset: 0x30 */ + __IO const uint32_t STA; /*!< SDIO status register, Address offset: 0x34 */ + __IO uint32_t ICR; /*!< SDIO interrupt clear register, Address offset: 0x38 */ + __IO uint32_t MASK; /*!< SDIO mask register, Address offset: 0x3C */ + uint32_t RESERVED0[2]; /*!< Reserved, 0x40-0x44 */ + __IO const uint32_t FIFOCNT; /*!< SDIO FIFO counter register, Address offset: 0x48 */ + uint32_t RESERVED1[13]; /*!< Reserved, 0x4C-0x7C */ + __IO uint32_t FIFO; /*!< SDIO data FIFO register, Address offset: 0x80 */ +} SDIO_TypeDef; + +/** + * @brief Serial Peripheral Interface + */ + +typedef struct +{ + __IO uint32_t CR1; /*!< SPI control register 1 (not used in I2S mode), Address offset: 0x00 */ + __IO uint32_t CR2; /*!< SPI control register 2, Address offset: 0x04 */ + __IO uint32_t SR; /*!< SPI status register, Address offset: 0x08 */ + __IO uint32_t DR; /*!< SPI data register, Address offset: 0x0C */ + __IO uint32_t CRCPR; /*!< SPI CRC polynomial register (not used in I2S mode), Address offset: 0x10 */ + __IO uint32_t RXCRCR; /*!< SPI RX CRC register (not used in I2S mode), Address offset: 0x14 */ + __IO uint32_t TXCRCR; /*!< SPI TX CRC register (not used in I2S mode), Address offset: 0x18 */ + __IO uint32_t I2SCFGR; /*!< SPI_I2S configuration register, Address offset: 0x1C */ + __IO uint32_t I2SPR; /*!< SPI_I2S prescaler register, Address offset: 0x20 */ +} SPI_TypeDef; + +/** + * @brief TIM + */ + +typedef struct +{ + __IO uint32_t CR1; /*!< TIM control register 1, Address offset: 0x00 */ + __IO uint32_t CR2; /*!< TIM control register 2, Address offset: 0x04 */ + __IO uint32_t SMCR; /*!< TIM slave mode control register, Address offset: 0x08 */ + __IO uint32_t DIER; /*!< TIM DMA/interrupt enable register, Address offset: 0x0C */ + __IO uint32_t SR; /*!< TIM status register, Address offset: 0x10 */ + __IO uint32_t EGR; /*!< TIM event generation register, Address offset: 0x14 */ + __IO uint32_t CCMR1; /*!< TIM capture/compare mode register 1, Address offset: 0x18 */ + __IO uint32_t CCMR2; /*!< TIM capture/compare mode register 2, Address offset: 0x1C */ + __IO uint32_t CCER; /*!< TIM capture/compare enable register, Address offset: 0x20 */ + __IO uint32_t CNT; /*!< TIM counter register, Address offset: 0x24 */ + __IO uint32_t PSC; /*!< TIM prescaler, Address offset: 0x28 */ + __IO uint32_t ARR; /*!< TIM auto-reload register, Address offset: 0x2C */ + __IO uint32_t RCR; /*!< TIM repetition counter register, Address offset: 0x30 */ + __IO uint32_t CCR1; /*!< TIM capture/compare register 1, Address offset: 0x34 */ + __IO uint32_t CCR2; /*!< TIM capture/compare register 2, Address offset: 0x38 */ + __IO uint32_t CCR3; /*!< TIM capture/compare register 3, Address offset: 0x3C */ + __IO uint32_t CCR4; /*!< TIM capture/compare register 4, Address offset: 0x40 */ + __IO uint32_t BDTR; /*!< TIM break and dead-time register, Address offset: 0x44 */ + __IO uint32_t DCR; /*!< TIM DMA control register, Address offset: 0x48 */ + __IO uint32_t DMAR; /*!< TIM DMA address for full transfer, Address offset: 0x4C */ + __IO uint32_t OR; /*!< TIM option register, Address offset: 0x50 */ +} TIM_TypeDef; + +/** + * @brief Universal Synchronous Asynchronous Receiver Transmitter + */ + +typedef struct +{ + __IO uint32_t SR; /*!< USART Status register, Address offset: 0x00 */ + __IO uint32_t DR; /*!< USART Data register, Address offset: 0x04 */ + __IO uint32_t BRR; /*!< USART Baud rate register, Address offset: 0x08 */ + __IO uint32_t CR1; /*!< USART Control register 1, Address offset: 0x0C */ + __IO uint32_t CR2; /*!< USART Control register 2, Address offset: 0x10 */ + __IO uint32_t CR3; /*!< USART Control register 3, Address offset: 0x14 */ + __IO uint32_t GTPR; /*!< USART Guard time and prescaler register, Address offset: 0x18 */ +} USART_TypeDef; + +/** + * @brief Window WATCHDOG + */ + +typedef struct +{ + __IO uint32_t CR; /*!< WWDG Control register, Address offset: 0x00 */ + __IO uint32_t CFR; /*!< WWDG Configuration register, Address offset: 0x04 */ + __IO uint32_t SR; /*!< WWDG Status register, Address offset: 0x08 */ +} WWDG_TypeDef; + + +/** + * @brief RNG + */ + +typedef struct +{ + __IO uint32_t CR; /*!< RNG control register, Address offset: 0x00 */ + __IO uint32_t SR; /*!< RNG status register, Address offset: 0x04 */ + __IO uint32_t DR; /*!< RNG data register, Address offset: 0x08 */ +} RNG_TypeDef; + + + +/** + * @brief __USB_OTG_Core_register + */ +typedef struct +{ + __IO uint32_t GOTGCTL; /*!< USB_OTG Control and Status Register Address offset : 0x00 */ + __IO uint32_t GOTGINT; /*!< USB_OTG Interrupt Register Address offset : 0x04 */ + __IO uint32_t GAHBCFG; /*!< Core AHB Configuration Register Address offset : 0x08 */ + __IO uint32_t GUSBCFG; /*!< Core USB Configuration Register Address offset : 0x0C */ + __IO uint32_t GRSTCTL; /*!< Core Reset Register Address offset : 0x10 */ + __IO uint32_t GINTSTS; /*!< Core Interrupt Register Address offset : 0x14 */ + __IO uint32_t GINTMSK; /*!< Core Interrupt Mask Register Address offset : 0x18 */ + __IO uint32_t GRXSTSR; /*!< Receive Sts Q Read Register Address offset : 0x1C */ + __IO uint32_t GRXSTSP; /*!< Receive Sts Q Read & POP Register Address offset : 0x20 */ + __IO uint32_t GRXFSIZ; /* Receive FIFO Size Register Address offset : 0x24 */ + __IO uint32_t DIEPTXF0_HNPTXFSIZ; /*!< EP0 / Non Periodic Tx FIFO Size Register Address offset : 0x28 */ + __IO uint32_t HNPTXSTS; /*!< Non Periodic Tx FIFO/Queue Sts reg Address offset : 0x2C */ + uint32_t Reserved30[2]; /* Reserved Address offset : 0x30 */ + __IO uint32_t GCCFG; /*!< General Purpose IO Register Address offset : 0x38 */ + __IO uint32_t CID; /*!< User ID Register Address offset : 0x3C */ + uint32_t Reserved40[48]; /*!< Reserved Address offset : 0x40-0xFF */ + __IO uint32_t HPTXFSIZ; /*!< Host Periodic Tx FIFO Size Reg Address offset : 0x100 */ + __IO uint32_t DIEPTXF[0x0F]; /*!< dev Periodic Transmit FIFO */ +} +USB_OTG_GlobalTypeDef; + + + +/** + * @brief __device_Registers + */ +typedef struct +{ + __IO uint32_t DCFG; /*!< dev Configuration Register Address offset : 0x800 */ + __IO uint32_t DCTL; /*!< dev Control Register Address offset : 0x804 */ + __IO uint32_t DSTS; /*!< dev Status Register (RO) Address offset : 0x808 */ + uint32_t Reserved0C; /*!< Reserved Address offset : 0x80C */ + __IO uint32_t DIEPMSK; /* !< dev IN Endpoint Mask Address offset : 0x810 */ + __IO uint32_t DOEPMSK; /*!< dev OUT Endpoint Mask Address offset : 0x814 */ + __IO uint32_t DAINT; /*!< dev All Endpoints Itr Reg Address offset : 0x818 */ + __IO uint32_t DAINTMSK; /*!< dev All Endpoints Itr Mask Address offset : 0x81C */ + uint32_t Reserved20; /*!< Reserved Address offset : 0x820 */ + uint32_t Reserved9; /*!< Reserved Address offset : 0x824 */ + __IO uint32_t DVBUSDIS; /*!< dev VBUS discharge Register Address offset : 0x828 */ + __IO uint32_t DVBUSPULSE; /*!< dev VBUS Pulse Register Address offset : 0x82C */ + __IO uint32_t DTHRCTL; /*!< dev thr Address offset : 0x830 */ + __IO uint32_t DIEPEMPMSK; /*!< dev empty msk Address offset : 0x834 */ + __IO uint32_t DEACHINT; /*!< dedicated EP interrupt Address offset : 0x838 */ + __IO uint32_t DEACHMSK; /*!< dedicated EP msk Address offset : 0x83C */ + uint32_t Reserved40; /*!< dedicated EP mask Address offset : 0x840 */ + __IO uint32_t DINEP1MSK; /*!< dedicated EP mask Address offset : 0x844 */ + uint32_t Reserved44[15]; /*!< Reserved Address offset : 0x844-0x87C */ + __IO uint32_t DOUTEP1MSK; /*!< dedicated EP msk Address offset : 0x884 */ +} +USB_OTG_DeviceTypeDef; + + +/** + * @brief __IN_Endpoint-Specific_Register + */ +typedef struct +{ + __IO uint32_t DIEPCTL; /* dev IN Endpoint Control Reg 900h + (ep_num * 20h) + 00h */ + uint32_t Reserved04; /* Reserved 900h + (ep_num * 20h) + 04h */ + __IO uint32_t DIEPINT; /* dev IN Endpoint Itr Reg 900h + (ep_num * 20h) + 08h */ + uint32_t Reserved0C; /* Reserved 900h + (ep_num * 20h) + 0Ch */ + __IO uint32_t DIEPTSIZ; /* IN Endpoint Txfer Size 900h + (ep_num * 20h) + 10h */ + __IO uint32_t DIEPDMA; /* IN Endpoint DMA Address Reg 900h + (ep_num * 20h) + 14h */ + __IO uint32_t DTXFSTS; /*IN Endpoint Tx FIFO Status Reg 900h + (ep_num * 20h) + 18h */ + uint32_t Reserved18; /* Reserved 900h+(ep_num*20h)+1Ch-900h+ (ep_num * 20h) + 1Ch */ +} +USB_OTG_INEndpointTypeDef; + + +/** + * @brief __OUT_Endpoint-Specific_Registers + */ +typedef struct +{ + __IO uint32_t DOEPCTL; /* dev OUT Endpoint Control Reg B00h + (ep_num * 20h) + 00h*/ + uint32_t Reserved04; /* Reserved B00h + (ep_num * 20h) + 04h*/ + __IO uint32_t DOEPINT; /* dev OUT Endpoint Itr Reg B00h + (ep_num * 20h) + 08h*/ + uint32_t Reserved0C; /* Reserved B00h + (ep_num * 20h) + 0Ch*/ + __IO uint32_t DOEPTSIZ; /* dev OUT Endpoint Txfer Size B00h + (ep_num * 20h) + 10h*/ + __IO uint32_t DOEPDMA; /* dev OUT Endpoint DMA Address B00h + (ep_num * 20h) + 14h*/ + uint32_t Reserved18[2]; /* Reserved B00h + (ep_num * 20h) + 18h - B00h + (ep_num * 20h) + 1Ch*/ +} +USB_OTG_OUTEndpointTypeDef; + + +/** + * @brief __Host_Mode_Register_Structures + */ +typedef struct +{ + __IO uint32_t HCFG; /* Host Configuration Register 400h*/ + __IO uint32_t HFIR; /* Host Frame Interval Register 404h*/ + __IO uint32_t HFNUM; /* Host Frame Nbr/Frame Remaining 408h*/ + uint32_t Reserved40C; /* Reserved 40Ch*/ + __IO uint32_t HPTXSTS; /* Host Periodic Tx FIFO/ Queue Status 410h*/ + __IO uint32_t HAINT; /* Host All Channels Interrupt Register 414h*/ + __IO uint32_t HAINTMSK; /* Host All Channels Interrupt Mask 418h*/ +} +USB_OTG_HostTypeDef; + + +/** + * @brief __Host_Channel_Specific_Registers + */ +typedef struct +{ + __IO uint32_t HCCHAR; + __IO uint32_t HCSPLT; + __IO uint32_t HCINT; + __IO uint32_t HCINTMSK; + __IO uint32_t HCTSIZ; + __IO uint32_t HCDMA; + uint32_t Reserved[2]; +} +USB_OTG_HostChannelTypeDef; + + +/** + * @brief Peripheral_memory_map + */ +#define FLASH_BASE 0x08000000U /*!< FLASH(up to 1 MB) base address in the alias region */ +#define SRAM1_BASE 0x20000000U /*!< SRAM1(112 KB) base address in the alias region */ +#define SRAM2_BASE 0x2001C000U /*!< SRAM2(16 KB) base address in the alias region */ +#define PERIPH_BASE 0x40000000U /*!< Peripheral base address in the alias region */ +#define BKPSRAM_BASE 0x40024000U /*!< Backup SRAM(4 KB) base address in the alias region */ +#define FSMC_R_BASE 0xA0000000U /*!< FSMC registers base address */ +#define SRAM1_BB_BASE 0x22000000U /*!< SRAM1(112 KB) base address in the bit-band region */ +#define SRAM2_BB_BASE 0x22380000U /*!< SRAM2(16 KB) base address in the bit-band region */ +#define PERIPH_BB_BASE 0x42000000U /*!< Peripheral base address in the bit-band region */ +#define BKPSRAM_BB_BASE 0x42480000U /*!< Backup SRAM(4 KB) base address in the bit-band region */ +#define FLASH_END 0x080FFFFFU /*!< FLASH end address */ + +/* Legacy defines */ +#define SRAM_BASE SRAM1_BASE +#define SRAM_BB_BASE SRAM1_BB_BASE + + +/*!< Peripheral memory map */ +#define APB1PERIPH_BASE PERIPH_BASE +#define APB2PERIPH_BASE (PERIPH_BASE + 0x00010000U) +#define AHB1PERIPH_BASE (PERIPH_BASE + 0x00020000U) +#define AHB2PERIPH_BASE (PERIPH_BASE + 0x10000000U) + +/*!< APB1 peripherals */ +#define TIM2_BASE (APB1PERIPH_BASE + 0x0000U) +#define TIM3_BASE (APB1PERIPH_BASE + 0x0400U) +#define TIM4_BASE (APB1PERIPH_BASE + 0x0800U) +#define TIM5_BASE (APB1PERIPH_BASE + 0x0C00U) +#define TIM6_BASE (APB1PERIPH_BASE + 0x1000U) +#define TIM7_BASE (APB1PERIPH_BASE + 0x1400U) +#define TIM12_BASE (APB1PERIPH_BASE + 0x1800U) +#define TIM13_BASE (APB1PERIPH_BASE + 0x1C00U) +#define TIM14_BASE (APB1PERIPH_BASE + 0x2000U) +#define RTC_BASE (APB1PERIPH_BASE + 0x2800U) +#define WWDG_BASE (APB1PERIPH_BASE + 0x2C00U) +#define IWDG_BASE (APB1PERIPH_BASE + 0x3000U) +#define SPI2_BASE (APB1PERIPH_BASE + 0x3800U) +#define SPI3_BASE (APB1PERIPH_BASE + 0x3C00U) +#define USART2_BASE (APB1PERIPH_BASE + 0x4400U) +#define USART3_BASE (APB1PERIPH_BASE + 0x4800U) +#define UART4_BASE (APB1PERIPH_BASE + 0x4C00U) +#define UART5_BASE (APB1PERIPH_BASE + 0x5000U) +#define I2C1_BASE (APB1PERIPH_BASE + 0x5400U) +#define I2C2_BASE (APB1PERIPH_BASE + 0x5800U) +#define I2C3_BASE (APB1PERIPH_BASE + 0x5C00U) +#define CAN1_BASE (APB1PERIPH_BASE + 0x6400U) +#define CAN2_BASE (APB1PERIPH_BASE + 0x6800U) +#define PWR_BASE (APB1PERIPH_BASE + 0x7000U) +#define DAC_BASE (APB1PERIPH_BASE + 0x7400U) + +/*!< APB2 peripherals */ +#define TIM1_BASE (APB2PERIPH_BASE + 0x0000U) +#define TIM8_BASE (APB2PERIPH_BASE + 0x0400U) +#define USART1_BASE (APB2PERIPH_BASE + 0x1000U) +#define USART6_BASE (APB2PERIPH_BASE + 0x1400U) +#define ADC1_BASE (APB2PERIPH_BASE + 0x2000U) +#define ADC2_BASE (APB2PERIPH_BASE + 0x2100U) +#define ADC3_BASE (APB2PERIPH_BASE + 0x2200U) +#define ADC_BASE (APB2PERIPH_BASE + 0x2300U) +#define SDIO_BASE (APB2PERIPH_BASE + 0x2C00U) +#define SPI1_BASE (APB2PERIPH_BASE + 0x3000U) +#define SYSCFG_BASE (APB2PERIPH_BASE + 0x3800U) +#define EXTI_BASE (APB2PERIPH_BASE + 0x3C00U) +#define TIM9_BASE (APB2PERIPH_BASE + 0x4000U) +#define TIM10_BASE (APB2PERIPH_BASE + 0x4400U) +#define TIM11_BASE (APB2PERIPH_BASE + 0x4800U) + +/*!< AHB1 peripherals */ +#define GPIOA_BASE (AHB1PERIPH_BASE + 0x0000U) +#define GPIOB_BASE (AHB1PERIPH_BASE + 0x0400U) +#define GPIOC_BASE (AHB1PERIPH_BASE + 0x0800U) +#define GPIOD_BASE (AHB1PERIPH_BASE + 0x0C00U) +#define GPIOE_BASE (AHB1PERIPH_BASE + 0x1000U) +#define GPIOF_BASE (AHB1PERIPH_BASE + 0x1400U) +#define GPIOG_BASE (AHB1PERIPH_BASE + 0x1800U) +#define GPIOH_BASE (AHB1PERIPH_BASE + 0x1C00U) +#define GPIOI_BASE (AHB1PERIPH_BASE + 0x2000U) +#define CRC_BASE (AHB1PERIPH_BASE + 0x3000U) +#define RCC_BASE (AHB1PERIPH_BASE + 0x3800U) +#define FLASH_R_BASE (AHB1PERIPH_BASE + 0x3C00U) +#define DMA1_BASE (AHB1PERIPH_BASE + 0x6000U) +#define DMA1_Stream0_BASE (DMA1_BASE + 0x010U) +#define DMA1_Stream1_BASE (DMA1_BASE + 0x028U) +#define DMA1_Stream2_BASE (DMA1_BASE + 0x040U) +#define DMA1_Stream3_BASE (DMA1_BASE + 0x058U) +#define DMA1_Stream4_BASE (DMA1_BASE + 0x070U) +#define DMA1_Stream5_BASE (DMA1_BASE + 0x088U) +#define DMA1_Stream6_BASE (DMA1_BASE + 0x0A0U) +#define DMA1_Stream7_BASE (DMA1_BASE + 0x0B8U) +#define DMA2_BASE (AHB1PERIPH_BASE + 0x6400U) +#define DMA2_Stream0_BASE (DMA2_BASE + 0x010U) +#define DMA2_Stream1_BASE (DMA2_BASE + 0x028U) +#define DMA2_Stream2_BASE (DMA2_BASE + 0x040U) +#define DMA2_Stream3_BASE (DMA2_BASE + 0x058U) +#define DMA2_Stream4_BASE (DMA2_BASE + 0x070U) +#define DMA2_Stream5_BASE (DMA2_BASE + 0x088U) +#define DMA2_Stream6_BASE (DMA2_BASE + 0x0A0U) +#define DMA2_Stream7_BASE (DMA2_BASE + 0x0B8U) + +/*!< AHB2 peripherals */ +#define RNG_BASE (AHB2PERIPH_BASE + 0x60800U) + +/*!< FSMC Bankx registers base address */ +#define FSMC_Bank1_R_BASE (FSMC_R_BASE + 0x0000U) +#define FSMC_Bank1E_R_BASE (FSMC_R_BASE + 0x0104U) +#define FSMC_Bank2_3_R_BASE (FSMC_R_BASE + 0x0060U) +#define FSMC_Bank4_R_BASE (FSMC_R_BASE + 0x00A0U) + +/* Debug MCU registers base address */ +#define DBGMCU_BASE 0xE0042000U + +/*!< USB registers base address */ +#define USB_OTG_HS_PERIPH_BASE 0x40040000U +#define USB_OTG_FS_PERIPH_BASE 0x50000000U + +#define USB_OTG_GLOBAL_BASE 0x000U +#define USB_OTG_DEVICE_BASE 0x800U +#define USB_OTG_IN_ENDPOINT_BASE 0x900U +#define USB_OTG_OUT_ENDPOINT_BASE 0xB00U +#define USB_OTG_EP_REG_SIZE 0x20U +#define USB_OTG_HOST_BASE 0x400U +#define USB_OTG_HOST_PORT_BASE 0x440U +#define USB_OTG_HOST_CHANNEL_BASE 0x500U +#define USB_OTG_HOST_CHANNEL_SIZE 0x20U +#define USB_OTG_PCGCCTL_BASE 0xE00U +#define USB_OTG_FIFO_BASE 0x1000U +#define USB_OTG_FIFO_SIZE 0x1000U + +/** + * @} + */ + +/** @addtogroup Peripheral_declaration + * @{ + */ +#define TIM2 ((TIM_TypeDef *) TIM2_BASE) +#define TIM3 ((TIM_TypeDef *) TIM3_BASE) +#define TIM4 ((TIM_TypeDef *) TIM4_BASE) +#define TIM5 ((TIM_TypeDef *) TIM5_BASE) +#define TIM6 ((TIM_TypeDef *) TIM6_BASE) +#define TIM7 ((TIM_TypeDef *) TIM7_BASE) +#define TIM12 ((TIM_TypeDef *) TIM12_BASE) +#define TIM13 ((TIM_TypeDef *) TIM13_BASE) +#define TIM14 ((TIM_TypeDef *) TIM14_BASE) +#define RTC ((RTC_TypeDef *) RTC_BASE) +#define WWDG ((WWDG_TypeDef *) WWDG_BASE) +#define IWDG ((IWDG_TypeDef *) IWDG_BASE) +#define SPI2 ((SPI_TypeDef *) SPI2_BASE) +#define SPI3 ((SPI_TypeDef *) SPI3_BASE) +#define USART2 ((USART_TypeDef *) USART2_BASE) +#define USART3 ((USART_TypeDef *) USART3_BASE) +#define UART4 ((USART_TypeDef *) UART4_BASE) +#define UART5 ((USART_TypeDef *) UART5_BASE) +#define I2C1 ((I2C_TypeDef *) I2C1_BASE) +#define I2C2 ((I2C_TypeDef *) I2C2_BASE) +#define I2C3 ((I2C_TypeDef *) I2C3_BASE) +#define CAN1 ((CAN_TypeDef *) CAN1_BASE) +#define CAN2 ((CAN_TypeDef *) CAN2_BASE) +#define PWR ((PWR_TypeDef *) PWR_BASE) +#define DAC ((DAC_TypeDef *) DAC_BASE) +#define TIM1 ((TIM_TypeDef *) TIM1_BASE) +#define TIM8 ((TIM_TypeDef *) TIM8_BASE) +#define USART1 ((USART_TypeDef *) USART1_BASE) +#define USART6 ((USART_TypeDef *) USART6_BASE) +#define ADC ((ADC_Common_TypeDef *) ADC_BASE) +#define ADC1 ((ADC_TypeDef *) ADC1_BASE) +#define ADC2 ((ADC_TypeDef *) ADC2_BASE) +#define ADC3 ((ADC_TypeDef *) ADC3_BASE) +#define SDIO ((SDIO_TypeDef *) SDIO_BASE) +#define SPI1 ((SPI_TypeDef *) SPI1_BASE) +#define SYSCFG ((SYSCFG_TypeDef *) SYSCFG_BASE) +#define EXTI ((EXTI_TypeDef *) EXTI_BASE) +#define TIM9 ((TIM_TypeDef *) TIM9_BASE) +#define TIM10 ((TIM_TypeDef *) TIM10_BASE) +#define TIM11 ((TIM_TypeDef *) TIM11_BASE) +#define GPIOA ((GPIO_TypeDef *) GPIOA_BASE) +#define GPIOB ((GPIO_TypeDef *) GPIOB_BASE) +#define GPIOC ((GPIO_TypeDef *) GPIOC_BASE) +#define GPIOD ((GPIO_TypeDef *) GPIOD_BASE) +#define GPIOE ((GPIO_TypeDef *) GPIOE_BASE) +#define GPIOF ((GPIO_TypeDef *) GPIOF_BASE) +#define GPIOG ((GPIO_TypeDef *) GPIOG_BASE) +#define GPIOH ((GPIO_TypeDef *) GPIOH_BASE) +#define GPIOI ((GPIO_TypeDef *) GPIOI_BASE) +#define CRC ((CRC_TypeDef *) CRC_BASE) +#define RCC ((RCC_TypeDef *) RCC_BASE) +#define FLASH ((FLASH_TypeDef *) FLASH_R_BASE) +#define DMA1 ((DMA_TypeDef *) DMA1_BASE) +#define DMA1_Stream0 ((DMA_Stream_TypeDef *) DMA1_Stream0_BASE) +#define DMA1_Stream1 ((DMA_Stream_TypeDef *) DMA1_Stream1_BASE) +#define DMA1_Stream2 ((DMA_Stream_TypeDef *) DMA1_Stream2_BASE) +#define DMA1_Stream3 ((DMA_Stream_TypeDef *) DMA1_Stream3_BASE) +#define DMA1_Stream4 ((DMA_Stream_TypeDef *) DMA1_Stream4_BASE) +#define DMA1_Stream5 ((DMA_Stream_TypeDef *) DMA1_Stream5_BASE) +#define DMA1_Stream6 ((DMA_Stream_TypeDef *) DMA1_Stream6_BASE) +#define DMA1_Stream7 ((DMA_Stream_TypeDef *) DMA1_Stream7_BASE) +#define DMA2 ((DMA_TypeDef *) DMA2_BASE) +#define DMA2_Stream0 ((DMA_Stream_TypeDef *) DMA2_Stream0_BASE) +#define DMA2_Stream1 ((DMA_Stream_TypeDef *) DMA2_Stream1_BASE) +#define DMA2_Stream2 ((DMA_Stream_TypeDef *) DMA2_Stream2_BASE) +#define DMA2_Stream3 ((DMA_Stream_TypeDef *) DMA2_Stream3_BASE) +#define DMA2_Stream4 ((DMA_Stream_TypeDef *) DMA2_Stream4_BASE) +#define DMA2_Stream5 ((DMA_Stream_TypeDef *) DMA2_Stream5_BASE) +#define DMA2_Stream6 ((DMA_Stream_TypeDef *) DMA2_Stream6_BASE) +#define DMA2_Stream7 ((DMA_Stream_TypeDef *) DMA2_Stream7_BASE) +#define RNG ((RNG_TypeDef *) RNG_BASE) +#define FSMC_Bank1 ((FSMC_Bank1_TypeDef *) FSMC_Bank1_R_BASE) +#define FSMC_Bank1E ((FSMC_Bank1E_TypeDef *) FSMC_Bank1E_R_BASE) +#define FSMC_Bank2_3 ((FSMC_Bank2_3_TypeDef *) FSMC_Bank2_3_R_BASE) +#define FSMC_Bank4 ((FSMC_Bank4_TypeDef *) FSMC_Bank4_R_BASE) + +#define DBGMCU ((DBGMCU_TypeDef *) DBGMCU_BASE) + +#define USB_OTG_FS ((USB_OTG_GlobalTypeDef *) USB_OTG_FS_PERIPH_BASE) +#define USB_OTG_HS ((USB_OTG_GlobalTypeDef *) USB_OTG_HS_PERIPH_BASE) + +/** + * @} + */ + +/** @addtogroup Exported_constants + * @{ + */ + + /** @addtogroup Peripheral_Registers_Bits_Definition + * @{ + */ + +/******************************************************************************/ +/* Peripheral Registers_Bits_Definition */ +/******************************************************************************/ + +/******************************************************************************/ +/* */ +/* Analog to Digital Converter */ +/* */ +/******************************************************************************/ +/******************** Bit definition for ADC_SR register ********************/ +#define ADC_SR_AWD 0x00000001U /*!
© COPYRIGHT(c) 2016 STMicroelectronics
+ * + * Redistribution and use in source and binary forms, with or without modification, + * are permitted provided that the following conditions are met: + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * 3. Neither the name of STMicroelectronics nor the names of its contributors + * may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************** + */ + +/** @addtogroup CMSIS + * @{ + */ + +/** @addtogroup stm32f2xx + * @{ + */ + +#ifndef __STM32F2xx_H +#define __STM32F2xx_H + +#ifdef __cplusplus + extern "C" { +#endif /* __cplusplus */ + +/** @addtogroup Library_configuration_section + * @{ + */ + +/** + * @brief STM32 Family + */ +#if !defined (STM32F2) +#define STM32F2 +#endif /* STM32F2 */ + +/* Uncomment the line below according to the target STM32 device used in your + application + */ +#if !defined (STM32F205xx) && !defined (STM32F215xx) && !defined (STM32F207xx) && !defined (STM32F217xx) + + /* #define STM32F205xx */ /*!< STM32F205RG, STM32F205VG, STM32F205ZG, STM32F205RF, STM32F205VF, STM32F205ZF, + STM32F205RE, STM32F205VE, STM32F205ZE, STM32F205RC, STM32F205VC, STM32F205ZC, + STM32F205RB and STM32F205VB Devices */ + /* #define STM32F215xx */ /*!< STM32F215RG, STM32F215VG, STM32F215ZG, STM32F215RE, STM32F215VE and STM32F215ZE Devices */ + /* #define STM32F207xx */ /*!< STM32F207VG, STM32F207ZG, STM32F207IG, STM32F207VF, STM32F207ZF, STM32F207IF, + STM32F207VE, STM32F207ZE, STM32F207IE, STM32F207VC, STM32F207ZC and STM32F207IC Devices */ + /* #define STM32F217xx */ /*!< STM32F217VG, STM32F217ZG, STM32F217IG, STM32F217VE, STM32F217ZE and STM32F217IE Devices */ + +#endif + +/* Tip: To avoid modifying this file each time you need to switch between these + devices, you can define the device in your toolchain compiler preprocessor. + */ +#if !defined (USE_HAL_DRIVER) +/** + * @brief Comment the line below if you will not use the peripherals drivers. + In this case, these drivers will not be included and the application code will + be based on direct access to peripherals registers + */ + /*#define USE_HAL_DRIVER */ +#endif /* USE_HAL_DRIVER */ + +/** + * @brief CMSIS Device version number V2.1.2 + */ +#define __STM32F2xx_CMSIS_VERSION_MAIN (0x02U) /*!< [31:24] main version */ +#define __STM32F2xx_CMSIS_VERSION_SUB1 (0x01U) /*!< [23:16] sub1 version */ +#define __STM32F2xx_CMSIS_VERSION_SUB2 (0x02U) /*!< [15:8] sub2 version */ +#define __STM32F2xx_CMSIS_VERSION_RC (0x00U) /*!< [7:0] release candidate */ +#define __STM32F2xx_CMSIS_VERSION ((__STM32F2xx_CMSIS_VERSION_MAIN << 24)\ + |(__STM32F2xx_CMSIS_VERSION_SUB1 << 16)\ + |(__STM32F2xx_CMSIS_VERSION_SUB2 << 8 )\ + |(__STM32F2xx_CMSIS_VERSION)) + +/** + * @} + */ + +/** @addtogroup Device_Included + * @{ + */ + +#if defined(STM32F205xx) + #include "stm32f205xx.h" +#elif defined(STM32F215xx) + #include "stm32f215xx.h" +#elif defined(STM32F207xx) + #include "stm32f207xx.h" +#elif defined(STM32F217xx) + #include "stm32f217xx.h" +#else + #error "Please select first the target STM32F2xx device used in your application (in stm32f2xx.h file)" +#endif + +/** + * @} + */ + +/** @addtogroup Exported_types + * @{ + */ +typedef enum +{ + RESET = 0, + SET = !RESET +} FlagStatus, ITStatus; + +typedef enum +{ + DISABLE = 0, + ENABLE = !DISABLE +} FunctionalState; +#define IS_FUNCTIONAL_STATE(STATE) (((STATE) == DISABLE) || ((STATE) == ENABLE)) + +typedef enum +{ + ERROR = 0, + SUCCESS = !ERROR +} ErrorStatus; + +/** + * @} + */ + + +/** @addtogroup Exported_macro + * @{ + */ +#define SET_BIT(REG, BIT) ((REG) |= (BIT)) + +#define CLEAR_BIT(REG, BIT) ((REG) &= ~(BIT)) + +#define READ_BIT(REG, BIT) ((REG) & (BIT)) + +#define CLEAR_REG(REG) ((REG) = (0x0)) + +#define WRITE_REG(REG, VAL) ((REG) = (VAL)) + +#define READ_REG(REG) ((REG)) + +#define MODIFY_REG(REG, CLEARMASK, SETMASK) WRITE_REG((REG), (((READ_REG(REG)) & (~(CLEARMASK))) | (SETMASK))) + +#define POSITION_VAL(VAL) (__CLZ(__RBIT(VAL))) + + +/** + * @} + */ + +#if defined (USE_HAL_DRIVER) + #include "stm32f2xx_hal.h" +#endif /* USE_HAL_DRIVER */ + +#ifdef __cplusplus +} +#endif /* __cplusplus */ + +#endif /* __STM32F2xx_H */ + +/** + * @} + */ + +/** + * @} + */ + + + + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/panda/board/inc/stm32f2xx_hal_def.h b/panda/board/inc/stm32f2xx_hal_def.h new file mode 100644 index 00000000000000..231aa74ae293a1 --- /dev/null +++ b/panda/board/inc/stm32f2xx_hal_def.h @@ -0,0 +1,181 @@ +/** + ****************************************************************************** + * @file stm32f2xx_hal_def.h + * @author MCD Application Team + * @version V1.1.3 + * @date 29-June-2016 + * @brief This file contains HAL common defines, enumeration, macros and + * structures definitions. + ****************************************************************************** + * @attention + * + *

© COPYRIGHT(c) 2016 STMicroelectronics

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

© COPYRIGHT(c) 2016 STMicroelectronics

+ * + * Redistribution and use in source and binary forms, with or without modification, + * are permitted provided that the following conditions are met: + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * 3. Neither the name of STMicroelectronics nor the names of its contributors + * may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F2xx_HAL_GPIO_EX_H +#define __STM32F2xx_HAL_GPIO_EX_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f2xx_hal_def.h" + +/** @addtogroup STM32F2xx_HAL_Driver + * @{ + */ + +/** @defgroup GPIOEx GPIOEx + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ +/* Exported constants --------------------------------------------------------*/ +/* Exported constants --------------------------------------------------------*/ + +/** @defgroup GPIOEx_Exported_Constants GPIO Exported Constants + * @{ + */ + +/** @defgroup GPIO_Alternate_function_selection GPIO Alternate function selection + * @{ + */ + +/** + * @brief AF 0 selection + */ +#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00U) /* RTC_50Hz Alternate Function mapping */ +#define GPIO_AF0_MCO ((uint8_t)0x00U) /* MCO (MCO1 and MCO2) Alternate Function mapping */ +#define GPIO_AF0_TAMPER ((uint8_t)0x00U) /* TAMPER (TAMPER_1 and TAMPER_2) Alternate Function mapping */ +#define GPIO_AF0_SWJ ((uint8_t)0x00U) /* SWJ (SWD and JTAG) Alternate Function mapping */ +#define GPIO_AF0_TRACE ((uint8_t)0x00U) /* TRACE Alternate Function mapping */ + +/** + * @brief AF 1 selection + */ +#define GPIO_AF1_TIM1 ((uint8_t)0x01U) /* TIM1 Alternate Function mapping */ +#define GPIO_AF1_TIM2 ((uint8_t)0x01U) /* TIM2 Alternate Function mapping */ + +/** + * @brief AF 2 selection + */ +#define GPIO_AF2_TIM3 ((uint8_t)0x02U) /* TIM3 Alternate Function mapping */ +#define GPIO_AF2_TIM4 ((uint8_t)0x02U) /* TIM4 Alternate Function mapping */ +#define GPIO_AF2_TIM5 ((uint8_t)0x02U) /* TIM5 Alternate Function mapping */ + +/** + * @brief AF 3 selection + */ +#define GPIO_AF3_TIM8 ((uint8_t)0x03U) /* TIM8 Alternate Function mapping */ +#define GPIO_AF3_TIM9 ((uint8_t)0x03U) /* TIM9 Alternate Function mapping */ +#define GPIO_AF3_TIM10 ((uint8_t)0x03U) /* TIM10 Alternate Function mapping */ +#define GPIO_AF3_TIM11 ((uint8_t)0x03U) /* TIM11 Alternate Function mapping */ + +/** + * @brief AF 4 selection + */ +#define GPIO_AF4_I2C1 ((uint8_t)0x04U) /* I2C1 Alternate Function mapping */ +#define GPIO_AF4_I2C2 ((uint8_t)0x04U) /* I2C2 Alternate Function mapping */ +#define GPIO_AF4_I2C3 ((uint8_t)0x04U) /* I2C3 Alternate Function mapping */ + +/** + * @brief AF 5 selection + */ +#define GPIO_AF5_SPI1 ((uint8_t)0x05U) /* SPI1 Alternate Function mapping */ +#define GPIO_AF5_SPI2 ((uint8_t)0x05U) /* SPI2/I2S2 Alternate Function mapping */ +/** + * @brief AF 6 selection + */ +#define GPIO_AF6_SPI3 ((uint8_t)0x06U) /* SPI3/I2S3 Alternate Function mapping */ + +/** + * @brief AF 7 selection + */ +#define GPIO_AF7_USART1 ((uint8_t)0x07U) /* USART1 Alternate Function mapping */ +#define GPIO_AF7_USART2 ((uint8_t)0x07U) /* USART2 Alternate Function mapping */ +#define GPIO_AF7_USART3 ((uint8_t)0x07U) /* USART3 Alternate Function mapping */ + +/** + * @brief AF 8 selection + */ +#define GPIO_AF8_UART4 ((uint8_t)0x08U) /* UART4 Alternate Function mapping */ +#define GPIO_AF8_UART5 ((uint8_t)0x08U) /* UART5 Alternate Function mapping */ +#define GPIO_AF8_USART6 ((uint8_t)0x08U) /* USART6 Alternate Function mapping */ + +/** + * @brief AF 9 selection + */ +#define GPIO_AF9_CAN1 ((uint8_t)0x09U) /* CAN1 Alternate Function mapping */ +#define GPIO_AF9_CAN2 ((uint8_t)0x09U) /* CAN2 Alternate Function mapping */ +#define GPIO_AF9_TIM12 ((uint8_t)0x09U) /* TIM12 Alternate Function mapping */ +#define GPIO_AF9_TIM13 ((uint8_t)0x09U) /* TIM13 Alternate Function mapping */ +#define GPIO_AF9_TIM14 ((uint8_t)0x09U) /* TIM14 Alternate Function mapping */ + +/** + * @brief AF 10 selection + */ +#define GPIO_AF10_OTG_FS ((uint8_t)0xAU) /* OTG_FS Alternate Function mapping */ +#define GPIO_AF10_OTG_HS ((uint8_t)0xAU) /* OTG_HS Alternate Function mapping */ + +/** + * @brief AF 11 selection + */ +#if defined(STM32F207xx) || defined(STM32F217xx) +#define GPIO_AF11_ETH ((uint8_t)0x0BU) /* ETHERNET Alternate Function mapping */ +#endif /* STM32F207xx || STM32F217xx */ + +/** + * @brief AF 12 selection + */ +#define GPIO_AF12_FSMC ((uint8_t)0xCU) /* FSMC Alternate Function mapping */ +#define GPIO_AF12_OTG_HS_FS ((uint8_t)0xCU) /* OTG HS configured in FS, Alternate Function mapping */ +#define GPIO_AF12_SDIO ((uint8_t)0xCU) /* SDIO Alternate Function mapping */ + +/** + * @brief AF 13 selection + */ +#if defined(STM32F207xx) || defined(STM32F217xx) +#define GPIO_AF13_DCMI ((uint8_t)0x0DU) /* DCMI Alternate Function mapping */ +#endif /* STM32F207xx || STM32F217xx */ + +/** + * @brief AF 15 selection + */ +#define GPIO_AF15_EVENTOUT ((uint8_t)0x0FU) /* EVENTOUT Alternate Function mapping */ + +/** + * @} + */ + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/** @defgroup GPIOEx_Exported_Macros GPIO Exported Macros + * @{ + */ +/** + * @} + */ + +/* Exported functions --------------------------------------------------------*/ +/** @defgroup GPIOEx_Exported_Functions GPIO Exported Functions + * @{ + */ +/** + * @} + */ + +/* Private types -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private constants ---------------------------------------------------------*/ +/** @defgroup GPIOEx_Private_Constants GPIO Private Constants + * @{ + */ +/** + * @} + */ + +/* Private macros ------------------------------------------------------------*/ +/** @defgroup GPIOEx_Private_Macros GPIO Private Macros + * @{ + */ +/** @defgroup GPIOEx_Get_Port_Index GPIO Get Port Index + * @{ + */ +#define GPIO_GET_INDEX(__GPIOx__) (uint8_t)(((__GPIOx__) == (GPIOA))? 0U :\ + ((__GPIOx__) == (GPIOB))? 1U :\ + ((__GPIOx__) == (GPIOC))? 2U :\ + ((__GPIOx__) == (GPIOD))? 3U :\ + ((__GPIOx__) == (GPIOE))? 4U :\ + ((__GPIOx__) == (GPIOF))? 5U :\ + ((__GPIOx__) == (GPIOG))? 6U :\ + ((__GPIOx__) == (GPIOH))? 7U :\ + ((__GPIOx__) == (GPIOI))? 8U : 9U) +/** + * @} + */ + +/** @defgroup GPIOEx_IS_Alternat_function_selection GPIO Check Alternate Function + * @{ + */ +#if defined(STM32F207xx) || defined(STM32F217xx) + +#define IS_GPIO_AF(AF) (((AF) == GPIO_AF0_RTC_50Hz) || ((AF) == GPIO_AF9_TIM14) || \ + ((AF) == GPIO_AF0_MCO) || ((AF) == GPIO_AF0_TAMPER) || \ + ((AF) == GPIO_AF0_SWJ) || ((AF) == GPIO_AF0_TRACE) || \ + ((AF) == GPIO_AF1_TIM1) || ((AF) == GPIO_AF1_TIM2) || \ + ((AF) == GPIO_AF2_TIM3) || ((AF) == GPIO_AF2_TIM4) || \ + ((AF) == GPIO_AF2_TIM5) || ((AF) == GPIO_AF3_TIM8) || \ + ((AF) == GPIO_AF4_I2C1) || ((AF) == GPIO_AF4_I2C2) || \ + ((AF) == GPIO_AF4_I2C3) || ((AF) == GPIO_AF5_SPI1) || \ + ((AF) == GPIO_AF5_SPI2) || ((AF) == GPIO_AF9_TIM13) || \ + ((AF) == GPIO_AF6_SPI3) || ((AF) == GPIO_AF9_TIM12) || \ + ((AF) == GPIO_AF7_USART1) || ((AF) == GPIO_AF7_USART2) || \ + ((AF) == GPIO_AF7_USART3) || ((AF) == GPIO_AF8_UART4) || \ + ((AF) == GPIO_AF8_UART5) || ((AF) == GPIO_AF8_USART6) || \ + ((AF) == GPIO_AF9_CAN1) || ((AF) == GPIO_AF9_CAN2) || \ + ((AF) == GPIO_AF10_OTG_FS) || ((AF) == GPIO_AF10_OTG_HS) || \ + ((AF) == GPIO_AF11_ETH) || ((AF) == GPIO_AF12_OTG_HS_FS) || \ + ((AF) == GPIO_AF12_SDIO) || ((AF) == GPIO_AF13_DCMI) || \ + ((AF) == GPIO_AF12_FSMC) || ((AF) == GPIO_AF15_EVENTOUT)) +#else /* STM32F207xx || STM32F217xx */ +#define IS_GPIO_AF(AF) (((AF) == GPIO_AF0_RTC_50Hz) || ((AF) == GPIO_AF9_TIM14) || \ + ((AF) == GPIO_AF0_MCO) || ((AF) == GPIO_AF0_TAMPER) || \ + ((AF) == GPIO_AF0_SWJ) || ((AF) == GPIO_AF0_TRACE) || \ + ((AF) == GPIO_AF1_TIM1) || ((AF) == GPIO_AF1_TIM2) || \ + ((AF) == GPIO_AF2_TIM3) || ((AF) == GPIO_AF2_TIM4) || \ + ((AF) == GPIO_AF2_TIM5) || ((AF) == GPIO_AF3_TIM8) || \ + ((AF) == GPIO_AF4_I2C1) || ((AF) == GPIO_AF4_I2C2) || \ + ((AF) == GPIO_AF4_I2C3) || ((AF) == GPIO_AF5_SPI1) || \ + ((AF) == GPIO_AF5_SPI2) || ((AF) == GPIO_AF9_TIM13) || \ + ((AF) == GPIO_AF6_SPI3) || ((AF) == GPIO_AF9_TIM12) || \ + ((AF) == GPIO_AF7_USART1) || ((AF) == GPIO_AF7_USART2) || \ + ((AF) == GPIO_AF7_USART3) || ((AF) == GPIO_AF8_UART4) || \ + ((AF) == GPIO_AF8_UART5) || ((AF) == GPIO_AF8_USART6) || \ + ((AF) == GPIO_AF9_CAN1) || ((AF) == GPIO_AF9_CAN2) || \ + ((AF) == GPIO_AF10_OTG_FS) || ((AF) == GPIO_AF10_OTG_HS) || \ + ((AF) == GPIO_AF12_OTG_HS_FS) || ((AF) == GPIO_AF12_SDIO) || \ + ((AF) == GPIO_AF12_FSMC) || ((AF) == GPIO_AF15_EVENTOUT)) +#endif /* STM32F207xx || STM32F217xx */ + +/** + * @} + */ + +/** + * @} + */ + +/* Private functions ---------------------------------------------------------*/ +/** @defgroup GPIOEx_Private_Functions GPIO Private Functions + * @{ + */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F2xx_HAL_GPIO_EX_H */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/panda/board/inc/stm32f413xx.h b/panda/board/inc/stm32f413xx.h new file mode 100644 index 00000000000000..f520dbf920b0cf --- /dev/null +++ b/panda/board/inc/stm32f413xx.h @@ -0,0 +1,14994 @@ +/** + ****************************************************************************** + * @file stm32f413xx.h + * @author MCD Application Team + * @version V2.6.0 + * @date 04-November-2016 + * @brief CMSIS STM32F413xx Device Peripheral Access Layer Header File. + * + * This file contains: + * - Data structures and the address mapping for all peripherals + * - peripherals registers declarations and bits definition + * - Macros to access peripheral’s registers hardware + * + ****************************************************************************** + * @attention + * + *

© COPYRIGHT(c) 2016 STMicroelectronics

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

© COPYRIGHT(c) 2016 STMicroelectronics

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

© COPYRIGHT(c) 2016 STMicroelectronics

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

© COPYRIGHT(c) 2016 STMicroelectronics

+ * + * Redistribution and use in source and binary forms, with or without modification, + * are permitted provided that the following conditions are met: + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * 3. Neither the name of STMicroelectronics nor the names of its contributors + * may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************** + */ + +/** @addtogroup CMSIS + * @{ + */ + +/** @addtogroup stm32f2xx_system + * @{ + */ + +/** + * @brief Define to prevent recursive inclusion + */ +#ifndef __SYSTEM_STM32F2XX_H +#define __SYSTEM_STM32F2XX_H + +#ifdef __cplusplus + extern "C" { +#endif + +/** @addtogroup STM32F2xx_System_Includes + * @{ + */ + +/** + * @} + */ + + +/** @addtogroup STM32F2xx_System_Exported_types + * @{ + */ + /* This variable is updated in three ways: + 1) by calling CMSIS function SystemCoreClockUpdate() + 2) by calling HAL API function HAL_RCC_GetSysClockFreq() + 3) each time HAL_RCC_ClockConfig() is called to configure the system clock frequency + Note: If you use this function to configure the system clock; then there + is no need to call the 2 first functions listed above, since SystemCoreClock + variable is updated automatically. + */ +extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */ + + +/** + * @} + */ + +/** @addtogroup STM32F2xx_System_Exported_Constants + * @{ + */ + +/** + * @} + */ + +/** @addtogroup STM32F2xx_System_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @addtogroup STM32F2xx_System_Exported_Functions + * @{ + */ + +extern void SystemInit(void); +extern void SystemCoreClockUpdate(void); +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif /*__SYSTEM_STM32F2XX_H */ + +/** + * @} + */ + +/** + * @} + */ +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/panda/board/inc/system_stm32f4xx.h b/panda/board/inc/system_stm32f4xx.h new file mode 100644 index 00000000000000..369b605dddddeb --- /dev/null +++ b/panda/board/inc/system_stm32f4xx.h @@ -0,0 +1,124 @@ +/** + ****************************************************************************** + * @file system_stm32f4xx.h + * @author MCD Application Team + * @version V2.6.0 + * @date 04-November-2016 + * @brief CMSIS Cortex-M4 Device System Source File for STM32F4xx devices. + ****************************************************************************** + * @attention + * + *

© COPYRIGHT(c) 2016 STMicroelectronics

+ * + * Redistribution and use in source and binary forms, with or without modification, + * are permitted provided that the following conditions are met: + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * 3. Neither the name of STMicroelectronics nor the names of its contributors + * may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************** + */ + +/** @addtogroup CMSIS + * @{ + */ + +/** @addtogroup stm32f4xx_system + * @{ + */ + +/** + * @brief Define to prevent recursive inclusion + */ +#ifndef __SYSTEM_STM32F4XX_H +#define __SYSTEM_STM32F4XX_H + +#ifdef __cplusplus + extern "C" { +#endif + +/** @addtogroup STM32F4xx_System_Includes + * @{ + */ + +/** + * @} + */ + + +/** @addtogroup STM32F4xx_System_Exported_types + * @{ + */ + /* This variable is updated in three ways: + 1) by calling CMSIS function SystemCoreClockUpdate() + 2) by calling HAL API function HAL_RCC_GetSysClockFreq() + 3) each time HAL_RCC_ClockConfig() is called to configure the system clock frequency + Note: If you use this function to configure the system clock; then there + is no need to call the 2 first functions listed above, since SystemCoreClock + variable is updated automatically. + */ +extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */ + +extern const uint8_t AHBPrescTable[16]; /*!< AHB prescalers table values */ +extern const uint8_t APBPrescTable[8]; /*!< APB prescalers table values */ + +/** + * @} + */ + +/** @addtogroup STM32F4xx_System_Exported_Constants + * @{ + */ + +/** + * @} + */ + +/** @addtogroup STM32F4xx_System_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @addtogroup STM32F4xx_System_Exported_Functions + * @{ + */ + +extern void SystemInit(void); +extern void SystemCoreClockUpdate(void); +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif /*__SYSTEM_STM32F4XX_H */ + +/** + * @} + */ + +/** + * @} + */ +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/panda/board/libc.h b/panda/board/libc.h new file mode 100644 index 00000000000000..8d80a3aad855a9 --- /dev/null +++ b/panda/board/libc.h @@ -0,0 +1,51 @@ +// **** shitty libc **** + +void delay(int a) { + volatile int i; + for (i=0;iCCMR2 = TIM_CCMR2_OC3M_2 | TIM_CCMR2_OC3M_1; + TIM3->CCER = TIM_CCER_CC3E; + timer_init(TIM3, 10); +} + +void fan_set_speed(int fan_speed) { + TIM3->CCR3 = fan_speed; +} + +// ********************* serial debugging ********************* + +void debug_ring_callback(uart_ring *ring) { + char rcv; + while (getc(ring, &rcv)) { + putc(ring, rcv); + + // jump to DFU flash + if (rcv == 'z') { + enter_bootloader_mode = ENTER_BOOTLOADER_MAGIC; + NVIC_SystemReset(); + } + + // normal reset + if (rcv == 'x') { + NVIC_SystemReset(); + } + + // enable CDP mode + if (rcv == 'C') { + puts("switching USB to CDP mode\n"); + set_usb_power_mode(USB_POWER_CDP); + } + if (rcv == 'c') { + puts("switching USB to client mode\n"); + set_usb_power_mode(USB_POWER_CLIENT); + } + if (rcv == 'D') { + puts("switching USB to DCP mode\n"); + set_usb_power_mode(USB_POWER_DCP); + } + } +} + +// ***************************** USB port ***************************** + +int get_health_pkt(void *dat) { + struct __attribute__((packed)) { + uint32_t voltage; + uint32_t current; + uint8_t started; + uint8_t controls_allowed; + uint8_t gas_interceptor_detected; + uint8_t started_signal_detected; + uint8_t started_alt; + } *health = dat; + + //Voltage will be measured in mv. 5000 = 5V + uint32_t voltage = adc_get(ADCCHAN_VOLTAGE); + if (revision == PANDA_REV_AB) { + //REVB has a 100, 27 (27/127) voltage divider + //Here is the calculation for the scale + //ADCV = VIN_S * (27/127) * (4095/3.3) + //RETVAL = ADCV * s = VIN_S*1000 + //s = 1000/((4095/3.3)*(27/127)) = 3.79053046 + + //Avoid needing floating point math + health->voltage = (voltage * 3791) / 1000; + } else { + //REVC has a 10, 1 (1/11) voltage divider + //Here is the calculation for the scale (s) + //ADCV = VIN_S * (1/11) * (4095/3.3) + //RETVAL = ADCV * s = VIN_S*1000 + //s = 1000/((4095/3.3)*(1/11)) = 8.8623046875 + + //Avoid needing floating point math + health->voltage = (voltage * 8862) / 1000; + } + +#ifdef PANDA + health->current = adc_get(ADCCHAN_CURRENT); + int safety_ignition = safety_ignition_hook(); + if (safety_ignition < 0) { + //Use the GPIO pin to determine ignition + health->started = (GPIOA->IDR & (1 << 1)) == 0; + } else { + //Current safety hooks want to determine ignition (ex: GM) + health->started = safety_ignition; + } +#else + health->current = 0; + health->started = (GPIOC->IDR & (1 << 13)) != 0; +#endif + + health->controls_allowed = controls_allowed; + health->gas_interceptor_detected = gas_interceptor_detected; + + // DEPRECATED + health->started_alt = 0; + health->started_signal_detected = 0; + + return sizeof(*health); +} + +int usb_cb_ep1_in(uint8_t *usbdata, int len, int hardwired) { + CAN_FIFOMailBox_TypeDef *reply = (CAN_FIFOMailBox_TypeDef *)usbdata; + int ilen = 0; + while (ilen < min(len/0x10, 4) && can_pop(&can_rx_q, &reply[ilen])) ilen++; + return ilen*0x10; +} + +// send on serial, first byte to select the ring +void usb_cb_ep2_out(uint8_t *usbdata, int len, int hardwired) { + if (len == 0) return; + uart_ring *ur = get_ring_by_number(usbdata[0]); + if (!ur) return; + if ((usbdata[0] < 2) || safety_tx_lin_hook(usbdata[0]-2, usbdata+1, len-1)) { + for (int i = 1; i < len; i++) while (!putc(ur, usbdata[i])); + } +} + +// send on CAN +void usb_cb_ep3_out(uint8_t *usbdata, int len, int hardwired) { + int dpkt = 0; + for (dpkt = 0; dpkt < len; dpkt += 0x10) { + uint32_t *tf = (uint32_t*)(&usbdata[dpkt]); + + // make a copy + CAN_FIFOMailBox_TypeDef to_push; + to_push.RDHR = tf[3]; + to_push.RDLR = tf[2]; + to_push.RDTR = tf[1]; + to_push.RIR = tf[0]; + + uint8_t bus_number = (to_push.RDTR >> 4) & CAN_BUS_NUM_MASK; + can_send(&to_push, bus_number); + } +} + +int is_enumerated = 0; + +void usb_cb_enumeration_complete() { + puts("USB enumeration complete\n"); + is_enumerated = 1; +} + +int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, int hardwired) { + int resp_len = 0; + uart_ring *ur = NULL; + int i; + switch (setup->b.bRequest) { + // **** 0xc0: get CAN debug info + case 0xc0: + puts("can tx: "); puth(can_tx_cnt); + puts(" txd: "); puth(can_txd_cnt); + puts(" rx: "); puth(can_rx_cnt); + puts(" err: "); puth(can_err_cnt); + puts("\n"); + break; + // **** 0xc1: is grey panda + case 0xc1: + resp[0] = is_grey_panda; + resp_len = 1; + break; + // **** 0xd0: fetch serial number + case 0xd0: + #ifdef PANDA + // addresses are OTP + if (setup->b.wValue.w == 1) { + memcpy(resp, (void *)0x1fff79c0, 0x10); + resp_len = 0x10; + } else { + get_provision_chunk(resp); + resp_len = PROVISION_CHUNK_LEN; + } + #endif + break; + // **** 0xd1: enter bootloader mode + case 0xd1: + // this allows reflashing of the bootstub + // so it's blocked over wifi + switch (setup->b.wValue.w) { + case 0: + if (hardwired) { + puts("-> entering bootloader\n"); + enter_bootloader_mode = ENTER_BOOTLOADER_MAGIC; + NVIC_SystemReset(); + } + break; + case 1: + puts("-> entering softloader\n"); + enter_bootloader_mode = ENTER_SOFTLOADER_MAGIC; + NVIC_SystemReset(); + break; + } + break; + // **** 0xd2: get health packet + case 0xd2: + resp_len = get_health_pkt(resp); + break; + // **** 0xd3: set fan speed + case 0xd3: + fan_set_speed(setup->b.wValue.w); + break; + // **** 0xd6: get version + case 0xd6: + COMPILE_TIME_ASSERT(sizeof(gitversion) <= MAX_RESP_LEN) + memcpy(resp, gitversion, sizeof(gitversion)); + resp_len = sizeof(gitversion)-1; + break; + // **** 0xd8: reset ST + case 0xd8: + NVIC_SystemReset(); + break; + // **** 0xd9: set ESP power + case 0xd9: + if (setup->b.wValue.w == 1) { + set_esp_mode(ESP_ENABLED); + } else if (setup->b.wValue.w == 2) { + set_esp_mode(ESP_BOOTMODE); + } else { + set_esp_mode(ESP_DISABLED); + } + break; + // **** 0xda: reset ESP, with optional boot mode + case 0xda: + set_esp_mode(ESP_DISABLED); + delay(1000000); + if (setup->b.wValue.w == 1) { + set_esp_mode(ESP_BOOTMODE); + } else { + set_esp_mode(ESP_ENABLED); + } + delay(1000000); + set_esp_mode(ESP_ENABLED); + break; + // **** 0xdb: set GMLAN multiplexing mode + case 0xdb: + #ifdef PANDA + if (setup->b.wValue.w == 1) { + // GMLAN ON + if (setup->b.wIndex.w == 1) { + can_set_gmlan(1); + } else if (setup->b.wIndex.w == 2) { + // might be ignored on rev b panda + can_set_gmlan(2); + } + } else { + can_set_gmlan(-1); + } + #endif + break; + // **** 0xdc: set safety mode + case 0xdc: + // this is the only way to leave silent mode + // and it's blocked over WiFi + // Allow ELM security mode to be set over wifi. + if (hardwired || setup->b.wValue.w == SAFETY_NOOUTPUT || setup->b.wValue.w == SAFETY_ELM327) { + safety_set_mode(setup->b.wValue.w, (int16_t)setup->b.wIndex.w); + switch (setup->b.wValue.w) { + case SAFETY_NOOUTPUT: + can_silent = ALL_CAN_SILENT; + break; + case SAFETY_ELM327: + can_silent = ALL_CAN_BUT_MAIN_SILENT; + can_autobaud_enabled[0] = false; + break; + default: + can_silent = ALL_CAN_LIVE; + can_autobaud_enabled[0] = false; + can_autobaud_enabled[1] = false; + #ifdef PANDA + can_autobaud_enabled[2] = false; + #endif + break; + } + can_init_all(); + } + break; + // **** 0xdd: enable can forwarding + case 0xdd: + // wValue = Can Bus Num to forward from + // wIndex = Can Bus Num to forward to + if (setup->b.wValue.w < BUS_MAX && setup->b.wIndex.w < BUS_MAX && + setup->b.wValue.w != setup->b.wIndex.w) { // set forwarding + can_set_forwarding(setup->b.wValue.w, setup->b.wIndex.w & CAN_BUS_NUM_MASK); + } else if(setup->b.wValue.w < BUS_MAX && setup->b.wIndex.w == 0xFF){ //Clear Forwarding + can_set_forwarding(setup->b.wValue.w, -1); + } + break; + // **** 0xde: set can bitrate + case 0xde: + if (setup->b.wValue.w < BUS_MAX) { + can_autobaud_enabled[setup->b.wValue.w] = false; + can_speed[setup->b.wValue.w] = setup->b.wIndex.w; + can_init(CAN_NUM_FROM_BUS_NUM(setup->b.wValue.w)); + } + break; + // **** 0xe0: uart read + case 0xe0: + ur = get_ring_by_number(setup->b.wValue.w); + if (!ur) break; + if (ur == &esp_ring) uart_dma_drain(); + // read + while ((resp_len < min(setup->b.wLength.w, MAX_RESP_LEN)) && + getc(ur, (char*)&resp[resp_len])) { + ++resp_len; + } + break; + // **** 0xe1: uart set baud rate + case 0xe1: + ur = get_ring_by_number(setup->b.wValue.w); + if (!ur) break; + uart_set_baud(ur->uart, setup->b.wIndex.w); + break; + // **** 0xe2: uart set parity + case 0xe2: + ur = get_ring_by_number(setup->b.wValue.w); + if (!ur) break; + switch (setup->b.wIndex.w) { + case 0: + // disable parity, 8-bit + ur->uart->CR1 &= ~(USART_CR1_PCE | USART_CR1_M); + break; + case 1: + // even parity, 9-bit + ur->uart->CR1 &= ~USART_CR1_PS; + ur->uart->CR1 |= USART_CR1_PCE | USART_CR1_M; + break; + case 2: + // odd parity, 9-bit + ur->uart->CR1 |= USART_CR1_PS; + ur->uart->CR1 |= USART_CR1_PCE | USART_CR1_M; + break; + default: + break; + } + break; + // **** 0xe4: uart set baud rate extended + case 0xe4: + ur = get_ring_by_number(setup->b.wValue.w); + if (!ur) break; + uart_set_baud(ur->uart, (int)setup->b.wIndex.w*300); + break; + // **** 0xe5: set CAN loopback (for testing) + case 0xe5: + can_loopback = (setup->b.wValue.w > 0); + can_init_all(); + break; + // **** 0xe6: set USB power + case 0xe6: + if (revision == PANDA_REV_C) { + if (setup->b.wValue.w == 1) { + puts("user setting CDP mode\n"); + set_usb_power_mode(USB_POWER_CDP); + } else if (setup->b.wValue.w == 2) { + puts("user setting DCP mode\n"); + set_usb_power_mode(USB_POWER_DCP); + } else { + puts("user setting CLIENT mode\n"); + set_usb_power_mode(USB_POWER_CLIENT); + } + } + break; + // **** 0xf0: do k-line wValue pulse on uart2 for Acura + case 0xf0: + if (setup->b.wValue.w == 1) { + GPIOC->ODR &= ~(1 << 10); + GPIOC->MODER &= ~GPIO_MODER_MODER10_1; + GPIOC->MODER |= GPIO_MODER_MODER10_0; + } else { + GPIOC->ODR &= ~(1 << 12); + GPIOC->MODER &= ~GPIO_MODER_MODER12_1; + GPIOC->MODER |= GPIO_MODER_MODER12_0; + } + + for (i = 0; i < 80; i++) { + delay(8000); + if (setup->b.wValue.w == 1) { + GPIOC->ODR |= (1 << 10); + GPIOC->ODR &= ~(1 << 10); + } else { + GPIOC->ODR |= (1 << 12); + GPIOC->ODR &= ~(1 << 12); + } + } + + if (setup->b.wValue.w == 1) { + GPIOC->MODER &= ~GPIO_MODER_MODER10_0; + GPIOC->MODER |= GPIO_MODER_MODER10_1; + } else { + GPIOC->MODER &= ~GPIO_MODER_MODER12_0; + GPIOC->MODER |= GPIO_MODER_MODER12_1; + } + + delay(140 * 9000); + break; + // **** 0xf1: Clear CAN ring buffer. + case 0xf1: + if (setup->b.wValue.w == 0xFFFF) { + puts("Clearing CAN Rx queue\n"); + can_clear(&can_rx_q); + } else if (setup->b.wValue.w < BUS_MAX) { + puts("Clearing CAN Tx queue\n"); + can_clear(can_queues[setup->b.wValue.w]); + } + break; + // **** 0xf2: Clear UART ring buffer. + case 0xf2: + { + uart_ring * rb = get_ring_by_number(setup->b.wValue.w); + if (rb) { + puts("Clearing UART queue.\n"); + clear_uart_buff(rb); + } + break; + } + default: + puts("NO HANDLER "); + puth(setup->b.bRequest); + puts("\n"); + break; + } + return resp_len; +} + +#ifdef PANDA +int spi_cb_rx(uint8_t *data, int len, uint8_t *data_out) { + // data[0] = endpoint + // data[2] = length + // data[4:] = data + + int resp_len = 0; + switch (data[0]) { + case 0: + // control transfer + resp_len = usb_cb_control_msg((USB_Setup_TypeDef *)(data+4), data_out, 0); + break; + case 1: + // ep 1, read + resp_len = usb_cb_ep1_in(data_out, 0x40, 0); + break; + case 2: + // ep 2, send serial + usb_cb_ep2_out(data+4, data[2], 0); + break; + case 3: + // ep 3, send CAN + usb_cb_ep3_out(data+4, data[2], 0); + break; + } + return resp_len; +} + +#else + +int spi_cb_rx(uint8_t *data, int len, uint8_t *data_out) { return 0; }; + +#endif + + +// ***************************** main code ***************************** + +void __initialize_hardware_early() { + early(); +} + +void __attribute__ ((noinline)) enable_fpu() { + // enable the FPU + SCB->CPACR |= ((3UL << 10*2) | (3UL << 11*2)); +} + +int main() { + // shouldn't have interrupts here, but just in case + __disable_irq(); + + // init early devices + clock_init(); + periph_init(); + detect(); + + // print hello + puts("\n\n\n************************ MAIN START ************************\n"); + + // detect the revision and init the GPIOs + puts("config:\n"); + #ifdef PANDA + puts(revision == PANDA_REV_C ? " panda rev c\n" : " panda rev a or b\n"); + #else + puts(" legacy\n"); + #endif + puts(has_external_debug_serial ? " real serial\n" : " USB serial\n"); + puts(is_giant_panda ? " GIANTpanda detected\n" : " not GIANTpanda\n"); + puts(is_grey_panda ? " gray panda detected!\n" : " white panda\n"); + puts(is_entering_bootmode ? " ESP wants bootmode\n" : " no bootmode\n"); + gpio_init(); + +#ifdef PANDA + // panda has an FPU, let's use it! + enable_fpu(); +#endif + + // enable main uart if it's connected + if (has_external_debug_serial) { + // WEIRDNESS: without this gate around the UART, it would "crash", but only if the ESP is enabled + // assuming it's because the lines were left floating and spurious noise was on them + uart_init(USART2, 115200); + } + +#ifdef PANDA + if (is_grey_panda) { + uart_init(USART1, 9600); + } else { + // enable ESP uart + uart_init(USART1, 115200); + } + // enable LIN + uart_init(UART5, 10400); + UART5->CR2 |= USART_CR2_LINEN; + uart_init(USART3, 10400); + USART3->CR2 |= USART_CR2_LINEN; +#endif + + // init microsecond system timer + // increments 1000000 times per second + // generate an update to set the prescaler + TIM2->PSC = 48-1; + TIM2->CR1 = TIM_CR1_CEN; + TIM2->EGR = TIM_EGR_UG; + // use TIM2->CNT to read + + // enable USB + usb_init(); + + // default to silent mode to prevent issues with Ford + safety_set_mode(SAFETY_NOOUTPUT, 0); + can_silent = ALL_CAN_SILENT; + can_init_all(); + + adc_init(); + +#ifdef PANDA + spi_init(); +#endif + + // set PWM + fan_init(); + fan_set_speed(0); + + puts("**** INTERRUPTS ON ****\n"); + + __enable_irq(); + + // if the error interrupt is enabled to quickly when the CAN bus is active + // something bad happens and you can't connect to the device over USB + delay(10000000); + CAN1->IER |= CAN_IER_ERRIE | CAN_IER_LECIE; + + // LED should keep on blinking all the time + uint64_t cnt = 0; + + #ifdef PANDA + uint64_t marker = 0; + #define CURRENT_THRESHOLD 0xF00 + #define CLICKS 8 + // Enough clicks to ensure that enumeration happened. Should be longer than bootup time of the device connected to EON + #define CLICKS_BOOTUP 30 + #endif + + for (cnt=0;;cnt++) { + can_live = pending_can_live; + + //puth(usart1_dma); puts(" "); puth(DMA2_Stream5->M0AR); puts(" "); puth(DMA2_Stream5->NDTR); puts("\n"); + + #ifdef PANDA + int current = adc_get(ADCCHAN_CURRENT); + + switch (usb_power_mode) { + case USB_POWER_CLIENT: + if ((cnt-marker) >= CLICKS) { + if (!is_enumerated) { + puts("USBP: didn't enumerate, switching to CDP mode\n"); + // switch to CDP + set_usb_power_mode(USB_POWER_CDP); + marker = cnt; + } + } + // keep resetting the timer if it's enumerated + if (is_enumerated) { + marker = cnt; + } + break; + case USB_POWER_CDP: + // been CLICKS_BOOTUP clicks since we switched to CDP + if ((cnt-marker) >= CLICKS_BOOTUP ) { + // measure current draw, if positive and no enumeration, switch to DCP + if (!is_enumerated && current < CURRENT_THRESHOLD) { + puts("USBP: no enumeration with current draw, switching to DCP mode\n"); + set_usb_power_mode(USB_POWER_DCP); + marker = cnt; + } + } + // keep resetting the timer if there's no current draw in CDP + if (current >= CURRENT_THRESHOLD) { + marker = cnt; + } + break; + case USB_POWER_DCP: + // been at least CLICKS clicks since we switched to DCP + if ((cnt-marker) >= CLICKS) { + // if no current draw, switch back to CDP + if (current >= CURRENT_THRESHOLD) { + puts("USBP: no current draw, switching back to CDP mode\n"); + set_usb_power_mode(USB_POWER_CDP); + marker = cnt; + } + } + // keep resetting the timer if there's current draw in DCP + if (current < CURRENT_THRESHOLD) { + marker = cnt; + } + break; + } + + // ~0x9a = 500 ma + /*puth(current); + puts("\n");*/ + #endif + + // reset this every 16th pass + if ((cnt&0xF) == 0) pending_can_live = 0; + + #ifdef DEBUG + puts("** blink "); + puth(can_rx_q.r_ptr); puts(" "); puth(can_rx_q.w_ptr); puts(" "); + puth(can_tx1_q.r_ptr); puts(" "); puth(can_tx1_q.w_ptr); puts(" "); + puth(can_tx2_q.r_ptr); puts(" "); puth(can_tx2_q.w_ptr); puts("\n"); + #endif + + // set green LED to be controls allowed + set_led(LED_GREEN, controls_allowed); + + // blink the red LED + int div_mode = ((usb_power_mode == USB_POWER_DCP) ? 4 : 1); + + for (int div_mode_loop = 0; div_mode_loop < div_mode; div_mode_loop++) { + for (int fade = 0; fade < 1024; fade += 8) { + for (int i = 0; i < 128/div_mode; i++) { + set_led(LED_RED, 0); + if (fade < 512) { delay(512-fade); } else { delay(fade-512); } + set_led(LED_RED, 1); + if (fade < 512) { delay(fade); } else { delay(1024-fade); } + } + } + } + + // turn off the blue LED, turned on by CAN + #ifdef PANDA + set_led(LED_BLUE, 0); + #endif + } + + return 0; +} diff --git a/panda/board/obj/.placeholder b/panda/board/obj/.placeholder new file mode 100644 index 00000000000000..e69de29bb2d1d6 diff --git a/panda/board/pedal/.gitignore b/panda/board/pedal/.gitignore new file mode 100644 index 00000000000000..94053f2925089b --- /dev/null +++ b/panda/board/pedal/.gitignore @@ -0,0 +1 @@ +obj/* diff --git a/panda/board/pedal/Makefile b/panda/board/pedal/Makefile new file mode 100644 index 00000000000000..9917e381503b03 --- /dev/null +++ b/panda/board/pedal/Makefile @@ -0,0 +1,59 @@ +# :set noet +PROJ_NAME = comma + +CFLAGS = -O2 -Wall -std=gnu11 -DPEDAL +CFLAGS += -mlittle-endian -mthumb -mcpu=cortex-m3 +CFLAGS += -msoft-float -DSTM32F2 -DSTM32F205xx +CFLAGS += -I ../inc -I ../ -I ../../ -nostdlib +CFLAGS += -T../stm32_flash.ld + +STARTUP_FILE = startup_stm32f205xx + +CC = arm-none-eabi-gcc +OBJCOPY = arm-none-eabi-objcopy +OBJDUMP = arm-none-eabi-objdump +DFU_UTIL = "dfu-util" + +# pedal only uses the debug cert +CERT = ../../certs/debug +CFLAGS += "-DALLOW_DEBUG" + +canflash: obj/$(PROJ_NAME).bin + ../../tests/pedal/enter_canloader.py $< + +usbflash: obj/$(PROJ_NAME).bin + ../../tests/pedal/enter_canloader.py; sleep 0.5 + PYTHONPATH=../../ python -c "from python import Panda; p = [x for x in [Panda(x) for x in Panda.list()] if x.bootstub]; assert(len(p)==1); p[0].flash('obj/$(PROJ_NAME).bin', reconnect=False)" + +recover: obj/bootstub.bin obj/$(PROJ_NAME).bin + ../../tests/pedal/enter_canloader.py --recover; sleep 0.5 + $(DFU_UTIL) -d 0483:df11 -a 0 -s 0x08004000 -D obj/$(PROJ_NAME).bin + $(DFU_UTIL) -d 0483:df11 -a 0 -s 0x08000000:leave -D obj/bootstub.bin + +obj/main.o: main.c ../*.h + mkdir -p obj + $(CC) $(CFLAGS) -o $@ -c $< + +obj/bootstub.o: ../bootstub.c ../*.h + mkdir -p obj + $(CC) $(CFLAGS) -o $@ -c $< + +obj/$(STARTUP_FILE).o: ../$(STARTUP_FILE).s + $(CC) $(CFLAGS) -o $@ -c $< + +obj/%.o: ../../crypto/%.c + $(CC) $(CFLAGS) -o $@ -c $< + +obj/$(PROJ_NAME).bin: obj/$(STARTUP_FILE).o obj/main.o + # hack + $(CC) -Wl,--section-start,.isr_vector=0x8004000 $(CFLAGS) -o obj/$(PROJ_NAME).elf $^ + $(OBJCOPY) -v -O binary obj/$(PROJ_NAME).elf obj/code.bin + SETLEN=1 ../../crypto/sign.py obj/code.bin $@ $(CERT) + +obj/bootstub.bin: obj/$(STARTUP_FILE).o obj/bootstub.o obj/sha.o obj/rsa.o + $(CC) $(CFLAGS) -o obj/bootstub.$(PROJ_NAME).elf $^ + $(OBJCOPY) -v -O binary obj/bootstub.$(PROJ_NAME).elf $@ + +clean: + rm -f obj/* + diff --git a/panda/board/pedal/README b/panda/board/pedal/README new file mode 100644 index 00000000000000..cf779db258fe14 --- /dev/null +++ b/panda/board/pedal/README @@ -0,0 +1,28 @@ +This is the firmware for the comma pedal. It borrows a lot from panda. + +The comma pedal is a gas pedal interceptor for Honda/Acura. It allows you to "virtually" press the pedal. + +This is the open source software. Note that it is not ready to use yet. + +== Test Plan == + +* Startup +** Confirm STATE_FAULT_STARTUP +* Timeout +** Send value +** Confirm value is output +** Stop sending messages +** Confirm value is passthru after 100ms +** Confirm STATE_FAULT_TIMEOUT +* Random values +** Send random 6 byte messages +** Confirm random values cause passthru +** Confirm STATE_FAULT_BAD_CHECKSUM +* Same message lockout +** Send same message repeated +** Confirm timeout behavior +* Don't set enable +** Confirm no output +* Set enable and values +** Confirm output + diff --git a/panda/board/pedal/main.c b/panda/board/pedal/main.c new file mode 100644 index 00000000000000..5d5264791ccf54 --- /dev/null +++ b/panda/board/pedal/main.c @@ -0,0 +1,295 @@ +//#define DEBUG +//#define CAN_LOOPBACK_MODE +//#define USE_INTERNAL_OSC + +#include "../config.h" + +#include "drivers/drivers.h" +#include "drivers/llgpio.h" +#include "gpio.h" + +#define CUSTOM_CAN_INTERRUPTS + +#include "libc.h" +#include "safety.h" +#include "drivers/adc.h" +#include "drivers/uart.h" +#include "drivers/dac.h" +#include "drivers/can.h" +#include "drivers/timer.h" + +#define CAN CAN1 + +//#define PEDAL_USB + +#ifdef PEDAL_USB + #include "drivers/usb.h" +#endif + +#define ENTER_BOOTLOADER_MAGIC 0xdeadbeef +uint32_t enter_bootloader_mode; + +void __initialize_hardware_early() { + early(); +} + +// ********************* serial debugging ********************* + +void debug_ring_callback(uart_ring *ring) { + char rcv; + while (getc(ring, &rcv)) { + putc(ring, rcv); + } +} + +#ifdef PEDAL_USB + +int usb_cb_ep1_in(uint8_t *usbdata, int len, int hardwired) { return 0; } +void usb_cb_ep2_out(uint8_t *usbdata, int len, int hardwired) {} +void usb_cb_ep3_out(uint8_t *usbdata, int len, int hardwired) {} +void usb_cb_enumeration_complete() {} + +int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, int hardwired) { + int resp_len = 0; + uart_ring *ur = NULL; + switch (setup->b.bRequest) { + // **** 0xe0: uart read + case 0xe0: + ur = get_ring_by_number(setup->b.wValue.w); + if (!ur) break; + if (ur == &esp_ring) uart_dma_drain(); + // read + while ((resp_len < min(setup->b.wLength.w, MAX_RESP_LEN)) && + getc(ur, (char*)&resp[resp_len])) { + ++resp_len; + } + break; + } + return resp_len; +} + +#endif + +// ***************************** honda can checksum ***************************** + +int can_cksum(uint8_t *dat, int len, int addr, int idx) { + int i; + int s = 0; + for (i = 0; i < len; i++) { + s += (dat[i] >> 4); + s += dat[i] & 0xF; + } + s += (addr>>0)&0xF; + s += (addr>>4)&0xF; + s += (addr>>8)&0xF; + s += idx; + s = 8-s; + return s&0xF; +} + +// ***************************** can port ***************************** + +// addresses to be used on CAN +#define CAN_GAS_INPUT 0x200 +#define CAN_GAS_OUTPUT 0x201 + +void CAN1_TX_IRQHandler() { + // clear interrupt + CAN->TSR |= CAN_TSR_RQCP0; +} + +// two independent values +uint16_t gas_set_0 = 0; +uint16_t gas_set_1 = 0; + +#define MAX_TIMEOUT 10 +uint32_t timeout = 0; +uint32_t current_index = 0; + +#define NO_FAULT 0 +#define FAULT_BAD_CHECKSUM 1 +#define FAULT_SEND 2 +#define FAULT_SCE 3 +#define FAULT_STARTUP 4 +#define FAULT_TIMEOUT 5 +#define FAULT_INVALID 6 +uint8_t state = FAULT_STARTUP; + +void CAN1_RX0_IRQHandler() { + while (CAN->RF0R & CAN_RF0R_FMP0) { + #ifdef DEBUG + puts("CAN RX\n"); + #endif + uint32_t address = CAN->sFIFOMailBox[0].RIR>>21; + if (address == CAN_GAS_INPUT) { + // softloader entry + if (CAN->sFIFOMailBox[0].RDLR == 0xdeadface) { + if (CAN->sFIFOMailBox[0].RDHR == 0x0ab00b1e) { + enter_bootloader_mode = ENTER_SOFTLOADER_MAGIC; + NVIC_SystemReset(); + } else if (CAN->sFIFOMailBox[0].RDHR == 0x02b00b1e) { + enter_bootloader_mode = ENTER_BOOTLOADER_MAGIC; + NVIC_SystemReset(); + } + } + + // normal packet + uint8_t *dat = (uint8_t *)&CAN->sFIFOMailBox[0].RDLR; + uint8_t *dat2 = (uint8_t *)&CAN->sFIFOMailBox[0].RDHR; + uint16_t value_0 = (dat[0] << 8) | dat[1]; + uint16_t value_1 = (dat[2] << 8) | dat[3]; + uint8_t enable = (dat2[0] >> 7) & 1; + uint8_t index = (dat2[1] >> 4) & 3; + if (can_cksum(dat, 5, CAN_GAS_INPUT, index) == (dat2[1] & 0xF)) { + if (((current_index+1)&3) == index) { + #ifdef DEBUG + puts("setting gas "); + puth(value); + puts("\n"); + #endif + if (enable) { + gas_set_0 = value_0; + gas_set_1 = value_1; + } else { + // clear the fault state if values are 0 + if (value_0 == 0 && value_1 == 0) { + state = NO_FAULT; + } else { + state = FAULT_INVALID; + } + gas_set_0 = gas_set_1 = 0; + } + // clear the timeout + timeout = 0; + } + current_index = index; + } else { + // wrong checksum = fault + state = FAULT_BAD_CHECKSUM; + } + } + // next + CAN->RF0R |= CAN_RF0R_RFOM0; + } +} + +void CAN1_SCE_IRQHandler() { + state = FAULT_SCE; + can_sce(CAN); +} + +int pdl0 = 0, pdl1 = 0; +int pkt_idx = 0; + +int led_value = 0; + +void TIM3_IRQHandler() { + #ifdef DEBUG + puth(TIM3->CNT); + puts(" "); + puth(pdl0); + puts(" "); + puth(pdl1); + puts("\n"); + #endif + + // check timer for sending the user pedal and clearing the CAN + if ((CAN->TSR & CAN_TSR_TME0) == CAN_TSR_TME0) { + uint8_t dat[8]; + dat[0] = (pdl0>>8)&0xFF; + dat[1] = (pdl0>>0)&0xFF; + dat[2] = (pdl1>>8)&0xFF; + dat[3] = (pdl1>>0)&0xFF; + dat[4] = state; + dat[5] = can_cksum(dat, 5, CAN_GAS_OUTPUT, pkt_idx) | (pkt_idx<<4); + CAN->sTxMailBox[0].TDLR = dat[0] | (dat[1]<<8) | (dat[2]<<16) | (dat[3]<<24); + CAN->sTxMailBox[0].TDHR = dat[4] | (dat[5]<<8); + CAN->sTxMailBox[0].TDTR = 6; // len of packet is 5 + CAN->sTxMailBox[0].TIR = (CAN_GAS_OUTPUT << 21) | 1; + ++pkt_idx; + pkt_idx &= 3; + } else { + // old can packet hasn't sent! + state = FAULT_SEND; + #ifdef DEBUG + puts("CAN MISS\n"); + #endif + } + + // blink the LED + set_led(LED_GREEN, led_value); + led_value = !led_value; + + TIM3->SR = 0; + + // up timeout for gas set + if (timeout == MAX_TIMEOUT) { + state = FAULT_TIMEOUT; + } else { + timeout += 1; + } +} + +// ***************************** main code ***************************** + +void pedal() { + // read/write + pdl0 = adc_get(ADCCHAN_ACCEL0); + pdl1 = adc_get(ADCCHAN_ACCEL1); + + // write the pedal to the DAC + if (state == NO_FAULT) { + dac_set(0, max(gas_set_0, pdl0)); + dac_set(1, max(gas_set_1, pdl1)); + } else { + dac_set(0, pdl0); + dac_set(1, pdl1); + } + + // feed the watchdog + IWDG->KR = 0xAAAA; +} + +int main() { + __disable_irq(); + + // init devices + clock_init(); + periph_init(); + gpio_init(); + +#ifdef PEDAL_USB + // enable USB + usb_init(); +#endif + + // pedal stuff + dac_init(); + adc_init(); + + // init can + can_silent = ALL_CAN_LIVE; + can_init(0); + + // 48mhz / 65536 ~= 732 + timer_init(TIM3, 15); + NVIC_EnableIRQ(TIM3_IRQn); + + // setup watchdog + IWDG->KR = 0x5555; + IWDG->PR = 0; // divider /4 + // 0 = 0.125 ms, let's have a 50ms watchdog + IWDG->RLR = 400 - 1; + IWDG->KR = 0xCCCC; + + puts("**** INTERRUPTS ON ****\n"); + __enable_irq(); + + // main pedal loop + while (1) { + pedal(); + } + + return 0; +} + diff --git a/panda/board/pedal/obj/.gitkeep b/panda/board/pedal/obj/.gitkeep new file mode 100644 index 00000000000000..e69de29bb2d1d6 diff --git a/panda/board/provision.h b/panda/board/provision.h new file mode 100644 index 00000000000000..2fad513508132d --- /dev/null +++ b/panda/board/provision.h @@ -0,0 +1,13 @@ +#define PROVISION_CHUNK_LEN 0x20 + +// WiFi SSID = 0x0 - 0x10 +// WiFi password = 0x10 - 0x1C +// SHA1 checksum = 0x1C - 0x20 + +void get_provision_chunk(uint8_t *resp) { + memcpy(resp, (void *)0x1fff79e0, PROVISION_CHUNK_LEN); + if (memcmp(resp, "\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff", 0x20) == 0) { + memcpy(resp, "unprovisioned\x00\x00\x00testing123\x00\x00\xa3\xa6\x99\xec", 0x20); + } +} + diff --git a/panda/board/safety.h b/panda/board/safety.h new file mode 100644 index 00000000000000..4d2b46899f7969 --- /dev/null +++ b/panda/board/safety.h @@ -0,0 +1,251 @@ +// sample struct that keeps 3 samples in memory +struct sample_t { + int values[6]; + int min; + int max; +} sample_t_default = {{0}, 0, 0}; + +// no float support in STM32F2 micros (cortex-m3) +#ifdef PANDA +struct lookup_t { + float x[3]; + float y[3]; +}; +#endif + +void safety_rx_hook(CAN_FIFOMailBox_TypeDef *to_push); +int safety_tx_hook(CAN_FIFOMailBox_TypeDef *to_send); +int safety_tx_lin_hook(int lin_num, uint8_t *data, int len); +int safety_ignition_hook(); +uint32_t get_ts_elapsed(uint32_t ts, uint32_t ts_last); +int to_signed(int d, int bits); +void update_sample(struct sample_t *sample, int sample_new); +int max_limit_check(int val, const int MAX, const int MIN); +int dist_to_meas_check(int val, int val_last, struct sample_t *val_meas, + const int MAX_RATE_UP, const int MAX_RATE_DOWN, const int MAX_ERROR); +int driver_limit_check(int val, int val_last, struct sample_t *val_driver, + const int MAX, const int MAX_RATE_UP, const int MAX_RATE_DOWN, + const int MAX_ALLOWANCE, const int DRIVER_FACTOR); +int rt_rate_limit_check(int val, int val_last, const int MAX_RT_DELTA); +#ifdef PANDA +float interpolate(struct lookup_t xy, float x); +#endif + +typedef void (*safety_hook_init)(int16_t param); +typedef void (*rx_hook)(CAN_FIFOMailBox_TypeDef *to_push); +typedef int (*tx_hook)(CAN_FIFOMailBox_TypeDef *to_send); +typedef int (*tx_lin_hook)(int lin_num, uint8_t *data, int len); +typedef int (*ign_hook)(); +typedef int (*fwd_hook)(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd); + +typedef struct { + safety_hook_init init; + ign_hook ignition; + rx_hook rx; + tx_hook tx; + tx_lin_hook tx_lin; + fwd_hook fwd; +} safety_hooks; + +// This can be set by the safety hooks. +int controls_allowed = 0; + +// Include the actual safety policies. +#include "safety/safety_defaults.h" +#include "safety/safety_honda.h" +#include "safety/safety_toyota.h" +#ifdef PANDA +#include "safety/safety_toyota_ipas.h" +#include "safety/safety_tesla.h" +#endif +#include "safety/safety_gm.h" +#include "safety/safety_ford.h" +#include "safety/safety_cadillac.h" +#include "safety/safety_hyundai.h" +#include "safety/safety_chrysler.h" +#include "safety/safety_elm327.h" + +const safety_hooks *current_hooks = &nooutput_hooks; + +void safety_rx_hook(CAN_FIFOMailBox_TypeDef *to_push){ + current_hooks->rx(to_push); +} + +int safety_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) { + return current_hooks->tx(to_send); +} + +int safety_tx_lin_hook(int lin_num, uint8_t *data, int len){ + return current_hooks->tx_lin(lin_num, data, len); +} + +// -1 = Disabled (Use GPIO to determine ignition) +// 0 = Off (not started) +// 1 = On (started) +int safety_ignition_hook() { + return current_hooks->ignition(); +} +int safety_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) { + return current_hooks->fwd(bus_num, to_fwd); +} + +typedef struct { + uint16_t id; + const safety_hooks *hooks; +} safety_hook_config; + +#define SAFETY_NOOUTPUT 0 +#define SAFETY_HONDA 1 +#define SAFETY_TOYOTA 2 +#define SAFETY_GM 3 +#define SAFETY_HONDA_BOSCH 4 +#define SAFETY_FORD 5 +#define SAFETY_CADILLAC 6 +#define SAFETY_HYUNDAI 7 +#define SAFETY_TESLA 8 +#define SAFETY_CHRYSLER 9 +#define SAFETY_TOYOTA_IPAS 0x1335 +#define SAFETY_TOYOTA_NOLIMITS 0x1336 +#define SAFETY_ALLOUTPUT 0x1337 +#define SAFETY_ELM327 0xE327 + +const safety_hook_config safety_hook_registry[] = { + {SAFETY_NOOUTPUT, &nooutput_hooks}, + {SAFETY_HONDA, &honda_hooks}, + {SAFETY_HONDA_BOSCH, &honda_bosch_hooks}, + {SAFETY_TOYOTA, &toyota_hooks}, + {SAFETY_GM, &gm_hooks}, + {SAFETY_FORD, &ford_hooks}, + {SAFETY_CADILLAC, &cadillac_hooks}, + {SAFETY_HYUNDAI, &hyundai_hooks}, + {SAFETY_CHRYSLER, &chrysler_hooks}, + {SAFETY_TOYOTA_NOLIMITS, &toyota_nolimits_hooks}, +#ifdef PANDA + {SAFETY_TOYOTA_IPAS, &toyota_ipas_hooks}, + {SAFETY_TESLA, &tesla_hooks}, +#endif + {SAFETY_ALLOUTPUT, &alloutput_hooks}, + {SAFETY_ELM327, &elm327_hooks}, +}; + +#define HOOK_CONFIG_COUNT (sizeof(safety_hook_registry)/sizeof(safety_hook_config)) + +int safety_set_mode(uint16_t mode, int16_t param) { + for (int i = 0; i < HOOK_CONFIG_COUNT; i++) { + if (safety_hook_registry[i].id == mode) { + current_hooks = safety_hook_registry[i].hooks; + if (current_hooks->init) current_hooks->init(param); + return 0; + } + } + return -1; +} + +// compute the time elapsed (in microseconds) from 2 counter samples +uint32_t get_ts_elapsed(uint32_t ts, uint32_t ts_last) { + return ts > ts_last ? ts - ts_last : (0xFFFFFFFF - ts_last) + 1 + ts; +} + +// convert a trimmed integer to signed 32 bit int +int to_signed(int d, int bits) { + if (d >= (1 << (bits - 1))) { + d -= (1 << bits); + } + return d; +} + +// given a new sample, update the smaple_t struct +void update_sample(struct sample_t *sample, int sample_new) { + for (int i = sizeof(sample->values)/sizeof(sample->values[0]) - 1; i > 0; i--) { + sample->values[i] = sample->values[i-1]; + } + sample->values[0] = sample_new; + + // get the minimum and maximum measured samples + sample->min = sample->max = sample->values[0]; + for (int i = 1; i < sizeof(sample->values)/sizeof(sample->values[0]); i++) { + if (sample->values[i] < sample->min) sample->min = sample->values[i]; + if (sample->values[i] > sample->max) sample->max = sample->values[i]; + } +} + +int max_limit_check(int val, const int MAX, const int MIN) { + return (val > MAX) || (val < MIN); +} + +// check that commanded value isn't too far from measured +int dist_to_meas_check(int val, int val_last, struct sample_t *val_meas, + const int MAX_RATE_UP, const int MAX_RATE_DOWN, const int MAX_ERROR) { + + // *** val rate limit check *** + int highest_allowed_val = max(val_last, 0) + MAX_RATE_UP; + int lowest_allowed_val = min(val_last, 0) - MAX_RATE_UP; + + // if we've exceeded the meas val, we must start moving toward 0 + highest_allowed_val = min(highest_allowed_val, max(val_last - MAX_RATE_DOWN, max(val_meas->max, 0) + MAX_ERROR)); + lowest_allowed_val = max(lowest_allowed_val, min(val_last + MAX_RATE_DOWN, min(val_meas->min, 0) - MAX_ERROR)); + + // check for violation + return (val < lowest_allowed_val) || (val > highest_allowed_val); +} + +// check that commanded value isn't fighting against driver +int driver_limit_check(int val, int val_last, struct sample_t *val_driver, + const int MAX, const int MAX_RATE_UP, const int MAX_RATE_DOWN, + const int MAX_ALLOWANCE, const int DRIVER_FACTOR) { + + int highest_allowed = max(val_last, 0) + MAX_RATE_UP; + int lowest_allowed = min(val_last, 0) - MAX_RATE_UP; + + int driver_max_limit = MAX + (MAX_ALLOWANCE + val_driver->max) * DRIVER_FACTOR; + int driver_min_limit = -MAX + (-MAX_ALLOWANCE + val_driver->min) * DRIVER_FACTOR; + + // if we've exceeded the applied torque, we must start moving toward 0 + highest_allowed = min(highest_allowed, max(val_last - MAX_RATE_DOWN, + max(driver_max_limit, 0))); + lowest_allowed = max(lowest_allowed, min(val_last + MAX_RATE_DOWN, + min(driver_min_limit, 0))); + + // check for violation + return (val < lowest_allowed) || (val > highest_allowed); +} + + +// real time check, mainly used for steer torque rate limiter +int rt_rate_limit_check(int val, int val_last, const int MAX_RT_DELTA) { + + // *** torque real time rate limit check *** + int highest_val = max(val_last, 0) + MAX_RT_DELTA; + int lowest_val = min(val_last, 0) - MAX_RT_DELTA; + + // check for violation + return (val < lowest_val) || (val > highest_val); +} + + +#ifdef PANDA +// interp function that holds extreme values +float interpolate(struct lookup_t xy, float x) { + int size = sizeof(xy.x) / sizeof(xy.x[0]); + // x is lower than the first point in the x array. Return the first point + if (x <= xy.x[0]) { + return xy.y[0]; + + } else { + // find the index such that (xy.x[i] <= x < xy.x[i+1]) and linearly interp + for (int i=0; i < size-1; i++) { + if (x < xy.x[i+1]) { + float x0 = xy.x[i]; + float y0 = xy.y[i]; + float dx = xy.x[i+1] - x0; + float dy = xy.y[i+1] - y0; + // dx should not be zero as xy.x is supposed ot be monotonic + if (dx <= 0.) dx = 0.0001; + return dy * (x - x0) / dx + y0; + } + } + // if no such point is found, then x > xy.x[size-1]. Return last point + return xy.y[size - 1]; + } +} +#endif diff --git a/panda/board/safety/safety_cadillac.h b/panda/board/safety/safety_cadillac.h new file mode 100644 index 00000000000000..2a2d8b9857ff91 --- /dev/null +++ b/panda/board/safety/safety_cadillac.h @@ -0,0 +1,131 @@ +const int CADILLAC_MAX_STEER = 150; // 1s +// real time torque limit to prevent controls spamming +// the real time limit is 1500/sec +const int CADILLAC_MAX_RT_DELTA = 75; // max delta torque allowed for real time checks +const int32_t CADILLAC_RT_INTERVAL = 250000; // 250ms between real time checks +const int CADILLAC_MAX_RATE_UP = 2; +const int CADILLAC_MAX_RATE_DOWN = 5; +const int CADILLAC_DRIVER_TORQUE_ALLOWANCE = 50; +const int CADILLAC_DRIVER_TORQUE_FACTOR = 4; + +int cadillac_ign = 0; +int cadillac_cruise_engaged_last = 0; +int cadillac_rt_torque_last = 0; +int cadillac_desired_torque_last[4] = {0}; // 4 torque messages +uint32_t cadillac_ts_last = 0; +int cadillac_supercruise_on = 0; +struct sample_t cadillac_torque_driver; // last few driver torques measured + +int cadillac_get_torque_idx(uint32_t addr) { + if (addr==0x151) return 0; + else if (addr==0x152) return 1; + else if (addr==0x153) return 2; + else return 3; +} + +static void cadillac_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) { + int bus_number = (to_push->RDTR >> 4) & 0xFF; + uint32_t addr = to_push->RIR >> 21; + + if (addr == 356) { + int torque_driver_new = ((to_push->RDLR & 0x7) << 8) | ((to_push->RDLR >> 8) & 0xFF); + torque_driver_new = to_signed(torque_driver_new, 11); + // update array of samples + update_sample(&cadillac_torque_driver, torque_driver_new); + } + + // this message isn't all zeros when ignition is on + if (addr == 0x160 && bus_number == 0) { + cadillac_ign = to_push->RDLR > 0; + } + + // enter controls on rising edge of ACC, exit controls on ACC off + if ((addr == 0x370) && (bus_number == 0)) { + int cruise_engaged = to_push->RDLR & 0x800000; // bit 23 + if (cruise_engaged && !cadillac_cruise_engaged_last) { + controls_allowed = 1; + } else if (!cruise_engaged) { + controls_allowed = 0; + } + cadillac_cruise_engaged_last = cruise_engaged; + } + + // know supercruise mode and block openpilot msgs if on + if ((addr == 0x152) || (addr == 0x154)) { + cadillac_supercruise_on = (to_push->RDHR>>4) & 0x1; + } +} + +static int cadillac_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) { + uint32_t addr = to_send->RIR >> 21; + + // steer cmd checks + if (addr == 0x151 || addr == 0x152 || addr == 0x153 || addr == 0x154) { + int desired_torque = ((to_send->RDLR & 0x3f) << 8) + ((to_send->RDLR & 0xff00) >> 8); + int violation = 0; + uint32_t ts = TIM2->CNT; + int idx = cadillac_get_torque_idx(addr); + desired_torque = to_signed(desired_torque, 14); + + if (controls_allowed) { + + // *** global torque limit check *** + violation |= max_limit_check(desired_torque, CADILLAC_MAX_STEER, -CADILLAC_MAX_STEER); + + // *** torque rate limit check *** + int desired_torque_last = cadillac_desired_torque_last[idx]; + violation |= driver_limit_check(desired_torque, desired_torque_last, &cadillac_torque_driver, + CADILLAC_MAX_STEER, CADILLAC_MAX_RATE_UP, CADILLAC_MAX_RATE_DOWN, + CADILLAC_DRIVER_TORQUE_ALLOWANCE, CADILLAC_DRIVER_TORQUE_FACTOR); + + // used next time + cadillac_desired_torque_last[idx] = desired_torque; + + // *** torque real time rate limit check *** + violation |= rt_rate_limit_check(desired_torque, cadillac_rt_torque_last, CADILLAC_MAX_RT_DELTA); + + // every RT_INTERVAL set the new limits + uint32_t ts_elapsed = get_ts_elapsed(ts, cadillac_ts_last); + if (ts_elapsed > CADILLAC_RT_INTERVAL) { + cadillac_rt_torque_last = desired_torque; + cadillac_ts_last = ts; + } + } + + // no torque if controls is not allowed + if (!controls_allowed && (desired_torque != 0)) { + violation = 1; + } + + // reset to 0 if either controls is not allowed or there's a violation + if (violation || !controls_allowed) { + cadillac_desired_torque_last[idx] = 0; + cadillac_rt_torque_last = 0; + cadillac_ts_last = ts; + } + + if (violation || cadillac_supercruise_on) { + return false; + } + + } + return true; +} + +static void cadillac_init(int16_t param) { + controls_allowed = 0; + cadillac_ign = 0; +} + +static int cadillac_ign_hook() { + return cadillac_ign; +} + +const safety_hooks cadillac_hooks = { + .init = cadillac_init, + .rx = cadillac_rx_hook, + .tx = cadillac_tx_hook, + .tx_lin = nooutput_tx_lin_hook, + .ignition = cadillac_ign_hook, + .fwd = alloutput_fwd_hook, +}; diff --git a/panda/board/safety/safety_chrysler.h b/panda/board/safety/safety_chrysler.h new file mode 100644 index 00000000000000..b1c6a743f10258 --- /dev/null +++ b/panda/board/safety/safety_chrysler.h @@ -0,0 +1,136 @@ +const int CHRYSLER_MAX_STEER = 261; +const int CHRYSLER_MAX_RT_DELTA = 112; // max delta torque allowed for real time checks +const int32_t CHRYSLER_RT_INTERVAL = 250000; // 250ms between real time checks +const int CHRYSLER_MAX_RATE_UP = 3; +const int CHRYSLER_MAX_RATE_DOWN = 3; +const int CHRYSLER_MAX_TORQUE_ERROR = 80; // max torque cmd in excess of torque motor + +int chrysler_camera_detected = 0; +int chrysler_rt_torque_last = 0; +int chrysler_desired_torque_last = 0; +int chrysler_cruise_engaged_last = 0; +uint32_t chrysler_ts_last = 0; +struct sample_t chrysler_torque_meas; // last few torques measured + +static void chrysler_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) { + int bus = (to_push->RDTR >> 4) & 0xFF; + uint32_t addr; + if (to_push->RIR & 4) { + // Extended + // Not looked at, but have to be separated + // to avoid address collision + addr = to_push->RIR >> 3; + } else { + // Normal + addr = to_push->RIR >> 21; + } + + // Measured eps torque + if (addr == 544) { + int rdhr = to_push->RDHR; + int torque_meas_new = ((rdhr & 0x7) << 8) + ((rdhr & 0xFF00) >> 8) - 1024; + + // update array of samples + update_sample(&chrysler_torque_meas, torque_meas_new); + } + + // enter controls on rising edge of ACC, exit controls on ACC off + if (addr == 0x1f4) { + int cruise_engaged = ((to_push->RDLR & 0x380000) >> 19) == 7; + if (cruise_engaged && !chrysler_cruise_engaged_last) { + controls_allowed = 1; + } else if (!cruise_engaged) { + controls_allowed = 0; + } + chrysler_cruise_engaged_last = cruise_engaged; + } + + // check if stock camera ECU is still online + if (bus == 0 && addr == 0x292) { + chrysler_camera_detected = 1; + controls_allowed = 0; + } +} + +static int chrysler_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) { + + // There can be only one! (camera) + if (chrysler_camera_detected) { + return 0; + } + + uint32_t addr; + if (to_send->RIR & 4) { + // Extended + addr = to_send->RIR >> 3; + } else { + // Normal + addr = to_send->RIR >> 21; + } + + + // LKA STEER + if (addr == 0x292) { + int rdlr = to_send->RDLR; + int desired_torque = ((rdlr & 0x7) << 8) + ((rdlr & 0xFF00) >> 8) - 1024; + uint32_t ts = TIM2->CNT; + int violation = 0; + + if (controls_allowed) { + + // *** global torque limit check *** + violation |= max_limit_check(desired_torque, CHRYSLER_MAX_STEER, -CHRYSLER_MAX_STEER); + + // *** torque rate limit check *** + violation |= dist_to_meas_check(desired_torque, chrysler_desired_torque_last, + &chrysler_torque_meas, CHRYSLER_MAX_RATE_UP, CHRYSLER_MAX_RATE_DOWN, CHRYSLER_MAX_TORQUE_ERROR); + + // used next time + chrysler_desired_torque_last = desired_torque; + + // *** torque real time rate limit check *** + violation |= rt_rate_limit_check(desired_torque, chrysler_rt_torque_last, CHRYSLER_MAX_RT_DELTA); + + // every RT_INTERVAL set the new limits + uint32_t ts_elapsed = get_ts_elapsed(ts, chrysler_ts_last); + if (ts_elapsed > CHRYSLER_RT_INTERVAL) { + chrysler_rt_torque_last = desired_torque; + chrysler_ts_last = ts; + } + } + + // no torque if controls is not allowed + if (!controls_allowed && (desired_torque != 0)) { + violation = 1; + } + + // reset to 0 if either controls is not allowed or there's a violation + if (violation || !controls_allowed) { + chrysler_desired_torque_last = 0; + chrysler_rt_torque_last = 0; + chrysler_ts_last = ts; + } + + if (violation) { + return false; + } + } + + // FORCE CANCEL: safety check only relevant when spamming the cancel button. + // ensuring that only the cancel button press is sent when controls are off. + // This avoids unintended engagements while still allowing resume spam + // TODO: fix bug preventing the button msg to be fwd'd on bus 2 + + // 1 allows the message through + return true; +} + + +const safety_hooks chrysler_hooks = { + .init = nooutput_init, + .rx = chrysler_rx_hook, + .tx = chrysler_tx_hook, + .tx_lin = nooutput_tx_lin_hook, + .ignition = default_ign_hook, + .fwd = nooutput_fwd_hook, +}; diff --git a/panda/board/safety/safety_defaults.h b/panda/board/safety/safety_defaults.h new file mode 100644 index 00000000000000..196df65d2f8eb6 --- /dev/null +++ b/panda/board/safety/safety_defaults.h @@ -0,0 +1,59 @@ +void default_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {} + +int default_ign_hook() { + return -1; // use GPIO to determine ignition +} + +// *** no output safety mode *** + +static void nooutput_init(int16_t param) { + controls_allowed = 0; +} + +static int nooutput_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) { + return false; +} + +static int nooutput_tx_lin_hook(int lin_num, uint8_t *data, int len) { + return false; +} + +static int nooutput_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) { + return -1; +} + +const safety_hooks nooutput_hooks = { + .init = nooutput_init, + .rx = default_rx_hook, + .tx = nooutput_tx_hook, + .tx_lin = nooutput_tx_lin_hook, + .ignition = default_ign_hook, + .fwd = nooutput_fwd_hook, +}; + +// *** all output safety mode *** + +static void alloutput_init(int16_t param) { + controls_allowed = 1; +} + +static int alloutput_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) { + return true; +} + +static int alloutput_tx_lin_hook(int lin_num, uint8_t *data, int len) { + return true; +} + +static int alloutput_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) { + return -1; +} + +const safety_hooks alloutput_hooks = { + .init = alloutput_init, + .rx = default_rx_hook, + .tx = alloutput_tx_hook, + .tx_lin = alloutput_tx_lin_hook, + .ignition = default_ign_hook, + .fwd = alloutput_fwd_hook, +}; diff --git a/panda/board/safety/safety_elm327.h b/panda/board/safety/safety_elm327.h new file mode 100644 index 00000000000000..98dce6532ac8ba --- /dev/null +++ b/panda/board/safety/safety_elm327.h @@ -0,0 +1,45 @@ +static void elm327_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {} + +static int elm327_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) { + //All ELM traffic must appear on CAN0 + if(((to_send->RDTR >> 4) & 0xf) != 0) return 0; + //All ISO 15765-4 messages must be 8 bytes long + if((to_send->RDTR & 0xf) != 8) return 0; + + if(to_send->RIR & 4){ + uint32_t addr = to_send->RIR >> 3; + //Check valid 29 bit send addresses for ISO 15765-4 + if(!(addr == 0x18DB33F1 || (addr & 0x1FFF00FF) == 0x18DA00F1)) return 0; + } else { + uint32_t addr = to_send->RIR >> 21; + //Check valid 11 bit send addresses for ISO 15765-4 + if(!(addr == 0x7DF || (addr & 0x7F8) == 0x7E0)) return 0; + } + + return true; +} + +static int elm327_tx_lin_hook(int lin_num, uint8_t *data, int len) { + if(lin_num != 0) return false; //Only operate on LIN 0, aka serial 2 + if(len < 5 || len > 11) return false; //Valid KWP size + if(!((data[0] & 0xF8) == 0xC0 && (data[0] & 0x07) > 0 && + data[1] == 0x33 && data[2] == 0xF1)) return false; //Bad msg + return true; +} + +static void elm327_init(int16_t param) { + controls_allowed = 1; +} + +static int elm327_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) { + return -1; +} + +const safety_hooks elm327_hooks = { + .init = elm327_init, + .rx = elm327_rx_hook, + .tx = elm327_tx_hook, + .tx_lin = elm327_tx_lin_hook, + .ignition = default_ign_hook, + .fwd = elm327_fwd_hook, +}; diff --git a/panda/board/safety/safety_ford.h b/panda/board/safety/safety_ford.h new file mode 100644 index 00000000000000..075029fb623e0f --- /dev/null +++ b/panda/board/safety/safety_ford.h @@ -0,0 +1,93 @@ +// board enforces +// in-state +// accel set/resume +// out-state +// cancel button +// accel rising edge +// brake rising edge +// brake > 0mph + +int ford_brake_prev = 0; +int ford_gas_prev = 0; +int ford_is_moving = 0; + +static void ford_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) { + + if ((to_push->RIR>>21) == 0x217) { + // wheel speeds are 14 bits every 16 + ford_is_moving = 0xFCFF & (to_push->RDLR | (to_push->RDLR >> 16) | + to_push->RDHR | (to_push->RDHR >> 16)); + } + + // state machine to enter and exit controls + if ((to_push->RIR>>21) == 0x83) { + int cancel = ((to_push->RDLR >> 8) & 0x1); + int set_or_resume = (to_push->RDLR >> 28) & 0x3; + if (cancel) { + controls_allowed = 0; + } else if (set_or_resume) { + controls_allowed = 1; + } + } + + // exit controls on rising edge of brake press or on brake press when + // speed > 0 + if ((to_push->RIR>>21) == 0x165) { + int brake = to_push->RDLR & 0x20; + if (brake && (!(ford_brake_prev) || ford_is_moving)) { + controls_allowed = 0; + } + ford_brake_prev = brake; + } + + // exit controls on rising edge of gas press + if ((to_push->RIR>>21) == 0x204) { + int gas = to_push->RDLR & 0xFF03; + if (gas && !(ford_gas_prev)) { + controls_allowed = 0; + } + ford_gas_prev = gas; + } +} + +// all commands: just steering +// if controls_allowed and no pedals pressed +// allow all commands up to limit +// else +// block all commands that produce actuation + +static int ford_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) { + + // disallow actuator commands if gas or brake (with vehicle moving) are pressed + // and the the latching controls_allowed flag is True + int pedal_pressed = ford_gas_prev || (ford_brake_prev && ford_is_moving); + int current_controls_allowed = controls_allowed && !(pedal_pressed); + + // STEER: safety check + if ((to_send->RIR>>21) == 0x3CA) { + if (current_controls_allowed) { + // all messages are fine here + } else { + // bits 7-4 need to be 0xF to disallow lkas commands + if (((to_send->RDLR >> 4) & 0xF) != 0xF) return 0; + } + } + + // FORCE CANCEL: safety check only relevant when spamming the cancel button + // ensuring that set and resume aren't sent + if ((to_send->RIR>>21) == 0x83) { + if ((to_send->RDLR >> 28) & 0x3) return 0; + } + + // 1 allows the message through + return true; +} + +const safety_hooks ford_hooks = { + .init = nooutput_init, + .rx = ford_rx_hook, + .tx = ford_tx_hook, + .tx_lin = nooutput_tx_lin_hook, + .ignition = default_ign_hook, + .fwd = nooutput_fwd_hook, +}; diff --git a/panda/board/safety/safety_gm.h b/panda/board/safety/safety_gm.h new file mode 100644 index 00000000000000..f35b26b4ef84d3 --- /dev/null +++ b/panda/board/safety/safety_gm.h @@ -0,0 +1,245 @@ +// board enforces +// in-state +// accel set/resume +// out-state +// cancel button +// regen paddle +// accel rising edge +// brake rising edge +// brake > 0mph + +const int GM_MAX_STEER = 300; +const int GM_MAX_RT_DELTA = 128; // max delta torque allowed for real time checks +const int32_t GM_RT_INTERVAL = 250000; // 250ms between real time checks +const int GM_MAX_RATE_UP = 7; +const int GM_MAX_RATE_DOWN = 17; +const int GM_DRIVER_TORQUE_ALLOWANCE = 50; +const int GM_DRIVER_TORQUE_FACTOR = 4; +const int GM_MAX_GAS = 3072; +const int GM_MAX_REGEN = 1404; +const int GM_MAX_BRAKE = 350; + +int gm_brake_prev = 0; +int gm_gas_prev = 0; +int gm_speed = 0; +// silence everything if stock car control ECUs are still online +int gm_ascm_detected = 0; +int gm_ignition_started = 0; +int gm_rt_torque_last = 0; +int gm_desired_torque_last = 0; +uint32_t gm_ts_last = 0; +struct sample_t gm_torque_driver; // last few driver torques measured + +static void gm_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) { + int bus_number = (to_push->RDTR >> 4) & 0xFF; + uint32_t addr; + if (to_push->RIR & 4) { + // Extended + // Not looked at, but have to be separated + // to avoid address collision + addr = to_push->RIR >> 3; + } else { + // Normal + addr = to_push->RIR >> 21; + } + + if (addr == 388) { + int torque_driver_new = (((to_push->RDHR >> 16) & 0x7) << 8) | ((to_push->RDHR >> 24) & 0xFF); + torque_driver_new = to_signed(torque_driver_new, 11); + // update array of samples + update_sample(&gm_torque_driver, torque_driver_new); + } + + if (addr == 0x1f1 && bus_number == 0) { + //Bit 5 should be ignition "on" + //Backup plan is Bit 2 (accessory power) + uint32_t ign = (to_push->RDLR) & 0x20; + gm_ignition_started = ign > 0; + } + + // sample speed, really only care if car is moving or not + // rear left wheel speed + if (addr == 842) { + gm_speed = to_push->RDLR & 0xFFFF; + } + + // Check if ASCM or LKA camera are online + // on powertrain bus. + // 384 = ASCMLKASteeringCmd + // 715 = ASCMGasRegenCmd + if (bus_number == 0 && (addr == 384 || addr == 715)) { + gm_ascm_detected = 1; + controls_allowed = 0; + } + + // ACC steering wheel buttons + if (addr == 481) { + int buttons = (to_push->RDHR >> 12) & 0x7; + // res/set - enable, cancel button - disable + if (buttons == 2 || buttons == 3) { + controls_allowed = 1; + } else if (buttons == 6) { + controls_allowed = 0; + } + } + + // exit controls on rising edge of brake press or on brake press when + // speed > 0 + if (addr == 241) { + int brake = (to_push->RDLR & 0xFF00) >> 8; + // Brake pedal's potentiometer returns near-zero reading + // even when pedal is not pressed + if (brake < 10) { + brake = 0; + } + if (brake && (!gm_brake_prev || gm_speed)) { + controls_allowed = 0; + } + gm_brake_prev = brake; + } + + // exit controls on rising edge of gas press + if (addr == 417) { + int gas = to_push->RDHR & 0xFF0000; + if (gas && !gm_gas_prev) { + controls_allowed = 0; + } + gm_gas_prev = gas; + } + + // exit controls on regen paddle + if (addr == 189) { + int regen = to_push->RDLR & 0x20; + if (regen) { + controls_allowed = 0; + } + } +} + +// all commands: gas/regen, friction brake and steering +// if controls_allowed and no pedals pressed +// allow all commands up to limit +// else +// block all commands that produce actuation + +static int gm_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) { + + // There can be only one! (ASCM) + if (gm_ascm_detected) { + return 0; + } + + // disallow actuator commands if gas or brake (with vehicle moving) are pressed + // and the the latching controls_allowed flag is True + int pedal_pressed = gm_gas_prev || (gm_brake_prev && gm_speed); + int current_controls_allowed = controls_allowed && !pedal_pressed; + + uint32_t addr; + if (to_send->RIR & 4) { + // Extended + addr = to_send->RIR >> 3; + } else { + // Normal + addr = to_send->RIR >> 21; + } + + // BRAKE: safety check + if (addr == 789) { + int rdlr = to_send->RDLR; + int brake = ((rdlr & 0xF) << 8) + ((rdlr & 0xFF00) >> 8); + brake = (0x1000 - brake) & 0xFFF; + if (current_controls_allowed) { + if (brake > GM_MAX_BRAKE) return 0; + } else { + if (brake != 0) return 0; + } + } + + // LKA STEER: safety check + if (addr == 384) { + int rdlr = to_send->RDLR; + int desired_torque = ((rdlr & 0x7) << 8) + ((rdlr & 0xFF00) >> 8); + uint32_t ts = TIM2->CNT; + int violation = 0; + desired_torque = to_signed(desired_torque, 11); + + if (current_controls_allowed) { + + // *** global torque limit check *** + violation |= max_limit_check(desired_torque, GM_MAX_STEER, -GM_MAX_STEER); + + // *** torque rate limit check *** + violation |= driver_limit_check(desired_torque, gm_desired_torque_last, &gm_torque_driver, + GM_MAX_STEER, GM_MAX_RATE_UP, GM_MAX_RATE_DOWN, + GM_DRIVER_TORQUE_ALLOWANCE, GM_DRIVER_TORQUE_FACTOR); + + // used next time + gm_desired_torque_last = desired_torque; + + // *** torque real time rate limit check *** + violation |= rt_rate_limit_check(desired_torque, gm_rt_torque_last, GM_MAX_RT_DELTA); + + // every RT_INTERVAL set the new limits + uint32_t ts_elapsed = get_ts_elapsed(ts, gm_ts_last); + if (ts_elapsed > GM_RT_INTERVAL) { + gm_rt_torque_last = desired_torque; + gm_ts_last = ts; + } + } + + // no torque if controls is not allowed + if (!current_controls_allowed && (desired_torque != 0)) { + violation = 1; + } + + // reset to 0 if either controls is not allowed or there's a violation + if (violation || !current_controls_allowed) { + gm_desired_torque_last = 0; + gm_rt_torque_last = 0; + gm_ts_last = ts; + } + + if (violation) { + return false; + } + } + + // PARK ASSIST STEER: unlimited torque, no thanks + if (addr == 823) return 0; + + // GAS/REGEN: safety check + if (addr == 715) { + int rdlr = to_send->RDLR; + int gas_regen = ((rdlr & 0x7F0000) >> 11) + ((rdlr & 0xF8000000) >> 27); + int apply = rdlr & 1; + if (current_controls_allowed) { + if (gas_regen > GM_MAX_GAS) return 0; + } else { + // Disabled message is !engaed with gas + // value that corresponds to max regen. + if (apply || gas_regen != GM_MAX_REGEN) return 0; + } + } + + // 1 allows the message through + return true; +} + +static void gm_init(int16_t param) { + controls_allowed = 0; + gm_ignition_started = 0; +} + +static int gm_ign_hook() { + return gm_ignition_started; +} + +const safety_hooks gm_hooks = { + .init = gm_init, + .rx = gm_rx_hook, + .tx = gm_tx_hook, + .tx_lin = nooutput_tx_lin_hook, + .ignition = gm_ign_hook, + .fwd = nooutput_fwd_hook, +}; + diff --git a/panda/board/safety/safety_honda.h b/panda/board/safety/safety_honda.h new file mode 100644 index 00000000000000..fbee6cfe861f53 --- /dev/null +++ b/panda/board/safety/safety_honda.h @@ -0,0 +1,188 @@ +// board enforces +// in-state +// accel set/resume +// out-state +// cancel button +// accel rising edge +// brake rising edge +// brake > 0mph + +// these are set in the Honda safety hooks...this is the wrong place +const int gas_interceptor_threshold = 328; +int gas_interceptor_detected = 0; +int brake_prev = 0; +int gas_prev = 0; +int gas_interceptor_prev = 0; +int ego_speed = 0; +// TODO: auto-detect bosch hardware based on CAN messages? +bool bosch_hardware = false; +bool honda_alt_brake_msg = false; + +static void honda_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) { + + // sample speed + if ((to_push->RIR>>21) == 0x158) { + // first 2 bytes + ego_speed = to_push->RDLR & 0xFFFF; + } + + // state machine to enter and exit controls + // 0x1A6 for the ILX, 0x296 for the Civic Touring + if ((to_push->RIR>>21) == 0x1A6 || (to_push->RIR>>21) == 0x296) { + int buttons = (to_push->RDLR & 0xE0) >> 5; + if (buttons == 4 || buttons == 3) { + controls_allowed = 1; + } else if (buttons == 2) { + controls_allowed = 0; + } + } + + // user brake signal on 0x17C reports applied brake from computer brake on accord + // and crv, which prevents the usual brake safety from working correctly. these + // cars have a signal on 0x1BE which only detects user's brake being applied so + // in these cases, this is used instead. + // most hondas: 0x17C bit 53 + // accord, crv: 0x1BE bit 4 + #define IS_USER_BRAKE_MSG(to_push) (!honda_alt_brake_msg ? to_push->RIR>>21 == 0x17C : to_push->RIR>>21 == 0x1BE) + #define USER_BRAKE_VALUE(to_push) (!honda_alt_brake_msg ? to_push->RDHR & 0x200000 : to_push->RDLR & 0x10) + // exit controls on rising edge of brake press or on brake press when + // speed > 0 + if (IS_USER_BRAKE_MSG(to_push)) { + int brake = USER_BRAKE_VALUE(to_push); + if (brake && (!(brake_prev) || ego_speed)) { + controls_allowed = 0; + } + brake_prev = brake; + } + + // exit controls on rising edge of gas press if interceptor (0x201 w/ len = 6) + // length check because bosch hardware also uses this id (0x201 w/ len = 8) + if ((to_push->RIR>>21) == 0x201 && (to_push->RDTR & 0xf) == 6) { + gas_interceptor_detected = 1; + int gas_interceptor = ((to_push->RDLR & 0xFF) << 8) | ((to_push->RDLR & 0xFF00) >> 8); + if ((gas_interceptor > gas_interceptor_threshold) && + (gas_interceptor_prev <= gas_interceptor_threshold)) { + controls_allowed = 0; + } + gas_interceptor_prev = gas_interceptor; + } + + // exit controls on rising edge of gas press if no interceptor + if (!gas_interceptor_detected) { + if ((to_push->RIR>>21) == 0x17C) { + int gas = to_push->RDLR & 0xFF; + if (gas && !(gas_prev)) { + controls_allowed = 0; + } + gas_prev = gas; + } + } +} + +// all commands: gas, brake and steering +// if controls_allowed and no pedals pressed +// allow all commands up to limit +// else +// block all commands that produce actuation + +static int honda_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) { + + // disallow actuator commands if gas or brake (with vehicle moving) are pressed + // and the the latching controls_allowed flag is True + int pedal_pressed = gas_prev || (gas_interceptor_prev > gas_interceptor_threshold) || + (brake_prev && ego_speed); + int current_controls_allowed = controls_allowed && !(pedal_pressed); + + // BRAKE: safety check + if ((to_send->RIR>>21) == 0x1FA) { + if (current_controls_allowed) { + if ((to_send->RDLR & 0xFFFFFF3F) != to_send->RDLR) return 0; + } else { + if ((to_send->RDLR & 0xFFFF0000) != to_send->RDLR) return 0; + } + } + + // STEER: safety check + if ((to_send->RIR>>21) == 0xE4 || (to_send->RIR>>21) == 0x194) { + if (current_controls_allowed) { + // all messages are fine here + } else { + if ((to_send->RDLR & 0xFFFF0000) != to_send->RDLR) return 0; + } + } + + // GAS: safety check + if ((to_send->RIR>>21) == 0x200) { + if (current_controls_allowed) { + // all messages are fine here + } else { + if ((to_send->RDLR & 0xFFFF0000) != to_send->RDLR) return 0; + } + } + + // FORCE CANCEL: safety check only relevant when spamming the cancel button in Bosch HW + // ensuring that only the cancel button press is sent (VAL 2) when controls are off. + // This avoids unintended engagements while still allowing resume spam + if (((to_send->RIR>>21) == 0x296) && bosch_hardware && + !current_controls_allowed && ((to_send->RDTR >> 4) & 0xFF) == 0) { + if (((to_send->RDLR >> 5) & 0x7) != 2) return 0; + } + + // 1 allows the message through + return true; +} + +static void honda_init(int16_t param) { + controls_allowed = 0; + bosch_hardware = false; + honda_alt_brake_msg = false; +} + +static void honda_bosch_init(int16_t param) { + controls_allowed = 0; + bosch_hardware = true; + // Checking for alternate brake override from safety parameter + honda_alt_brake_msg = param == 1 ? true : false; +} + +static int honda_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) { + // fwd from car to camera. also fwd certain msgs from camera to car + // 0xE4 is steering on all cars except CRV and RDX, 0x194 for CRV and RDX, + // 0x1FA is brake control, 0x30C is acc hud, 0x33D is lkas hud, + // 0x39f is radar hud + int addr = to_fwd->RIR>>21; + if (bus_num == 0) { + return 2; + } else if (bus_num == 2 && addr != 0xE4 && addr != 0x194 && addr != 0x1FA && + addr != 0x30C && addr != 0x33D && addr != 0x39F) { + return 0; + } + + return -1; +} + +static int honda_bosch_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) { + if (bus_num == 1 || bus_num == 2) { + int addr = to_fwd->RIR>>21; + return addr != 0xE4 && addr != 0x33D ? (uint8_t)(~bus_num & 0x3) : -1; + } + return -1; +} + +const safety_hooks honda_hooks = { + .init = honda_init, + .rx = honda_rx_hook, + .tx = honda_tx_hook, + .tx_lin = nooutput_tx_lin_hook, + .ignition = default_ign_hook, + .fwd = honda_fwd_hook, +}; + +const safety_hooks honda_bosch_hooks = { + .init = honda_bosch_init, + .rx = honda_rx_hook, + .tx = honda_tx_hook, + .tx_lin = nooutput_tx_lin_hook, + .ignition = default_ign_hook, + .fwd = honda_bosch_fwd_hook, +}; diff --git a/panda/board/safety/safety_hyundai.h b/panda/board/safety/safety_hyundai.h new file mode 100644 index 00000000000000..caac727303716e --- /dev/null +++ b/panda/board/safety/safety_hyundai.h @@ -0,0 +1,164 @@ +const int HYUNDAI_MAX_STEER = 250; +const int HYUNDAI_MAX_RT_DELTA = 112; // max delta torque allowed for real time checks +const int32_t HYUNDAI_RT_INTERVAL = 250000; // 250ms between real time checks +const int HYUNDAI_MAX_RATE_UP = 3; +const int HYUNDAI_MAX_RATE_DOWN = 7; +const int HYUNDAI_DRIVER_TORQUE_ALLOWANCE = 50; +const int HYUNDAI_DRIVER_TORQUE_FACTOR = 2; + +int hyundai_camera_detected = 0; +int hyundai_camera_bus = 0; +int hyundai_giraffe_switch_2 = 0; // is giraffe switch 2 high? +int hyundai_rt_torque_last = 0; +int hyundai_desired_torque_last = 0; +int hyundai_cruise_engaged_last = 0; +uint32_t hyundai_ts_last = 0; +struct sample_t hyundai_torque_driver; // last few driver torques measured + +static void hyundai_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) { + int bus = (to_push->RDTR >> 4) & 0xFF; + uint32_t addr; + if (to_push->RIR & 4) { + // Extended + // Not looked at, but have to be separated + // to avoid address collision + addr = to_push->RIR >> 3; + } else { + // Normal + addr = to_push->RIR >> 21; + } + + if (addr == 897) { + int torque_driver_new = ((to_push->RDLR >> 11) & 0xfff) - 2048; + // update array of samples + update_sample(&hyundai_torque_driver, torque_driver_new); + } + + // check if stock camera ECU is still online + if (bus == 0 && addr == 832) { + hyundai_camera_detected = 1; + controls_allowed = 0; + } + + // Find out which bus the camera is on + if (addr == 832) { + hyundai_camera_bus = bus; + } + + // enter controls on rising edge of ACC, exit controls on ACC off + if ((to_push->RIR>>21) == 1057) { + // 2 bits: 13-14 + int cruise_engaged = (to_push->RDLR >> 13) & 0x3; + if (cruise_engaged && !hyundai_cruise_engaged_last) { + controls_allowed = 1; + } else if (!cruise_engaged) { + controls_allowed = 0; + } + hyundai_cruise_engaged_last = cruise_engaged; + } + + // 832 is lkas cmd. If it is on camera bus, then giraffe switch 2 is high + if ((to_push->RIR>>21) == 832 && (bus == hyundai_camera_bus) && (hyundai_camera_bus != 0)) { + hyundai_giraffe_switch_2 = 1; + } +} + +static int hyundai_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) { + + // There can be only one! (camera) + if (hyundai_camera_detected) { + return 0; + } + + uint32_t addr; + if (to_send->RIR & 4) { + // Extended + addr = to_send->RIR >> 3; + } else { + // Normal + addr = to_send->RIR >> 21; + } + + // LKA STEER: safety check + if (addr == 832) { + int desired_torque = ((to_send->RDLR >> 16) & 0x7ff) - 1024; + uint32_t ts = TIM2->CNT; + int violation = 0; + + if (controls_allowed) { + + // *** global torque limit check *** + violation |= max_limit_check(desired_torque, HYUNDAI_MAX_STEER, -HYUNDAI_MAX_STEER); + + // *** torque rate limit check *** + violation |= driver_limit_check(desired_torque, hyundai_desired_torque_last, &hyundai_torque_driver, + HYUNDAI_MAX_STEER, HYUNDAI_MAX_RATE_UP, HYUNDAI_MAX_RATE_DOWN, + HYUNDAI_DRIVER_TORQUE_ALLOWANCE, HYUNDAI_DRIVER_TORQUE_FACTOR); + + // used next time + hyundai_desired_torque_last = desired_torque; + + // *** torque real time rate limit check *** + violation |= rt_rate_limit_check(desired_torque, hyundai_rt_torque_last, HYUNDAI_MAX_RT_DELTA); + + // every RT_INTERVAL set the new limits + uint32_t ts_elapsed = get_ts_elapsed(ts, hyundai_ts_last); + if (ts_elapsed > HYUNDAI_RT_INTERVAL) { + hyundai_rt_torque_last = desired_torque; + hyundai_ts_last = ts; + } + } + + // no torque if controls is not allowed + if (!controls_allowed && (desired_torque != 0)) { + violation = 1; + } + + // reset to 0 if either controls is not allowed or there's a violation + if (violation || !controls_allowed) { + hyundai_desired_torque_last = 0; + hyundai_rt_torque_last = 0; + hyundai_ts_last = ts; + } + + if (violation) { + return false; + } + } + + // FORCE CANCEL: safety check only relevant when spamming the cancel button. + // ensuring that only the cancel button press is sent (VAL 4) when controls are off. + // This avoids unintended engagements while still allowing resume spam + // TODO: fix bug preventing the button msg to be fwd'd on bus 2 + //if (((to_send->RIR>>21) == 1265) && !controls_allowed && ((to_send->RDTR >> 4) & 0xFF) == 0) { + // if ((to_send->RDLR & 0x7) != 4) return 0; + //} + + // 1 allows the message through + return true; +} + +static int hyundai_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) { + // forward cam to ccan and viceversa, except lkas cmd + if ((bus_num == 0 || bus_num == hyundai_camera_bus) && hyundai_giraffe_switch_2) { + + if ((to_fwd->RIR>>21) == 832 && bus_num == hyundai_camera_bus) return -1; + if (bus_num == 0) return hyundai_camera_bus; + if (bus_num == hyundai_camera_bus) return 0; + } + return -1; +} + +static void hyundai_init(int16_t param) { + controls_allowed = 0; + hyundai_giraffe_switch_2 = 0; +} + +const safety_hooks hyundai_hooks = { + .init = hyundai_init, + .rx = hyundai_rx_hook, + .tx = hyundai_tx_hook, + .tx_lin = nooutput_tx_lin_hook, + .ignition = default_ign_hook, + .fwd = hyundai_fwd_hook, +}; diff --git a/panda/board/safety/safety_tesla.h b/panda/board/safety/safety_tesla.h new file mode 100644 index 00000000000000..78c450e85e31c6 --- /dev/null +++ b/panda/board/safety/safety_tesla.h @@ -0,0 +1,287 @@ +// board enforces +// in-state +// accel set/resume +// out-state +// cancel button +// regen paddle +// accel rising edge +// brake rising edge +// brake > 0mph +// +int fmax_limit_check(float val, const float MAX, const float MIN) { + return (val > MAX) || (val < MIN); +} + +// 2m/s are added to be less restrictive +const struct lookup_t TESLA_LOOKUP_ANGLE_RATE_UP = { + {2., 7., 17.}, + {5., .8, .25}}; + +const struct lookup_t TESLA_LOOKUP_ANGLE_RATE_DOWN = { + {2., 7., 17.}, + {5., 3.5, .8}}; + +const struct lookup_t TESLA_LOOKUP_MAX_ANGLE = { + {2., 29., 38.}, + {410., 92., 36.}}; + +const int TESLA_RT_INTERVAL = 250000; // 250ms between real time checks + +// state of angle limits +float tesla_desired_angle_last = 0; // last desired steer angle +float tesla_rt_angle_last = 0.; // last real time angle +float tesla_ts_angle_last = 0; + +int tesla_controls_allowed_last = 0; + +int tesla_brake_prev = 0; +int tesla_gas_prev = 0; +int tesla_speed = 0; +int eac_status = 0; + +int tesla_ignition_started = 0; + + +void set_gmlan_digital_output(int to_set); +void reset_gmlan_switch_timeout(void); +void gmlan_switch_init(int timeout_enable); + + +static void tesla_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) +{ + set_gmlan_digital_output(0); // #define GMLAN_HIGH 0 + reset_gmlan_switch_timeout(); //we're still in tesla safety mode, reset the timeout counter and make sure our output is enabled + + //int bus_number = (to_push->RDTR >> 4) & 0xFF; + uint32_t addr; + if (to_push->RIR & 4) + { + // Extended + // Not looked at, but have to be separated + // to avoid address collision + addr = to_push->RIR >> 3; + } + else + { + // Normal + addr = to_push->RIR >> 21; + } + + if (addr == 0x45) + { + // 6 bits starting at position 0 + int lever_position = (to_push->RDLR & 0x3F); + if (lever_position == 2) + { // pull forward + // activate openpilot + controls_allowed = 1; + //} + } + else if (lever_position == 1) + { // push towards the back + // deactivate openpilot + controls_allowed = 0; + } + } + + // Detect drive rail on (ignition) (start recording) + if (addr == 0x348) + { + // GTW_status + int drive_rail_on = (to_push->RDLR & 0x0001); + tesla_ignition_started = drive_rail_on == 1; + } + + // exit controls on brake press + // DI_torque2::DI_brakePedal 0x118 + if (addr == 0x118) + { + // 1 bit at position 16 + if (((to_push->RDLR & 0x8000)) >> 15 == 1) + { + //disable break cancel by commenting line below + controls_allowed = 0; + } + //get vehicle speed in m/s. Tesla gives MPH + tesla_speed = ((((((to_push->RDLR >> 24) & 0x0F) << 8) + ((to_push->RDLR >> 16) & 0xFF)) * 0.05 - 25) * 1.609 / 3.6); + if (tesla_speed < 0) + { + tesla_speed = 0; + } + } + + // exit controls on EPAS error + // EPAS_sysStatus::EPAS_eacStatus 0x370 + if (addr == 0x370) + { + // if EPAS_eacStatus is not 1 or 2, disable control + eac_status = ((to_push->RDHR >> 21)) & 0x7; + // For human steering override we must not disable controls when eac_status == 0 + // Additional safety: we could only allow eac_status == 0 when we have human steering allowed + if ((controls_allowed == 1) && (eac_status != 0) && (eac_status != 1) && (eac_status != 2)) + { + controls_allowed = 0; + //puts("EPAS error! \n"); + } + } + //get latest steering wheel angle + if (addr == 0x00E) + { + float angle_meas_now = (int)((((to_push->RDLR & 0x3F) << 8) + ((to_push->RDLR >> 8) & 0xFF)) * 0.1 - 819.2); + uint32_t ts = TIM2->CNT; + uint32_t ts_elapsed = get_ts_elapsed(ts, tesla_ts_angle_last); + + // *** angle real time check + // add 1 to not false trigger the violation and multiply by 25 since the check is done every 250 ms and steer angle is updated at 100Hz + float rt_delta_angle_up = interpolate(TESLA_LOOKUP_ANGLE_RATE_UP, tesla_speed) * 25. + 1.; + float rt_delta_angle_down = interpolate(TESLA_LOOKUP_ANGLE_RATE_DOWN, tesla_speed) * 25. + 1.; + float highest_rt_angle = tesla_rt_angle_last + (tesla_rt_angle_last > 0 ? rt_delta_angle_up : rt_delta_angle_down); + float lowest_rt_angle = tesla_rt_angle_last - (tesla_rt_angle_last > 0 ? rt_delta_angle_down : rt_delta_angle_up); + + if ((ts_elapsed > TESLA_RT_INTERVAL) || (controls_allowed && !tesla_controls_allowed_last)) + { + tesla_rt_angle_last = angle_meas_now; + tesla_ts_angle_last = ts; + } + + // check for violation; + if (fmax_limit_check(angle_meas_now, highest_rt_angle, lowest_rt_angle)) + { + // We should not be able to STEER under these conditions + // Other sending is fine (to allow human override) + controls_allowed = 0; + //puts("WARN: RT Angle - No steer allowed! \n"); + } + else + { + controls_allowed = 1; + } + + tesla_controls_allowed_last = controls_allowed; + } +} + +// all commands: gas/regen, friction brake and steering +// if controls_allowed and no pedals pressed +// allow all commands up to limit +// else +// block all commands that produce actuation + +static int tesla_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) +{ + + uint32_t addr; + float angle_raw; + float desired_angle; + + addr = to_send->RIR >> 21; + + // do not transmit CAN message if steering angle too high + // DAS_steeringControl::DAS_steeringAngleRequest + if (addr == 0x488) + { + angle_raw = ((to_send->RDLR & 0x7F) << 8) + ((to_send->RDLR & 0xFF00) >> 8); + desired_angle = angle_raw * 0.1 - 1638.35; + int16_t violation = 0; + int st_enabled = (to_send->RDLR & 0x400000) >> 22; + + if (st_enabled == 0) { + //steering is not enabled, do not check angles and do send + tesla_desired_angle_last = desired_angle; + return true; + } + + if (controls_allowed) + { + // add 1 to not false trigger the violation + float delta_angle_up = interpolate(TESLA_LOOKUP_ANGLE_RATE_UP, tesla_speed) + 1.; + float delta_angle_down = interpolate(TESLA_LOOKUP_ANGLE_RATE_DOWN, tesla_speed) + 1.; + float highest_desired_angle = tesla_desired_angle_last + (tesla_desired_angle_last > 0 ? delta_angle_up : delta_angle_down); + float lowest_desired_angle = tesla_desired_angle_last - (tesla_desired_angle_last > 0 ? delta_angle_down : delta_angle_up); + float TESLA_MAX_ANGLE = interpolate(TESLA_LOOKUP_MAX_ANGLE, tesla_speed) + 1.; + + //check for max angles + violation |= fmax_limit_check(desired_angle, TESLA_MAX_ANGLE, -TESLA_MAX_ANGLE); + + //check for angle delta changes + violation |= fmax_limit_check(desired_angle, highest_desired_angle, lowest_desired_angle); + + if (violation) + { + controls_allowed = 0; + return false; + } + tesla_desired_angle_last = desired_angle; + return true; + } + return false; + } + return true; +} + +static int tesla_tx_lin_hook(int lin_num, uint8_t *data, int len) +{ + // LIN is not used on the Tesla + return false; +} + +static void tesla_init(int16_t param) +{ + controls_allowed = 0; + tesla_ignition_started = 0; + gmlan_switch_init(1); //init the gmlan switch with 1s timeout enabled +} + +static int tesla_ign_hook() +{ + return tesla_ignition_started; +} + +static int tesla_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) +{ + + int32_t addr = to_fwd->RIR >> 21; + + if (bus_num == 0) + { + + // change inhibit of GTW_epasControl + if (addr == 0x101) + { + to_fwd->RDLR = to_fwd->RDLR | 0x4000; // 0x4000: WITH_ANGLE, 0xC000: WITH_BOTH (angle and torque) + int checksum = (((to_fwd->RDLR & 0xFF00) >> 8) + (to_fwd->RDLR & 0xFF) + 2) & 0xFF; + to_fwd->RDLR = to_fwd->RDLR & 0xFFFF; + to_fwd->RDLR = to_fwd->RDLR + (checksum << 16); + return 2; + } + + // remove EPB_epasControl + if (addr == 0x214) + { + return -1; + } + + return 2; // Custom EPAS bus + } + if (bus_num == 2) + { + + // remove GTW_epasControl in forwards + if (addr == 0x101) + { + return -1; + } + + return 0; // Chassis CAN + } + return -1; +} + +const safety_hooks tesla_hooks = { + .init = tesla_init, + .rx = tesla_rx_hook, + .tx = tesla_tx_hook, + .tx_lin = tesla_tx_lin_hook, + .ignition = tesla_ign_hook, + .fwd = tesla_fwd_hook, +}; diff --git a/panda/board/safety/safety_toyota.h b/panda/board/safety/safety_toyota.h new file mode 100644 index 00000000000000..9cab1512f167cb --- /dev/null +++ b/panda/board/safety/safety_toyota.h @@ -0,0 +1,192 @@ +int toyota_giraffe_switch_1 = 0; // is giraffe switch 1 high? +int toyota_camera_forwarded = 0; // should we forward the camera bus? + +// global torque limit +const int TOYOTA_MAX_TORQUE = 1500; // max torque cmd allowed ever + +// rate based torque limit + stay within actually applied +// packet is sent at 100hz, so this limit is 1000/sec +const int TOYOTA_MAX_RATE_UP = 10; // ramp up slow +const int TOYOTA_MAX_RATE_DOWN = 25; // ramp down fast +const int TOYOTA_MAX_TORQUE_ERROR = 350; // max torque cmd in excess of torque motor + +// real time torque limit to prevent controls spamming +// the real time limit is 1500/sec +const int TOYOTA_MAX_RT_DELTA = 375; // max delta torque allowed for real time checks +const int TOYOTA_RT_INTERVAL = 250000; // 250ms between real time checks + +// longitudinal limits +const int TOYOTA_MAX_ACCEL = 1500; // 1.5 m/s2 +const int TOYOTA_MIN_ACCEL = -3000; // 3.0 m/s2 + +// global actuation limit state +int toyota_actuation_limits = 1; // by default steer limits are imposed +int toyota_dbc_eps_torque_factor = 100; // conversion factor for STEER_TORQUE_EPS in %: see dbc file + +// state of torque limits +int toyota_desired_torque_last = 0; // last desired steer torque +int toyota_rt_torque_last = 0; // last desired torque for real time check +uint32_t toyota_ts_last = 0; +int toyota_cruise_engaged_last = 0; // cruise state +struct sample_t toyota_torque_meas; // last 3 motor torques produced by the eps + + +static void toyota_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) { + // get eps motor torque (0.66 factor in dbc) + if ((to_push->RIR>>21) == 0x260) { + int torque_meas_new = (((to_push->RDHR) & 0xFF00) | ((to_push->RDHR >> 16) & 0xFF)); + torque_meas_new = to_signed(torque_meas_new, 16); + + // scale by dbc_factor + torque_meas_new = (torque_meas_new * toyota_dbc_eps_torque_factor) / 100; + + // increase torque_meas by 1 to be conservative on rounding + torque_meas_new += (torque_meas_new > 0 ? 1 : -1); + + // update array of sample + update_sample(&toyota_torque_meas, torque_meas_new); + } + + // enter controls on rising edge of ACC, exit controls on ACC off + if ((to_push->RIR>>21) == 0x1D2) { + // 5th bit is CRUISE_ACTIVE + int cruise_engaged = to_push->RDLR & 0x20; + if (cruise_engaged && !toyota_cruise_engaged_last) { + controls_allowed = 1; + } else if (!cruise_engaged) { + controls_allowed = 0; + } + toyota_cruise_engaged_last = cruise_engaged; + } + + int bus = (to_push->RDTR >> 4) & 0xF; + // msgs are only on bus 2 if panda is connected to frc + if (bus == 2) { + toyota_camera_forwarded = 1; + } + + // 0x2E4 is lkas cmd. If it is on bus 0, then giraffe switch 1 is high + if ((to_push->RIR>>21) == 0x2E4 && (bus == 0)) { + toyota_giraffe_switch_1 = 1; + } +} + +static int toyota_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) { + + // Check if msg is sent on BUS 0 + if (((to_send->RDTR >> 4) & 0xF) == 0) { + + // no IPAS in non IPAS mode + if (((to_send->RIR>>21) == 0x266) || ((to_send->RIR>>21) == 0x167)) return false; + + // ACCEL: safety check on byte 1-2 + if ((to_send->RIR>>21) == 0x343) { + int desired_accel = ((to_send->RDLR & 0xFF) << 8) | ((to_send->RDLR >> 8) & 0xFF); + desired_accel = to_signed(desired_accel, 16); + if (controls_allowed && toyota_actuation_limits) { + int violation = max_limit_check(desired_accel, TOYOTA_MAX_ACCEL, TOYOTA_MIN_ACCEL); + if (violation) return 0; + } else if (!controls_allowed && (desired_accel != 0)) { + return 0; + } + } + + // STEER: safety check on bytes 2-3 + if ((to_send->RIR>>21) == 0x2E4) { + int desired_torque = (to_send->RDLR & 0xFF00) | ((to_send->RDLR >> 16) & 0xFF); + desired_torque = to_signed(desired_torque, 16); + int violation = 0; + + uint32_t ts = TIM2->CNT; + + // only check if controls are allowed and actuation_limits are imposed + if (controls_allowed && toyota_actuation_limits) { + + // *** global torque limit check *** + violation |= max_limit_check(desired_torque, TOYOTA_MAX_TORQUE, -TOYOTA_MAX_TORQUE); + + // *** torque rate limit check *** + violation |= dist_to_meas_check(desired_torque, toyota_desired_torque_last, + &toyota_torque_meas, TOYOTA_MAX_RATE_UP, TOYOTA_MAX_RATE_DOWN, TOYOTA_MAX_TORQUE_ERROR); + + // used next time + toyota_desired_torque_last = desired_torque; + + // *** torque real time rate limit check *** + violation |= rt_rate_limit_check(desired_torque, toyota_rt_torque_last, TOYOTA_MAX_RT_DELTA); + + // every RT_INTERVAL set the new limits + uint32_t ts_elapsed = get_ts_elapsed(ts, toyota_ts_last); + if (ts_elapsed > TOYOTA_RT_INTERVAL) { + toyota_rt_torque_last = desired_torque; + toyota_ts_last = ts; + } + } + + // no torque if controls is not allowed + if (!controls_allowed && (desired_torque != 0)) { + violation = 1; + } + + // reset to 0 if either controls is not allowed or there's a violation + if (violation || !controls_allowed) { + toyota_desired_torque_last = 0; + toyota_rt_torque_last = 0; + toyota_ts_last = ts; + } + + if (violation) { + return false; + } + } + } + + // 1 allows the message through + return true; +} + +static void toyota_init(int16_t param) { + controls_allowed = 0; + toyota_actuation_limits = 1; + toyota_giraffe_switch_1 = 0; + toyota_camera_forwarded = 0; + toyota_dbc_eps_torque_factor = param; +} + +static int toyota_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) { + + // forward cam to radar and viceversa if car, except lkas cmd and hud + // don't forward when switch 1 is high + if ((bus_num == 0 || bus_num == 2) && toyota_camera_forwarded && !toyota_giraffe_switch_1) { + int addr = to_fwd->RIR>>21; + bool is_lkas_msg = (addr == 0x2E4 || addr == 0x412) && bus_num == 2; + return is_lkas_msg? -1 : (uint8_t)(~bus_num & 0x2); + } + return -1; +} + +const safety_hooks toyota_hooks = { + .init = toyota_init, + .rx = toyota_rx_hook, + .tx = toyota_tx_hook, + .tx_lin = nooutput_tx_lin_hook, + .ignition = default_ign_hook, + .fwd = toyota_fwd_hook, +}; + +static void toyota_nolimits_init(int16_t param) { + controls_allowed = 0; + toyota_actuation_limits = 0; + toyota_giraffe_switch_1 = 0; + toyota_camera_forwarded = 0; + toyota_dbc_eps_torque_factor = param; +} + +const safety_hooks toyota_nolimits_hooks = { + .init = toyota_nolimits_init, + .rx = toyota_rx_hook, + .tx = toyota_tx_hook, + .tx_lin = nooutput_tx_lin_hook, + .ignition = default_ign_hook, + .fwd = toyota_fwd_hook, +}; diff --git a/panda/board/safety/safety_toyota_ipas.h b/panda/board/safety/safety_toyota_ipas.h new file mode 100644 index 00000000000000..ff4158e3c77c3b --- /dev/null +++ b/panda/board/safety/safety_toyota_ipas.h @@ -0,0 +1,156 @@ +// uses tons from safety_toyota +// TODO: refactor to repeat less code + +// IPAS override +const int32_t TOYOTA_IPAS_OVERRIDE_THRESHOLD = 200; // disallow controls when user torque exceeds this value + +// 2m/s are added to be less restrictive +const struct lookup_t LOOKUP_ANGLE_RATE_UP = { + {2., 7., 17.}, + {5., .8, .15}}; + +const struct lookup_t LOOKUP_ANGLE_RATE_DOWN = { + {2., 7., 17.}, + {5., 3.5, .4}}; + +const float RT_ANGLE_FUDGE = 1.5; // for RT checks allow 50% more angle change +const float CAN_TO_DEG = 2. / 3.; // convert angles from CAN unit to degrees + +int ipas_state = 1; // 1 disabled, 3 executing angle control, 5 override +int angle_control = 0; // 1 if direct angle control packets are seen +float speed = 0.; + +struct sample_t angle_meas; // last 3 steer angles +struct sample_t torque_driver; // last 3 driver steering torque + +// state of angle limits +int16_t desired_angle_last = 0; // last desired steer angle +int16_t rt_angle_last = 0; // last desired torque for real time check +uint32_t ts_angle_last = 0; + +int controls_allowed_last = 0; + + +static void toyota_ipas_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) { + // check standard toyota stuff as well + toyota_rx_hook(to_push); + + if ((to_push->RIR>>21) == 0x260) { + // get driver steering torque + int16_t torque_driver_new = (((to_push->RDLR) & 0xFF00) | ((to_push->RDLR >> 16) & 0xFF)); + + // update array of samples + update_sample(&torque_driver, torque_driver_new); + } + + // get steer angle + if ((to_push->RIR>>21) == 0x25) { + int angle_meas_new = ((to_push->RDLR & 0xf) << 8) + ((to_push->RDLR & 0xff00) >> 8); + uint32_t ts = TIM2->CNT; + + angle_meas_new = to_signed(angle_meas_new, 12); + + // update array of samples + update_sample(&angle_meas, angle_meas_new); + + // *** angle real time check + // add 1 to not false trigger the violation and multiply by 20 since the check is done every 250ms and steer angle is updated at 80Hz + int rt_delta_angle_up = ((int)(RT_ANGLE_FUDGE * (interpolate(LOOKUP_ANGLE_RATE_UP, speed) * 20. * CAN_TO_DEG + 1.))); + int rt_delta_angle_down = ((int)(RT_ANGLE_FUDGE * (interpolate(LOOKUP_ANGLE_RATE_DOWN, speed) * 20. * CAN_TO_DEG + 1.))); + int highest_rt_angle = rt_angle_last + (rt_angle_last > 0? rt_delta_angle_up:rt_delta_angle_down); + int lowest_rt_angle = rt_angle_last - (rt_angle_last > 0? rt_delta_angle_down:rt_delta_angle_up); + + // every RT_INTERVAL or when controls are turned on, set the new limits + uint32_t ts_elapsed = get_ts_elapsed(ts, ts_angle_last); + if ((ts_elapsed > TOYOTA_RT_INTERVAL) || (controls_allowed && !controls_allowed_last)) { + rt_angle_last = angle_meas_new; + ts_angle_last = ts; + } + + // check for violation + if (angle_control && + ((angle_meas_new < lowest_rt_angle) || + (angle_meas_new > highest_rt_angle))) { + controls_allowed = 0; + } + + controls_allowed_last = controls_allowed; + } + + // get speed + if ((to_push->RIR>>21) == 0xb4) { + speed = ((float) (((to_push->RDHR) & 0xFF00) | ((to_push->RDHR >> 16) & 0xFF))) * 0.01 / 3.6; + } + + // get ipas state + if ((to_push->RIR>>21) == 0x262) { + ipas_state = (to_push->RDLR & 0xf); + } + + // exit controls on high steering override + if (angle_control && ((torque_driver.min > TOYOTA_IPAS_OVERRIDE_THRESHOLD) || + (torque_driver.max < -TOYOTA_IPAS_OVERRIDE_THRESHOLD) || + (ipas_state==5))) { + controls_allowed = 0; + } +} + +static int toyota_ipas_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) { + + // Check if msg is sent on BUS 0 + if (((to_send->RDTR >> 4) & 0xF) == 0) { + + // STEER ANGLE + if (((to_send->RIR>>21) == 0x266) || ((to_send->RIR>>21) == 0x167)) { + + angle_control = 1; // we are in angle control mode + int desired_angle = ((to_send->RDLR & 0xf) << 8) + ((to_send->RDLR & 0xff00) >> 8); + int ipas_state_cmd = ((to_send->RDLR & 0xff) >> 4); + int16_t violation = 0; + + desired_angle = to_signed(desired_angle, 12); + + if (controls_allowed) { + // add 1 to not false trigger the violation + int delta_angle_up = (int) (interpolate(LOOKUP_ANGLE_RATE_UP, speed) * CAN_TO_DEG + 1.); + int delta_angle_down = (int) (interpolate(LOOKUP_ANGLE_RATE_DOWN, speed) * CAN_TO_DEG + 1.); + int highest_desired_angle = desired_angle_last + (desired_angle_last > 0? delta_angle_up:delta_angle_down); + int lowest_desired_angle = desired_angle_last - (desired_angle_last > 0? delta_angle_down:delta_angle_up); + if ((desired_angle > highest_desired_angle) || + (desired_angle < lowest_desired_angle)){ + violation = 1; + controls_allowed = 0; + } + } + + // desired steer angle should be the same as steer angle measured when controls are off + if ((!controls_allowed) && + ((desired_angle < (angle_meas.min - 1)) || + (desired_angle > (angle_meas.max + 1)) || + (ipas_state_cmd != 1))) { + violation = 1; + } + + desired_angle_last = desired_angle; + + if (violation) { + return false; + } + + return true; + } + } + + // check standard toyota stuff as well + return toyota_tx_hook(to_send); +} + +const safety_hooks toyota_ipas_hooks = { + .init = toyota_init, + .rx = toyota_ipas_rx_hook, + .tx = toyota_ipas_tx_hook, + .tx_lin = nooutput_tx_lin_hook, + .ignition = default_ign_hook, + .fwd = toyota_fwd_hook, +}; + diff --git a/panda/board/spi_flasher.h b/panda/board/spi_flasher.h new file mode 100644 index 00000000000000..179a095b970ef9 --- /dev/null +++ b/panda/board/spi_flasher.h @@ -0,0 +1,314 @@ +// flasher state variables +uint32_t *prog_ptr = NULL; +int unlocked = 0; + +void debug_ring_callback(uart_ring *ring) {} + +int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, int hardwired) { + int resp_len = 0; + + // flasher machine + memset(resp, 0, 4); + memcpy(resp+4, "\xde\xad\xd0\x0d", 4); + resp[0] = 0xff; + resp[2] = setup->b.bRequest; + resp[3] = ~setup->b.bRequest; + *((uint32_t **)&resp[8]) = prog_ptr; + resp_len = 0xc; + + int sec; + switch (setup->b.bRequest) { + // **** 0xb0: flasher echo + case 0xb0: + resp[1] = 0xff; + break; + // **** 0xb1: unlock flash + case 0xb1: + if (FLASH->CR & FLASH_CR_LOCK) { + FLASH->KEYR = 0x45670123; + FLASH->KEYR = 0xCDEF89AB; + resp[1] = 0xff; + } + set_led(LED_GREEN, 1); + unlocked = 1; + prog_ptr = (uint32_t *)0x8004000; + break; + // **** 0xb2: erase sector + case 0xb2: + sec = setup->b.wValue.w; + // don't erase the bootloader + if (sec != 0 && sec < 12 && unlocked) { + FLASH->CR = (sec << 3) | FLASH_CR_SER; + FLASH->CR |= FLASH_CR_STRT; + while (FLASH->SR & FLASH_SR_BSY); + resp[1] = 0xff; + } + break; + // **** 0xd0: fetch serial number + case 0xd0: + #ifdef PANDA + // addresses are OTP + if (setup->b.wValue.w == 1) { + memcpy(resp, (void *)0x1fff79c0, 0x10); + resp_len = 0x10; + } else { + get_provision_chunk(resp); + resp_len = PROVISION_CHUNK_LEN; + } + #endif + break; + // **** 0xd1: enter bootloader mode + case 0xd1: + // this allows reflashing of the bootstub + // so it's blocked over wifi + switch (setup->b.wValue.w) { + case 0: + if (hardwired) { + puts("-> entering bootloader\n"); + enter_bootloader_mode = ENTER_BOOTLOADER_MAGIC; + NVIC_SystemReset(); + } + break; + case 1: + puts("-> entering softloader\n"); + enter_bootloader_mode = ENTER_SOFTLOADER_MAGIC; + NVIC_SystemReset(); + break; + } + break; + // **** 0xd6: get version + case 0xd6: + COMPILE_TIME_ASSERT(sizeof(gitversion) <= MAX_RESP_LEN) + memcpy(resp, gitversion, sizeof(gitversion)); + resp_len = sizeof(gitversion); + break; + // **** 0xd8: reset ST + case 0xd8: + NVIC_SystemReset(); + break; + } + return resp_len; +} + +int usb_cb_ep1_in(uint8_t *usbdata, int len, int hardwired) { return 0; } +void usb_cb_ep3_out(uint8_t *usbdata, int len, int hardwired) { } + +int is_enumerated = 0; +void usb_cb_enumeration_complete() { + puts("USB enumeration complete\n"); + is_enumerated = 1; +} + +void usb_cb_ep2_out(uint8_t *usbdata, int len, int hardwired) { + set_led(LED_RED, 0); + for (int i = 0; i < len/4; i++) { + // program byte 1 + FLASH->CR = FLASH_CR_PSIZE_1 | FLASH_CR_PG; + + *prog_ptr = *(uint32_t*)(usbdata+(i*4)); + while (FLASH->SR & FLASH_SR_BSY); + + //*(uint64_t*)(&spi_tx_buf[0x30+(i*4)]) = *prog_ptr; + prog_ptr++; + } + set_led(LED_RED, 1); +} + + +int spi_cb_rx(uint8_t *data, int len, uint8_t *data_out) { + int resp_len = 0; + switch (data[0]) { + case 0: + // control transfer + resp_len = usb_cb_control_msg((USB_Setup_TypeDef *)(data+4), data_out, 0); + break; + case 2: + // ep 2, flash! + usb_cb_ep2_out(data+4, data[2], 0); + break; + } + return resp_len; +} + +#ifdef PEDAL + +#define CAN CAN1 + +#define CAN_BL_INPUT 0x1 +#define CAN_BL_OUTPUT 0x2 + +void CAN1_TX_IRQHandler() { + // clear interrupt + CAN->TSR |= CAN_TSR_RQCP0; +} + +#define ISOTP_BUF_SIZE 0x110 + +uint8_t isotp_buf[ISOTP_BUF_SIZE]; +uint8_t *isotp_buf_ptr = NULL; +int isotp_buf_remain = 0; + +uint8_t isotp_buf_out[ISOTP_BUF_SIZE]; +uint8_t *isotp_buf_out_ptr = NULL; +int isotp_buf_out_remain = 0; +int isotp_buf_out_idx = 0; + +void bl_can_send(uint8_t *odat) { + // wait for send + while (!(CAN->TSR & CAN_TSR_TME0)); + + // send continue + CAN->sTxMailBox[0].TDLR = ((uint32_t*)odat)[0]; + CAN->sTxMailBox[0].TDHR = ((uint32_t*)odat)[1]; + CAN->sTxMailBox[0].TDTR = 8; + CAN->sTxMailBox[0].TIR = (CAN_BL_OUTPUT << 21) | 1; +} + +void CAN1_RX0_IRQHandler() { + while (CAN->RF0R & CAN_RF0R_FMP0) { + if ((CAN->sFIFOMailBox[0].RIR>>21) == CAN_BL_INPUT) { + uint8_t dat[8]; + ((uint32_t*)dat)[0] = CAN->sFIFOMailBox[0].RDLR; + ((uint32_t*)dat)[1] = CAN->sFIFOMailBox[0].RDHR; + uint8_t odat[8]; + uint8_t type = dat[0] & 0xF0; + if (type == 0x30) { + // continue + while (isotp_buf_out_remain > 0) { + // wait for send + while (!(CAN->TSR & CAN_TSR_TME0)); + + odat[0] = 0x20 | isotp_buf_out_idx; + memcpy(odat+1, isotp_buf_out_ptr, 7); + isotp_buf_out_remain -= 7; + isotp_buf_out_ptr += 7; + isotp_buf_out_idx++; + + bl_can_send(odat); + } + } else if (type == 0x20) { + if (isotp_buf_remain > 0) { + memcpy(isotp_buf_ptr, dat+1, 7); + isotp_buf_ptr += 7; + isotp_buf_remain -= 7; + } + if (isotp_buf_remain <= 0) { + int len = isotp_buf_ptr - isotp_buf + isotp_buf_remain; + + // call the function + memset(isotp_buf_out, 0, ISOTP_BUF_SIZE); + isotp_buf_out_remain = spi_cb_rx(isotp_buf, len, isotp_buf_out); + isotp_buf_out_ptr = isotp_buf_out; + isotp_buf_out_idx = 0; + + // send initial + if (isotp_buf_out_remain <= 7) { + odat[0] = isotp_buf_out_remain; + memcpy(odat+1, isotp_buf_out_ptr, isotp_buf_out_remain); + } else { + odat[0] = 0x10 | (isotp_buf_out_remain>>8); + odat[1] = isotp_buf_out_remain & 0xFF; + memcpy(odat+2, isotp_buf_out_ptr, 6); + isotp_buf_out_remain -= 6; + isotp_buf_out_ptr += 6; + isotp_buf_out_idx++; + } + + bl_can_send(odat); + } + } else if (type == 0x10) { + int len = ((dat[0]&0xF)<<8) | dat[1]; + + // setup buffer + isotp_buf_ptr = isotp_buf; + memcpy(isotp_buf_ptr, dat+2, 6); + + if (len < (ISOTP_BUF_SIZE-0x10)) { + isotp_buf_ptr += 6; + isotp_buf_remain = len-6; + } + + memset(odat, 0, 8); + odat[0] = 0x30; + bl_can_send(odat); + } + } + // next + CAN->RF0R |= CAN_RF0R_RFOM0; + } +} + +void CAN1_SCE_IRQHandler() { + can_sce(CAN); +} + +#endif + +void soft_flasher_start() { + puts("\n\n\n************************ FLASHER START ************************\n"); + + enter_bootloader_mode = 0; + + RCC->AHB1ENR |= RCC_AHB1ENR_DMA2EN; + RCC->APB2ENR |= RCC_APB2ENR_SPI1EN; + RCC->AHB2ENR |= RCC_AHB2ENR_OTGFSEN; + RCC->APB1ENR |= RCC_APB1ENR_USART2EN; + +// pedal has the canloader +#ifdef PEDAL + RCC->APB1ENR |= RCC_APB1ENR_CAN1EN; + + // B8,B9: CAN 1 + set_gpio_alternate(GPIOB, 8, GPIO_AF9_CAN1); + set_gpio_alternate(GPIOB, 9, GPIO_AF9_CAN1); + set_can_enable(CAN1, 1); + + // init can + can_silent = ALL_CAN_LIVE; + can_init(0); +#endif + + // A4,A5,A6,A7: setup SPI + set_gpio_alternate(GPIOA, 4, GPIO_AF5_SPI1); + set_gpio_alternate(GPIOA, 5, GPIO_AF5_SPI1); + set_gpio_alternate(GPIOA, 6, GPIO_AF5_SPI1); + set_gpio_alternate(GPIOA, 7, GPIO_AF5_SPI1); + + // A2,A3: USART 2 for debugging + set_gpio_alternate(GPIOA, 2, GPIO_AF7_USART2); + set_gpio_alternate(GPIOA, 3, GPIO_AF7_USART2); + + // A11,A12: USB + set_gpio_alternate(GPIOA, 11, GPIO_AF10_OTG_FS); + set_gpio_alternate(GPIOA, 12, GPIO_AF10_OTG_FS); + GPIOA->OSPEEDR = GPIO_OSPEEDER_OSPEEDR11 | GPIO_OSPEEDER_OSPEEDR12; + + // flasher + spi_init(); + + // enable USB + usb_init(); + + // green LED on for flashing + set_led(LED_GREEN, 1); + + __enable_irq(); + + uint64_t cnt = 0; + + for (cnt=0;;cnt++) { + if (cnt == 35 && !is_enumerated && usb_power_mode == USB_POWER_CLIENT) { + // if you are connected through a hub to the phone + // you need power to be able to see the device + puts("USBP: didn't enumerate, switching to CDP mode\n"); + set_usb_power_mode(USB_POWER_CDP); + set_led(LED_BLUE, 1); + } + // blink the green LED fast + set_led(LED_GREEN, 0); + delay(500000); + set_led(LED_GREEN, 1); + delay(500000); + } +} + diff --git a/panda/board/startup_stm32f205xx.s b/panda/board/startup_stm32f205xx.s new file mode 100644 index 00000000000000..f4b6c6cb741272 --- /dev/null +++ b/panda/board/startup_stm32f205xx.s @@ -0,0 +1,511 @@ +/** + ****************************************************************************** + * @file startup_stm32f205xx.s + * @author MCD Application Team + * @version V2.1.2 + * @date 29-June-2016 + * @brief STM32F205xx Devices vector table for Atollic TrueSTUDIO toolchain. + * This module performs: + * - Set the initial SP + * - Set the initial PC == Reset_Handler, + * - Set the vector table entries with the exceptions ISR address + * - Branches to main in the C library (which eventually + * calls main()). + * After Reset the Cortex-M3 processor is in Thread mode, + * priority is Privileged, and the Stack is set to Main. + ****************************************************************************** + * @attention + * + *

© COPYRIGHT 2016 STMicroelectronics

+ * + * Redistribution and use in source and binary forms, with or without modification, + * are permitted provided that the following conditions are met: + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * 3. Neither the name of STMicroelectronics nor the names of its contributors + * may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************** + */ + + .syntax unified + .cpu cortex-m3 + .thumb + +.global g_pfnVectors +.global Default_Handler + +/* start address for the initialization values of the .data section. +defined in linker script */ +.word _sidata +/* start address for the .data section. defined in linker script */ +.word _sdata +/* end address for the .data section. defined in linker script */ +.word _edata +/* start address for the .bss section. defined in linker script */ +.word _sbss +/* end address for the .bss section. defined in linker script */ +.word _ebss +/* stack used for SystemInit_ExtMemCtl; always internal RAM used */ + +/** + * @brief This is the code that gets called when the processor first + * starts execution following a reset event. Only the absolutely + * necessary set is performed, after which the application + * supplied main() routine is called. + * @param None + * @retval : None +*/ + + .section .text.Reset_Handler + .weak Reset_Handler + .type Reset_Handler, %function +Reset_Handler: + ldr sp, =_estack /* set stack pointer */ + bl __initialize_hardware_early + +/* Copy the data segment initializers from flash to SRAM */ + movs r1, #0 + b LoopCopyDataInit + +CopyDataInit: + ldr r3, =_sidata + ldr r3, [r3, r1] + str r3, [r0, r1] + adds r1, r1, #4 + +LoopCopyDataInit: + ldr r0, =_sdata + ldr r3, =_edata + adds r2, r0, r1 + cmp r2, r3 + bcc CopyDataInit + ldr r2, =_sbss + b LoopFillZerobss +/* Zero fill the bss segment. */ +FillZerobss: + movs r3, #0 + str r3, [r2], #4 + +LoopFillZerobss: + ldr r3, = _ebss + cmp r2, r3 + bcc FillZerobss + +/* Call the clock system initialization function.*/ + /*bl SystemInit */ +/* Call static constructors */ + /*bl __libc_init_array*/ +/* Call the application's entry point.*/ + bl main + bx lr +.size Reset_Handler, .-Reset_Handler + +/** + * @brief This is the code that gets called when the processor receives an + * unexpected interrupt. This simply enters an infinite loop, preserving + * the system state for examination by a debugger. + * @param None + * @retval None +*/ + .section .text.Default_Handler,"ax",%progbits +Default_Handler: +Infinite_Loop: + b Infinite_Loop + .size Default_Handler, .-Default_Handler +/****************************************************************************** +* +* The minimal vector table for a Cortex M3. Note that the proper constructs +* must be placed on this to ensure that it ends up at physical address +* 0x0000.0000. +* +*******************************************************************************/ + .section .isr_vector,"a",%progbits + .type g_pfnVectors, %object + .size g_pfnVectors, .-g_pfnVectors + + + +g_pfnVectors: + .word _estack + .word Reset_Handler + + .word NMI_Handler + .word HardFault_Handler + .word MemManage_Handler + .word BusFault_Handler + .word UsageFault_Handler + .word 0 + .word 0 + .word 0 + .word 0 + .word SVC_Handler + .word DebugMon_Handler + .word 0 + .word PendSV_Handler + .word SysTick_Handler + + /* External Interrupts */ + .word WWDG_IRQHandler /* Window WatchDog */ + .word PVD_IRQHandler /* PVD through EXTI Line detection */ + .word TAMP_STAMP_IRQHandler /* Tamper and TimeStamps through the EXTI line */ + .word RTC_WKUP_IRQHandler /* RTC Wakeup through the EXTI line */ + .word FLASH_IRQHandler /* FLASH */ + .word RCC_IRQHandler /* RCC */ + .word EXTI0_IRQHandler /* EXTI Line0 */ + .word EXTI1_IRQHandler /* EXTI Line1 */ + .word EXTI2_IRQHandler /* EXTI Line2 */ + .word EXTI3_IRQHandler /* EXTI Line3 */ + .word EXTI4_IRQHandler /* EXTI Line4 */ + .word DMA1_Stream0_IRQHandler /* DMA1 Stream 0 */ + .word DMA1_Stream1_IRQHandler /* DMA1 Stream 1 */ + .word DMA1_Stream2_IRQHandler /* DMA1 Stream 2 */ + .word DMA1_Stream3_IRQHandler /* DMA1 Stream 3 */ + .word DMA1_Stream4_IRQHandler /* DMA1 Stream 4 */ + .word DMA1_Stream5_IRQHandler /* DMA1 Stream 5 */ + .word DMA1_Stream6_IRQHandler /* DMA1 Stream 6 */ + .word ADC_IRQHandler /* ADC1, ADC2 and ADC3s */ + .word CAN1_TX_IRQHandler /* CAN1 TX */ + .word CAN1_RX0_IRQHandler /* CAN1 RX0 */ + .word CAN1_RX1_IRQHandler /* CAN1 RX1 */ + .word CAN1_SCE_IRQHandler /* CAN1 SCE */ + .word EXTI9_5_IRQHandler /* External Line[9:5]s */ + .word TIM1_BRK_TIM9_IRQHandler /* TIM1 Break and TIM9 */ + .word TIM1_UP_TIM10_IRQHandler /* TIM1 Update and TIM10 */ + .word TIM1_TRG_COM_TIM11_IRQHandler /* TIM1 Trigger and Commutation and TIM11 */ + .word TIM1_CC_IRQHandler /* TIM1 Capture Compare */ + .word TIM2_IRQHandler /* TIM2 */ + .word TIM3_IRQHandler /* TIM3 */ + .word TIM4_IRQHandler /* TIM4 */ + .word I2C1_EV_IRQHandler /* I2C1 Event */ + .word I2C1_ER_IRQHandler /* I2C1 Error */ + .word I2C2_EV_IRQHandler /* I2C2 Event */ + .word I2C2_ER_IRQHandler /* I2C2 Error */ + .word SPI1_IRQHandler /* SPI1 */ + .word SPI2_IRQHandler /* SPI2 */ + .word USART1_IRQHandler /* USART1 */ + .word USART2_IRQHandler /* USART2 */ + .word USART3_IRQHandler /* USART3 */ + .word EXTI15_10_IRQHandler /* External Line[15:10]s */ + .word RTC_Alarm_IRQHandler /* RTC Alarm (A and B) through EXTI Line */ + .word OTG_FS_WKUP_IRQHandler /* USB OTG FS Wakeup through EXTI line */ + .word TIM8_BRK_TIM12_IRQHandler /* TIM8 Break and TIM12 */ + .word TIM8_UP_TIM13_IRQHandler /* TIM8 Update and TIM13 */ + .word TIM8_TRG_COM_TIM14_IRQHandler /* TIM8 Trigger and Commutation and TIM14 */ + .word TIM8_CC_IRQHandler /* TIM8 Capture Compare */ + .word DMA1_Stream7_IRQHandler /* DMA1 Stream7 */ + .word FSMC_IRQHandler /* FSMC */ + .word SDIO_IRQHandler /* SDIO */ + .word TIM5_IRQHandler /* TIM5 */ + .word SPI3_IRQHandler /* SPI3 */ + .word UART4_IRQHandler /* UART4 */ + .word UART5_IRQHandler /* UART5 */ + .word TIM6_DAC_IRQHandler /* TIM6 and DAC1&2 underrun errors */ + .word TIM7_IRQHandler /* TIM7 */ + .word DMA2_Stream0_IRQHandler /* DMA2 Stream 0 */ + .word DMA2_Stream1_IRQHandler /* DMA2 Stream 1 */ + .word DMA2_Stream2_IRQHandler /* DMA2 Stream 2 */ + .word DMA2_Stream3_IRQHandler /* DMA2 Stream 3 */ + .word DMA2_Stream4_IRQHandler /* DMA2 Stream 4 */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word CAN2_TX_IRQHandler /* CAN2 TX */ + .word CAN2_RX0_IRQHandler /* CAN2 RX0 */ + .word CAN2_RX1_IRQHandler /* CAN2 RX1 */ + .word CAN2_SCE_IRQHandler /* CAN2 SCE */ + .word OTG_FS_IRQHandler /* USB OTG FS */ + .word DMA2_Stream5_IRQHandler /* DMA2 Stream 5 */ + .word DMA2_Stream6_IRQHandler /* DMA2 Stream 6 */ + .word DMA2_Stream7_IRQHandler /* DMA2 Stream 7 */ + .word USART6_IRQHandler /* USART6 */ + .word I2C3_EV_IRQHandler /* I2C3 event */ + .word I2C3_ER_IRQHandler /* I2C3 error */ + .word OTG_HS_EP1_OUT_IRQHandler /* USB OTG HS End Point 1 Out */ + .word OTG_HS_EP1_IN_IRQHandler /* USB OTG HS End Point 1 In */ + .word OTG_HS_WKUP_IRQHandler /* USB OTG HS Wakeup through EXTI */ + .word OTG_HS_IRQHandler /* USB OTG HS */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word HASH_RNG_IRQHandler /* Hash and Rng */ + +/******************************************************************************* +* +* Provide weak aliases for each Exception handler to the Default_Handler. +* As they are weak aliases, any function with the same name will override +* this definition. +* +*******************************************************************************/ + .weak NMI_Handler + .thumb_set NMI_Handler,Default_Handler + + .weak HardFault_Handler + .thumb_set HardFault_Handler,Default_Handler + + .weak MemManage_Handler + .thumb_set MemManage_Handler,Default_Handler + + .weak BusFault_Handler + .thumb_set BusFault_Handler,Default_Handler + + .weak UsageFault_Handler + .thumb_set UsageFault_Handler,Default_Handler + + .weak SVC_Handler + .thumb_set SVC_Handler,Default_Handler + + .weak DebugMon_Handler + .thumb_set DebugMon_Handler,Default_Handler + + .weak PendSV_Handler + .thumb_set PendSV_Handler,Default_Handler + + .weak SysTick_Handler + .thumb_set SysTick_Handler,Default_Handler + + .weak WWDG_IRQHandler + .thumb_set WWDG_IRQHandler,Default_Handler + + .weak PVD_IRQHandler + .thumb_set PVD_IRQHandler,Default_Handler + + .weak TAMP_STAMP_IRQHandler + .thumb_set TAMP_STAMP_IRQHandler,Default_Handler + + .weak RTC_WKUP_IRQHandler + .thumb_set RTC_WKUP_IRQHandler,Default_Handler + + .weak FLASH_IRQHandler + .thumb_set FLASH_IRQHandler,Default_Handler + + .weak RCC_IRQHandler + .thumb_set RCC_IRQHandler,Default_Handler + + .weak EXTI0_IRQHandler + .thumb_set EXTI0_IRQHandler,Default_Handler + + .weak EXTI1_IRQHandler + .thumb_set EXTI1_IRQHandler,Default_Handler + + .weak EXTI2_IRQHandler + .thumb_set EXTI2_IRQHandler,Default_Handler + + .weak EXTI3_IRQHandler + .thumb_set EXTI3_IRQHandler,Default_Handler + + .weak EXTI4_IRQHandler + .thumb_set EXTI4_IRQHandler,Default_Handler + + .weak DMA1_Stream0_IRQHandler + .thumb_set DMA1_Stream0_IRQHandler,Default_Handler + + .weak DMA1_Stream1_IRQHandler + .thumb_set DMA1_Stream1_IRQHandler,Default_Handler + + .weak DMA1_Stream2_IRQHandler + .thumb_set DMA1_Stream2_IRQHandler,Default_Handler + + .weak DMA1_Stream3_IRQHandler + .thumb_set DMA1_Stream3_IRQHandler,Default_Handler + + .weak DMA1_Stream4_IRQHandler + .thumb_set DMA1_Stream4_IRQHandler,Default_Handler + + .weak DMA1_Stream5_IRQHandler + .thumb_set DMA1_Stream5_IRQHandler,Default_Handler + + .weak DMA1_Stream6_IRQHandler + .thumb_set DMA1_Stream6_IRQHandler,Default_Handler + + .weak ADC_IRQHandler + .thumb_set ADC_IRQHandler,Default_Handler + + .weak CAN1_TX_IRQHandler + .thumb_set CAN1_TX_IRQHandler,Default_Handler + + .weak CAN1_RX0_IRQHandler + .thumb_set CAN1_RX0_IRQHandler,Default_Handler + + .weak CAN1_RX1_IRQHandler + .thumb_set CAN1_RX1_IRQHandler,Default_Handler + + .weak CAN1_SCE_IRQHandler + .thumb_set CAN1_SCE_IRQHandler,Default_Handler + + .weak EXTI9_5_IRQHandler + .thumb_set EXTI9_5_IRQHandler,Default_Handler + + .weak TIM1_BRK_TIM9_IRQHandler + .thumb_set TIM1_BRK_TIM9_IRQHandler,Default_Handler + + .weak TIM1_UP_TIM10_IRQHandler + .thumb_set TIM1_UP_TIM10_IRQHandler,Default_Handler + + .weak TIM1_TRG_COM_TIM11_IRQHandler + .thumb_set TIM1_TRG_COM_TIM11_IRQHandler,Default_Handler + + .weak TIM1_CC_IRQHandler + .thumb_set TIM1_CC_IRQHandler,Default_Handler + + .weak TIM2_IRQHandler + .thumb_set TIM2_IRQHandler,Default_Handler + + .weak TIM3_IRQHandler + .thumb_set TIM3_IRQHandler,Default_Handler + + .weak TIM4_IRQHandler + .thumb_set TIM4_IRQHandler,Default_Handler + + .weak I2C1_EV_IRQHandler + .thumb_set I2C1_EV_IRQHandler,Default_Handler + + .weak I2C1_ER_IRQHandler + .thumb_set I2C1_ER_IRQHandler,Default_Handler + + .weak I2C2_EV_IRQHandler + .thumb_set I2C2_EV_IRQHandler,Default_Handler + + .weak I2C2_ER_IRQHandler + .thumb_set I2C2_ER_IRQHandler,Default_Handler + + .weak SPI1_IRQHandler + .thumb_set SPI1_IRQHandler,Default_Handler + + .weak SPI2_IRQHandler + .thumb_set SPI2_IRQHandler,Default_Handler + + .weak USART1_IRQHandler + .thumb_set USART1_IRQHandler,Default_Handler + + .weak USART2_IRQHandler + .thumb_set USART2_IRQHandler,Default_Handler + + .weak USART3_IRQHandler + .thumb_set USART3_IRQHandler,Default_Handler + + .weak EXTI15_10_IRQHandler + .thumb_set EXTI15_10_IRQHandler,Default_Handler + + .weak RTC_Alarm_IRQHandler + .thumb_set RTC_Alarm_IRQHandler,Default_Handler + + .weak OTG_FS_WKUP_IRQHandler + .thumb_set OTG_FS_WKUP_IRQHandler,Default_Handler + + .weak TIM8_BRK_TIM12_IRQHandler + .thumb_set TIM8_BRK_TIM12_IRQHandler,Default_Handler + + .weak TIM8_UP_TIM13_IRQHandler + .thumb_set TIM8_UP_TIM13_IRQHandler,Default_Handler + + .weak TIM8_TRG_COM_TIM14_IRQHandler + .thumb_set TIM8_TRG_COM_TIM14_IRQHandler,Default_Handler + + .weak TIM8_CC_IRQHandler + .thumb_set TIM8_CC_IRQHandler,Default_Handler + + .weak DMA1_Stream7_IRQHandler + .thumb_set DMA1_Stream7_IRQHandler,Default_Handler + + .weak FSMC_IRQHandler + .thumb_set FSMC_IRQHandler,Default_Handler + + .weak SDIO_IRQHandler + .thumb_set SDIO_IRQHandler,Default_Handler + + .weak TIM5_IRQHandler + .thumb_set TIM5_IRQHandler,Default_Handler + + .weak SPI3_IRQHandler + .thumb_set SPI3_IRQHandler,Default_Handler + + .weak UART4_IRQHandler + .thumb_set UART4_IRQHandler,Default_Handler + + .weak UART5_IRQHandler + .thumb_set UART5_IRQHandler,Default_Handler + + .weak TIM6_DAC_IRQHandler + .thumb_set TIM6_DAC_IRQHandler,Default_Handler + + .weak TIM7_IRQHandler + .thumb_set TIM7_IRQHandler,Default_Handler + + .weak DMA2_Stream0_IRQHandler + .thumb_set DMA2_Stream0_IRQHandler,Default_Handler + + .weak DMA2_Stream1_IRQHandler + .thumb_set DMA2_Stream1_IRQHandler,Default_Handler + + .weak DMA2_Stream2_IRQHandler + .thumb_set DMA2_Stream2_IRQHandler,Default_Handler + + .weak DMA2_Stream3_IRQHandler + .thumb_set DMA2_Stream3_IRQHandler,Default_Handler + + .weak DMA2_Stream4_IRQHandler + .thumb_set DMA2_Stream4_IRQHandler,Default_Handler + + .weak CAN2_TX_IRQHandler + .thumb_set CAN2_TX_IRQHandler,Default_Handler + + .weak CAN2_RX0_IRQHandler + .thumb_set CAN2_RX0_IRQHandler,Default_Handler + + .weak CAN2_RX1_IRQHandler + .thumb_set CAN2_RX1_IRQHandler,Default_Handler + + .weak CAN2_SCE_IRQHandler + .thumb_set CAN2_SCE_IRQHandler,Default_Handler + + .weak OTG_FS_IRQHandler + .thumb_set OTG_FS_IRQHandler,Default_Handler + + .weak DMA2_Stream5_IRQHandler + .thumb_set DMA2_Stream5_IRQHandler,Default_Handler + + .weak DMA2_Stream6_IRQHandler + .thumb_set DMA2_Stream6_IRQHandler,Default_Handler + + .weak DMA2_Stream7_IRQHandler + .thumb_set DMA2_Stream7_IRQHandler,Default_Handler + + .weak USART6_IRQHandler + .thumb_set USART6_IRQHandler,Default_Handler + + .weak I2C3_EV_IRQHandler + .thumb_set I2C3_EV_IRQHandler,Default_Handler + + .weak I2C3_ER_IRQHandler + .thumb_set I2C3_ER_IRQHandler,Default_Handler + + .weak OTG_HS_EP1_OUT_IRQHandler + .thumb_set OTG_HS_EP1_OUT_IRQHandler,Default_Handler + + .weak OTG_HS_EP1_IN_IRQHandler + .thumb_set OTG_HS_EP1_IN_IRQHandler,Default_Handler + + .weak OTG_HS_WKUP_IRQHandler + .thumb_set OTG_HS_WKUP_IRQHandler,Default_Handler + + .weak OTG_HS_IRQHandler + .thumb_set OTG_HS_IRQHandler,Default_Handler + + .weak HASH_RNG_IRQHandler + .thumb_set HASH_RNG_IRQHandler,Default_Handler + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/panda/board/startup_stm32f413xx.s b/panda/board/startup_stm32f413xx.s new file mode 100644 index 00000000000000..00b645d11b098b --- /dev/null +++ b/panda/board/startup_stm32f413xx.s @@ -0,0 +1,583 @@ +/** + ****************************************************************************** + * @file startup_stm32f413xx.s + * @author MCD Application Team + * @version V2.6.0 + * @date 04-November-2016 + * @brief STM32F413xx Devices vector table for GCC based toolchains. + * This module performs: + * - Set the initial SP + * - Set the initial PC == Reset_Handler, + * - Set the vector table entries with the exceptions ISR address + * - Branches to main in the C library (which eventually + * calls main()). + * After Reset the Cortex-M4 processor is in Thread mode, + * priority is Privileged, and the Stack is set to Main. + ****************************************************************************** + * @attention + * + *

© COPYRIGHT 2016 STMicroelectronics

+ * + * Redistribution and use in source and binary forms, with or without modification, + * are permitted provided that the following conditions are met: + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * 3. Neither the name of STMicroelectronics nor the names of its contributors + * may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************** + */ + + .syntax unified + .cpu cortex-m4 + .fpu softvfp + .thumb + +.global g_pfnVectors +.global Default_Handler + +/* start address for the initialization values of the .data section. +defined in linker script */ +.word _sidata +/* start address for the .data section. defined in linker script */ +.word _sdata +/* end address for the .data section. defined in linker script */ +.word _edata +/* start address for the .bss section. defined in linker script */ +.word _sbss +/* end address for the .bss section. defined in linker script */ +.word _ebss +/* stack used for SystemInit_ExtMemCtl; always internal RAM used */ + +/** + * @brief This is the code that gets called when the processor first + * starts execution following a reset event. Only the absolutely + * necessary set is performed, after which the application + * supplied main() routine is called. + * @param None + * @retval : None +*/ + + .section .text.Reset_Handler + .weak Reset_Handler + .type Reset_Handler, %function +Reset_Handler: + ldr sp, =_estack /* set stack pointer */ + bl __initialize_hardware_early + +/* Copy the data segment initializers from flash to SRAM */ + movs r1, #0 + b LoopCopyDataInit + +CopyDataInit: + ldr r3, =_sidata + ldr r3, [r3, r1] + str r3, [r0, r1] + adds r1, r1, #4 + +LoopCopyDataInit: + ldr r0, =_sdata + ldr r3, =_edata + adds r2, r0, r1 + cmp r2, r3 + bcc CopyDataInit + ldr r2, =_sbss + b LoopFillZerobss +/* Zero fill the bss segment. */ +FillZerobss: + movs r3, #0 + str r3, [r2], #4 + +LoopFillZerobss: + ldr r3, = _ebss + cmp r2, r3 + bcc FillZerobss + +/* Call the clock system intitialization function.*/ + /* bl SystemInit */ +/* Call static constructors */ + /* bl __libc_init_array */ +/* Call the application's entry point.*/ + bl main + bx lr +.size Reset_Handler, .-Reset_Handler + +/** + * @brief This is the code that gets called when the processor receives an + * unexpected interrupt. This simply enters an infinite loop, preserving + * the system state for examination by a debugger. + * @param None + * @retval None +*/ + .section .text.Default_Handler,"ax",%progbits +Default_Handler: +Infinite_Loop: + b Infinite_Loop + .size Default_Handler, .-Default_Handler +/****************************************************************************** +* +* The minimal vector table for a Cortex M3. Note that the proper constructs +* must be placed on this to ensure that it ends up at physical address +* 0x0000.0000. +* +*******************************************************************************/ + .section .isr_vector,"a",%progbits + .type g_pfnVectors, %object + .size g_pfnVectors, .-g_pfnVectors + +g_pfnVectors: + .word _estack + .word Reset_Handler + .word NMI_Handler + .word HardFault_Handler + .word MemManage_Handler + .word BusFault_Handler + .word UsageFault_Handler + .word 0 + .word 0 + .word 0 + .word 0 + .word SVC_Handler + .word DebugMon_Handler + .word 0 + .word PendSV_Handler + .word SysTick_Handler + + /* External Interrupts */ + .word WWDG_IRQHandler /* Window WatchDog */ + .word PVD_IRQHandler /* PVD through EXTI Line detection */ + .word TAMP_STAMP_IRQHandler /* Tamper and TimeStamps through the EXTI line */ + .word RTC_WKUP_IRQHandler /* RTC Wakeup through the EXTI line */ + .word FLASH_IRQHandler /* FLASH */ + .word RCC_IRQHandler /* RCC */ + .word EXTI0_IRQHandler /* EXTI Line0 */ + .word EXTI1_IRQHandler /* EXTI Line1 */ + .word EXTI2_IRQHandler /* EXTI Line2 */ + .word EXTI3_IRQHandler /* EXTI Line3 */ + .word EXTI4_IRQHandler /* EXTI Line4 */ + .word DMA1_Stream0_IRQHandler /* DMA1 Stream 0 */ + .word DMA1_Stream1_IRQHandler /* DMA1 Stream 1 */ + .word DMA1_Stream2_IRQHandler /* DMA1 Stream 2 */ + .word DMA1_Stream3_IRQHandler /* DMA1 Stream 3 */ + .word DMA1_Stream4_IRQHandler /* DMA1 Stream 4 */ + .word DMA1_Stream5_IRQHandler /* DMA1 Stream 5 */ + .word DMA1_Stream6_IRQHandler /* DMA1 Stream 6 */ + .word ADC_IRQHandler /* ADC1, ADC2 and ADC3s */ + .word CAN1_TX_IRQHandler /* CAN1 TX */ + .word CAN1_RX0_IRQHandler /* CAN1 RX0 */ + .word CAN1_RX1_IRQHandler /* CAN1 RX1 */ + .word CAN1_SCE_IRQHandler /* CAN1 SCE */ + .word EXTI9_5_IRQHandler /* External Line[9:5]s */ + .word TIM1_BRK_TIM9_IRQHandler /* TIM1 Break and TIM9 */ + .word TIM1_UP_TIM10_IRQHandler /* TIM1 Update and TIM10 */ + .word TIM1_TRG_COM_TIM11_IRQHandler /* TIM1 Trigger and Commutation and TIM11 */ + .word TIM1_CC_IRQHandler /* TIM1 Capture Compare */ + .word TIM2_IRQHandler /* TIM2 */ + .word TIM3_IRQHandler /* TIM3 */ + .word TIM4_IRQHandler /* TIM4 */ + .word I2C1_EV_IRQHandler /* I2C1 Event */ + .word I2C1_ER_IRQHandler /* I2C1 Error */ + .word I2C2_EV_IRQHandler /* I2C2 Event */ + .word I2C2_ER_IRQHandler /* I2C2 Error */ + .word SPI1_IRQHandler /* SPI1 */ + .word SPI2_IRQHandler /* SPI2 */ + .word USART1_IRQHandler /* USART1 */ + .word USART2_IRQHandler /* USART2 */ + .word USART3_IRQHandler /* USART3 */ + .word EXTI15_10_IRQHandler /* External Line[15:10]s */ + .word RTC_Alarm_IRQHandler /* RTC Alarm (A and B) through EXTI Line */ + .word OTG_FS_WKUP_IRQHandler /* USB OTG FS Wakeup through EXTI line */ + .word TIM8_BRK_TIM12_IRQHandler /* TIM8 Break and TIM12 */ + .word TIM8_UP_TIM13_IRQHandler /* TIM8 Update and TIM13 */ + .word TIM8_TRG_COM_TIM14_IRQHandler /* TIM8 Trigger and Commutation and TIM14 */ + .word TIM8_CC_IRQHandler /* TIM8 Capture Compare */ + .word DMA1_Stream7_IRQHandler /* DMA1 Stream7 */ + .word FSMC_IRQHandler /* FSMC */ + .word SDIO_IRQHandler /* SDIO */ + .word TIM5_IRQHandler /* TIM5 */ + .word SPI3_IRQHandler /* SPI3 */ + .word UART4_IRQHandler /* UART4 */ + .word UART5_IRQHandler /* UART5 */ + .word TIM6_DAC_IRQHandler /* TIM6, DAC1 and DAC2 */ + .word TIM7_IRQHandler /* TIM7 */ + .word DMA2_Stream0_IRQHandler /* DMA2 Stream 0 */ + .word DMA2_Stream1_IRQHandler /* DMA2 Stream 1 */ + .word DMA2_Stream2_IRQHandler /* DMA2 Stream 2 */ + .word DMA2_Stream3_IRQHandler /* DMA2 Stream 3 */ + .word DMA2_Stream4_IRQHandler /* DMA2 Stream 4 */ + .word DFSDM1_FLT0_IRQHandler /* DFSDM1 Filter0 */ + .word DFSDM1_FLT1_IRQHandler /* DFSDM1 Filter1 */ + .word CAN2_TX_IRQHandler /* CAN2 TX */ + .word CAN2_RX0_IRQHandler /* CAN2 RX0 */ + .word CAN2_RX1_IRQHandler /* CAN2 RX1 */ + .word CAN2_SCE_IRQHandler /* CAN2 SCE */ + .word OTG_FS_IRQHandler /* USB OTG FS */ + .word DMA2_Stream5_IRQHandler /* DMA2 Stream 5 */ + .word DMA2_Stream6_IRQHandler /* DMA2 Stream 6 */ + .word DMA2_Stream7_IRQHandler /* DMA2 Stream 7 */ + .word USART6_IRQHandler /* USART6 */ + .word I2C3_EV_IRQHandler /* I2C3 event */ + .word I2C3_ER_IRQHandler /* I2C3 error */ + .word CAN3_TX_IRQHandler /* CAN3 TX */ + .word CAN3_RX0_IRQHandler /* CAN3 RX0 */ + .word CAN3_RX1_IRQHandler /* CAN3 RX1 */ + .word CAN3_SCE_IRQHandler /* CAN3 SCE */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word RNG_IRQHandler /* RNG */ + .word FPU_IRQHandler /* FPU */ + .word UART7_IRQHandler /* UART7 */ + .word UART8_IRQHandler /* UART8 */ + .word SPI4_IRQHandler /* SPI4 */ + .word SPI5_IRQHandler /* SPI5 */ + .word 0 /* Reserved */ + .word SAI1_IRQHandler /* SAI1 */ + .word UART9_IRQHandler /* UART9 */ + .word UART10_IRQHandler /* UART10 */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word QUADSPI_IRQHandler /* QuadSPI */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word FMPI2C1_EV_IRQHandler /* FMPI2C1 Event */ + .word FMPI2C1_ER_IRQHandler /* FMPI2C1 Error */ + .word LPTIM1_IRQHandler /* LPTIM1 */ + .word DFSDM2_FLT0_IRQHandler /* DFSDM2 Filter0 */ + .word DFSDM2_FLT1_IRQHandler /* DFSDM2 Filter1 */ + .word DFSDM2_FLT2_IRQHandler /* DFSDM2 Filter2 */ + .word DFSDM2_FLT3_IRQHandler /* DFSDM2 Filter3 */ + +/******************************************************************************* +* +* Provide weak aliases for each Exception handler to the Default_Handler. +* As they are weak aliases, any function with the same name will override +* this definition. +* +*******************************************************************************/ + .weak NMI_Handler + .thumb_set NMI_Handler,Default_Handler + + .weak HardFault_Handler + .thumb_set HardFault_Handler,Default_Handler + + .weak MemManage_Handler + .thumb_set MemManage_Handler,Default_Handler + + .weak BusFault_Handler + .thumb_set BusFault_Handler,Default_Handler + + .weak UsageFault_Handler + .thumb_set UsageFault_Handler,Default_Handler + + .weak SVC_Handler + .thumb_set SVC_Handler,Default_Handler + + .weak DebugMon_Handler + .thumb_set DebugMon_Handler,Default_Handler + + .weak PendSV_Handler + .thumb_set PendSV_Handler,Default_Handler + + .weak SysTick_Handler + .thumb_set SysTick_Handler,Default_Handler + + .weak WWDG_IRQHandler + .thumb_set WWDG_IRQHandler,Default_Handler + + .weak PVD_IRQHandler + .thumb_set PVD_IRQHandler,Default_Handler + + .weak TAMP_STAMP_IRQHandler + .thumb_set TAMP_STAMP_IRQHandler,Default_Handler + + .weak RTC_WKUP_IRQHandler + .thumb_set RTC_WKUP_IRQHandler,Default_Handler + + .weak FLASH_IRQHandler + .thumb_set FLASH_IRQHandler,Default_Handler + + .weak RCC_IRQHandler + .thumb_set RCC_IRQHandler,Default_Handler + + .weak EXTI0_IRQHandler + .thumb_set EXTI0_IRQHandler,Default_Handler + + .weak EXTI1_IRQHandler + .thumb_set EXTI1_IRQHandler,Default_Handler + + .weak EXTI2_IRQHandler + .thumb_set EXTI2_IRQHandler,Default_Handler + + .weak EXTI3_IRQHandler + .thumb_set EXTI3_IRQHandler,Default_Handler + + .weak EXTI4_IRQHandler + .thumb_set EXTI4_IRQHandler,Default_Handler + + .weak DMA1_Stream0_IRQHandler + .thumb_set DMA1_Stream0_IRQHandler,Default_Handler + + .weak DMA1_Stream1_IRQHandler + .thumb_set DMA1_Stream1_IRQHandler,Default_Handler + + .weak DMA1_Stream2_IRQHandler + .thumb_set DMA1_Stream2_IRQHandler,Default_Handler + + .weak DMA1_Stream3_IRQHandler + .thumb_set DMA1_Stream3_IRQHandler,Default_Handler + + .weak DMA1_Stream4_IRQHandler + .thumb_set DMA1_Stream4_IRQHandler,Default_Handler + + .weak DMA1_Stream5_IRQHandler + .thumb_set DMA1_Stream5_IRQHandler,Default_Handler + + .weak DMA1_Stream6_IRQHandler + .thumb_set DMA1_Stream6_IRQHandler,Default_Handler + + .weak ADC_IRQHandler + .thumb_set ADC_IRQHandler,Default_Handler + + .weak CAN1_TX_IRQHandler + .thumb_set CAN1_TX_IRQHandler,Default_Handler + + .weak CAN1_RX0_IRQHandler + .thumb_set CAN1_RX0_IRQHandler,Default_Handler + + .weak CAN1_RX1_IRQHandler + .thumb_set CAN1_RX1_IRQHandler,Default_Handler + + .weak CAN1_SCE_IRQHandler + .thumb_set CAN1_SCE_IRQHandler,Default_Handler + + .weak EXTI9_5_IRQHandler + .thumb_set EXTI9_5_IRQHandler,Default_Handler + + .weak TIM1_BRK_TIM9_IRQHandler + .thumb_set TIM1_BRK_TIM9_IRQHandler,Default_Handler + + .weak TIM1_UP_TIM10_IRQHandler + .thumb_set TIM1_UP_TIM10_IRQHandler,Default_Handler + + .weak TIM1_TRG_COM_TIM11_IRQHandler + .thumb_set TIM1_TRG_COM_TIM11_IRQHandler,Default_Handler + + .weak TIM1_CC_IRQHandler + .thumb_set TIM1_CC_IRQHandler,Default_Handler + + .weak TIM2_IRQHandler + .thumb_set TIM2_IRQHandler,Default_Handler + + .weak TIM3_IRQHandler + .thumb_set TIM3_IRQHandler,Default_Handler + + .weak TIM4_IRQHandler + .thumb_set TIM4_IRQHandler,Default_Handler + + .weak I2C1_EV_IRQHandler + .thumb_set I2C1_EV_IRQHandler,Default_Handler + + .weak I2C1_ER_IRQHandler + .thumb_set I2C1_ER_IRQHandler,Default_Handler + + .weak I2C2_EV_IRQHandler + .thumb_set I2C2_EV_IRQHandler,Default_Handler + + .weak I2C2_ER_IRQHandler + .thumb_set I2C2_ER_IRQHandler,Default_Handler + + .weak SPI1_IRQHandler + .thumb_set SPI1_IRQHandler,Default_Handler + + .weak SPI2_IRQHandler + .thumb_set SPI2_IRQHandler,Default_Handler + + .weak USART1_IRQHandler + .thumb_set USART1_IRQHandler,Default_Handler + + .weak USART2_IRQHandler + .thumb_set USART2_IRQHandler,Default_Handler + + .weak USART3_IRQHandler + .thumb_set USART3_IRQHandler,Default_Handler + + .weak EXTI15_10_IRQHandler + .thumb_set EXTI15_10_IRQHandler,Default_Handler + + .weak RTC_Alarm_IRQHandler + .thumb_set RTC_Alarm_IRQHandler,Default_Handler + + .weak OTG_FS_WKUP_IRQHandler + .thumb_set OTG_FS_WKUP_IRQHandler,Default_Handler + + .weak TIM8_BRK_TIM12_IRQHandler + .thumb_set TIM8_BRK_TIM12_IRQHandler,Default_Handler + + .weak TIM8_UP_TIM13_IRQHandler + .thumb_set TIM8_UP_TIM13_IRQHandler,Default_Handler + + .weak TIM8_TRG_COM_TIM14_IRQHandler + .thumb_set TIM8_TRG_COM_TIM14_IRQHandler,Default_Handler + + .weak TIM8_CC_IRQHandler + .thumb_set TIM8_CC_IRQHandler,Default_Handler + + .weak DMA1_Stream7_IRQHandler + .thumb_set DMA1_Stream7_IRQHandler,Default_Handler + + .weak FSMC_IRQHandler + .thumb_set FSMC_IRQHandler,Default_Handler + + .weak SDIO_IRQHandler + .thumb_set SDIO_IRQHandler,Default_Handler + + .weak TIM5_IRQHandler + .thumb_set TIM5_IRQHandler,Default_Handler + + .weak SPI3_IRQHandler + .thumb_set SPI3_IRQHandler,Default_Handler + + .weak UART4_IRQHandler + .thumb_set UART4_IRQHandler,Default_Handler + + .weak UART5_IRQHandler + .thumb_set UART5_IRQHandler,Default_Handler + + .weak TIM6_DAC_IRQHandler + .thumb_set TIM6_DAC_IRQHandler,Default_Handler + + .weak TIM7_IRQHandler + .thumb_set TIM7_IRQHandler,Default_Handler + + .weak DMA2_Stream0_IRQHandler + .thumb_set DMA2_Stream0_IRQHandler,Default_Handler + + .weak DMA2_Stream1_IRQHandler + .thumb_set DMA2_Stream1_IRQHandler,Default_Handler + + .weak DMA2_Stream2_IRQHandler + .thumb_set DMA2_Stream2_IRQHandler,Default_Handler + + .weak DMA2_Stream3_IRQHandler + .thumb_set DMA2_Stream3_IRQHandler,Default_Handler + + .weak DMA2_Stream4_IRQHandler + .thumb_set DMA2_Stream4_IRQHandler,Default_Handler + + .weak DFSDM1_FLT0_IRQHandler + .thumb_set DFSDM1_FLT0_IRQHandler,Default_Handler + + .weak DFSDM1_FLT1_IRQHandler + .thumb_set DFSDM1_FLT1_IRQHandler,Default_Handler + + .weak CAN2_TX_IRQHandler + .thumb_set CAN2_TX_IRQHandler,Default_Handler + + .weak CAN2_RX0_IRQHandler + .thumb_set CAN2_RX0_IRQHandler,Default_Handler + + .weak CAN2_RX1_IRQHandler + .thumb_set CAN2_RX1_IRQHandler,Default_Handler + + .weak CAN2_SCE_IRQHandler + .thumb_set CAN2_SCE_IRQHandler,Default_Handler + + .weak OTG_FS_IRQHandler + .thumb_set OTG_FS_IRQHandler,Default_Handler + + .weak DMA2_Stream5_IRQHandler + .thumb_set DMA2_Stream5_IRQHandler,Default_Handler + + .weak DMA2_Stream6_IRQHandler + .thumb_set DMA2_Stream6_IRQHandler,Default_Handler + + .weak DMA2_Stream7_IRQHandler + .thumb_set DMA2_Stream7_IRQHandler,Default_Handler + + .weak USART6_IRQHandler + .thumb_set USART6_IRQHandler,Default_Handler + + .weak I2C3_EV_IRQHandler + .thumb_set I2C3_EV_IRQHandler,Default_Handler + + .weak I2C3_ER_IRQHandler + .thumb_set I2C3_ER_IRQHandler,Default_Handler + + .weak CAN3_TX_IRQHandler + .thumb_set CAN3_TX_IRQHandler,Default_Handler + + .weak CAN3_RX0_IRQHandler + .thumb_set CAN3_RX0_IRQHandler,Default_Handler + + .weak CAN3_RX1_IRQHandler + .thumb_set CAN3_RX1_IRQHandler,Default_Handler + + .weak CAN3_SCE_IRQHandler + .thumb_set CAN3_SCE_IRQHandler,Default_Handler + + .weak RNG_IRQHandler + .thumb_set RNG_IRQHandler,Default_Handler + + .weak FPU_IRQHandler + .thumb_set FPU_IRQHandler,Default_Handler + + .weak UART7_IRQHandler + .thumb_set UART7_IRQHandler,Default_Handler + + .weak UART8_IRQHandler + .thumb_set UART8_IRQHandler,Default_Handler + + .weak SPI4_IRQHandler + .thumb_set SPI4_IRQHandler,Default_Handler + + .weak SPI5_IRQHandler + .thumb_set SPI5_IRQHandler,Default_Handler + + .weak SAI1_IRQHandler + .thumb_set SAI1_IRQHandler,Default_Handler + + .weak UART9_IRQHandler + .thumb_set UART9_IRQHandler,Default_Handler + + .weak UART10_IRQHandler + .thumb_set UART10_IRQHandler,Default_Handler + + .weak QUADSPI_IRQHandler + .thumb_set QUADSPI_IRQHandler,Default_Handler + + .weak FMPI2C1_EV_IRQHandler + .thumb_set FMPI2C1_EV_IRQHandler,Default_Handler + + .weak FMPI2C1_ER_IRQHandler + .thumb_set FMPI2C1_ER_IRQHandler,Default_Handler + + .weak LPTIM1_IRQHandler + .thumb_set LPTIM1_IRQHandler,Default_Handler + + .weak DFSDM2_FLT0_IRQHandler + .thumb_set DFSDM2_FLT0_IRQHandler,Default_Handler + + .weak DFSDM2_FLT1_IRQHandler + .thumb_set DFSDM2_FLT1_IRQHandler,Default_Handler + + .weak DFSDM2_FLT2_IRQHandler + .thumb_set DFSDM2_FLT2_IRQHandler,Default_Handler + + .weak DFSDM2_FLT3_IRQHandler + .thumb_set DFSDM2_FLT3_IRQHandler,Default_Handler +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/panda/board/stm32_flash.ld b/panda/board/stm32_flash.ld new file mode 100644 index 00000000000000..500319377efee1 --- /dev/null +++ b/panda/board/stm32_flash.ld @@ -0,0 +1,165 @@ +/* +***************************************************************************** +** +** File : stm32_flash.ld +** +** Abstract : Linker script for STM32F407VG Device with +** 1024KByte FLASH, 192KByte RAM +** +** Set heap size, stack size and stack location according +** to application requirements. +** +** Set memory bank area and size if external memory is used. +** +** Target : STMicroelectronics STM32 +** +** Environment : Atollic TrueSTUDIO(R) +** +** Distribution: The file is distributed “as is,” without any warranty +** of any kind. +** +** (c)Copyright Atollic AB. +** You may use this file as-is or modify it according to the needs of your +** project. Distribution of this file (unmodified or modified) is not +** permitted. Atollic AB permit registered Atollic TrueSTUDIO(R) users the +** rights to distribute the assembled, compiled & linked contents of this +** file as part of an application binary file, provided that it is built +** using the Atollic TrueSTUDIO(R) toolchain. +** +***************************************************************************** +*/ + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* Highest address of the user mode stack */ +enter_bootloader_mode = 0x2001FFFC; +_estack = 0x2001FFFC; /* end of 128K RAM on AHB bus*/ +_app_start = 0x08004000; /* Reserve 16K for bootloader */ + +/* Generate a link error if heap and stack don't fit into RAM */ +_Min_Heap_Size = 0; /* required amount of heap */ +_Min_Stack_Size = 0x400; /* required amount of stack */ + +/* Specify the memory areas */ +MEMORY +{ + FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 128K + RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 128K + MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K +} + +/* Define output sections */ +SECTIONS +{ + /* The startup code goes first into FLASH */ + .isr_vector : + { + . = ALIGN(4); + KEEP(*(.isr_vector)) /* Startup code */ + . = ALIGN(4); + } >FLASH + + /* The program code and other data goes into FLASH */ + .text : + { + . = ALIGN(4); + *(.text) /* .text sections (code) */ + *(.text*) /* .text* sections (code) */ + *(.rodata) /* .rodata sections (constants, strings, etc.) */ + *(.rodata*) /* .rodata* sections (constants, strings, etc.) */ + *(.glue_7) /* glue arm to thumb code */ + *(.glue_7t) /* glue thumb to arm code */ + *(.eh_frame) + + KEEP (*(.init)) + KEEP (*(.fini)) + + . = ALIGN(4); + _etext = .; /* define a global symbols at end of code */ + _exit = .; + } >FLASH + + + .ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH + .ARM : { + __exidx_start = .; + *(.ARM.exidx*) + __exidx_end = .; + } >FLASH + + .preinit_array : + { + PROVIDE_HIDDEN (__preinit_array_start = .); + KEEP (*(.preinit_array*)) + PROVIDE_HIDDEN (__preinit_array_end = .); + } >FLASH + .init_array : + { + PROVIDE_HIDDEN (__init_array_start = .); + KEEP (*(SORT(.init_array.*))) + KEEP (*(.init_array*)) + PROVIDE_HIDDEN (__init_array_end = .); + } >FLASH + .fini_array : + { + PROVIDE_HIDDEN (__fini_array_start = .); + KEEP (*(.fini_array*)) + KEEP (*(SORT(.fini_array.*))) + PROVIDE_HIDDEN (__fini_array_end = .); + } >FLASH + + /* used by the startup to initialize data */ + _sidata = .; + + /* Initialized data sections goes into RAM, load LMA copy after code */ + .data : AT ( _sidata ) + { + . = ALIGN(4); + _sdata = .; /* create a global symbol at data start */ + *(.data) /* .data sections */ + *(.data*) /* .data* sections */ + + . = ALIGN(4); + _edata = .; /* define a global symbol at data end */ + } >RAM + + /* Uninitialized data section */ + . = ALIGN(4); + .bss : + { + /* This is used by the startup in order to initialize the .bss secion */ + _sbss = .; /* define a global symbol at bss start */ + __bss_start__ = _sbss; + *(.bss) + *(.bss*) + *(COMMON) + + . = ALIGN(4); + _ebss = .; /* define a global symbol at bss end */ + __bss_end__ = _ebss; + } >RAM + + /* User_heap_stack section, used to check that there is enough RAM left */ + ._user_heap_stack : + { + . = ALIGN(4); + PROVIDE ( end = . ); + PROVIDE ( _end = . ); + . = . + _Min_Heap_Size; + . = . + _Min_Stack_Size; + . = ALIGN(4); + } >RAM + + /* MEMORY_bank1 section, code must be located here explicitly */ + /* Example: extern int foo(void) __attribute__ ((section (".mb1text"))); */ + .memory_b1_text : + { + *(.mb1text) /* .mb1text sections (code) */ + *(.mb1text*) /* .mb1text* sections (code) */ + *(.mb1rodata) /* read-only data (constants) */ + *(.mb1rodata*) + } >MEMORY_B1 + + .ARM.attributes 0 : { *(.ARM.attributes) } +} diff --git a/panda/board/tests/test_rsa.c b/panda/board/tests/test_rsa.c new file mode 100644 index 00000000000000..f4a7d6be0faba4 --- /dev/null +++ b/panda/board/tests/test_rsa.c @@ -0,0 +1,35 @@ +/* +gcc -DTEST_RSA test_rsa.c ../crypto/rsa.c ../crypto/sha.c && ./a.out +*/ + +#include +#include + +#define MAX_LEN 0x40000 +char buf[MAX_LEN]; + +#include "../crypto/sha.h" +#include "../crypto/rsa.h" +#include "../obj/cert.h" + +int main() { + FILE *f = fopen("../obj/panda.bin", "rb"); + int tlen = fread(buf, 1, MAX_LEN, f); + fclose(f); + printf("read %d\n", tlen); + uint32_t *_app_start = (uint32_t *)buf; + + int len = _app_start[0]; + char digest[SHA_DIGEST_SIZE]; + SHA_hash(&_app_start[1], len-4, digest); + printf("SHA hash done\n"); + + if (!RSA_verify(&rsa_key, ((void*)&_app_start[0]) + len, RSANUMBYTES, digest, SHA_DIGEST_SIZE)) { + printf("RSA fail\n"); + } else { + printf("RSA match!!!\n"); + } + + return 0; +} + diff --git a/panda/board/tools/dfu-util-aarch64 b/panda/board/tools/dfu-util-aarch64 new file mode 100755 index 00000000000000..250c592ada9795 Binary files /dev/null and b/panda/board/tools/dfu-util-aarch64 differ diff --git a/panda/board/tools/dfu-util-aarch64-linux b/panda/board/tools/dfu-util-aarch64-linux new file mode 100755 index 00000000000000..b366f869ace1cd Binary files /dev/null and b/panda/board/tools/dfu-util-aarch64-linux differ diff --git a/panda/board/tools/dfu-util-x86_64-linux b/panda/board/tools/dfu-util-x86_64-linux new file mode 100755 index 00000000000000..7be3dc3a7ef682 Binary files /dev/null and b/panda/board/tools/dfu-util-x86_64-linux differ diff --git a/panda/board/tools/enter_download_mode.py b/panda/board/tools/enter_download_mode.py new file mode 100755 index 00000000000000..ff3cf84ca97aa3 --- /dev/null +++ b/panda/board/tools/enter_download_mode.py @@ -0,0 +1,33 @@ +#!/usr/bin/env python +from __future__ import print_function + +import sys +import time +import usb1 + +def enter_download_mode(device): + handle = device.open() + handle.claimInterface(0) + + try: + handle.controlWrite(usb1.TYPE_VENDOR | usb1.RECIPIENT_DEVICE, 0xd1, 0, 0, b'') + except (usb1.USBErrorIO, usb1.USBErrorPipe) as e: + print("Device download mode enabled.") + time.sleep(1) + else: + print("Device failed to enter download mode.") + sys.exit(1) + +def find_first_panda(context=None): + context = context or usb1.USBContext() + for device in context.getDeviceList(skip_on_error=True): + if device.getVendorID() == 0xbbaa and device.getProductID()&0xFF00 == 0xdd00: + return device + +if __name__ == "__main__": + panda_dev = find_first_panda() + if panda_dev == None: + print("no device found") + sys.exit(0) + print("found device") + enter_download_mode(panda_dev) diff --git a/panda/boardesp/.gitignore b/panda/boardesp/.gitignore new file mode 100644 index 00000000000000..75255a58518e15 --- /dev/null +++ b/panda/boardesp/.gitignore @@ -0,0 +1,8 @@ +proxy +*.bin +esp-open-sdk +a.out +cert.h +gitversion.h +esp-open-sdk.dmg +obj/* diff --git a/panda/boardesp/ELM327.md b/panda/boardesp/ELM327.md new file mode 100644 index 00000000000000..6453b35ca41119 --- /dev/null +++ b/panda/boardesp/ELM327.md @@ -0,0 +1,101 @@ +ELM327 support for panda +====== +The panda now has basic ELM327 support. + +### What is ELM327? + +ELM327 is a command protocol for interfacing with cars using an OBD-II +port to read [list](standard vehicle diagnostic codes). ELM327 +originally referred to a line of programmable microcontrollers that +implemented the ELM327 command protocol, and are still being +developed. + +ELM327 devices present a shell and commands are sent via a UART. The +official ELM327 chips only support raw UART communication, but most +devices built with the ELM327 devices (official or clones) expose the +UART in a more modern way (Wifi, USB, etc). + +Mechanics use ELM to diagnose vehicles, and reset fault codes in the +car's computer after fixing the issue (turning off the dreaded check +engine light). Car owners can use ELM devices to perform the same +diagnostics in their garage using either a raw terminal to send +commands to the ELM device directly, or using a GUI (like one of +several popular smart phone apps) to translate the OBD error codes +into readable messages. These GUIs also often allow monitoring of the +performance of the car's speed, engine rpm, etc. + +The panda natively supports sending all the important OBD diagnostic +messages, but ELM327 support removes the need for the user to manually +craft CAN or LIN packets using the native panda API, and grants +compatibility with many existing tools. + +[Wikipedia](https://en.wikipedia.org/wiki/ELM327) can provide +additional information. + +### OBD Protocols? + +While the commands that the OBD standard describe are in fact +standard, there are several different protocols that those messages +can be sent and received with. All cars after 1991 support one of +these protocols. Which one depends on the car's year and country, as +legal requirements change over the years. + +The panda supports the most popular/modern of these protocols, and all +but two can be added as needed. Below is a chart of the OBD-II +protocols supported by the panda. + +| Protocol | Support Status | +| --- | --- | +| SAE J1850 PWM (41.6 kbit/s) | Never/Obsolete | +| SAE J1850 VPW (10.4 kbit/s) | Never/Obsolete | +| ISO 9141-2 (5 baud init, 10.4 kbit/s) | Unsupported | +| ISO 14230-4 KWP (5 baud init, 10.4 kbit/s) | Unsupported | +| ISO 14230-4 KWP (fast init, 10.4 kbit/s) | Supported | +| ISO 15765-4 CAN (11 bit ID, 500 kbit/s) | Supported | +| ISO 15765-4 CAN (29 bit ID, 500 kbit/s) | Supported | +| ISO 15765-4 CAN (11 bit ID, 250 kbit/s) | Supported | +| ISO 15765-4 CAN (29 bit ID, 250 kbit/s) | Supported | +| SAE J1939 (250kbps) | Unsupported | + +### The Implementation + +The panda ELM327 implementation is not a full implementation of all +the features of the official ELM327 microcontroller. Like most ELM327 +clones, the panda reports its ELM version as the unreleased version +1.5, despite only implementing commands from protocol version 1.0. + + +### Testing + +These tests require two pandas. One to be tested, and the second to +simulate the vehicle. + +The panda used to simulate the vehicle must be plugged into a USB port +of the testing computer. + +The computer running the tests must be connected to the panda being +tested's wifi network. + +The following command will run the tests (nosetest should work fine +instead of pytest if you still prefer using that). The CANSIMSERIAL +environment variable will force the car simulator to use the correct +panda as the simulator if multiple pandas are attached via usb to the +host computer. + +``` +CANSIMSERIAL=car_sim_panda_serial pytest tests/automated/elm_wifi.py +``` + +A single test can be run by putting the test name after the file name +and two colons, like so: + +``` +CANSIMSERIAL=car_sim_panda_serial pytest tests/automated/elm_wifi.py::test_important_thing +``` + +For more detail, provide the -s (show output) and the -vv (very +verbose) flags. + +``` +CANSIMSERIAL=car_sim_panda_serial pytest -s -vv tests/automated/elm_wifi.py +``` diff --git a/panda/boardesp/Makefile b/panda/boardesp/Makefile new file mode 100644 index 00000000000000..0b8fe32b693ff5 --- /dev/null +++ b/panda/boardesp/Makefile @@ -0,0 +1,74 @@ +PATH := esp-open-sdk/xtensa-lx106-elf/bin:$(PATH) +CC = esp-open-sdk/xtensa-lx106-elf/bin/xtensa-lx106-elf-gcc +CFLAGS = -Iinclude/ -I. -I../ -mlongcalls -Iesp-open-sdk/ESP8266_NONOS_SDK_V1.5.4_16_05_20/driver_lib/include -std=c99 -DICACHE_FLASH +LDLIBS = -nostdlib -Wl,--start-group -lmain -lnet80211 -lwpa -llwip -lpp -lphy -Wl,--end-group -lgcc -ldriver -Wl,--gc-sections +LDFLAGS = -Teagle.app.v6.ld +OBJCP = esp-open-sdk/xtensa-lx106-elf/bin/xtensa-lx106-elf-objcopy +SDK_BASE = esp-open-sdk/ESP8266_NONOS_SDK_V1.5.4_16_05_20 + +ifeq ($(RELEASE),1) + CERT = ../../pandaextra/certs/releaseesp +else + CERT = ../certs/debugesp + CFLAGS += "-DALLOW_DEBUG" +endif + +flashall: user1.bin user2.bin + ../python/esptool.py write_flash 0 $(SDK_BASE)/bin/boot_v1.5.bin 0x01000 user1.bin 0x81000 user2.bin 0x3FE000 $(SDK_BASE)/bin/blank.bin + +proxy-0x00000.bin: proxy + ../python/esptool.py elf2image $^ + +proxy: proxy.o elm327.o webserver.o sha.o + +obj/proxy.o: proxy.c + $(CC) $(CFLAGS) -c $^ -o $@ + +obj/elm327.o: elm327.c + $(CC) $(CFLAGS) -c $^ -o $@ + +obj/webserver.o: webserver.c obj/cert.h obj/gitversion.h + $(CC) $(CFLAGS) -c $< -o $@ + +obj/cert.h: ../crypto/getcertheader.py + ../crypto/getcertheader.py ../certs/debugesp.pub ../certs/releaseesp.pub > obj/cert.h + +include ../common/version.mk + +obj/sha.o: ../crypto/sha.c + $(CC) $(CFLAGS) -c $^ -o $@ + +obj/rsa.o: ../crypto/rsa.c + $(CC) $(CFLAGS) -c $^ -o $@ + +oldflash: proxy-0x00000.bin + ../python/esptool.py write_flash 0 proxy-0x00000.bin 0x40000 proxy-0x40000.bin + +user1.bin: obj/proxy.o obj/elm327.o obj/webserver.o obj/sha.o obj/rsa.o + $(CC) $(CFLAGS) $^ -o a.out -L$(SDK_BASE)/ld -T$(SDK_BASE)/ld/eagle.app.v6.new.1024.app1.ld $(LDLIBS) + $(OBJCP) --only-section .text -O binary a.out eagle.app.v6.text.bin + $(OBJCP) --only-section .data -O binary a.out eagle.app.v6.data.bin + $(OBJCP) --only-section .rodata -O binary a.out eagle.app.v6.rodata.bin + $(OBJCP) --only-section .irom0.text -O binary a.out eagle.app.v6.irom0text.bin + COMPILE=gcc python ./esp-open-sdk/ESP8266_NONOS_SDK_V1.5.4_16_05_20/tools/gen_appbin.py a.out 2 0 32 4 0 + rm -f eagle.app.v6.*.bin + mv eagle.app.flash.bin $@ + ../crypto/sign.py $@ $@ $(CERT) + +user2.bin: obj/proxy.o obj/elm327.o obj/webserver.o obj/sha.o obj/rsa.o + $(CC) $(CFLAGS) $^ -o a.out -L$(SDK_BASE)/ld -T$(SDK_BASE)/ld/eagle.app.v6.new.1024.app2.ld $(LDLIBS) + $(OBJCP) --only-section .text -O binary a.out eagle.app.v6.text.bin + $(OBJCP) --only-section .data -O binary a.out eagle.app.v6.data.bin + $(OBJCP) --only-section .rodata -O binary a.out eagle.app.v6.rodata.bin + $(OBJCP) --only-section .irom0.text -O binary a.out eagle.app.v6.irom0text.bin + COMPILE=gcc python ./esp-open-sdk/ESP8266_NONOS_SDK_V1.5.4_16_05_20/tools/gen_appbin.py a.out 2 0 32 4 0 + rm -f eagle.app.v6.*.bin + mv eagle.app.flash.bin $@ + ../crypto/sign.py $@ $@ $(CERT) + +ota: user1.bin user2.bin + curl http://192.168.0.10/espupdate1 --upload-file user1.bin + curl http://192.168.0.10/espupdate2 --upload-file user2.bin + +clean: + rm -f proxy proxy.o proxy-0x00000.bin proxy-0x40000.bin eagle.app.* user1.bin user2.bin a.out obj/* diff --git a/panda/boardesp/README.md b/panda/boardesp/README.md new file mode 100644 index 00000000000000..5a8fab14777fee --- /dev/null +++ b/panda/boardesp/README.md @@ -0,0 +1,22 @@ + +Dependencies +----- + +**Debian / Ubuntu** + +``` +./get_sdk.sh +``` + +**Mac** + +``` +./get_sdk_mac.sh +``` + +Programming +----- + +``` +make +``` diff --git a/panda/boardesp/elm327.c b/panda/boardesp/elm327.c new file mode 100644 index 00000000000000..6c18c4463b484d --- /dev/null +++ b/panda/boardesp/elm327.c @@ -0,0 +1,1576 @@ +#include "ets_sys.h" +#include "osapi.h" +#include "gpio.h" +#include "os_type.h" +#include "user_interface.h" +#include "espconn.h" +#include "mem.h" + +#include "driver/uart.h" + +//#define ELM_DEBUG + +#define min(a,b) ((a) < (b) ? (a) : (b)) +#define max(a,b) ((a) > (b) ? (a) : (b)) +int ICACHE_FLASH_ATTR spi_comm(char *dat, int len, uint32_t *recvData, int recvDataLen); + +#define ELM_PORT 35000 + +//Version 1.5 is an invalid version used by many pirate clones +//that only partially support 1.0. +#define IDENT_MSG "ELM327 v1.5\r\r" +#define DEVICE_DESC "Panda\n\n" + +#define SHOW_CONNECTION(msg, p_conn) os_printf("%s %p, proto %p, %d.%d.%d.%d:%d disconnect\r\n", \ + msg, p_conn, (p_conn)->proto.tcp, (p_conn)->proto.tcp->remote_ip[0], \ + (p_conn)->proto.tcp->remote_ip[1], (p_conn)->proto.tcp->remote_ip[2], \ + (p_conn)->proto.tcp->remote_ip[3], (p_conn)->proto.tcp->remote_port) + +const static char hex_lookup[] = {'0', '1', '2', '3', '4', '5', '6', '7', + '8', '9', 'A', 'B', 'C', 'D', 'E', 'F'}; + +typedef struct __attribute__((packed)) { + bool tx : 1; + bool : 1; + bool ext : 1; + uint32_t addr : 29; + + uint8_t len : 4; + uint8_t bus : 8; + uint8_t : 4; //unused + uint16_t ts : 16; + uint8_t data[8]; +} panda_can_msg_t; + +//TODO: Masking is likely unnecessary for these bit fields. Check. +#define panda_get_can_addr(recv) (((recv)->ext) ? ((recv)->addr & 0x1FFFFFFF) :\ + (((recv)->addr >> 18) & 0x7FF)) + +#define PANDA_CAN_FLAG_TRANSMIT 1 +#define PANDA_CAN_FLAG_EXTENDED 4 + +#define PANDA_USB_CAN_WRITE_BUS_NUM 3 +#define PANDA_USB_LIN_WRITE_BUS_NUM 2 + +typedef struct _elm_tcp_conn { + struct espconn *conn; + struct _elm_tcp_conn *next; +} elm_tcp_conn_t; + +typedef struct __attribute__((packed)) { + uint8_t len; + uint8_t dat[7]; //mode and data +} elm_can_obd_msg; + +typedef struct __attribute__((packed)) { + uint8_t priority; + uint8_t receiver; + uint8_t sender; + + uint8_t dat[8]; //mode, data, and checksum +} elm_lin_obd_msg; + +typedef struct __attribute__((packed)) { + uint16_t usb_ep_num; + uint16_t payload_len; + + uint8_t serial_port; + //uint8_t msg[8+3]; + elm_lin_obd_msg msg; +} elm_lin_usb_msg; + +static struct espconn elm_conn; +static esp_tcp elm_proto; +static elm_tcp_conn_t *connection_list = NULL; + +static char stripped_msg[0x100]; +static uint16 stripped_msg_len = 0; + +static char in_msg[0x100]; +static uint16 in_msg_len = 0; + +static char rsp_buff[536]; //TCP min MTU +static uint16 rsp_buff_len = 0; + +static uint8_t pandaSendData[0x14] = {0}; +static uint32_t pandaRecvData[0x40] = {0}; +static uint32_t pandaRecvDataDummy[0x40] = {0}; // Used for CAN write operations (no received data) + +#define ELM_MODE_SELECTED_PROTOCOL_DEFAULT 6 +#define ELM_MODE_TIMEOUT_DEFAULT 20; +#define ELM_MODE_KEEPALIVE_PERIOD_DEFAULT (0x92*20) + +static bool elm_mode_echo = true; +static bool elm_mode_linefeed = false; +static bool elm_mode_additional_headers = false; +static bool elm_mode_auto_protocol = true; +static uint8_t elm_selected_protocol = ELM_MODE_SELECTED_PROTOCOL_DEFAULT; +static bool elm_mode_print_spaces = true; +static uint8_t elm_mode_adaptive_timing = 1; +static bool elm_mode_allow_long = false; +static uint16_t elm_mode_timeout = ELM_MODE_TIMEOUT_DEFAULT; +static uint16_t elm_mode_keepalive_period = ELM_MODE_KEEPALIVE_PERIOD_DEFAULT; + +bool lin_bus_initialized = false; + +/*********************************************** + *** ELM CLI response functions *** + *** (for sending data back to the terminal) *** + ***********************************************/ + +// All ELM operations are global, so send data out to all connections +void ICACHE_FLASH_ATTR elm_tcp_tx_flush() { + if(!rsp_buff_len) return; // Was causing small error messages + + for(elm_tcp_conn_t *iter = connection_list; iter != NULL; iter = iter->next){ + int8_t err = espconn_send(iter->conn, rsp_buff, rsp_buff_len); + if(err){ + os_printf(" Wifi %p TX error code %d\n", iter->conn, err); + if(err == ESPCONN_ARG) { + if(iter == connection_list) { + connection_list = iter->next; + } else { + for(elm_tcp_conn_t *iter2 = connection_list; iter2 != NULL; iter2 = iter2->next) + if(iter2->next == iter) { + iter2->next = iter->next; + break; + } + } + os_printf(" deleting orphaned connection. iter: %p; conn: %p\n", iter, iter->conn); + os_free(iter); + } + } + } + rsp_buff_len = 0; +} + +static void ICACHE_FLASH_ATTR elm_append_rsp(const char *data, uint16_t len) { + uint16_t overflow_len = 0; + if(rsp_buff_len + len > sizeof(rsp_buff)) { + overflow_len = rsp_buff_len + len - sizeof(rsp_buff); + len = sizeof(rsp_buff) - rsp_buff_len; + } + if(!elm_mode_linefeed) { + memcpy(rsp_buff + rsp_buff_len, data, len); + rsp_buff_len += len; + } else { + for(int i=0; i < len && rsp_buff_len < sizeof(rsp_buff); i++){ + rsp_buff[rsp_buff_len++] = data[i]; + if(data[i] == '\r' && rsp_buff_len < sizeof(rsp_buff)) + rsp_buff[rsp_buff_len++] = '\n'; + } + } + if(overflow_len) { + os_printf("Packet full, sending\n"); + elm_tcp_tx_flush(); + elm_append_rsp(data + len, overflow_len); + } +} + +#define elm_append_rsp_const(str) elm_append_rsp(str, sizeof(str)-1) + +static void ICACHE_FLASH_ATTR elm_append_rsp_hex_byte(uint8_t num) { + elm_append_rsp(&hex_lookup[num >> 4], 1); + elm_append_rsp(&hex_lookup[num & 0xF], 1); + if(elm_mode_print_spaces) elm_append_rsp_const(" "); +} + +void ICACHE_FLASH_ATTR elm_append_rsp_can_msg_addr(const panda_can_msg_t *recv) { + //Show address + uint32_t addr = panda_get_can_addr(recv); + if(recv->ext){ + elm_append_rsp_hex_byte(addr>>24); + elm_append_rsp_hex_byte(addr>>16); + elm_append_rsp_hex_byte(addr>>8); + elm_append_rsp_hex_byte(addr); + } else { + elm_append_rsp(&hex_lookup[addr>>8], 1); + elm_append_rsp_hex_byte(addr); + } +} + +/*************************************** + *** Panda communication functions *** + *** (for controlling the Panda MCU) *** + ***************************************/ + +static int ICACHE_FLASH_ATTR panda_usbemu_ctrl_write(uint8_t request_type, uint8_t request, + uint16_t value, uint16_t index, uint16_t length) { + //self.sock.send(struct.pack("HHBBHHH", 0, 0, request_type, request, value, index, length)); + *(uint16_t*)(pandaSendData) = 0; + *(uint16_t*)(pandaSendData+2) = 0; + pandaSendData[4] = request_type; + pandaSendData[5] = request; + *(uint16_t*)(pandaSendData+6) = value; + *(uint16_t*)(pandaSendData+8) = index; + *(uint16_t*)(pandaSendData+10) = length; + + int returned_count = spi_comm(pandaSendData, 0x10, pandaRecvData, 0x40); + if(returned_count > 0x40 || returned_count < 0) + return -1; + return returned_count; +} + +#define panda_set_can0_cbaud(cbps) panda_usbemu_ctrl_write(0x40, 0xde, 0, cbps, 0) +#define panda_set_can0_kbaud(kbps) panda_usbemu_ctrl_write(0x40, 0xde, 0, kbps*10, 0) +#define panda_set_safety_mode(mode) panda_usbemu_ctrl_write(0x40, 0xdc, mode, 0, 0) +#define panda_kline_wakeup_pulse() panda_usbemu_ctrl_write(0x40, 0xf0, 0, 0, 0) +#define panda_clear_can_rx() panda_usbemu_ctrl_write(0x40, 0xf1, 0xFFFF, 0, 0) +#define panda_clear_lin_txrx() panda_usbemu_ctrl_write(0x40, 0xf2, 2, 0, 0) + +static int ICACHE_FLASH_ATTR panda_usbemu_can_read(panda_can_msg_t** can_msgs) { + int returned_count = spi_comm((uint8_t *)((const uint16 []){1,0}), 4, pandaRecvData, 0x40); + if(returned_count > 0x40 || returned_count < 0){ + os_printf("CAN read got invalid length\n"); + return -1; + } + *can_msgs = (panda_can_msg_t*)(pandaRecvData+1); + return returned_count/sizeof(panda_can_msg_t); +} + +static int ICACHE_FLASH_ATTR panda_usbemu_can_write(bool ext, uint32_t addr, + char *candata, uint8_t canlen) { + uint32_t rir; + + if(canlen > 8) return 0; + + if(ext || addr >= 0x800){ + rir = (addr << 3) | PANDA_CAN_FLAG_TRANSMIT | PANDA_CAN_FLAG_EXTENDED; + }else{ + rir = (addr << 21) | PANDA_CAN_FLAG_TRANSMIT; + } + + #define MAX_CAN_LEN 8 + + //Wifi USB Wrapper + *(uint16_t*)(pandaSendData) = PANDA_USB_CAN_WRITE_BUS_NUM; //USB Bulk Endpoint ID. + *(uint16_t*)(pandaSendData+2) = MAX_CAN_LEN; + //BULK MESSAGE + *(uint32_t*)(pandaSendData+4) = rir; + *(uint32_t*)(pandaSendData+8) = MAX_CAN_LEN | (0 << 4); //0 is CAN bus number. + //CAN DATA + memcpy(pandaSendData+12, candata, canlen); + memset(pandaSendData+12+canlen, 0, MAX_CAN_LEN-canlen); + for(int i = 12+canlen; i < 20; i++) pandaSendData[i] = 0; //Zero the rest + + /* spi_comm will erase data in the recv buffer even if you are only + * interested in sending data that gets no response (like writing + * can data). This behavior becomes problematic when trying to send + * a can message while processsing received can messages. A dummy + * recv buffer is used here so received data is not overwritten. */ + int returned_count = spi_comm(pandaSendData, 0x14, pandaRecvDataDummy, 0x40); + if(returned_count) + os_printf("ELM Can send expected 0 bytes back from panda. Got %d bytes instead\n", returned_count); + if(returned_count > 0x40) return 0; + return returned_count; +} + +elm_lin_obd_msg lin_last_sent_msg; +uint16_t lin_last_sent_msg_len = 0; +bool lin_await_msg_echo = false; + +static int ICACHE_FLASH_ATTR panda_usbemu_kline_read(uint16_t len) { + int returned_count = panda_usbemu_ctrl_write(0xC0, 0xE0, 2, 0, len); + if(returned_count > len || returned_count < 0){ + os_printf("LIN read got invalid length\n"); + return -1; + } + + #ifdef ELM_DEBUG + if(returned_count) { + os_printf("LIN Received %d bytes\n", returned_count); + os_printf(" Data: "); + for(int i = 0; i < returned_count; i++) + os_printf("%02x ", ((char*)(pandaRecvData+1))[i]); + os_printf("\n"); + } + #endif + return returned_count; +} + +static int ICACHE_FLASH_ATTR panda_usbemu_kline_write(elm_lin_obd_msg *msg) { + elm_lin_usb_msg usb_msg = {}; + + usb_msg.usb_ep_num = PANDA_USB_LIN_WRITE_BUS_NUM; //USB Bulk Endpoint ID. + usb_msg.payload_len = (msg->priority & 0x07) + 4 + 1; //The +1 is for serial_port + usb_msg.serial_port = 2; + memcpy(&usb_msg.msg, msg, sizeof(elm_lin_obd_msg)); + + /* spi_comm will erase data in the recv buffer even if you are only + * interested in sending data that gets no response (like writing + * can data). This behavior becomes problematic when trying to send + * a can message while processsing received can messages. A dummy + * recv buffer is used here so received data is not overwritten. */ + int returned_count = spi_comm((char*)&usb_msg, sizeof(elm_lin_usb_msg), pandaRecvDataDummy, 0x40); + + if(returned_count) + os_printf("ELM LIN send expected 0 bytes back from panda. Got %d bytes instead\n", returned_count); + if(returned_count > 0x40) return 0; + + return returned_count; +} + +/**************************************** + *** Ringbuffer *** + ****************************************/ + +//LIN data is delivered in chunks of arbitrary size. Using a +//ringbuffer to handle it. +uint8_t lin_ringbuff[0x20]; +uint8_t lin_ringbuff_start = 0; +uint8_t lin_ringbuff_end = 0; +#define lin_ringbuff_len \ + (((sizeof(lin_ringbuff) + lin_ringbuff_end) - lin_ringbuff_start)% sizeof(lin_ringbuff)) +#define lin_ringbuff_get(index) (lin_ringbuff[(lin_ringbuff_start + index) % sizeof(lin_ringbuff)]) +#define lin_ringbuff_consume(len) lin_ringbuff_start = ((lin_ringbuff_start + len) % sizeof(lin_ringbuff)) +#define lin_ringbuff_clear()\ + {lin_ringbuff_start = 0; \ + lin_ringbuff_end = 0;} + +int ICACHE_FLASH_ATTR elm_LIN_ringbuff_memcmp(uint8_t *data, uint16_t len) { + if(len > lin_ringbuff_len) return 1; + for(int i = 0; i < len; i++) + if(lin_ringbuff_get(i) != data[i]) return 1; + return 0; // Going with memcpy ret format where 0 means 'equal' +} + +uint16_t ICACHE_FLASH_ATTR elm_LIN_read_into_ringbuff() { + int bytelen = panda_usbemu_kline_read((sizeof(lin_ringbuff) - lin_ringbuff_len) - 1); + if(bytelen < 0) return 0; + for(int j = 0; j < bytelen; j++) { + lin_ringbuff[lin_ringbuff_end % sizeof(lin_ringbuff)] = ((char*)(pandaRecvData+1))[j]; + lin_ringbuff_end = (lin_ringbuff_end + 1) % sizeof(lin_ringbuff); + if(lin_ringbuff_start == lin_ringbuff_end) lin_ringbuff_start++; + } + + #ifdef ELM_DEBUG + if(bytelen){ + os_printf(" RB Data (%d %d %d): ", lin_ringbuff_start, lin_ringbuff_end, lin_ringbuff_len); + for(int i = 0; i < sizeof(lin_ringbuff); i++) + os_printf("%02x ", lin_ringbuff[i]); + os_printf("\n"); + } + #endif + + return bytelen; +} + +/**************************************** + *** String parsing utility functions *** + ****************************************/ + +static int8_t ICACHE_FLASH_ATTR elm_decode_hex_char(char b){ + if(b >= '0' && b <= '9') return b - '0'; + if(b >= 'A' && b <= 'F') return (b - 'A') + 10; + if(b >= 'a' && b <= 'f') return (b - 'a') + 10; + return -1; +} + +static uint8_t ICACHE_FLASH_ATTR elm_decode_hex_byte(const char* data) { + return (elm_decode_hex_char(data[0]) << 4) | elm_decode_hex_char(data[1]); +} + +static bool ICACHE_FLASH_ATTR elm_check_valid_hex_chars(const char* data, uint8_t len) { + for(int i = 0; i < len; i++){ + char b = data[i]; + if(!((b >= '0' && b <= '9') || (b >= 'A' && b <= 'F') || (b >= 'a' && b <= 'f'))) + return 0; + } + return 1; +} + +static uint16_t ICACHE_FLASH_ATTR elm_strip(const char *data, uint16_t lenin, + char *outbuff, uint16_t outbufflen) { + uint16_t count = 0; + for(uint16_t i = 0; i < lenin; i++) { + if(count >= outbufflen) break; + if(data[i] == ' ') continue; + if(data[i] >= 'a' && data[i] <= 'z'){ + outbuff[count++] = data[i] - ('a' - 'A'); + } else { + outbuff[count++] = data[i]; + } + if(data[i] == '\r') break; + } + return count; +} + +static int ICACHE_FLASH_ATTR elm_msg_find_cr_or_eos(char *data, uint16_t len){ + uint16_t i; + for(i = 0; i < len; i++) + if(data[i] == '\r') { + i++; + break; + } + return i; +} + +/***************************************************** + *** ELM protocol specification and implementation *** + *****************************************************/ + +typedef enum { + AUTO, LIN, CAN11, CAN29, NA +} elm_proto_type_t; + +typedef struct elm_protocol { + bool supported; + elm_proto_type_t type; + uint16_t cbaud; //Centibaud (cbaud * 10 = kbaud) + void (*process_obd)(const struct elm_protocol*, const char*, uint16_t); + //init is used to init and de-init a protocol. Init functions should + //not do things that would leave a new protocol in an invalid state + //after the new protocol's init is called (e.g. No arming timers). + void (*init)(const struct elm_protocol*); + char* name; +} elm_protocol_t; + +static const elm_protocol_t* ICACHE_FLASH_ATTR elm_current_proto(); +void ICACHE_FLASH_ATTR elm_reset_aux_timer(); +static void ICACHE_FLASH_ATTR elm_autodetect_cb(bool); + +static const elm_protocol_t elm_protocols[]; +//(sizeof(elm_protocols)/sizeof(elm_protocol_t)) +#define ELM_PROTOCOL_COUNT 13 + +#define LOOPCOUNT_FULL 4 +static int loopcount = 0; +static volatile os_timer_t elm_timeout; +static volatile os_timer_t elm_proto_aux_timeout; + +static bool is_auto_detecting = false; + +// Used only by elm_timer_cb, so not volatile +static bool did_multimessage = false; +static bool got_msg_this_run = false; +static bool can_tx_worked = false; +static uint8_t elm_msg_mode_ret_filter; +static uint8_t elm_msg_pid_ret_filter; + +/***************************************************** + *** ELM protocol specification and implementation *** + *** -> SAE J1850 implementation (Unsupported) *** + *****************************************************/ + +static void ICACHE_FLASH_ATTR elm_process_obd_cmd_J1850(const elm_protocol_t* proto, + const char *cmd, uint16_t len) { + elm_append_rsp_const("NO DATA\r\r>"); +} + +/***************************************************** + *** ELM protocol specification and implementation *** + *** -> ISO 14230-4 implementation *** + *****************************************************/ + +const char *lin_cmd_backup = NULL; //Holds msg while bus init is done +uint16_t lin_cmd_backup_len = 0; +bool lin_waiting_keepalive_echo = false; + +static void ICACHE_FLASH_ATTR elm_process_obd_cmd_LIN5baud(const elm_protocol_t* proto, + const char *cmd, uint16_t len) { + elm_append_rsp_const("BUS INIT: ...ERROR\r\r>"); +} + +bool ICACHE_FLASH_ATTR elm_lin_keepalive_echo() { + if(lin_waiting_keepalive_echo) { + for(int pass = 0; pass < 4 && lin_ringbuff_len < 5; pass++) { + elm_LIN_read_into_ringbuff(); + } + + lin_waiting_keepalive_echo = false; + //keepalive Echo should always come before other message echo. + if(lin_ringbuff_len >= 5 && !elm_LIN_ringbuff_memcmp("\xc1\x33\xf1\x3e\x23", 5)){ + lin_ringbuff_consume(5); + return true; + } else { + os_printf("Keep alive echo failed\n"); + return false; + } + } + return true; +} + +void ICACHE_FLASH_ATTR elm_LINFast_keepalive_timer_cb(void *arg) { + if(!lin_bus_initialized) { + os_printf("WARNING! Elm LIN keepalive timer running while bus is not initialized\n"); + return; + } + if(loopcount) { + os_printf("WARNING! Elm LIN keepalive timer during a tx/rx loop!\n"); + return; + } + if(lin_ringbuff_len) { + os_printf("WARNING! lin_ringbuff_len should be 0 when a keepalive echo is processed.\n"); + return; + } + + if(!elm_lin_keepalive_echo()) { + lin_bus_initialized = false; + return; + } + + elm_lin_obd_msg msg = {}; + + msg.priority = 0xC0 | 1; + msg.receiver = 0x33; + msg.sender = 0xF1; + msg.dat[0] = 0x3E; + msg.dat[1] = msg.dat[0] + msg.priority + msg.receiver + msg.sender; // checksum + + #ifdef ELM_DEBUG + os_printf("Sending LIN KEEPALIVE: Priority: %02x; RecvAddr: %02x; SendAddr: %02x; (%02x); ", + msg.priority, msg.receiver, msg.sender, 1); + for(int i = 0; i < 2; i++) os_printf("%02x ", msg.dat[i]); + os_printf("\n"); + #endif + + lin_waiting_keepalive_echo = true; + + panda_usbemu_kline_write(&msg); + elm_reset_aux_timer(); +} + +static void ICACHE_FLASH_ATTR elm_init_LINFast(const elm_protocol_t* proto){ + os_timer_disarm(&elm_proto_aux_timeout); + os_timer_setfn(&elm_proto_aux_timeout, (os_timer_func_t *)elm_LINFast_keepalive_timer_cb, proto); + + lin_bus_initialized = false; + lin_await_msg_echo = false; + lin_waiting_keepalive_echo = false; + + lin_cmd_backup = NULL; + lin_cmd_backup_len = 0; + + lin_ringbuff_clear(); + panda_clear_lin_txrx(); +} + +int ICACHE_FLASH_ATTR elm_LINFast_process_echo() { + if(!elm_lin_keepalive_echo()) { + os_printf("Keepalive echo not detected.\n"); + lin_ringbuff_clear(); + return -1; + } + + if(!lin_await_msg_echo) { + os_printf("Echo abort. Nothing waiting echo\n"); + return 1; + } + + for(int i = 0; i < 4; i++){ + if(lin_ringbuff_len < lin_last_sent_msg_len) elm_LIN_read_into_ringbuff(); + + if(lin_ringbuff_len >= lin_last_sent_msg_len){ + #ifdef ELM_DEBUG + os_printf("Got enough data %d\n", lin_last_sent_msg_len); + #endif + if(!elm_LIN_ringbuff_memcmp((uint8_t*)&lin_last_sent_msg, lin_last_sent_msg_len)) { + #ifdef ELM_DEBUG + os_printf("LIN data was sent successfully.\n"); + #endif + lin_ringbuff_consume(lin_last_sent_msg_len); + lin_await_msg_echo = false; + return 1; + } else { + #ifdef ELM_DEBUG + os_printf("Echo not correct.\n"); + os_printf(" RB Data (%d %d %d): ", lin_ringbuff_start, lin_ringbuff_end, lin_ringbuff_len); + for(int i = 0; i < sizeof(lin_ringbuff); i++) + os_printf("%02x ", lin_ringbuff[i]); + os_printf("\n"); + os_printf(" MSG Data (%d): ", lin_last_sent_msg_len); + for(int i = 0; i < lin_last_sent_msg_len; i++) + os_printf("%02x ", ((uint8_t*)&lin_last_sent_msg)[i]); + os_printf("\n"); + #endif + + if(lin_bus_initialized || loopcount == 0 && i == 4) { + lin_ringbuff_clear(); + return -1; + } else { + os_printf("Lin init echo misaligned? Consuming byte (%02x). Retry.\n", lin_ringbuff_get(0)); + lin_ringbuff_consume(1); + continue; + } + } + } + } + + return !lin_await_msg_echo; //true if echo handled +} + +void ICACHE_FLASH_ATTR elm_LINFast_timer_cb(void *arg){ + const elm_protocol_t* proto = (const elm_protocol_t*) arg; + loopcount--; + #ifdef ELM_DEBUG + os_printf("LIN CB call\n"); + #endif + + if(!lin_bus_initialized) { + os_printf("WARNING: LIN CB called without bus initialized!"); + return; // TODO: shoulnd't ever happen. Handle? + } + + int echo_result = elm_LINFast_process_echo(); + + if(echo_result == -1 || (echo_result == 0 && loopcount == 0)) { + if(!is_auto_detecting){ + elm_append_rsp_const("BUS ERROR\r\r>"); + elm_tcp_tx_flush(); + } + loopcount = 0; + lin_bus_initialized = false; + return; + } + + if(echo_result == 0) { + #ifdef ELM_DEBUG + os_printf("Not ready to process\n"); + #endif + os_timer_arm(&elm_timeout, 30, 0); + return; // Not ready to go on + } + + #ifdef ELM_DEBUG + os_printf("Processing ELM %d\n", lin_ringbuff_len); + #endif + + if(loopcount>0) { + for(int pass = 0; pass < 16 && loopcount; pass++){ + elm_LIN_read_into_ringbuff(); + + while(lin_ringbuff_len > 0){ + //if(lin_ringbuff_len > 0){ + if(lin_ringbuff_get(0) & 0x80 != 0x80){ + os_printf("Resetting LIN bus due to bad first byte.\n"); + loopcount = 0; + lin_bus_initialized = false; + lin_ringbuff_clear(); + + if(!is_auto_detecting){ + elm_append_rsp_const("ERROR\r\r>"); + elm_tcp_tx_flush(); + } + return; + } + + uint8_t newmsg_len = 4 + (lin_ringbuff_get(0) & 0x7); + if(lin_ringbuff_len >= newmsg_len) { + #ifdef ELM_DEBUG + os_printf("Processing LIN MSG. BuffLen %d; expect %d. Dat: ", lin_ringbuff_len, newmsg_len); + for(int i = 0; i < newmsg_len; i++) os_printf("%02x ", lin_ringbuff_get(i)); + os_printf("\n"); + #endif + got_msg_this_run = true; + loopcount = LOOPCOUNT_FULL; + + if(!is_auto_detecting){ + if(elm_mode_additional_headers){ + for(int i = 0; i < newmsg_len; i++) elm_append_rsp_hex_byte(lin_ringbuff_get(i)); + } else { + for(int i = 3; i < newmsg_len - 1; i++) elm_append_rsp_hex_byte(lin_ringbuff_get(i)); + } + elm_append_rsp_const("\r"); + } + + lin_ringbuff_consume(newmsg_len); + //elm_reset_aux_timer(); + } else { + break; //Stop consuming data if there is not enough data for the next msg. + } + } + } + os_timer_arm(&elm_timeout, 50, 0); + } else { + bool got_msg_this_run_backup = got_msg_this_run; + if(!got_msg_this_run) { + #ifdef ELM_DEBUG + os_printf(" No data collected\n"); + #endif + if(!is_auto_detecting) { + elm_append_rsp_const("NO DATA\r"); + } + } + got_msg_this_run = false; + + if(!is_auto_detecting) { + elm_append_rsp_const("\r>"); + elm_tcp_tx_flush(); + } else { + elm_autodetect_cb(got_msg_this_run_backup); + } + + //TX RX over, resume Keepalive timer + elm_reset_aux_timer(); + } +} + +void ICACHE_FLASH_ATTR elm_LINFast_businit_timer_cb(void *arg){ + const elm_protocol_t* proto = (const elm_protocol_t*) arg; + loopcount--; + #ifdef ELM_DEBUG + os_printf("LIN INIT CB call\n"); + #endif + + int echo_result = elm_LINFast_process_echo(); + + if(echo_result == -1 || (echo_result == 0 && loopcount == 0)) { + #ifdef ELM_DEBUG + os_printf("Init failed with echo test\n"); + #endif + + loopcount = 0; + lin_bus_initialized = 0; + + if(!is_auto_detecting){ + if(echo_result == -1) + elm_append_rsp_const("BUS ERROR\r\r>"); + else + elm_append_rsp_const("ERROR\r\r>"); + elm_tcp_tx_flush(); + } else { + elm_autodetect_cb(false); + } + return; + } + + if(echo_result == 0) { + #ifdef ELM_DEBUG + os_printf("Not ready to process\n"); + #endif + os_timer_arm(&elm_timeout, elm_mode_timeout, 0); + return; // Not ready to go on + } + + #ifdef ELM_DEBUG + os_printf("Bus init ready to process %d bytes\n", lin_ringbuff_len); + #endif + + if(lin_bus_initialized) return; // TODO: shoulnd't ever happen. Handle? + + if(loopcount>0) { + //Keep waiting for response + for(int i = 0; i < 4; i++){ + elm_LIN_read_into_ringbuff(); + + if(lin_ringbuff_len > 0){ + if(lin_ringbuff_get(0) & 0x80 != 0x80){ + os_printf("Resetting LIN bus due to bad first byte.\n"); + loopcount = 0; + lin_ringbuff_clear(); + + if(!is_auto_detecting){ + elm_append_rsp_const("ERROR\r\r>"); + elm_tcp_tx_flush(); + } else { + elm_autodetect_cb(false); + } + return; + } + + uint8_t newmsg_len = 4 + (lin_ringbuff_get(0) & 0x7); + if(lin_ringbuff_len < newmsg_len) { + os_printf("Resetting LIN because returned init data was wrong.\n"); + loopcount = 0; + lin_ringbuff_clear(); + + if(!is_auto_detecting){ + elm_append_rsp_const("ERROR\r\r>"); + elm_tcp_tx_flush(); + } else { + elm_autodetect_cb(false); + } + return; + } + + if(!elm_LIN_ringbuff_memcmp("\x83\xF1\x10\xC1\x8F\xE9\xBD", 7)) { + lin_ringbuff_consume(7); + lin_bus_initialized = true; + //lin_ringbuff_clear(); + + os_printf("BUS INITIALIZED\n"); + + elm_reset_aux_timer(); + + if(!is_auto_detecting) { + elm_append_rsp_const("OK\r"); + + //Do the send that was delayed + if(lin_cmd_backup_len) { + elm_tcp_tx_flush(); + proto->process_obd(proto, lin_cmd_backup, lin_cmd_backup_len); + } else { + elm_append_rsp_const("\r>"); + elm_tcp_tx_flush(); + } + } else { + #ifdef ELM_DEBUG + os_printf("LIN success. Silent because in autodetect.\n"); + #endif + elm_autodetect_cb(true); + // TODO: Since bus init is good, is it ok to skip sending the '0100' msg? + } + return; + } + } + } + os_timer_arm(&elm_timeout, elm_mode_timeout, 0); + } else { + #ifdef ELM_DEBUG + os_printf("Fall through on bus init\n"); + #endif + if(!is_auto_detecting){ + elm_append_rsp_const("ERROR\r\r>"); + elm_tcp_tx_flush(); + } else { + elm_autodetect_cb(false); + } + elm_reset_aux_timer(); + } +} + +static void ICACHE_FLASH_ATTR elm_process_obd_cmd_LINFast(const elm_protocol_t* proto, + const char *cmd, uint16_t len) { + elm_lin_obd_msg msg = {}; + uint8_t bytelen = (len-1)/2; + if((bytelen > 7 && !elm_mode_allow_long) || bytelen > 8) { + elm_append_rsp_const("?\r\r>"); + return; + } + + os_timer_disarm(&elm_proto_aux_timeout); + + if(!lin_bus_initialized) { + panda_clear_lin_txrx(); + + if(!is_auto_detecting) + elm_append_rsp_const("BUS INIT: "); + + lin_cmd_backup = cmd; + lin_cmd_backup_len = len; + + bytelen = 1; + msg.dat[0] = 0x81; + msg.dat[1] = 0x81; // checksum + + panda_kline_wakeup_pulse(); + } else { + bytelen = min(bytelen, 7); + for(int i = 0; i < bytelen; i++){ + msg.dat[i] = elm_decode_hex_byte(&cmd[i*2]); + msg.dat[bytelen] += msg.dat[i]; + } + + elm_msg_mode_ret_filter = msg.dat[0]; + elm_msg_pid_ret_filter = msg.dat[1]; + } + + msg.priority = 0xC0 | bytelen; + msg.receiver = 0x33; + msg.sender = 0xF1; + msg.dat[bytelen] += msg.priority + msg.receiver + msg.sender; // checksum + + #ifdef ELM_DEBUG + os_printf("Sending LIN OBD: Priority: %02x; RecvAddr: %02x; SendAddr: %02x; (%02x); ", + msg.priority, msg.receiver, msg.sender, bytelen); + for(int i = 0; i < 8; i++) os_printf("%02x ", msg.dat[i]); + os_printf("\n"); + #endif + + lin_last_sent_msg_len = (msg.priority & 0x07) + 4; + memcpy(&lin_last_sent_msg, &msg, lin_last_sent_msg_len); + lin_await_msg_echo = true; + panda_usbemu_kline_write(&msg); + + loopcount = LOOPCOUNT_FULL + 1; + os_timer_disarm(&elm_timeout); + + if(lin_bus_initialized) { + os_timer_setfn(&elm_timeout, (os_timer_func_t *)elm_LINFast_timer_cb, proto); + elm_LINFast_timer_cb((void*)proto); + } else { + os_timer_setfn(&elm_timeout, (os_timer_func_t *)elm_LINFast_businit_timer_cb, proto); + elm_LINFast_businit_timer_cb((void*)proto); + } +} + +/***************************************************** + *** ELM protocol specification and implementation *** + *** -> ISO 15765-4 implementation *** + *****************************************************/ + +void ICACHE_FLASH_ATTR elm_ISO15765_timer_cb(void *arg){ + const elm_protocol_t* proto = (const elm_protocol_t*) arg; + loopcount--; + if(loopcount>0) { + for(int pass = 0; pass < 16 && loopcount; pass++){ + panda_can_msg_t *can_msgs; + int num_can_msgs = panda_usbemu_can_read(&can_msgs); + + #ifdef ELM_DEBUG + if(num_can_msgs) os_printf(" Received %d can messages\n", num_can_msgs); + #endif + + if(num_can_msgs < 0) continue; + if(!num_can_msgs) break; + + for(int i = 0; i < num_can_msgs; i++){ + + panda_can_msg_t *recv = &can_msgs[i]; + + #ifdef ELM_DEBUG + os_printf(" RECV: Bus: %d; Addr: %08x; ext: %d; tx: %d; Len: %d; ", + recv->bus, panda_get_can_addr(recv), recv->ext, recv->tx, recv->len); + for(int j = 0; j < recv->len; j++) os_printf("%02x ", recv->data[j]); + os_printf("Ts: %d\n", recv->ts); + #endif + + if (recv->bus==0 && recv->len == 8 && + ( + (proto->type == CAN11 && !recv->ext && (panda_get_can_addr(recv) & 0x7F8) == 0x7E8) || + (proto->type == CAN29 && recv->ext && (panda_get_can_addr(recv) & 0x1FFFFF00) == 0x18DAF100) + ) + ) { + if(recv->data[0] <= 7 && + recv->data[1] == (0x40|elm_msg_mode_ret_filter) && + recv->data[2] == elm_msg_pid_ret_filter) { + got_msg_this_run = true; + loopcount = LOOPCOUNT_FULL; + + #ifdef ELM_DEBUG + os_printf(" CAN msg response, index: %d\n", i); + #endif + + if(!is_auto_detecting){ + if(elm_mode_additional_headers){ + elm_append_rsp_can_msg_addr(recv); + for(int j = 0; j < recv->data[0]+1; j++) elm_append_rsp_hex_byte(recv->data[j]); + } else { + for(int j = 1; j < recv->data[0]+1; j++) elm_append_rsp_hex_byte(recv->data[j]); + } + + elm_append_rsp_const("\r"); + elm_tcp_tx_flush(); + } + + } else if((recv->data[0] & 0xF0) == 0x10 && + recv->data[2] == (0x40|elm_msg_mode_ret_filter) && + recv->data[3] == elm_msg_pid_ret_filter) { + got_msg_this_run = true; + loopcount = LOOPCOUNT_FULL; + panda_usbemu_can_write(0, + (proto->type==CAN11) ? + 0x7E0 | (panda_get_can_addr(recv)&0x7) : + (0x18DA00F1 | (((panda_get_can_addr(recv))&0xFF)<<8)), + "\x30\x00\x00", 3); + + did_multimessage = true; + + #ifdef ELM_DEBUG + os_printf(" CAN multimsg start response, index: %d, len %d\n", i, + ((recv->data[0]&0xF)<<8) | recv->data[1]); + #endif + + if(!is_auto_detecting){ + if(!elm_mode_additional_headers) { + elm_append_rsp(&hex_lookup[recv->data[0]&0xF], 1); + elm_append_rsp_hex_byte(recv->data[1]); + elm_append_rsp_const("\r0:"); + if(elm_mode_print_spaces) elm_append_rsp_const(" "); + for(int j = 2; j < 8; j++) elm_append_rsp_hex_byte(recv->data[j]); + } else { + elm_append_rsp_can_msg_addr(recv); + for(int j = 0; j < 8; j++) elm_append_rsp_hex_byte(recv->data[j]); + } + + elm_append_rsp_const("\r"); + elm_tcp_tx_flush(); + } + + } else if (did_multimessage && (recv->data[0] & 0xF0) == 0x20) { + got_msg_this_run = true; + loopcount = LOOPCOUNT_FULL; + #ifdef ELM_DEBUG + os_printf(" CAN multimsg data response, index: %d\n", i); + #endif + + if(!is_auto_detecting){ + if(!elm_mode_additional_headers) { + elm_append_rsp(&hex_lookup[recv->data[0] & 0xF], 1); + elm_append_rsp_const(":"); + if(elm_mode_print_spaces) elm_append_rsp_const(" "); + for(int j = 1; j < 8; j++) elm_append_rsp_hex_byte(recv->data[j]); + } else { + elm_append_rsp_can_msg_addr(recv); + for(int j = 0; j < 8; j++) elm_append_rsp_hex_byte(recv->data[j]); + } + elm_append_rsp_const("\r"); + } + } + } else if (recv->bus == 0x80 && recv->len == 8 && + (panda_get_can_addr(recv) == ((proto->type==CAN11) ? 0x7DF : 0x18DB33F1)) + ) { + //Can send receipt + #ifdef ELM_DEBUG + os_printf(" Got CAN tx receipt\n"); + #endif + can_tx_worked = true; + } + } + } + os_timer_arm(&elm_timeout, elm_mode_timeout, 0); + } else { + bool got_msg_this_run_backup = got_msg_this_run; + if(did_multimessage) { + os_printf(" End of multi message\n"); + } else if(!got_msg_this_run) { + os_printf(" No data collected\n"); + if(!is_auto_detecting) { + if(can_tx_worked) { + elm_append_rsp_const("NO DATA\r"); + } else { + elm_append_rsp_const("CAN ERROR\r"); + } + } + } + did_multimessage = false; + got_msg_this_run = false; + can_tx_worked = false; + + if(!is_auto_detecting) { + elm_append_rsp_const("\r>"); + elm_tcp_tx_flush(); + } else { + elm_autodetect_cb(got_msg_this_run_backup); + } + } +} + +static void ICACHE_FLASH_ATTR elm_init_ISO15765(const elm_protocol_t* proto){ + panda_set_can0_cbaud(proto->cbaud); +} + +static void ICACHE_FLASH_ATTR elm_process_obd_cmd_ISO15765(const elm_protocol_t* proto, + const char *cmd, uint16_t len) { + elm_can_obd_msg msg = {}; + msg.len = (len-1)/2; + if((msg.len > 7 && !elm_mode_allow_long) || msg.len > 8) { + elm_append_rsp_const("?\r\r>"); + return; + } + + msg.len = min(msg.len, 7); + + for(int i = 0; i < msg.len; i++) + msg.dat[i] = elm_decode_hex_byte(&cmd[i*2]); + + elm_msg_mode_ret_filter = msg.dat[0]; + elm_msg_pid_ret_filter = msg.dat[1]; + + #ifdef ELM_DEBUG + os_printf("Sending CAN OBD: %02x; ", msg.len); + for(int i = 0; i < 7; i++) + os_printf("%02x ", msg.dat[i]); + os_printf("\n"); + #endif + + panda_clear_can_rx(); + + panda_usbemu_can_write(0, (proto->type==CAN11) ? 0x7DF : 0x18DB33F1, + (uint8_t*)&msg, msg.len+1); + + #ifdef ELM_DEBUG + os_printf("Starting up timer\n"); + #endif + + loopcount = LOOPCOUNT_FULL; + os_timer_disarm(&elm_timeout); + os_timer_setfn(&elm_timeout, (os_timer_func_t *)elm_ISO15765_timer_cb, proto); + os_timer_arm(&elm_timeout, elm_mode_timeout, 0); +} + +/***************************************************** + *** ELM protocol specification and implementation *** + *** -> Stuf for unsupported CAN protocols *** + *****************************************************/ + +static void ICACHE_FLASH_ATTR elm_process_obd_cmd_CANGen(const elm_protocol_t* proto, + const char *cmd, uint16_t len) { + elm_append_rsp_const("NO DATA\r\r>"); +} + +/***************************************************** + *** ELM protocol specification and implementation *** + *** -> AUTO Detect implementation *** + *****************************************************/ + +static int elm_autodetect_proto_iter; +static uint16_t elm_staged_auto_msg_len; +static const char* elm_staged_auto_msg; + +static void ICACHE_FLASH_ATTR elm_autodetect_cb(bool proto_worked){ + if(proto_worked) { + os_printf("Autodetect proto success\n"); + is_auto_detecting = false; + elm_selected_protocol = elm_autodetect_proto_iter; + elm_current_proto()->process_obd(elm_current_proto(), + elm_staged_auto_msg, elm_staged_auto_msg_len); + } else { + for(elm_autodetect_proto_iter++; elm_autodetect_proto_iter < ELM_PROTOCOL_COUNT; + elm_autodetect_proto_iter++){ + const elm_protocol_t *proto = &elm_protocols[elm_autodetect_proto_iter]; + if(proto->supported && proto->type != AUTO) { + os_printf("*** AUTO trying '%s'\n", proto->name); + proto->init(proto); + proto->process_obd(proto, "0100\r", 5); // Try sending on the bus + return; + } + } + + //if(elm_autodetect_main()) return; + is_auto_detecting = false; + os_printf("Autodetect failed\n"); + elm_append_rsp_const("UNABLE TO CONNECT\r\r>"); + elm_tcp_tx_flush(); + } +} + +static void ICACHE_FLASH_ATTR elm_process_obd_cmd_AUTO(const elm_protocol_t* proto, + const char *cmd, uint16_t len) { + elm_append_rsp_const("SEARCHING...\r"); + elm_staged_auto_msg_len = len; + elm_staged_auto_msg = cmd; + is_auto_detecting = true; + + elm_autodetect_proto_iter = 0; + elm_autodetect_cb(false); +} + +/***************************************************** + *** ELM protocol specification and implementation *** + *** -> Protocol Registry and related functions. *** + *****************************************************/ + +static const elm_protocol_t elm_protocols[] = { + {true, AUTO, 0, elm_process_obd_cmd_AUTO, NULL, "AUTO", }, + {false, NA, 416, elm_process_obd_cmd_J1850, NULL, "SAE J1850 PWM", }, + {false, NA, 104, elm_process_obd_cmd_J1850, NULL, "SAE J1850 VPW", }, + {false, LIN, 104, elm_process_obd_cmd_LIN5baud, NULL, "ISO 9141-2", }, + {false, LIN, 104, elm_process_obd_cmd_LIN5baud, NULL, "ISO 14230-4 (KWP 5BAUD)", }, + {true, LIN, 104, elm_process_obd_cmd_LINFast, NULL, "ISO 14230-4 (KWP FAST)", }, + {true, CAN11, 5000, elm_process_obd_cmd_ISO15765, elm_init_ISO15765, "ISO 15765-4 (CAN 11/500)",}, + {true, CAN29, 5000, elm_process_obd_cmd_ISO15765, elm_init_ISO15765, "ISO 15765-4 (CAN 29/500)",}, + {true, CAN11, 2500, elm_process_obd_cmd_ISO15765, elm_init_ISO15765, "ISO 15765-4 (CAN 11/250)",}, + {true, CAN29, 2500, elm_process_obd_cmd_ISO15765, elm_init_ISO15765, "ISO 15765-4 (CAN 29/250)",}, + {false, CAN29, 2500, elm_process_obd_cmd_CANGen, NULL, "SAE J1939 (CAN 29/250)", }, + {false, CAN11, 1250, elm_process_obd_cmd_CANGen, NULL, "USER1 (CAN 11/125)", }, + {false, CAN11, 500, elm_process_obd_cmd_CANGen, NULL, "USER2 (CAN 11/50)", }, +}; + +static const elm_protocol_t* ICACHE_FLASH_ATTR elm_current_proto() { + return &elm_protocols[elm_selected_protocol]; +} + +void ICACHE_FLASH_ATTR elm_reset_aux_timer() { + os_timer_disarm(&elm_proto_aux_timeout); + if(elm_mode_keepalive_period) + os_timer_arm(&elm_proto_aux_timeout, elm_mode_keepalive_period, 0); +} + +void ICACHE_FLASH_ATTR elm_proto_reinit(const elm_protocol_t *proto) { + if(proto->init) proto->init(proto); +} + +/******************************************* + *** ELM AT command parsing and handling *** + *******************************************/ + +enum at_cmd_ids_t { // FULL ELM 1.0 list + AT_INVALID, //Fake + + AT_AMP1, + AT_AL, + AT_AT0, AT_AT1, AT_AT2, // Added ELM 1.2, expected by Torque + AT_BD, + AT_BI, + AT_CAF0, AT_CAF1, + AT_CF_8, AT_CF_3, + AT_CFC0, AT_CFC1, + AT_CM_8, AT_CM_3, + AT_CP, + AT_CS, + AT_CV, + AT_D, + AT_DP, AT_DPN, + AT_E0, AT_E1, + AT_H0, AT_H1, + AT_I, + AT_IB10, + AT_IB96, + AT_L0, AT_L1, + AT_M0, AT_M1, AT_MA, + AT_MR, + AT_MT, + AT_NL, + AT_PC, + AT_R0, AT_R1, + AT_RV, + AT_S0, AT_S1, // Added ELM 1.3, expected by Torque + AT_SH_6, AT_SH_3, + AT_SPA, AT_SP, + AT_ST, + AT_SW, + AT_TPA, AT_TP, + AT_WM_XYZA, AT_WM_XYZAB, AT_WM_XYZABC, + AT_WS, + AT_Z, +}; + +typedef struct { + char* name; + uint8_t name_len; + uint8_t cmd_len; + enum at_cmd_ids_t id; +} at_cmd_reg_t; + +static const at_cmd_reg_t at_cmd_reg[] = { + {"@1", 2, 2, AT_AMP1}, + {"AL", 2, 2, AT_AL}, + {"AT0", 3, 3, AT_AT0}, // Added ELM 1.2, expected by Torque + {"AT1", 3, 3, AT_AT1}, // Added ELM 1.2, expected by Torque + {"AT2", 3, 3, AT_AT2}, // Added ELM 1.2, expected by Torque + {"DP", 2, 2, AT_DP}, + {"DPN", 3, 3, AT_DPN}, + {"E0", 2, 2, AT_E0}, + {"E1", 2, 2, AT_E1}, + {"H0", 2, 2, AT_H0}, + {"H1", 2, 2, AT_H1}, + {"I", 1, 1, AT_I}, + {"L0", 2, 2, AT_L0}, + {"L1", 2, 2, AT_L1}, + {"M0", 2, 2, AT_M0}, + //{"M1", 2, 2, AT_M1}, + {"NL", 2, 2, AT_NL}, + {"PC", 2, 2, AT_PC}, + {"S0", 2, 2, AT_S0}, // Added ELM 1.3, expected by Torque + {"S1", 2, 2, AT_S1}, // Added ELM 1.3, expected by Torque + {"SP", 2, 3, AT_SP}, + {"SPA", 3, 4, AT_SPA}, + {"ST", 2, 4, AT_ST}, + {"SW", 2, 4, AT_SW}, + {"Z", 1, 1, AT_Z}, +}; +#define AT_CMD_REG_LEN (sizeof(at_cmd_reg)/sizeof(at_cmd_reg_t)) + +static enum at_cmd_ids_t ICACHE_FLASH_ATTR elm_parse_at_cmd(char *cmd, uint16_t len){ + int i; + for(i=0; i7 BYTES) + elm_mode_allow_long = true; + break; + case AT_AT0: //DISABLE ADAPTIVE TIMING + elm_mode_adaptive_timing = 0; + break; + case AT_AT1: //SET ADAPTIVE TIMING TO AUTO1 + elm_mode_adaptive_timing = 1; + break; + case AT_AT2: //SET ADAPTIVE TIMING TO AUTO2 + elm_mode_adaptive_timing = 2; + break; + case AT_DP: //DESCRIBE THE PROTOCOL BY NAME + if(elm_mode_auto_protocol && elm_selected_protocol != 0) + elm_append_rsp_const("AUTO, "); + elm_append_rsp(elm_current_proto()->name, + strlen(elm_current_proto()->name)); + elm_append_rsp_const("\r\r"); + return; + case AT_DPN: //DESCRIBE THE PROTOCOL BY NUMBER + //TODO: Required. Report currently selected protocol + if(elm_mode_auto_protocol) + elm_append_rsp_const("A"); + elm_append_rsp(&hex_lookup[elm_selected_protocol], 1); + elm_append_rsp_const("\r\r"); + return; // Don't display 'OK' + case AT_E0: //ECHO OFF + elm_mode_echo = false; + break; + case AT_E1: //ECHO ON + elm_mode_echo = true; + break; + case AT_H0: //SHOW FULL CAN HEADERS OFF + elm_mode_additional_headers = false; + break; + case AT_H1: //SHOW FULL CAN HEADERS ON + elm_mode_additional_headers = true; + break; + case AT_I: //IDENTIFY SELF + elm_append_rsp_const(IDENT_MSG); + return; + case AT_L0: //LINEFEED OFF + elm_mode_linefeed = false; + break; + case AT_L1: //LINEFEED ON + elm_mode_linefeed = true; + break; + case AT_M0: //DISABLE NONVOLATILE STORAGE + //Memory storage is likely unnecessary + break; + case AT_NL: //DISABLE LONG MESSAGE SUPPORT (>7 BYTES) + elm_mode_allow_long = false; + break; + case AT_PC: //PROTOCOL CANCEL (Stop timers and stuff) + { + //Init functions should idenpotently prepare the protocol to be used. + //Thus, the init function can be used as a protocol cancel function + elm_proto_reinit(elm_current_proto()); + break; + } + case AT_S0: //DISABLE PRINTING SPACES IN ECU RESPONSES + elm_mode_print_spaces = false; + break; + case AT_S1: //ENABLE PRINTING SPACES IN ECU RESPONSES + elm_mode_print_spaces = true; + break; + case AT_SP: //SET PROTOCOL + tmp = elm_decode_hex_char(cmd[2]); + if(tmp == -1 || tmp >= ELM_PROTOCOL_COUNT) { + elm_append_rsp_const("?\r\r"); + return; + } + + //De-Init previous protocol + elm_proto_reinit(elm_current_proto()); + + elm_selected_protocol = tmp; + elm_mode_auto_protocol = (tmp == 0); + + //Init new protocol + elm_proto_reinit(elm_current_proto()); + break; + case AT_SPA: //SET PROTOCOL WITH AUTO FALLBACK + tmp = elm_decode_hex_char(cmd[3]); + if(tmp == -1 || tmp >= ELM_PROTOCOL_COUNT) { + elm_append_rsp_const("?\r\r"); + return; + } + + //De-Init previous protocol + elm_proto_reinit(elm_current_proto()); + + elm_selected_protocol = tmp; + elm_mode_auto_protocol = true; + + //Init new protocol + elm_proto_reinit(elm_current_proto()); + break; + case AT_ST: //SET TIMEOUT + if(!elm_check_valid_hex_chars(&cmd[2], 2)) { + elm_append_rsp_const("?\r\r"); + return; + } + + tmp = elm_decode_hex_byte(&cmd[2]); + //20 for CAN, 4 for LIN + elm_mode_timeout = tmp ? tmp*20 : ELM_MODE_TIMEOUT_DEFAULT; + break; + case AT_SW: //SET WAKEUP TIME INTERVAL + if(!elm_check_valid_hex_chars(&cmd[2], 2)) { + elm_append_rsp_const("?\r\r"); + return; + } + + tmp = elm_decode_hex_byte(&cmd[2]); + elm_mode_keepalive_period = tmp ? max(tmp, 0x20) * 20 : 0; + + if(lin_bus_initialized){ + os_timer_disarm(&elm_proto_aux_timeout); + if(elm_mode_keepalive_period) + os_timer_arm(&elm_proto_aux_timeout, elm_mode_keepalive_period, 0); + } + break; + case AT_Z: //RESET + elm_mode_echo = true; + elm_mode_linefeed = false; + elm_mode_additional_headers = false; + elm_mode_auto_protocol = true; + elm_selected_protocol = ELM_MODE_SELECTED_PROTOCOL_DEFAULT; + elm_mode_print_spaces = true; + elm_mode_adaptive_timing = 1; + elm_mode_allow_long = false; + elm_mode_timeout = ELM_MODE_TIMEOUT_DEFAULT; + elm_mode_keepalive_period = ELM_MODE_KEEPALIVE_PERIOD_DEFAULT; + + elm_append_rsp_const("\r\r"); + elm_append_rsp_const(IDENT_MSG); + panda_set_safety_mode(0xE327); + + elm_proto_reinit(elm_current_proto()); + return; + default: + elm_append_rsp_const("?\r\r"); + return; + } + + elm_append_rsp_const("OK\r\r"); +} + +/************************************* + *** Connection and cli management *** + *************************************/ + +static void ICACHE_FLASH_ATTR elm_append_in_msg(char *data, uint16_t len) { + if(in_msg_len + len > sizeof(in_msg)) + len = sizeof(in_msg) - in_msg_len; + memcpy(in_msg + in_msg_len, data, len); + in_msg_len += len; +} + +static int ICACHE_FLASH_ATTR elm_msg_is_at_cmd(char *data, uint16_t len){ + return len >= 4 && data[0] == 'A' && data[1] == 'T'; +} + +static void ICACHE_FLASH_ATTR elm_rx_cb(void *arg, char *data, uint16_t len) { + #ifdef ELM_DEBUG + //os_printf("\nGot ELM Data In: '%s'\n", data); + #endif + + rsp_buff_len = 0; + len = elm_msg_find_cr_or_eos(data, len); + + if(loopcount){ + os_timer_disarm(&elm_timeout); + loopcount = 0; + got_msg_this_run = false; + can_tx_worked = false; + did_multimessage = false; + + os_printf("Interrupting operation, stopping timer. msg len: %d\n", len); + elm_append_rsp_const("STOPPED\r\r>"); + if(len == 1 && data[0] == '\r') { + os_printf("Empty msg source of interrupt.\n"); + elm_tcp_tx_flush(); + return; + } + } + + if(!(len == 1 && data[0] == '\r') && in_msg_len && in_msg[in_msg_len-1] == '\r'){ + in_msg_len = 0; + } + + if(!(len == 1 && data[0] == '\r' && in_msg_len && in_msg[in_msg_len-1] == '\r')) { + // Not Repeating last message + elm_append_in_msg(data, len); //Aim to remove this memcpy + } + if(elm_mode_echo) + elm_append_rsp(in_msg, in_msg_len); + + if(in_msg_len > 0 && in_msg[in_msg_len-1] == '\r') { //Got a full line + stripped_msg_len = elm_strip(in_msg, in_msg_len, stripped_msg, sizeof(stripped_msg)); + + if(elm_msg_is_at_cmd(stripped_msg, stripped_msg_len)) { + elm_process_at_cmd(stripped_msg+2, stripped_msg_len-2); + elm_append_rsp_const(">"); + } else if(elm_check_valid_hex_chars(stripped_msg, stripped_msg_len - 1)) { + elm_current_proto()->process_obd(elm_current_proto(), stripped_msg, stripped_msg_len); + } else { + elm_append_rsp_const("?\r\r>"); + } + } + + elm_tcp_tx_flush(); + + //Just clear the buffer if full with no termination + if(in_msg_len == sizeof(in_msg) && in_msg[in_msg_len-1] != '\r') + in_msg_len = 0; +} + +void ICACHE_FLASH_ATTR elm_tcp_disconnect_cb(void *arg){ + struct espconn *pesp_conn = (struct espconn *)arg; + + elm_tcp_conn_t * prev = NULL; + for(elm_tcp_conn_t *iter = connection_list; iter != NULL; iter=iter->next){ + struct espconn *conn = iter->conn; + //SHOW_CONNECTION("Considering Disconnecting", conn); + if(!memcmp(pesp_conn->proto.tcp->remote_ip, conn->proto.tcp->remote_ip, 4) && + pesp_conn->proto.tcp->remote_port == conn->proto.tcp->remote_port){ + os_printf("Deleting ELM Connection!\n"); + if(prev){ + prev->next = iter->next; + } else { + connection_list = iter->next; + } + os_free(iter); + break; + } + + prev = iter; + } + + if(connection_list == NULL) { + //If all clients are disconnected, reset the protocol (cancels + //keep alive timers). This will not detect inproperly killed + //connections. In this case, periodic events associated with the + //current protocol will continue until a new client attaches, a + //command is sent generating a response (ELM will try to responde + //to the dead connection, and remove it upon error), and finally, + //the new client disconnects. OFC a power cycle is also an option. + elm_proto_reinit(elm_current_proto()); + } +} + +void ICACHE_FLASH_ATTR elm_tcp_connect_cb(void *arg) { + struct espconn *pesp_conn = (struct espconn *)arg; + //SHOW_CONNECTION("New connection", pesp_conn); + espconn_set_opt(&elm_conn, ESPCONN_NODELAY); + espconn_regist_recvcb(pesp_conn, elm_rx_cb); + //Allow several sends to be queued at a time. + espconn_tcp_set_buf_count(pesp_conn, 3); + + bool connection_address_already_there = false; + for(elm_tcp_conn_t *iter2 = connection_list; iter2 != NULL; iter2 = iter2->next) + if(iter2->conn == pesp_conn){connection_address_already_there = true; break;} + + if(connection_address_already_there) { + os_printf("ELM WIFI: Memory reuse of recently killed connection\n"); + } else { + os_printf("ELM WIFI: Adding connection\n"); + elm_tcp_conn_t *newconn = os_malloc(sizeof(elm_tcp_conn_t)); + if(!newconn) { + os_printf("Failed to allocate place for connection\n"); + } else { + newconn->next = connection_list; + newconn->conn = pesp_conn; + connection_list = newconn; + } + } +} + +void ICACHE_FLASH_ATTR elm327_init() { + // control listener + elm_proto.local_port = ELM_PORT; + elm_conn.type = ESPCONN_TCP; + elm_conn.state = ESPCONN_NONE; + elm_conn.proto.tcp = &elm_proto; + espconn_regist_connectcb(&elm_conn, elm_tcp_connect_cb); + espconn_regist_disconcb(&elm_conn, elm_tcp_disconnect_cb); + espconn_accept(&elm_conn); + espconn_regist_time(&elm_conn, 0, 0); // 60s timeout for all connections +} diff --git a/panda/boardesp/get_sdk.sh b/panda/boardesp/get_sdk.sh new file mode 100755 index 00000000000000..adccf678f9c6a9 --- /dev/null +++ b/panda/boardesp/get_sdk.sh @@ -0,0 +1,12 @@ +#!/bin/bash +sudo apt-get install make unrar-free autoconf automake libtool gcc g++ gperf \ + flex bison texinfo gawk ncurses-dev libexpat-dev python-dev python python-serial \ + sed git unzip bash help2man wget bzip2 +# huh? +sudo apt-get install libtool +sudo apt-get install libtool-bin +git clone --recursive https://github.com/pfalcon/esp-open-sdk.git +cd esp-open-sdk +git checkout 03f5e898a059451ec5f3de30e7feff30455f7cec +LD_LIBRARY_PATH="" make STANDALONE=y + diff --git a/panda/boardesp/get_sdk_mac.sh b/panda/boardesp/get_sdk_mac.sh new file mode 100755 index 00000000000000..a8c2d709d45811 --- /dev/null +++ b/panda/boardesp/get_sdk_mac.sh @@ -0,0 +1,32 @@ +#!/bin/bash + +# from http://www.esp8266.com/wiki/doku.php?id=setup-osx-compiler-esp8266 + +brew install gnu-sed --with-default-names +brew tap homebrew/dupes +brew install gperf +brew install grep +brew install autoconf +brew install binutils +brew install gawk +brew install wget +brew install automake +brew install libtool +brew install help2man + +brew uninstall gperf + +hdiutil create esp-open-sdk.dmg -volname "esp-open-sdk" -size 10g -fs "Case-sensitive HFS+" +hdiutil mount esp-open-sdk.dmg +ln -s /Volumes/esp-open-sdk esp-open-sdk +cd esp-open-sdk + +git init +git remote add origin https://github.com/pfalcon/esp-open-sdk.git +git fetch origin +git checkout 03f5e898a059451ec5f3de30e7feff30455f7cec +git submodule init +git submodule update --recursive + +make STANDALONE=y + diff --git a/panda/boardesp/include/espmissingincludes.h b/panda/boardesp/include/espmissingincludes.h new file mode 100644 index 00000000000000..51672d3f50c54c --- /dev/null +++ b/panda/boardesp/include/espmissingincludes.h @@ -0,0 +1,78 @@ +#ifndef ESPMISSINGINCLUDES_H +#define ESPMISSINGINCLUDES_H + +#include +#include +#include + + +int strcasecmp(const char *a, const char *b); +#ifndef FREERTOS +#include +#include +//Missing function prototypes in include folders. Gcc will warn on these if we don't define 'em anywhere. +//MOST OF THESE ARE GUESSED! but they seem to swork and shut up the compiler. +typedef struct espconn espconn; + +int atoi(const char *nptr); +void ets_install_putc1(void *routine); +void ets_isr_attach(int intr, void *handler, void *arg); +void ets_isr_mask(unsigned intr); +void ets_isr_unmask(unsigned intr); +int ets_memcmp(const void *s1, const void *s2, size_t n); +void *ets_memcpy(void *dest, const void *src, size_t n); +void *ets_memset(void *s, int c, size_t n); +int ets_sprintf(char *str, const char *format, ...) __attribute__ ((format (printf, 2, 3))); +int ets_str2macaddr(void *, void *); +int ets_strcmp(const char *s1, const char *s2); +char *ets_strcpy(char *dest, const char *src); +size_t ets_strlen(const char *s); +int ets_strncmp(const char *s1, const char *s2, int len); +char *ets_strncpy(char *dest, const char *src, size_t n); +char *ets_strstr(const char *haystack, const char *needle); +void ets_timer_arm_new(os_timer_t *a, int b, int c, int isMstimer); +void ets_timer_disarm(os_timer_t *a); +void ets_timer_setfn(os_timer_t *t, ETSTimerFunc *fn, void *parg); +void ets_update_cpu_frequency(int freqmhz); +void *os_memmove(void *dest, const void *src, size_t n); +int os_printf(const char *format, ...) __attribute__ ((format (printf, 1, 2))); +int os_snprintf(char *str, size_t size, const char *format, ...) __attribute__ ((format (printf, 3, 4))); +int os_printf_plus(const char *format, ...) __attribute__ ((format (printf, 1, 2))); +void uart_div_modify(int no, unsigned int freq); +uint8 wifi_get_opmode(void); +uint32 system_get_time(); +int rand(void); +void ets_bzero(void *s, size_t n); +void ets_delay_us(int ms); + +//Hack: this is defined in SDK 1.4.0 and undefined in 1.3.0. It's only used for this, the symbol itself +//has no meaning here. +#ifndef RC_LIMIT_P2P_11N +//Defs for SDK <1.4.0 +void *pvPortMalloc(size_t xWantedSize); +void *pvPortZalloc(size_t); +void vPortFree(void *ptr); +void *vPortMalloc(size_t xWantedSize); +void pvPortFree(void *ptr); +#else +void *pvPortMalloc(size_t xWantedSize, const char *file, int line); +void *pvPortZalloc(size_t, const char *file, int line); +void vPortFree(void *ptr, const char *file, int line); +void *vPortMalloc(size_t xWantedSize, const char *file, int line); +void pvPortFree(void *ptr, const char *file, int line); +#endif + +//Standard PIN_FUNC_SELECT gives a warning. Replace by a non-warning one. +#ifdef PIN_FUNC_SELECT +#undef PIN_FUNC_SELECT +#define PIN_FUNC_SELECT(PIN_NAME, FUNC) do { \ + WRITE_PERI_REG(PIN_NAME, \ + (READ_PERI_REG(PIN_NAME) \ + & (~(PERIPHS_IO_MUX_FUNC< _b ? _a : _b; }) + +char ssid[32]; +char password[] = "testing123"; +int wifi_secure_mode = 0; + +static const int pin = 2; + +// Structure holding the TCP connection information. +struct espconn tcp_conn; +// TCP specific protocol structure. +esp_tcp tcp_proto; + +// interrupt communication on port 1338, UDP! +struct espconn inter_conn; +esp_udp inter_proto; + +uint32_t sendData[0x14] = {0}; +uint32_t recvData[0x40] = {0}; + +static int ICACHE_FLASH_ATTR __spi_comm(char *dat, int len, uint32_t *recvData, int recvDataLen) { + unsigned int length = 0; + + SpiData spiData; + + spiData.cmd = 2; + spiData.cmdLen = 0; + spiData.addr = NULL; + spiData.addrLen = 0; + + // float boot pin + gpio_output_set(0, 0, 0, (1 << 4)); + + // manual CS pin + gpio_output_set(0, (1 << 5), 0, 0); + memset(sendData, 0xCC, 0x14); + + // wait for ST to respond to CS interrupt + os_delay_us(50); + + // send request + memcpy(((void*)sendData), dat, len); + spiData.data = sendData; + spiData.dataLen = 0x14; + SPIMasterSendData(SpiNum_HSPI, &spiData); + + #define SPI_TIMEOUT 50000 + // give the ST time to be ready, up to 500ms + int i; + for (i = 0; (gpio_input_get() & (1 << 4)) && i < SPI_TIMEOUT; i++) { + os_delay_us(10); + system_soft_wdt_feed(); + } + + // TODO: handle this better + if (i == SPI_TIMEOUT) { + os_printf("ERROR: SPI receive failed\n"); + goto fail; + } + + // blank out recvData + memset(recvData, 0x00, 0x44); + + // receive the length + spiData.data = recvData; + spiData.dataLen = 4; + if(SPIMasterRecvData(SpiNum_HSPI, &spiData) == -1) { + // TODO: Handle gracefully. Maybe fail if len read fails? + os_printf("SPI: Failed to recv length\n"); + goto fail; + } + + length = recvData[0]; + if (length > 0x40) { + os_printf("SPI: BAD LENGTH RECEIVED %x\n", length); + length = 0; + goto fail; + } + + // got response, 0x40 works, 0x44 does not + spiData.data = recvData+1; + spiData.dataLen = (length+3)&(~3); // recvDataLen; + if(SPIMasterRecvData(SpiNum_HSPI, &spiData) == -1) { + // TODO: Handle gracefully. Maybe retry if payload failed. + os_printf("SPI: Failed to recv payload\n"); + length = 0; + goto fail; + } + +fail: + // clear CS + gpio_output_set((1 << 5), 0, 0, 0); + + // set boot pin back + gpio_output_set((1 << 4), 0, (1 << 4), 0); + + return length; +} + +int ICACHE_FLASH_ATTR spi_comm(char *dat, int len, uint32_t *recvData, int recvDataLen) { + // blink the led during SPI comm + if (GPIO_REG_READ(GPIO_OUT_ADDRESS) & (1 << pin)) { + // set gpio low + gpio_output_set(0, (1 << pin), 0, 0); + } else { + // set gpio high + gpio_output_set((1 << pin), 0, 0, 0); + } + + return __spi_comm(dat, len, recvData, recvDataLen); +} + +static void ICACHE_FLASH_ATTR tcp_rx_cb(void *arg, char *data, uint16_t len) { + // nothing too big + if (len > 0x14) return; + + // do the SPI comm + spi_comm(data, len, recvData, 0x40); + + espconn_send(&tcp_conn, recvData, 0x44); +} + +void ICACHE_FLASH_ATTR tcp_connect_cb(void *arg) { + struct espconn *conn = (struct espconn *)arg; + espconn_set_opt(&tcp_conn, ESPCONN_NODELAY); + espconn_regist_recvcb(conn, tcp_rx_cb); +} + +// must be 0x44, because we can fit 4 more +uint8_t buf[0x44*0x10]; +int queue_send_len = -1; + +void ICACHE_FLASH_ATTR poll_can(void *arg) { + uint8_t timerRecvData[0x44] = {0}; + int i = 0; + int j; + + while (i < 0x40) { + int len = spi_comm("\x01\x00\x00\x00", 4, timerRecvData, 0x40); + if (len == 0) break; + if (len > 0x40) { os_printf("SPI LENGTH ERROR!"); break; } + + // if it sends it, assume it's valid CAN + for (j = 0; j < len; j += 0x10) { + memcpy(buf + i*0x10, (timerRecvData+4)+j, 0x10); + i++; + } + } + + if (i != 0) { + int ret = espconn_sendto(&inter_conn, buf, i*0x10); + if (ret != 0) { + os_printf("send failed: %d\n", ret); + queue_send_len = i*0x10; + } else { + queue_send_len = -1; + } + } +} + +int udp_countdown = 0; + +static volatile os_timer_t udp_callback; +void ICACHE_FLASH_ATTR udp_callback_func(void *arg) { + if (queue_send_len == -1) { + poll_can(NULL); + } else { + int ret = espconn_sendto(&inter_conn, buf, queue_send_len); + if (ret == 0) { + queue_send_len = -1; + } + } + if (udp_countdown > 0) { + os_timer_arm(&udp_callback, 5, 0); + udp_countdown--; + } else { + os_printf("UDP timeout\n"); + } +} + +void ICACHE_FLASH_ATTR inter_recv_cb(void *arg, char *pusrdata, unsigned short length) { + remot_info *premot = NULL; + if (espconn_get_connection_info(&inter_conn,&premot,0) == ESPCONN_OK) { + inter_conn.proto.udp->remote_port = premot->remote_port; + inter_conn.proto.udp->remote_ip[0] = premot->remote_ip[0]; + inter_conn.proto.udp->remote_ip[1] = premot->remote_ip[1]; + inter_conn.proto.udp->remote_ip[2] = premot->remote_ip[2]; + inter_conn.proto.udp->remote_ip[3] = premot->remote_ip[3]; + + + if (udp_countdown == 0) { + os_printf("UDP recv\n"); + udp_countdown = 200*5; + + // start 5 second timer + os_timer_disarm(&udp_callback); + os_timer_setfn(&udp_callback, (os_timer_func_t *)udp_callback_func, NULL); + os_timer_arm(&udp_callback, 5, 0); + } else { + udp_countdown = 200*5; + } + } +} + +void ICACHE_FLASH_ATTR wifi_configure(int secure) { + wifi_secure_mode = secure; + + // start wifi AP + wifi_set_opmode(SOFTAP_MODE); + struct softap_config config = {0}; + wifi_softap_get_config(&config); + strcpy(config.ssid, ssid); + if (wifi_secure_mode == 0) strcat(config.ssid, "-pair"); + strcpy(config.password, password); + config.ssid_len = strlen(config.ssid); + config.authmode = wifi_secure_mode ? AUTH_WPA2_PSK : AUTH_OPEN; + config.beacon_interval = 100; + config.max_connection = 4; + wifi_softap_set_config(&config); + + if (wifi_secure_mode) { + // setup tcp server + tcp_proto.local_port = 1337; + tcp_conn.type = ESPCONN_TCP; + tcp_conn.state = ESPCONN_NONE; + tcp_conn.proto.tcp = &tcp_proto; + espconn_regist_connectcb(&tcp_conn, tcp_connect_cb); + espconn_accept(&tcp_conn); + espconn_regist_time(&tcp_conn, 60, 0); // 60s timeout for all connections + + // setup inter server + inter_proto.local_port = 1338; + const char udp_remote_ip[4] = {255, 255, 255, 255}; + os_memcpy(inter_proto.remote_ip, udp_remote_ip, 4); + inter_proto.remote_port = 1338; + + inter_conn.type = ESPCONN_UDP; + inter_conn.proto.udp = &inter_proto; + + espconn_regist_recvcb(&inter_conn, inter_recv_cb); + espconn_create(&inter_conn); + } +} + +void ICACHE_FLASH_ATTR wifi_init() { + // default ssid and password + memset(ssid, 0, 32); + os_sprintf(ssid, "panda-%08x-BROKEN", system_get_chip_id()); + + // fetch secure ssid and password + // update, try 20 times, for 1 second + for (int i = 0; i < 20; i++) { + uint8_t digest[SHA_DIGEST_SIZE]; + char resp[0x20]; + __spi_comm("\x00\x00\x00\x00\x40\xD0\x00\x00\x00\x00\x20\x00", 0xC, recvData, 0x40); + memcpy(resp, recvData+1, 0x20); + + SHA_hash(resp, 0x1C, digest); + if (memcmp(digest, resp+0x1C, 4) == 0) { + // OTP is valid + memcpy(ssid+6, resp, 0x10); + memcpy(password, resp+0x10, 10); + break; + } + os_delay_us(50000); + } + os_printf("Finished getting SID\n"); + os_printf(ssid); + os_printf("\n"); + + // set IP + wifi_softap_dhcps_stop(); //stop DHCP before setting static IP + struct ip_info ip_config; + IP4_ADDR(&ip_config.ip, 192, 168, 0, 10); + IP4_ADDR(&ip_config.gw, 0, 0, 0, 0); + IP4_ADDR(&ip_config.netmask, 255, 255, 255, 0); + wifi_set_ip_info(SOFTAP_IF, &ip_config); + int stupid_gateway = 0; + wifi_softap_set_dhcps_offer_option(OFFER_ROUTER, &stupid_gateway); + wifi_softap_dhcps_start(); + + wifi_configure(0); +} + +#define LOOP_PRIO 2 +#define QUEUE_SIZE 1 +static os_event_t my_queue[QUEUE_SIZE]; +void loop(); + +void ICACHE_FLASH_ATTR web_init(); +void ICACHE_FLASH_ATTR elm327_init(); + +void ICACHE_FLASH_ATTR user_init() { + // init gpio subsystem + gpio_init(); + + // configure UART TXD to be GPIO1, set as output + PIN_FUNC_SELECT(PERIPHS_IO_MUX_U0TXD_U, FUNC_GPIO1); + gpio_output_set(0, 0, (1 << pin), 0); + + // configure SPI + SpiAttr hSpiAttr; + hSpiAttr.bitOrder = SpiBitOrder_MSBFirst; + hSpiAttr.speed = SpiSpeed_10MHz; + hSpiAttr.mode = SpiMode_Master; + hSpiAttr.subMode = SpiSubMode_0; + + // TODO: is one of these CS? + WRITE_PERI_REG(PERIPHS_IO_MUX, 0x105); + PIN_FUNC_SELECT(PERIPHS_IO_MUX_MTDI_U, 2); // configure io to spi mode + PIN_FUNC_SELECT(PERIPHS_IO_MUX_MTCK_U, 2); // configure io to spi mode + PIN_FUNC_SELECT(PERIPHS_IO_MUX_MTMS_U, 2); // configure io to spi mode + PIN_FUNC_SELECT(PERIPHS_IO_MUX_MTDO_U, 2); // configure io to spi mode + SPIInit(SpiNum_HSPI, &hSpiAttr); + //SPICsPinSelect(SpiNum_HSPI, SpiPinCS_1); + + // configure UART TXD to be GPIO1, set as output + PIN_FUNC_SELECT(PERIPHS_IO_MUX_GPIO5_U, FUNC_GPIO5); + gpio_output_set(0, 0, (1 << 5), 0); + gpio_output_set((1 << 5), 0, 0, 0); + + // uart init + uart_init(BIT_RATE_115200, BIT_RATE_115200); + + // led init + PIN_FUNC_SELECT(PERIPHS_IO_MUX_GPIO2_U, FUNC_GPIO2); + gpio_output_set(0, (1 << pin), (1 << pin), 0); + + os_printf("hello\n"); + + // needs SPI + wifi_init(); + + // support ota upgrades + elm327_init(); + web_init(); + + // set gpio high, so LED is off by default + for (int i = 0; i < 5; i++) { + gpio_output_set(0, (1 << pin), 0, 0); + os_delay_us(50000); + gpio_output_set((1 << pin), 0, 0, 0); + os_delay_us(50000); + } + + // jump to OS + system_os_task(loop, LOOP_PRIO, my_queue, QUEUE_SIZE); + system_os_post(LOOP_PRIO, 0, 0); +} + +void ICACHE_FLASH_ATTR loop(os_event_t *events) { + system_os_post(LOOP_PRIO, 0, 0); +} + diff --git a/panda/boardesp/user_config.h b/panda/boardesp/user_config.h new file mode 100644 index 00000000000000..e69de29bb2d1d6 diff --git a/panda/boardesp/webserver.c b/panda/boardesp/webserver.c new file mode 100644 index 00000000000000..9266b08f70f605 --- /dev/null +++ b/panda/boardesp/webserver.c @@ -0,0 +1,381 @@ +#include "stdlib.h" +#include "ets_sys.h" +#include "osapi.h" +#include "gpio.h" +#include "mem.h" +#include "os_type.h" +#include "user_interface.h" +#include "espconn.h" +#include "upgrade.h" + +#include "crypto/rsa.h" +#include "crypto/sha.h" + +#include "obj/gitversion.h" +#include "obj/cert.h" + +#define max(a,b) ((a) > (b) ? (a) : (b)) +#define min(a,b) ((a) < (b) ? (a) : (b)) +#define espconn_send_string(conn, x) espconn_send(conn, x, strlen(x)) + +#define MAX_RESP 0x800 +char resp[MAX_RESP]; +char pageheader[] = "HTTP/1.0 200 OK\nContent-Type: text/html\n\n" +"\n" +"\n" +"\n" +"Panda\n" +"\n" +"\n" +"
This is your comma.ai panda\n\n"
+"It's open source. Find the code here\n"
+"Designed to work with our dashcam, chffr\n";
+
+char pagefooter[] = "
\n" +"\n" +"\n"; + +char OK_header[] = "HTTP/1.0 200 OK\nContent-Type: text/html\n\n"; + +static struct espconn web_conn; +static esp_tcp web_proto; +extern char ssid[]; +extern int wifi_secure_mode; + +char *st_firmware; +int real_content_length, content_length = 0; +char *st_firmware_ptr; +LOCAL os_timer_t ota_reboot_timer; + +#define FIRMWARE_SIZE 503808 + +typedef struct { + uint16_t ep; + uint16_t extra_len; + union { + struct { + uint8_t request_type; + uint8_t request; + uint16_t value; + uint16_t index; + uint16_t length; + } control; + uint8_t data[0x10]; + } u; +} usb_msg; + +int ICACHE_FLASH_ATTR usb_cmd(int ep, int len, int request, + int value, int index, char *data) { + usb_msg usb = {0}; + + usb.ep = ep; + usb.extra_len = (ep == 0) ? 0 : len; + if (ep == 0) { + usb.u.control.request_type = 0xc0; + usb.u.control.request = request; + usb.u.control.value = value; + usb.u.control.index = index; + } else { + memcpy(&usb.u.data, data, usb.extra_len); + } + + uint32_t recv[0x44/4]; + spi_comm(&usb, sizeof(usb), recv, 0x40); + + return recv[0]; +} + + +void ICACHE_FLASH_ATTR st_flash() { + if (st_firmware != NULL) { + // boot mode + os_printf("st_flash: enter boot mode\n"); + st_set_boot_mode(1); + + // echo + os_printf("st_flash: wait for echo\n"); + for (int i = 0; i < 10; i++) { + os_printf(" attempt: %d\n", i); + if (usb_cmd(0, 0, 0xb0, 0, 0, NULL) > 0) break; + } + + // unlock flash + os_printf("st_flash: unlock flash\n"); + usb_cmd(0, 0, 0xb1, 0, 0, NULL); + + // erase sector 1 + os_printf("st_flash: erase sector 1\n"); + usb_cmd(0, 0, 0xb2, 1, 0, NULL); + + if (real_content_length >= 16384) { + // erase sector 2 + os_printf("st_flash: erase sector 2\n"); + usb_cmd(0, 0, 0xb2, 2, 0, NULL); + } + + // real content length will always be 0x10 aligned + os_printf("st_flash: flashing\n"); + for (int i = 0; i < real_content_length; i += 0x10) { + int rl = min(0x10, real_content_length-i); + usb_cmd(2, rl, 0, 0, 0, &st_firmware[i]); + system_soft_wdt_feed(); + } + + // reboot into normal mode + os_printf("st_flash: rebooting\n"); + usb_cmd(0, 0, 0xd8, 0, 0, NULL); + + // done with this + os_free(st_firmware); + st_firmware = NULL; + } +} + +typedef enum { + NOT_STARTED, + CONNECTION_ESTABLISHED, + RECEIVING_HEADER, + RECEIVING_ST_FIRMWARE, + RECEIVING_ESP_FIRMWARE, + REBOOTING, + ERROR +} web_state_t; + +web_state_t state = NOT_STARTED; +int esp_address, esp_address_erase_limit, start_address; + +void ICACHE_FLASH_ATTR hexdump(char *data, int len) { + int i; + for (i=0;isecure it"); + } + + ets_strcat(resp,"\nSet USB Mode:" + "" + "" + "\n"); + + ets_strcat(resp, pagefooter); + + espconn_send_string(&web_conn, resp); + espconn_disconnect(conn); + } else if (memcmp(data, "GET /secure", 11) == 0 && !wifi_secure_mode) { + wifi_configure(1); + } else if (memcmp(data, "GET /set_property?usb_mode=", 27) == 0 && wifi_secure_mode) { + char mode_value = data[27] - '0'; + if (mode_value >= '\x00' && mode_value <= '\x02') { + memset(resp, 0, MAX_RESP); + char set_usb_mode_packet[] = "\x00\x00\x00\x00\x40\xE6\x00\x00\x00\x00\x40\x00"; + set_usb_mode_packet[6] = mode_value; + uint32_t recvData[1]; + spi_comm(set_usb_mode_packet, 0xC, recvData, 0); + os_sprintf(resp, "%sUSB Mode set to %02x\n\n", OK_header, mode_value); + espconn_send_string(&web_conn, resp); + espconn_disconnect(conn); + } + } else if (memcmp(data, "PUT /stupdate ", 14) == 0 && wifi_secure_mode) { + os_printf("init st firmware\n"); + char *cl = strstr(data, "Content-Length: "); + if (cl != NULL) { + // get content length + cl += strlen("Content-Length: "); + content_length = skip_atoi(&cl); + os_printf("with content length %d\n", content_length); + + // should be small enough to fit in RAM + real_content_length = (content_length+0xF)&(~0xF); + st_firmware_ptr = st_firmware = os_malloc(real_content_length); + memset(st_firmware, 0, real_content_length); + state = RECEIVING_ST_FIRMWARE; + } + + } else if (((memcmp(data, "PUT /espupdate1 ", 16) == 0) || + (memcmp(data, "PUT /espupdate2 ", 16) == 0)) && wifi_secure_mode) { + // 0x1000 = user1.bin + // 0x81000 = user2.bin + // 0x3FE000 = blank.bin + os_printf("init esp firmware\n"); + char *cl = strstr(data, "Content-Length: "); + if (cl != NULL) { + // get content length + cl += strlen("Content-Length: "); + content_length = skip_atoi(&cl); + os_printf("with content length %d\n", content_length); + + // setup flashing + uint8_t current = system_upgrade_userbin_check(); + if (data[14] == '2' && current == UPGRADE_FW_BIN1) { + os_printf("flashing boot2.bin\n"); + state = RECEIVING_ESP_FIRMWARE; + esp_address = 4*1024 + FIRMWARE_SIZE + 16*1024 + 4*1024; + } else if (data[14] == '1' && current == UPGRADE_FW_BIN2) { + os_printf("flashing boot1.bin\n"); + state = RECEIVING_ESP_FIRMWARE; + esp_address = 4*1024; + } else { + espconn_send_string(&web_conn, "HTTP/1.0 404 Not Found\nContent-Type: text/html\n\nwrong!\n"); + espconn_disconnect(conn); + } + esp_address_erase_limit = esp_address; + start_address = esp_address; + } + } else { + espconn_send_string(&web_conn, "HTTP/1.0 404 Not Found\nContent-Type: text/html\n\n404 Not Found!\n"); + espconn_disconnect(conn); + } + } else if (state == RECEIVING_ST_FIRMWARE) { + os_printf("receiving st firmware: %d/%d\n", len, content_length); + memcpy(st_firmware_ptr, data, min(content_length, len)); + st_firmware_ptr += len; + content_length -= len; + + if (content_length <= 0 && real_content_length > 1000) { + state = NOT_STARTED; + os_printf("done!\n"); + espconn_send_string(&web_conn, "HTTP/1.0 200 OK\nContent-Type: text/html\n\nsuccess!\n"); + espconn_disconnect(conn); + + // reboot + os_printf("Scheduling st_flash in 100ms.\n"); + os_timer_disarm(&ota_reboot_timer); + os_timer_setfn(&ota_reboot_timer, (os_timer_func_t *)st_flash, NULL); + os_timer_arm(&ota_reboot_timer, 100, 0); + } + } else if (state == RECEIVING_ESP_FIRMWARE) { + if ((esp_address+len) < (start_address + FIRMWARE_SIZE)) { + os_printf("receiving esp firmware: %d/%d -- 0x%x - 0x%x\n", len, content_length, + esp_address, esp_address_erase_limit); + content_length -= len; + while (esp_address_erase_limit < (esp_address + len)) { + os_printf("erasing 0x%X\n", esp_address_erase_limit); + spi_flash_erase_sector(esp_address_erase_limit / SPI_FLASH_SEC_SIZE); + esp_address_erase_limit += SPI_FLASH_SEC_SIZE; + } + SpiFlashOpResult res = spi_flash_write(esp_address, data, len); + if (res != SPI_FLASH_RESULT_OK) { + os_printf("flash fail @ 0x%x\n", esp_address); + } + esp_address += len; + + if (content_length == 0) { + + char digest[SHA_DIGEST_SIZE]; + uint32_t rsa[RSANUMBYTES/4]; + uint32_t dat[0x80/4]; + int ll; + spi_flash_read(esp_address-RSANUMBYTES, rsa, RSANUMBYTES); + + // 32-bit aligned accesses only + SHA_CTX ctx; + SHA_init(&ctx); + for (ll = start_address; ll < esp_address-RSANUMBYTES; ll += 0x80) { + spi_flash_read(ll, dat, 0x80); + SHA_update(&ctx, dat, min((esp_address-RSANUMBYTES)-ll, 0x80)); + } + memcpy(digest, SHA_final(&ctx), SHA_DIGEST_SIZE); + + if (RSA_verify(&releaseesp_rsa_key, rsa, RSANUMBYTES, digest, SHA_DIGEST_SIZE) || + #ifdef ALLOW_DEBUG + RSA_verify(&debugesp_rsa_key, rsa, RSANUMBYTES, digest, SHA_DIGEST_SIZE) + #else + false + #endif + ) { + os_printf("RSA verify success!\n"); + espconn_send_string(&web_conn, "HTTP/1.0 200 OK\nContent-Type: text/html\n\nsuccess!\n"); + system_upgrade_flag_set(UPGRADE_FLAG_FINISH); + + // reboot + os_printf("Scheduling reboot.\n"); + os_timer_disarm(&ota_reboot_timer); + os_timer_setfn(&ota_reboot_timer, (os_timer_func_t *)system_upgrade_reboot, NULL); + os_timer_arm(&ota_reboot_timer, 2000, 0); + } else { + os_printf("RSA verify FAILURE\n"); + espconn_send_string(&web_conn, "HTTP/1.0 500 Internal Server Error\nContent-Type: text/html\n\nrsa verify fail\n"); + } + espconn_disconnect(conn); + } + } + } +} + +void ICACHE_FLASH_ATTR web_tcp_connect_cb(void *arg) { + state = CONNECTION_ESTABLISHED; + struct espconn *conn = (struct espconn *)arg; + espconn_set_opt(&web_conn, ESPCONN_NODELAY); + espconn_regist_recvcb(conn, web_rx_cb); +} + +void ICACHE_FLASH_ATTR web_init() { + web_proto.local_port = 80; + web_conn.type = ESPCONN_TCP; + web_conn.state = ESPCONN_NONE; + web_conn.proto.tcp = &web_proto; + espconn_regist_connectcb(&web_conn, web_tcp_connect_cb); + espconn_accept(&web_conn); +} + diff --git a/panda/buy.png b/panda/buy.png new file mode 100644 index 00000000000000..72c70574225173 Binary files /dev/null and b/panda/buy.png differ diff --git a/panda/certs/debug b/panda/certs/debug new file mode 100644 index 00000000000000..39864b6b1a36e4 --- /dev/null +++ b/panda/certs/debug @@ -0,0 +1,15 @@ +-----BEGIN RSA PRIVATE KEY----- +MIICXQIBAAKBgQC948lnRo4x44Rd7Y8bQAML4aKDC4XRx958fHV8K6+FbCaP1Z42 +U2kX0yygak0LjoDutpgObmGHZA+Iz3HeUD6VGjr/teN24vPk+A95cRsjt8rgmGQ9 +6HNjaNgjR+gl1F9XxFimMzir82Xpl1ekTueJNXa7ia5HVH1nFdiksOKHGQIDAQAB +AoGAQuPw2I6EHJLW1/eNB75e1FqhUqRGeYV8nEGDaUBCTi+wzc4kM2LijF/5QnDv +vvht9qkfm0XK2VSoHDtnEzcVM/l1ksb68n4R/1nUooAWY6cQI7dCSk/A6yS1EJFg +BXsgGbT/65khw9pzBW2zVtMVcVNWFayqfCO1I9WcDdA1x1kCQQDfrhoZTZNoDEUE +JKM4fiUdWr1h3Aw8KLJFFexSWeGDwo+qqnujYcKWkHa9qaH1RG5x8Kir9s9Oi4Js +mzKwov8fAkEA2VPJPWxJ4vVQpXle6wC1nyoL7s739yxMWFcabvkzDDhlIVBNdVJd +gZKsFWV7QnVNdDMjn9D27FwKu3i2D+kKxwJBANp1SMojqO765MEKI1t+YDNONx6H +cm+i85Fjuv4nCIjOEdCGVuCYDxtMFpxgO2y3HAMuHx5sm8XDnWsDHLvFRdMCQD7V +XqWHnYUk8AAnqy2+ssQl3/VXmZG5GQmhhV74Za3u0C5ljT+SZL6FrYMyKAT67T3f +WzllrT6BDglNyTWoZxkCQQCt0XSoGM3603GGYNt6AUlGSgtXSo/2Px7odGUtQoKA +FH9q6FVMYpQJ38spZxIGufZJmLP8LLg6YIWJj1F+akxr +-----END RSA PRIVATE KEY----- diff --git a/panda/certs/debug.pub b/panda/certs/debug.pub new file mode 100644 index 00000000000000..00e219d7bb8cfa --- /dev/null +++ b/panda/certs/debug.pub @@ -0,0 +1 @@ +ssh-rsa AAAAB3NzaC1yc2EAAAADAQABAAAAgQC948lnRo4x44Rd7Y8bQAML4aKDC4XRx958fHV8K6+FbCaP1Z42U2kX0yygak0LjoDutpgObmGHZA+Iz3HeUD6VGjr/teN24vPk+A95cRsjt8rgmGQ96HNjaNgjR+gl1F9XxFimMzir82Xpl1ekTueJNXa7ia5HVH1nFdiksOKHGQ== batman@y840 diff --git a/panda/certs/debugesp b/panda/certs/debugesp new file mode 100644 index 00000000000000..789beaac195639 --- /dev/null +++ b/panda/certs/debugesp @@ -0,0 +1,15 @@ +-----BEGIN RSA PRIVATE KEY----- +MIICXAIBAAKBgQCjIHvrSCWN0Nec6ozbImYik30PIF7JSWgdwDKTxSJ05RM3pj5E +LQEGt3qcaVrTokO68tpt5Gu1p6ZsNqWg7iVTW9M7Qj7IH45YDzQP/PSRjgSosQA6 +6f5Gokba5QrW38myqimvj+0p+YH+CNGCBRlTUQGCO8uLCspMZneRSLPW9QIDAQAB +AoGADaUn+HRef9BaWMvd4G6uMHI54cwJYbj8NpDfKjExQqnuw5bqWnWRQmiSnwbJ +DC7kj3zE/LBAuj890ot3q1CAWqh47ZICZfoX9Qbi5TpvIHFCGy6YkOliF6iIQhR2 +4+zNKTAA0zNKskOM25PdI+grK1Ni/bEofSA6TrqvEwsmxnkCQQDVp9FUUor2Bo/h +/3oAIP51LTw7vfpztYbJr+BDV63czV2DLXzSwzeNrwH4sA3oy1mjUgMBBgAarNGE +DYlc4H5jAkEAw3UCHzzXPlxkw2QGp7nBly5y3p80Uqc31NuYz8rdX/U8KTngi2No +Ft/SGCEXNpeYbToj+WK3RJJ2Ey0mK8+IxwJAcpGd/5CPsaQNLcw4WK9Yo+8Q2Jxk +G/4gfDCSmqn+smNxnLEcuUwzkwdgkEGgA9BfjeOhdsAH+EXpx90WZrZ/LwJBAK0k +jq+rTqUQZbZsejTEKYjJ/bnV4BzDwoKN0Q1pkLc7X4LJoW74rTFuLgdv8MdMfRtt +IIb/eoeFEpGkMicnHesCQHgR7BTUGBM6Uxam7RCdsgVsxoHBma21E/44ivWUMZzN +3oVt0mPnjS4speOlqwED5pCJ7yw7jwLPFMs8kNxuIKU= +-----END RSA PRIVATE KEY----- diff --git a/panda/certs/debugesp.pub b/panda/certs/debugesp.pub new file mode 100644 index 00000000000000..3afcf3988ea651 --- /dev/null +++ b/panda/certs/debugesp.pub @@ -0,0 +1 @@ +ssh-rsa AAAAB3NzaC1yc2EAAAADAQABAAAAgQCjIHvrSCWN0Nec6ozbImYik30PIF7JSWgdwDKTxSJ05RM3pj5ELQEGt3qcaVrTokO68tpt5Gu1p6ZsNqWg7iVTW9M7Qj7IH45YDzQP/PSRjgSosQA66f5Gokba5QrW38myqimvj+0p+YH+CNGCBRlTUQGCO8uLCspMZneRSLPW9Q== batman@y840 diff --git a/panda/certs/release.pub b/panda/certs/release.pub new file mode 100644 index 00000000000000..19066e29a75cad --- /dev/null +++ b/panda/certs/release.pub @@ -0,0 +1 @@ +ssh-rsa AAAAB3NzaC1yc2EAAAADAQABAAAAgQDGN9GU2nOc0kKq6vdZI5qUMzHt234ngqofrgCFFxL0D2Whex0zACp9gar0HZp+bvtpoSgU/Ev8wexNKr+A9QTradljiuxi5ctrOra9k+wxqNj63Wrcu4+wU5UnJEVf/buV4jCOFffMT8z3PO4imt8LzHuEIC/m/ASKVYyvuvBRQQ== batman@y840 diff --git a/panda/certs/releaseesp.pub b/panda/certs/releaseesp.pub new file mode 100644 index 00000000000000..1d1d54bb7e73f4 --- /dev/null +++ b/panda/certs/releaseesp.pub @@ -0,0 +1 @@ +ssh-rsa AAAAB3NzaC1yc2EAAAADAQABAAAAgQDN4pVyGuJJSde1l3Fjay8qPxog09DsAJZtYPk+armoYO1L6YKReUTcMNyHQYZZMZFmhCdgjCgTIF2QYWMoP4KSe8l6JF04YPP51dIgefc6UXjtlSI8Pyutr0v9xXjSfsVm3RAJxDSHgzs9AoMsluKCL+LhAR1nd7cuHXITJ80O4w== batman@y840 diff --git a/panda/common/version.mk b/panda/common/version.mk new file mode 100644 index 00000000000000..cc42223da3d03d --- /dev/null +++ b/panda/common/version.mk @@ -0,0 +1,18 @@ +ifeq ($(RELEASE),1) + BUILD_TYPE = "RELEASE" +else + BUILD_TYPE = "DEBUG" +endif + +ifneq ($(wildcard ../.git/HEAD),) +obj/gitversion.h: ../VERSION ../.git/HEAD ../.git/index + echo "const uint8_t gitversion[] = \"$(shell cat ../VERSION)-$(shell git rev-parse --short=8 HEAD)-$(BUILD_TYPE)\";" > $@ +else +ifneq ($(wildcard ../../.git/modules/panda/HEAD),) +obj/gitversion.h: ../VERSION ../../.git/modules/panda/HEAD ../../.git/modules/panda/index + echo "const uint8_t gitversion[] = \"$(shell cat ../VERSION)-$(shell git rev-parse --short=8 HEAD)-$(BUILD_TYPE)\";" > $@ +else +obj/gitversion.h: ../VERSION + echo "const uint8_t gitversion[] = \"$(shell cat ../VERSION)-unknown-$(BUILD_TYPE)\";" > $@ +endif +endif diff --git a/panda/crypto/getcertheader.py b/panda/crypto/getcertheader.py new file mode 100755 index 00000000000000..75d04e977ad8c1 --- /dev/null +++ b/panda/crypto/getcertheader.py @@ -0,0 +1,46 @@ +#!/usr/bin/env python +import sys +import struct +from Crypto.PublicKey import RSA + +def egcd(a, b): + if a == 0: + return (b, 0, 1) + else: + g, y, x = egcd(b % a, a) + return (g, x - (b // a) * y, y) + +def modinv(a, m): + g, x, y = egcd(a, m) + if g != 1: + raise Exception('modular inverse does not exist') + else: + return x % m + +def to_c_string(x): + mod = (hex(x)[2:-1].rjust(0x100, '0')) + hh = ''.join('\\x'+mod[i:i+2] for i in range(0, 0x100, 2)) + return hh + +def to_c_uint32(x): + nums = [] + for i in range(0x20): + nums.append(x%(2**32)) + x /= (2**32) + return "{"+'U,'.join(map(str, nums))+"U}" + +for fn in sys.argv[1:]: + rsa = RSA.importKey(open(fn).read()) + rr = pow(2**1024, 2, rsa.n) + n0inv = 2**32 - modinv(rsa.n, 2**32) + + cname = fn.split("/")[-1].split(".")[0] + "_rsa_key" + + print 'RSAPublicKey '+cname+' = {.len = 0x20,' + print ' .n0inv = %dU,' % n0inv + print ' .n = %s,' % to_c_uint32(rsa.n) + print ' .rr = %s,' % to_c_uint32(rr) + print ' .exponent = %d,' % rsa.e + print '};' + + diff --git a/panda/crypto/hash-internal.h b/panda/crypto/hash-internal.h new file mode 100644 index 00000000000000..05ec3ec9fd22aa --- /dev/null +++ b/panda/crypto/hash-internal.h @@ -0,0 +1,63 @@ +/* + * Copyright 2007 The Android Open Source Project + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of Google Inc. nor the names of its contributors may + * be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY Google Inc. ``AS IS'' AND ANY EXPRESS OR + * IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO + * EVENT SHALL Google Inc. BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, + * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, + * PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; + * OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, + * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR + * OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF + * ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef SYSTEM_CORE_INCLUDE_MINCRYPT_HASH_INTERNAL_H_ +#define SYSTEM_CORE_INCLUDE_MINCRYPT_HASH_INTERNAL_H_ + +#include "stdint.h" + +#ifdef __cplusplus +extern "C" { +#endif // __cplusplus + +struct HASH_CTX; // forward decl + +typedef struct HASH_VTAB { + void (* const init)(struct HASH_CTX*); + void (* const update)(struct HASH_CTX*, const void*, int); + const uint8_t* (* const final)(struct HASH_CTX*); + const uint8_t* (* const hash)(const void*, int, uint8_t*); + int size; +} HASH_VTAB; + +typedef struct HASH_CTX { + const HASH_VTAB * f; + uint64_t count; + uint8_t buf[64]; + uint32_t state[8]; // upto SHA2 +} HASH_CTX; + +#define HASH_init(ctx) (ctx)->f->init(ctx) +#define HASH_update(ctx, data, len) (ctx)->f->update(ctx, data, len) +#define HASH_final(ctx) (ctx)->f->final(ctx) +#define HASH_hash(data, len, digest) (ctx)->f->hash(data, len, digest) +#define HASH_size(ctx) (ctx)->f->size + +#ifdef __cplusplus +} +#endif // __cplusplus + +#endif // SYSTEM_CORE_INCLUDE_MINCRYPT_HASH_INTERNAL_H_ diff --git a/panda/crypto/rsa.c b/panda/crypto/rsa.c new file mode 100644 index 00000000000000..24171e87909275 --- /dev/null +++ b/panda/crypto/rsa.c @@ -0,0 +1,294 @@ +/* rsa.c +** +** Copyright 2012, The Android Open Source Project +** +** Redistribution and use in source and binary forms, with or without +** modification, are permitted provided that the following conditions are met: +** * Redistributions of source code must retain the above copyright +** notice, this list of conditions and the following disclaimer. +** * Redistributions in binary form must reproduce the above copyright +** notice, this list of conditions and the following disclaimer in the +** documentation and/or other materials provided with the distribution. +** * Neither the name of Google Inc. nor the names of its contributors may +** be used to endorse or promote products derived from this software +** without specific prior written permission. +** +** THIS SOFTWARE IS PROVIDED BY Google Inc. ``AS IS'' AND ANY EXPRESS OR +** IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF +** MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO +** EVENT SHALL Google Inc. BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +** SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, +** PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; +** OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, +** WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR +** OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF +** ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*/ + +#include "rsa.h" +#include "sha.h" + +// a[] -= mod +static void subM(const RSAPublicKey* key, + uint32_t* a) { + int64_t A = 0; + int i; + for (i = 0; i < key->len; ++i) { + A += (uint64_t)a[i] - key->n[i]; + a[i] = (uint32_t)A; + A >>= 32; + } +} + +// return a[] >= mod +static int geM(const RSAPublicKey* key, + const uint32_t* a) { + int i; + for (i = key->len; i;) { + --i; + if (a[i] < key->n[i]) return 0; + if (a[i] > key->n[i]) return 1; + } + return 1; // equal +} + +// montgomery c[] += a * b[] / R % mod +static void montMulAdd(const RSAPublicKey* key, + uint32_t* c, + const uint32_t a, + const uint32_t* b) { + uint64_t A = (uint64_t)a * b[0] + c[0]; + uint32_t d0 = (uint32_t)A * key->n0inv; + uint64_t B = (uint64_t)d0 * key->n[0] + (uint32_t)A; + int i; + + for (i = 1; i < key->len; ++i) { + A = (A >> 32) + (uint64_t)a * b[i] + c[i]; + B = (B >> 32) + (uint64_t)d0 * key->n[i] + (uint32_t)A; + c[i - 1] = (uint32_t)B; + } + + A = (A >> 32) + (B >> 32); + + c[i - 1] = (uint32_t)A; + + if (A >> 32) { + subM(key, c); + } +} + +// montgomery c[] = a[] * b[] / R % mod +static void montMul(const RSAPublicKey* key, + uint32_t* c, + const uint32_t* a, + const uint32_t* b) { + int i; + for (i = 0; i < key->len; ++i) { + c[i] = 0; + } + for (i = 0; i < key->len; ++i) { + montMulAdd(key, c, a[i], b); + } +} + +// In-place public exponentiation. +// Input and output big-endian byte array in inout. +static void modpow(const RSAPublicKey* key, + uint8_t* inout) { + uint32_t a[RSANUMWORDS]; + uint32_t aR[RSANUMWORDS]; + uint32_t aaR[RSANUMWORDS]; + uint32_t* aaa = 0; + int i; + + // Convert from big endian byte array to little endian word array. + for (i = 0; i < key->len; ++i) { + uint32_t tmp = + (inout[((key->len - 1 - i) * 4) + 0] << 24) | + (inout[((key->len - 1 - i) * 4) + 1] << 16) | + (inout[((key->len - 1 - i) * 4) + 2] << 8) | + (inout[((key->len - 1 - i) * 4) + 3] << 0); + a[i] = tmp; + } + + if (key->exponent == 65537) { + aaa = aaR; // Re-use location. + montMul(key, aR, a, key->rr); // aR = a * RR / R mod M + for (i = 0; i < 16; i += 2) { + montMul(key, aaR, aR, aR); // aaR = aR * aR / R mod M + montMul(key, aR, aaR, aaR); // aR = aaR * aaR / R mod M + } + montMul(key, aaa, aR, a); // aaa = aR * a / R mod M + } else if (key->exponent == 3) { + aaa = aR; // Re-use location. + montMul(key, aR, a, key->rr); /* aR = a * RR / R mod M */ + montMul(key, aaR, aR, aR); /* aaR = aR * aR / R mod M */ + montMul(key, aaa, aaR, a); /* aaa = aaR * a / R mod M */ + } + + // Make sure aaa < mod; aaa is at most 1x mod too large. + if (geM(key, aaa)) { + subM(key, aaa); + } + + // Convert to bigendian byte array + for (i = key->len - 1; i >= 0; --i) { + uint32_t tmp = aaa[i]; + *inout++ = tmp >> 24; + *inout++ = tmp >> 16; + *inout++ = tmp >> 8; + *inout++ = tmp >> 0; + } +} + +// Expected PKCS1.5 signature padding bytes, for a keytool RSA signature. +// Has the 0-length optional parameter encoded in the ASN1 (as opposed to the +// other flavor which omits the optional parameter entirely). This code does not +// accept signatures without the optional parameter. + +/* +static const uint8_t sha_padding[RSANUMBYTES] = { + 0x00, 0x01, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0x00, 0x30, 0x21, 0x30, + 0x09, 0x06, 0x05, 0x2b, 0x0e, 0x03, 0x02, 0x1a, + 0x05, 0x00, 0x04, 0x14, + + // 20 bytes of hash go here. + 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0 +}; +*/ + +static const uint8_t sha_padding_1024[RSANUMBYTES] = { + 0x00, 0x01, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0x00, + + // 20 bytes of hash go here. + 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0 +}; + +// SHA-1 of PKCS1.5 signature sha_padding for 2048 bit, as above. +// At the location of the bytes of the hash all 00 are hashed. +/*static const uint8_t kExpectedPadShaRsa2048[SHA_DIGEST_SIZE] = { + 0xdc, 0xbd, 0xbe, 0x42, 0xd5, 0xf5, 0xa7, 0x2e, + 0x6e, 0xfc, 0xf5, 0x5d, 0xaf, 0x9d, 0xea, 0x68, + 0x7c, 0xfb, 0xf1, 0x67 +};*/ + +// Verify a 2048-bit RSA PKCS1.5 signature against an expected hash. +// Both e=3 and e=65537 are supported. hash_len may be +// SHA_DIGEST_SIZE (== 20) to indicate a SHA-1 hash, or +// SHA256_DIGEST_SIZE (== 32) to indicate a SHA-256 hash. No other +// values are supported. +// +// Returns 1 on successful verification, 0 on failure. +int RSA_verify(const RSAPublicKey *key, + const uint8_t *signature, + const int len, + const uint8_t *hash, + const int hash_len) { + uint8_t buf[RSANUMBYTES]; + int i; + //const uint8_t* padding_hash; + + if (key->len != RSANUMWORDS) { + return 0; // Wrong key passed in. + } + + if (len != sizeof(buf)) { + return 0; // Wrong input length. + } + + if (hash_len != SHA_DIGEST_SIZE) { + return 0; // Unsupported hash. + } + + if (key->exponent != 3 && key->exponent != 65537) { + return 0; // Unsupported exponent. + } + + for (i = 0; i < len; ++i) { // Copy input to local workspace. + buf[i] = signature[i]; + } + + modpow(key, buf); // In-place exponentiation. + +#ifdef TEST_RSA + printf("sig\n"); + for (i=0;i> (32 - (bits)))) + +static void SHA1_Transform(SHA_CTX* ctx) { + uint32_t W[80]; + uint32_t A, B, C, D, E; + uint8_t* p = ctx->buf; + int t; + + for(t = 0; t < 16; ++t) { + uint32_t tmp = *p++ << 24; + tmp |= *p++ << 16; + tmp |= *p++ << 8; + tmp |= *p++; + W[t] = tmp; + } + + for(; t < 80; t++) { + W[t] = rol(1,W[t-3] ^ W[t-8] ^ W[t-14] ^ W[t-16]); + } + + A = ctx->state[0]; + B = ctx->state[1]; + C = ctx->state[2]; + D = ctx->state[3]; + E = ctx->state[4]; + + for(t = 0; t < 80; t++) { + uint32_t tmp = rol(5,A) + E + W[t]; + + if (t < 20) + tmp += (D^(B&(C^D))) + 0x5A827999; + else if ( t < 40) + tmp += (B^C^D) + 0x6ED9EBA1; + else if ( t < 60) + tmp += ((B&C)|(D&(B|C))) + 0x8F1BBCDC; + else + tmp += (B^C^D) + 0xCA62C1D6; + + E = D; + D = C; + C = rol(30,B); + B = A; + A = tmp; + } + + ctx->state[0] += A; + ctx->state[1] += B; + ctx->state[2] += C; + ctx->state[3] += D; + ctx->state[4] += E; +} + +static const HASH_VTAB SHA_VTAB = { + SHA_init, + SHA_update, + SHA_final, + SHA_hash, + SHA_DIGEST_SIZE +}; + +void SHA_init(SHA_CTX* ctx) { + ctx->f = &SHA_VTAB; + ctx->state[0] = 0x67452301; + ctx->state[1] = 0xEFCDAB89; + ctx->state[2] = 0x98BADCFE; + ctx->state[3] = 0x10325476; + ctx->state[4] = 0xC3D2E1F0; + ctx->count = 0; +} + + +void SHA_update(SHA_CTX* ctx, const void* data, int len) { + int i = (int) (ctx->count & 63); + const uint8_t* p = (const uint8_t*)data; + + ctx->count += len; + + while (len--) { + ctx->buf[i++] = *p++; + if (i == 64) { + SHA1_Transform(ctx); + i = 0; + } + } +} + + +const uint8_t* SHA_final(SHA_CTX* ctx) { + uint8_t *p = ctx->buf; + uint64_t cnt = ctx->count * 8; + int i; + + SHA_update(ctx, (uint8_t*)"\x80", 1); + while ((ctx->count & 63) != 56) { + SHA_update(ctx, (uint8_t*)"\0", 1); + } + for (i = 0; i < 8; ++i) { + uint8_t tmp = (uint8_t) (cnt >> ((7 - i) * 8)); + SHA_update(ctx, &tmp, 1); + } + + for (i = 0; i < 5; i++) { + uint32_t tmp = ctx->state[i]; + *p++ = tmp >> 24; + *p++ = tmp >> 16; + *p++ = tmp >> 8; + *p++ = tmp >> 0; + } + + return ctx->buf; +} + +/* Convenience function */ +const uint8_t* SHA_hash(const void* data, int len, uint8_t* digest) { + SHA_CTX ctx; + SHA_init(&ctx); + SHA_update(&ctx, data, len); + memcpy(digest, SHA_final(&ctx), SHA_DIGEST_SIZE); + return digest; +} diff --git a/panda/crypto/sha.h b/panda/crypto/sha.h new file mode 100644 index 00000000000000..4b51a531bf582a --- /dev/null +++ b/panda/crypto/sha.h @@ -0,0 +1,51 @@ +/* + * Copyright 2005 The Android Open Source Project + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of Google Inc. nor the names of its contributors may + * be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY Google Inc. ``AS IS'' AND ANY EXPRESS OR + * IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO + * EVENT SHALL Google Inc. BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, + * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, + * PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; + * OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, + * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR + * OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF + * ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + */ +#ifndef SYSTEM_CORE_INCLUDE_MINCRYPT_SHA1_H_ +#define SYSTEM_CORE_INCLUDE_MINCRYPT_SHA1_H_ + +#include "hash-internal.h" + +#ifdef __cplusplus +extern "C" { +#endif // __cplusplus + +typedef HASH_CTX SHA_CTX; + +void SHA_init(SHA_CTX* ctx); +void SHA_update(SHA_CTX* ctx, const void* data, int len); +const uint8_t* SHA_final(SHA_CTX* ctx); + +// Convenience method. Returns digest address. +// NOTE: *digest needs to hold SHA_DIGEST_SIZE bytes. +const uint8_t* SHA_hash(const void* data, int len, uint8_t* digest); + +#define SHA_DIGEST_SIZE 20 + +#ifdef __cplusplus +} +#endif // __cplusplus + +#endif // SYSTEM_CORE_INCLUDE_MINCRYPT_SHA1_H_ diff --git a/panda/crypto/sign.py b/panda/crypto/sign.py new file mode 100755 index 00000000000000..159299271e91e0 --- /dev/null +++ b/panda/crypto/sign.py @@ -0,0 +1,29 @@ +#!/usr/bin/env python +import os +import sys +import struct +import hashlib +from Crypto.PublicKey import RSA + +rsa = RSA.importKey(open(sys.argv[3]).read()) + +with open(sys.argv[1]) as f: + dat = f.read() + +print "signing", len(dat), "bytes" + +with open(sys.argv[2], "wb") as f: + if os.getenv("SETLEN") is not None: + x = struct.pack("I", len(dat)) + dat[4:] + # mock signature of dat[4:] + dd = hashlib.sha1(dat[4:]).digest() + else: + x = dat + dd = hashlib.sha1(dat).digest() + print "hash:",dd.encode("hex") + dd = "\x00\x01" + "\xff"*0x69 + "\x00" + dd + rsa_out = pow(int(dd.encode("hex"), 16), rsa.d, rsa.n) + sig = (hex(rsa_out)[2:-1].rjust(0x100, '0')).decode("hex") + x += sig + f.write(x) + diff --git a/panda/crypto/stdint.h b/panda/crypto/stdint.h new file mode 100644 index 00000000000000..67ac93ed75f084 --- /dev/null +++ b/panda/crypto/stdint.h @@ -0,0 +1,4 @@ +#define uint8_t unsigned char +#define uint32_t unsigned int +#define int64_t long long +#define uint64_t unsigned long long diff --git a/panda/docs/guide.pdf b/panda/docs/guide.pdf new file mode 100644 index 00000000000000..5dbc95680aa4f7 Binary files /dev/null and b/panda/docs/guide.pdf differ diff --git a/panda/drivers/linux/.gitignore b/panda/drivers/linux/.gitignore new file mode 100644 index 00000000000000..93a6cde7630501 --- /dev/null +++ b/panda/drivers/linux/.gitignore @@ -0,0 +1,6 @@ +.*.cmd +*.ko +.tmp_versions +Module.symvers +modules.order +*.mod.c diff --git a/panda/drivers/linux/Makefile b/panda/drivers/linux/Makefile new file mode 100644 index 00000000000000..e5b1ec4219ea92 --- /dev/null +++ b/panda/drivers/linux/Makefile @@ -0,0 +1,18 @@ +VERSION=0.0.1 +obj-m+=panda.o + +link: + sudo dkms add `pwd` + +build: + sudo dkms build panda/$(VERSION) + +install: + sudo dkms install panda/$(VERSION) + +all: build install + +uninstall: + sudo dkms uninstall panda/$(VERSION) + sudo dkms remove panda/$(VERSION) --all + diff --git a/panda/drivers/linux/README.md b/panda/drivers/linux/README.md new file mode 100644 index 00000000000000..81e95523acaca1 --- /dev/null +++ b/panda/drivers/linux/README.md @@ -0,0 +1,19 @@ +Installs the panda linux kernel driver using DKMS. + +This will allow the panda to work with tools such as `can-utils` + +prerequisites: + - `apt-get install dkms gcc linux-headers-$(uname -r) make sudo` + +installation: + - `make link` (only needed the first time. It will report an error on subsequent attempts to link) + - `make all` + - `make install` + +uninstall: + - `make uninstall` + +usage: + +You will need to bring it up using `sudo ifconfig can0 up` or +`sudo ip link set dev can0 up`, depending on your platform. diff --git a/panda/drivers/linux/dkms.conf b/panda/drivers/linux/dkms.conf new file mode 100644 index 00000000000000..da9cba04a28bb7 --- /dev/null +++ b/panda/drivers/linux/dkms.conf @@ -0,0 +1,6 @@ +PACKAGE_NAME="panda" +PACKAGE_VERSION="0.0.1" +BUILT_MODULE_NAME[0]="panda" +DEST_MODULE_LOCATION[0]="/kernel/drivers/net/panda/" +AUTOINSTALL="yes" + diff --git a/panda/drivers/linux/panda.c b/panda/drivers/linux/panda.c new file mode 100644 index 00000000000000..4c5980a9d2ff3c --- /dev/null +++ b/panda/drivers/linux/panda.c @@ -0,0 +1,613 @@ +/** + * @file panda.c + * @author Jessy Diamond Exum + * @date 16 June 2017 + * @version 0.1 + * @brief Driver for the Comma.ai Panda CAN adapter to allow it to be controlled via + * the Linux SocketCAN interface. + * @see https://github.com/commaai/panda for the full project. + * @see Inspired by net/can/usb/mcba_usb.c from Linux Kernel 4.12-rc4. + */ + +#include +#include +#include +#include // Macros used to mark up functions e.g., __init __exit +#include // Contains types, macros, functions for the kernel +#include // Core header for loading LKMs into the kernel +#include +#include + +/* vendor and product id */ +#define PANDA_MODULE_NAME "panda" +#define PANDA_VENDOR_ID 0XBBAA +#define PANDA_PRODUCT_ID 0XDDCC + +#define PANDA_MAX_TX_URBS 20 +#define PANDA_CTX_FREE PANDA_MAX_TX_URBS + +#define PANDA_USB_RX_BUFF_SIZE 0x40 +#define PANDA_USB_TX_BUFF_SIZE (sizeof(struct panda_usb_can_msg)) + +#define PANDA_NUM_CAN_INTERFACES 3 + +#define PANDA_CAN_TRANSMIT 1 +#define PANDA_CAN_EXTENDED 4 + +#define PANDA_BITRATE 500000 + +#define PANDA_DLC_MASK 0x0F + +struct panda_usb_ctx { + struct panda_inf_priv *priv; + u32 ndx; + u8 dlc; +}; + +struct panda_dev_priv; + +struct panda_inf_priv { + struct can_priv can; + struct panda_usb_ctx tx_context[PANDA_MAX_TX_URBS]; + struct net_device *netdev; + struct usb_anchor tx_submitted; + atomic_t free_ctx_cnt; + u8 interface_num; + u8 mcu_can_ifnum; + struct panda_dev_priv *priv_dev; +}; + +struct panda_dev_priv { + struct usb_device *udev; + struct device *dev; + struct usb_anchor rx_submitted; + struct panda_inf_priv *interfaces[PANDA_NUM_CAN_INTERFACES]; +}; + +struct __packed panda_usb_can_msg { + u32 rir; + u32 bus_dat_len; + u8 data[8]; +}; + +static const struct usb_device_id panda_usb_table[] = { + { USB_DEVICE(PANDA_VENDOR_ID, PANDA_PRODUCT_ID) }, + {} /* Terminating entry */ +}; + +MODULE_DEVICE_TABLE(usb, panda_usb_table); + + +// panda: CAN1 = 0 CAN2 = 1 CAN3 = 4 +const int can_numbering[] = {0,1,4}; + +struct panda_inf_priv * +panda_get_inf_from_bus_id(struct panda_dev_priv *priv_dev, int bus_id){ + int inf_num; + for(inf_num = 0; inf_num < PANDA_NUM_CAN_INTERFACES; inf_num++) + if(can_numbering[inf_num] == bus_id) + return priv_dev->interfaces[inf_num]; + return NULL; +} + +// CTX handling shamlessly ripped from mcba_usb.c linux driver +static inline void panda_init_ctx(struct panda_inf_priv *priv) +{ + int i = 0; + + for (i = 0; i < PANDA_MAX_TX_URBS; i++) { + priv->tx_context[i].ndx = PANDA_CTX_FREE; + priv->tx_context[i].priv = priv; + } + + atomic_set(&priv->free_ctx_cnt, ARRAY_SIZE(priv->tx_context)); +} + +static inline struct panda_usb_ctx *panda_usb_get_free_ctx(struct panda_inf_priv *priv, + struct can_frame *cf) +{ + int i = 0; + struct panda_usb_ctx *ctx = NULL; + + for (i = 0; i < PANDA_MAX_TX_URBS; i++) { + if (priv->tx_context[i].ndx == PANDA_CTX_FREE) { + ctx = &priv->tx_context[i]; + ctx->ndx = i; + ctx->dlc = cf->can_dlc; + + atomic_dec(&priv->free_ctx_cnt); + break; + } + } + + printk("CTX num %d\n", atomic_read(&priv->free_ctx_cnt)); + if (!atomic_read(&priv->free_ctx_cnt)){ + /* That was the last free ctx. Slow down tx path */ + printk("SENDING TOO FAST\n"); + netif_stop_queue(priv->netdev); + } + + return ctx; +} + +/* panda_usb_free_ctx and panda_usb_get_free_ctx are executed by different + * threads. The order of execution in below function is important. + */ +static inline void panda_usb_free_ctx(struct panda_usb_ctx *ctx) +{ + /* Increase number of free ctxs before freeing ctx */ + atomic_inc(&ctx->priv->free_ctx_cnt); + + ctx->ndx = PANDA_CTX_FREE; + + /* Wake up the queue once ctx is marked free */ + netif_wake_queue(ctx->priv->netdev); +} + + + +static void panda_urb_unlink(struct panda_inf_priv *priv) +{ + usb_kill_anchored_urbs(&priv->priv_dev->rx_submitted); + usb_kill_anchored_urbs(&priv->tx_submitted); +} + +static int panda_set_output_enable(struct panda_inf_priv* priv, bool enable){ + return usb_control_msg(priv->priv_dev->udev, + usb_sndctrlpipe(priv->priv_dev->udev, 0), + 0xDC, USB_TYPE_VENDOR | USB_RECIP_DEVICE, + enable ? 0x1337 : 0, 0, NULL, 0, USB_CTRL_SET_TIMEOUT); +} + +static void panda_usb_write_bulk_callback(struct urb *urb) +{ + struct panda_usb_ctx *ctx = urb->context; + struct net_device *netdev; + + WARN_ON(!ctx); + + netdev = ctx->priv->netdev; + + /* free up our allocated buffer */ + usb_free_coherent(urb->dev, urb->transfer_buffer_length, + urb->transfer_buffer, urb->transfer_dma); + + if (!netif_device_present(netdev)) + return; + + netdev->stats.tx_packets++; + netdev->stats.tx_bytes += ctx->dlc; + + can_get_echo_skb(netdev, ctx->ndx); + + if (urb->status) + netdev_info(netdev, "Tx URB aborted (%d)\n", urb->status); + + /* Release the context */ + panda_usb_free_ctx(ctx); +} + + +static netdev_tx_t panda_usb_xmit(struct panda_inf_priv *priv, + struct panda_usb_can_msg *usb_msg, + struct panda_usb_ctx *ctx) +{ + struct urb *urb; + u8 *buf; + int err; + + /* create a URB, and a buffer for it, and copy the data to the URB */ + urb = usb_alloc_urb(0, GFP_ATOMIC); + if (!urb) + return -ENOMEM; + + buf = usb_alloc_coherent(priv->priv_dev->udev, + PANDA_USB_TX_BUFF_SIZE, GFP_ATOMIC, + &urb->transfer_dma); + if (!buf) { + err = -ENOMEM; + goto nomembuf; + } + + memcpy(buf, usb_msg, PANDA_USB_TX_BUFF_SIZE); + + usb_fill_bulk_urb(urb, priv->priv_dev->udev, + usb_sndbulkpipe(priv->priv_dev->udev, 3), buf, + PANDA_USB_TX_BUFF_SIZE, panda_usb_write_bulk_callback, + ctx); + + urb->transfer_flags |= URB_NO_TRANSFER_DMA_MAP; + usb_anchor_urb(urb, &priv->tx_submitted); + + err = usb_submit_urb(urb, GFP_ATOMIC); + if (unlikely(err)) + goto failed; + + /* Release our reference to this URB, the USB core will eventually free it entirely. */ + usb_free_urb(urb); + + return 0; + + failed: + usb_unanchor_urb(urb); + usb_free_coherent(priv->priv_dev->udev, PANDA_USB_TX_BUFF_SIZE, buf, urb->transfer_dma); + + if (err == -ENODEV) + netif_device_detach(priv->netdev); + else + netdev_warn(priv->netdev, "failed tx_urb %d\n", err); + + nomembuf: + usb_free_urb(urb); + + return err; +} + +static void panda_usb_process_can_rx(struct panda_dev_priv *priv_dev, + struct panda_usb_can_msg *msg) +{ + struct can_frame *cf; + struct sk_buff *skb; + int bus_num; + struct panda_inf_priv *priv_inf; + struct net_device_stats *stats; + + bus_num = (msg->bus_dat_len >> 4) & 0xf; + priv_inf = panda_get_inf_from_bus_id(priv_dev, bus_num); + if(!priv_inf){ + printk("Got something on an unused interface %d\n", bus_num); + return; + } + printk("Recv bus %d\n", bus_num); + + stats = &priv_inf->netdev->stats; + //u16 sid; + + if (!netif_device_present(priv_inf->netdev)) + return; + + skb = alloc_can_skb(priv_inf->netdev, &cf); + if (!skb) + return; + + if(msg->rir & PANDA_CAN_EXTENDED){ + cf->can_id = (msg->rir >> 3) | CAN_EFF_FLAG; + }else{ + cf->can_id = (msg->rir >> 21); + } + + // TODO: Handle Remote Frames + //if (msg->dlc & MCBA_DLC_RTR_MASK) + // cf->can_id |= CAN_RTR_FLAG; + + cf->can_dlc = get_can_dlc(msg->bus_dat_len & PANDA_DLC_MASK); + + memcpy(cf->data, msg->data, cf->can_dlc); + + stats->rx_packets++; + stats->rx_bytes += cf->can_dlc; + + netif_rx(skb); +} + +static void panda_usb_read_int_callback(struct urb *urb) +{ + struct panda_dev_priv *priv_dev = urb->context; + int retval; + int pos = 0; + int inf_num; + + switch (urb->status) { + case 0: /* success */ + break; + case -ENOENT: + case -ESHUTDOWN: + return; + default: + dev_info(priv_dev->dev, "Rx URB aborted (%d)\n", urb->status); + goto resubmit_urb; + } + + while (pos < urb->actual_length) { + struct panda_usb_can_msg *msg; + + if (pos + sizeof(struct panda_usb_can_msg) > urb->actual_length) { + dev_err(priv_dev->dev, "format error\n"); + break; + } + + msg = (struct panda_usb_can_msg *)(urb->transfer_buffer + pos); + + panda_usb_process_can_rx(priv_dev, msg); + + pos += sizeof(struct panda_usb_can_msg); + } + + resubmit_urb: + usb_fill_int_urb(urb, priv_dev->udev, + usb_rcvintpipe(priv_dev->udev, 1), + urb->transfer_buffer, PANDA_USB_RX_BUFF_SIZE, + panda_usb_read_int_callback, priv_dev, 5); + + retval = usb_submit_urb(urb, GFP_ATOMIC); + + if (retval == -ENODEV){ + for(inf_num = 0; inf_num < PANDA_NUM_CAN_INTERFACES; inf_num++) + if(priv_dev->interfaces[inf_num]) + netif_device_detach(priv_dev->interfaces[inf_num]->netdev); + }else if (retval) + dev_err(priv_dev->dev, "failed resubmitting read bulk urb: %d\n", retval); +} + + +static int panda_usb_start(struct panda_dev_priv *priv_dev) +{ + int err; + struct urb *urb = NULL; + u8 *buf; + int inf_num; + + for(inf_num = 0; inf_num < PANDA_NUM_CAN_INTERFACES; inf_num++) + panda_init_ctx(priv_dev->interfaces[inf_num]); + + err = usb_set_interface(priv_dev->udev, 0, 1); + if (err) { + dev_err(priv_dev->dev, "Can not set alternate setting to 1, error: %i", err); + return err; + } + + /* create a URB, and a buffer for it */ + urb = usb_alloc_urb(0, GFP_KERNEL); + if (!urb) { + return -ENOMEM; + } + + buf = usb_alloc_coherent(priv_dev->udev, PANDA_USB_RX_BUFF_SIZE, + GFP_KERNEL, &urb->transfer_dma); + if (!buf) { + dev_err(priv_dev->dev, "No memory left for USB buffer\n"); + usb_free_urb(urb); + return -ENOMEM; + } + + usb_fill_int_urb(urb, priv_dev->udev, + usb_rcvintpipe(priv_dev->udev, 1), + buf, PANDA_USB_RX_BUFF_SIZE, + panda_usb_read_int_callback, priv_dev, 5); + urb->transfer_flags |= URB_NO_TRANSFER_DMA_MAP; + + usb_anchor_urb(urb, &priv_dev->rx_submitted); + + err = usb_submit_urb(urb, GFP_KERNEL); + if (err) { + usb_unanchor_urb(urb); + usb_free_coherent(priv_dev->udev, PANDA_USB_RX_BUFF_SIZE, + buf, urb->transfer_dma); + usb_free_urb(urb); + dev_err(priv_dev->dev, "Failed in start, while submitting urb.\n"); + return err; + } + + /* Drop reference, USB core will take care of freeing it */ + usb_free_urb(urb); + + + return 0; +} + +/* Open USB device */ +static int panda_usb_open(struct net_device *netdev) +{ + struct panda_inf_priv *priv = netdev_priv(netdev); + int err; + + /* common open */ + err = open_candev(netdev); + if (err) + return err; + + //priv->can_speed_check = true; + priv->can.state = CAN_STATE_ERROR_ACTIVE; + + netif_start_queue(netdev); + + return 0; +} + +/* Close USB device */ +static int panda_usb_close(struct net_device *netdev) +{ + struct panda_inf_priv *priv = netdev_priv(netdev); + + priv->can.state = CAN_STATE_STOPPED; + + netif_stop_queue(netdev); + + /* Stop polling */ + panda_urb_unlink(priv); + + close_candev(netdev); + + return 0; +} + +static netdev_tx_t panda_usb_start_xmit(struct sk_buff *skb, + struct net_device *netdev) +{ + struct panda_inf_priv *priv_inf = netdev_priv(netdev); + struct can_frame *cf = (struct can_frame *)skb->data; + struct panda_usb_ctx *ctx = NULL; + struct net_device_stats *stats = &priv_inf->netdev->stats; + int err; + struct panda_usb_can_msg usb_msg = {}; + int bus = priv_inf->mcu_can_ifnum; + + if (can_dropped_invalid_skb(netdev, skb)){ + printk("Invalid CAN packet"); + return NETDEV_TX_OK; + } + + ctx = panda_usb_get_free_ctx(priv_inf, cf); + + //Warning: cargo cult. Can't tell what this is for, but it is + //everywhere and encouraged in the documentation. + can_put_echo_skb(skb, priv_inf->netdev, ctx->ndx); + + if(cf->can_id & CAN_EFF_FLAG){ + usb_msg.rir = cpu_to_le32(((cf->can_id & 0x1FFFFFFF) << 3) | + PANDA_CAN_TRANSMIT | PANDA_CAN_EXTENDED); + }else{ + usb_msg.rir = cpu_to_le32(((cf->can_id & 0x7FF) << 21) | PANDA_CAN_TRANSMIT); + } + usb_msg.bus_dat_len = cpu_to_le32((cf->can_dlc & 0x0F) | (bus << 4)); + + memcpy(usb_msg.data, cf->data, cf->can_dlc); + + //TODO Handle Remote Frames + //if (cf->can_id & CAN_RTR_FLAG) + // usb_msg.dlc |= PANDA_DLC_RTR_MASK; + + netdev_err(netdev, "Received data from socket. canid: %x; len: %d\n", cf->can_id, cf->can_dlc); + + err = panda_usb_xmit(priv_inf, &usb_msg, ctx); + if (err) + goto xmit_failed; + + return NETDEV_TX_OK; + + xmit_failed: + can_free_echo_skb(priv_inf->netdev, ctx->ndx); + panda_usb_free_ctx(ctx); + dev_kfree_skb(skb); + stats->tx_dropped++; + + return NETDEV_TX_OK; +} + +static const struct net_device_ops panda_netdev_ops = { + .ndo_open = panda_usb_open, + .ndo_stop = panda_usb_close, + .ndo_start_xmit = panda_usb_start_xmit, +}; + +static int panda_usb_probe(struct usb_interface *intf, + const struct usb_device_id *id) +{ + struct net_device *netdev; + struct panda_inf_priv *priv_inf; + int err = -ENOMEM; + int inf_num; + struct panda_dev_priv *priv_dev; + struct usb_device *usbdev = interface_to_usbdev(intf); + + priv_dev = kzalloc(sizeof(struct panda_dev_priv), GFP_KERNEL); + if (!priv_dev) { + dev_err(&intf->dev, "Couldn't alloc priv_dev\n"); + return -ENOMEM; + } + priv_dev->udev = usbdev; + priv_dev->dev = &intf->dev; + usb_set_intfdata(intf, priv_dev); + + ////// Interface privs + for(inf_num = 0; inf_num < PANDA_NUM_CAN_INTERFACES; inf_num++){ + netdev = alloc_candev(sizeof(struct panda_inf_priv), PANDA_MAX_TX_URBS); + if (!netdev) { + dev_err(&intf->dev, "Couldn't alloc candev\n"); + goto cleanup_candev; + } + netdev->netdev_ops = &panda_netdev_ops; + netdev->flags |= IFF_ECHO; /* we support local echo */ + + priv_inf = netdev_priv(netdev); + priv_inf->netdev = netdev; + priv_inf->priv_dev = priv_dev; + priv_inf->interface_num = inf_num; + priv_inf->mcu_can_ifnum = can_numbering[inf_num]; + + init_usb_anchor(&priv_dev->rx_submitted); + init_usb_anchor(&priv_inf->tx_submitted); + + /* Init CAN device */ + priv_inf->can.state = CAN_STATE_STOPPED; + priv_inf->can.bittiming.bitrate = PANDA_BITRATE; + + SET_NETDEV_DEV(netdev, &intf->dev); + + err = register_candev(netdev); + if (err) { + netdev_err(netdev, "couldn't register PANDA CAN device: %d\n", err); + free_candev(priv_inf->netdev); + goto cleanup_candev; + } + + priv_dev->interfaces[inf_num] = priv_inf; + } + + err = panda_usb_start(priv_dev); + if (err) { + dev_err(&intf->dev, "Failed to initialize Comma.ai Panda CAN controller\n"); + goto cleanup_candev; + } + + err = panda_set_output_enable(priv_inf, true); + if (err) { + dev_info(&intf->dev, "Failed to initialize send enable message to Panda.\n"); + goto cleanup_candev; + } + + dev_info(&intf->dev, "Comma.ai Panda CAN controller connected\n"); + + return 0; + + cleanup_candev: + for(inf_num = 0; inf_num < PANDA_NUM_CAN_INTERFACES; inf_num++){ + priv_inf = priv_dev->interfaces[inf_num]; + if(priv_inf){ + unregister_candev(priv_inf->netdev); + free_candev(priv_inf->netdev); + }else + break; + } + + kfree(priv_dev); + + return err; +} + +/* Called by the usb core when driver is unloaded or device is removed */ +static void panda_usb_disconnect(struct usb_interface *intf) +{ + struct panda_dev_priv *priv_dev = usb_get_intfdata(intf); + struct panda_inf_priv *priv_inf; + int inf_num; + + usb_set_intfdata(intf, NULL); + + for(inf_num = 0; inf_num < PANDA_NUM_CAN_INTERFACES; inf_num++){ + priv_inf = priv_dev->interfaces[inf_num]; + if(priv_inf){ + netdev_info(priv_inf->netdev, "device disconnected\n"); + unregister_candev(priv_inf->netdev); + free_candev(priv_inf->netdev); + }else + break; + } + + panda_urb_unlink(priv_inf); + kfree(priv_dev); +} + +static struct usb_driver panda_usb_driver = { + .name = PANDA_MODULE_NAME, + .probe = panda_usb_probe, + .disconnect = panda_usb_disconnect, + .id_table = panda_usb_table, +}; + +module_usb_driver(panda_usb_driver); + +MODULE_LICENSE("GPL"); +MODULE_AUTHOR("Jessy Diamond Exum "); +MODULE_DESCRIPTION("SocketCAN driver for Comma.ai's Panda Adapter."); +MODULE_VERSION("0.1"); diff --git a/panda/drivers/linux/test/Makefile b/panda/drivers/linux/test/Makefile new file mode 100644 index 00000000000000..c73945e4cd0702 --- /dev/null +++ b/panda/drivers/linux/test/Makefile @@ -0,0 +1,2 @@ +all: + gcc main.c -o cantest -pthread -lpthread diff --git a/panda/drivers/linux/test/main.c b/panda/drivers/linux/test/main.c new file mode 100644 index 00000000000000..1f44efc76e20a7 --- /dev/null +++ b/panda/drivers/linux/test/main.c @@ -0,0 +1,120 @@ +#include +#include +#include +#include +#include + +#include +#include +#include +#include + +#include +#include + +const char *ifname = "can0"; + +static unsigned char payload[] = {0xAA, 0xAA, 0xAA, 0xAA, 0x07, 0x00, 0x00, 0x00}; +int packet_len = 8; +int dir = 0; + +void *write_thread( void *dat ){ + int nbytes; + struct can_frame frame; + int s = *((int*) dat); + + while(1){ + for(int i = 0; i < 1; i ++){ + if(packet_len % 2){ + frame.can_id = 0x8AA | CAN_EFF_FLAG; + }else{ + frame.can_id = 0xAA; + } + + frame.can_dlc = packet_len; + memcpy(frame.data, payload, frame.can_dlc); + + nbytes = write(s, &frame, sizeof(struct can_frame)); + + printf("Wrote %d bytes; addr: %lx; datlen: %d\n", nbytes, frame.can_id, frame.can_dlc); + + if(dir){ + packet_len++; + if(packet_len >= 8) + dir = 0; + }else{ + packet_len--; + if(packet_len <= 0) + dir = 1; + } + } + sleep(2); + } +} + + +int main(void) +{ + pthread_t sndthread; + int err, s, nbytes; + struct sockaddr_can addr; + struct can_frame frame; + struct ifreq ifr; + + if((s = socket(PF_CAN, SOCK_RAW, CAN_RAW)) < 0) { + perror("Error while opening socket"); + return -1; + } + + strcpy(ifr.ifr_name, ifname); + ioctl(s, SIOCGIFINDEX, &ifr); + + addr.can_family = AF_CAN; + addr.can_ifindex = ifr.ifr_ifindex; + + printf("%s at index %d\n", ifname, ifr.ifr_ifindex); + + if(bind(s, (struct sockaddr *)&addr, sizeof(addr)) < 0) { + perror("Error in socket bind"); + return -2; + } + + /////// Create Write Thread + + err = pthread_create( &sndthread, NULL, write_thread, (void*) &s); + if(err){ + fprintf(stderr,"Error - pthread_create() return code: %d\n", err); + exit(EXIT_FAILURE); + } + + /////// Listen to socket + while (1) { + struct can_frame framein; + + // Read in a CAN frame + int numBytes = read(s, &framein, CANFD_MTU); + switch (numBytes) { + case CAN_MTU: + if(framein.can_id & 0x80000000) + printf("Received %u byte payload; canid 0x%lx (EXT)\n", + framein.can_dlc, framein.can_id & 0x7FFFFFFF); + else + printf("Received %u byte payload; canid 0x%lx\n", framein.can_dlc, framein.can_id); + break; + case CANFD_MTU: + // TODO: Should make an example for CAN FD + break; + case -1: + // Check the signal value on interrupt + //if (EINTR == errno) + // continue; + + // Delay before continuing + sleep(1); + default: + continue; + } + } + + return 0; +} diff --git a/panda/drivers/linux/test/run.sh b/panda/drivers/linux/test/run.sh new file mode 100755 index 00000000000000..5301719b497982 --- /dev/null +++ b/panda/drivers/linux/test/run.sh @@ -0,0 +1,4 @@ +#!/usr/bin/env bash +sudo ifconfig can0 up +make +./cantest diff --git a/panda/drivers/windows/.gitignore b/panda/drivers/windows/.gitignore new file mode 100644 index 00000000000000..dbe7ad5a91a227 --- /dev/null +++ b/panda/drivers/windows/.gitignore @@ -0,0 +1,306 @@ +## Ignore Visual Studio temporary files, build results, and +## files generated by popular Visual Studio add-ons. +## +## Get latest from https://github.com/github/gitignore/blob/master/VisualStudio.gitignore + +# User-specific files +*.suo +*.user +*.userosscache +*.sln.docstates + +# User-specific files (MonoDevelop/Xamarin Studio) +*.userprefs + +# Build results +Debug_x86/ +Debug_x64/ +Release_x86/ +Release_x64/ +[Dd]ebug/ +[Dd]ebugPublic/ +[Rr]elease/ +[Rr]eleases/ +x64/ +x86/ +bld/ +[Bb]in/ +[Oo]bj/ +[Ll]og/ + +# Visual Studio 2015 cache/options directory +.vs/ +# Uncomment if you have tasks that create the project's static files in wwwroot +#wwwroot/ + +# MSTest test Results +[Tt]est[Rr]esult*/ +[Bb]uild[Ll]og.* + +# NUNIT +*.VisualState.xml +TestResult.xml + +# Build Results of an ATL Project +[Dd]ebugPS/ +[Rr]eleasePS/ +dlldata.c + +# Benchmark Results +BenchmarkDotNet.Artifacts/ + +# .NET Core +project.lock.json +project.fragment.lock.json +artifacts/ +**/Properties/launchSettings.json + +*_i.c +*_p.c +*_i.h +*.ilk +*.meta +*.obj +*.pch +*.pdb +*.pgc +*.pgd +*.rsp +*.sbr +*.tlb +*.tli +*.tlh +*.tmp +*.tmp_proj +*.log +*.vspscc +*.vssscc +.builds +*.pidb +*.svclog +*.scc + +# Chutzpah Test files +_Chutzpah* + +# Visual C++ cache files +ipch/ +*.aps +*.ncb +*.opendb +*.opensdf +*.sdf +*.cachefile +*.VC.db +*.VC.VC.opendb + +# Visual Studio profiler +*.psess +*.vsp +*.vspx +*.sap + +# TFS 2012 Local Workspace +$tf/ + +# Guidance Automation Toolkit +*.gpState + +# ReSharper is a .NET coding add-in +_ReSharper*/ +*.[Rr]e[Ss]harper +*.DotSettings.user + +# JustCode is a .NET coding add-in +.JustCode + +# TeamCity is a build add-in +_TeamCity* + +# DotCover is a Code Coverage Tool +*.dotCover + +# AxoCover is a Code Coverage Tool +.axoCover/* +!.axoCover/settings.json + +# Visual Studio code coverage results +*.coverage +*.coveragexml + +# NCrunch +_NCrunch_* +.*crunch*.local.xml +nCrunchTemp_* + +# MightyMoose +*.mm.* +AutoTest.Net/ + +# Web workbench (sass) +.sass-cache/ + +# Installshield output folder +[Ee]xpress/ + +# DocProject is a documentation generator add-in +DocProject/buildhelp/ +DocProject/Help/*.HxT +DocProject/Help/*.HxC +DocProject/Help/*.hhc +DocProject/Help/*.hhk +DocProject/Help/*.hhp +DocProject/Help/Html2 +DocProject/Help/html + +# Click-Once directory +publish/ + +# Publish Web Output +*.[Pp]ublish.xml +*.azurePubxml +# Note: Comment the next line if you want to checkin your web deploy settings, +# but database connection strings (with potential passwords) will be unencrypted +*.pubxml +*.publishproj + +# Microsoft Azure Web App publish settings. Comment the next line if you want to +# checkin your Azure Web App publish settings, but sensitive information contained +# in these scripts will be unencrypted +PublishScripts/ + +# NuGet Packages +*.nupkg +# The packages folder can be ignored because of Package Restore +**/packages/* +# except build/, which is used as an MSBuild target. +!**/packages/build/ +# Uncomment if necessary however generally it will be regenerated when needed +#!**/packages/repositories.config +# NuGet v3's project.json files produces more ignorable files +*.nuget.props +*.nuget.targets + +# Microsoft Azure Build Output +csx/ +*.build.csdef + +# Microsoft Azure Emulator +ecf/ +rcf/ + +# Windows Store app package directories and files +AppPackages/ +BundleArtifacts/ +Package.StoreAssociation.xml +_pkginfo.txt +*.appx + +# Visual Studio cache files +# files ending in .cache can be ignored +*.[Cc]ache +# but keep track of directories ending in .cache +!*.[Cc]ache/ + +# Others +ClientBin/ +~$* +*~ +*.dbmdl +*.dbproj.schemaview +*.jfm +*.pfx +*.publishsettings +orleans.codegen.cs + +# Since there are multiple workflows, uncomment next line to ignore bower_components +# (https://github.com/github/gitignore/pull/1529#issuecomment-104372622) +#bower_components/ + +# RIA/Silverlight projects +Generated_Code/ + +# Backup & report files from converting an old project file +# to a newer Visual Studio version. Backup files are not needed, +# because we have git ;-) +_UpgradeReport_Files/ +Backup*/ +UpgradeLog*.XML +UpgradeLog*.htm + +# SQL Server files +*.mdf +*.ldf +*.ndf + +# Business Intelligence projects +*.rdl.data +*.bim.layout +*.bim_*.settings + +# Microsoft Fakes +FakesAssemblies/ + +# GhostDoc plugin setting file +*.GhostDoc.xml + +# Node.js Tools for Visual Studio +.ntvs_analysis.dat +node_modules/ + +# Typescript v1 declaration files +typings/ + +# Visual Studio 6 build log +*.plg + +# Visual Studio 6 workspace options file +*.opt + +# Visual Studio 6 auto-generated workspace file (contains which files were open etc.) +*.vbw + +# Visual Studio LightSwitch build output +**/*.HTMLClient/GeneratedArtifacts +**/*.DesktopClient/GeneratedArtifacts +**/*.DesktopClient/ModelManifest.xml +**/*.Server/GeneratedArtifacts +**/*.Server/ModelManifest.xml +_Pvt_Extensions + +# Paket dependency manager +.paket/paket.exe +paket-files/ + +# FAKE - F# Make +.fake/ + +# JetBrains Rider +.idea/ +*.sln.iml + +# CodeRush +.cr/ + +# Python Tools for Visual Studio (PTVS) +__pycache__/ +*.pyc + +# Cake - Uncomment if you are using it +# tools/** +# !tools/packages.config + +# Tabs Studio +*.tss + +# Telerik's JustMock configuration file +*.jmconfig + +# BizTalk build output +*.btp.cs +*.btm.cs +*.odx.cs +*.xsd.cs + +# installer +*.exe diff --git a/panda/drivers/windows/ECUsim CLI/ECUsim CLI.cpp b/panda/drivers/windows/ECUsim CLI/ECUsim CLI.cpp new file mode 100644 index 00000000000000..6c8a469acc8566 --- /dev/null +++ b/panda/drivers/windows/ECUsim CLI/ECUsim CLI.cpp @@ -0,0 +1,38 @@ +// ECUsim CLI.cpp : Defines the entry point for the console application. +// + +#include "stdafx.h" +#include "ECUsim DLL\ECUsim.h" + +std::unique_ptr sim; + +BOOL CtrlHandler(DWORD fdwCtrlType) +{ + if (fdwCtrlType != CTRL_C_EVENT) return FALSE; + + sim->stop(); + sim->join(); + + return(TRUE); +} + +int main(int argc, // Number of strings in array argv + char *argv[], // Array of command-line argument strings + char *envp[]) // Array of environment variable strings +{ + + int count; + + // Display each command-line argument. + std::cout << "\nCommand-line arguments:\n"; + for (count = 0; count < argc; count++) + std::cout << " argv[" << count << "] " << argv[count] << "\n"; + + SetConsoleCtrlHandler((PHANDLER_ROUTINE)CtrlHandler, TRUE); + + sim.reset(new ECUsim("", 500000)); + sim->join(); + + return 0; +} + diff --git a/panda/drivers/windows/ECUsim CLI/ECUsim CLI.vcxproj b/panda/drivers/windows/ECUsim CLI/ECUsim CLI.vcxproj new file mode 100644 index 00000000000000..4b9de8c442828a --- /dev/null +++ b/panda/drivers/windows/ECUsim CLI/ECUsim CLI.vcxproj @@ -0,0 +1,178 @@ + + + + + Debug + Win32 + + + Release + Win32 + + + Debug + x64 + + + Release + x64 + + + + {D99E2FCD-21A4-4065-949A-31E34E0E69D1} + Win32Proj + ECUsimCLI + 10.0.16299.0 + + + + Application + true + v141 + Unicode + + + Application + false + v141 + true + Unicode + + + Application + true + v141 + Unicode + + + Application + false + v141 + true + Unicode + + + + + + + + + + + + + + + + + + + + + true + $(SolutionDir)$(Configuration)_$(PlatformShortName)\ + + + true + $(SolutionDir)$(Configuration)_$(PlatformShortName)\ + + + false + $(SolutionDir)$(Configuration)_$(PlatformShortName)\ + + + false + $(SolutionDir)$(Configuration)_$(PlatformShortName)\ + + + + Use + Level3 + Disabled + WIN32;_DEBUG;_CONSOLE;%(PreprocessorDefinitions) + true + %(AdditionalIncludeDirectories);$(SolutionDir) + + + Console + true + kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);$(OutDir)ecusim.lib + + + + + Use + Level3 + Disabled + _DEBUG;_CONSOLE;%(PreprocessorDefinitions) + true + %(AdditionalIncludeDirectories);$(SolutionDir) + + + Console + true + kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);$(OutDir)ecusim.lib + + + + + Level3 + Use + MaxSpeed + true + true + WIN32;NDEBUG;_CONSOLE;%(PreprocessorDefinitions) + true + %(AdditionalIncludeDirectories);$(SolutionDir) + + + Console + true + true + true + kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);$(OutDir)ecusim.lib + + + + + Level3 + Use + MaxSpeed + true + true + NDEBUG;_CONSOLE;%(PreprocessorDefinitions) + true + %(AdditionalIncludeDirectories);$(SolutionDir) + + + Console + true + true + true + kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);$(OutDir)ecusim.lib + + + + + + + + + + + Create + Create + Create + Create + + + + + {96e0e646-ee76-444d-9a77-a0cd7f781deb} + + + + + + \ No newline at end of file diff --git a/panda/drivers/windows/ECUsim CLI/ECUsim CLI.vcxproj.filters b/panda/drivers/windows/ECUsim CLI/ECUsim CLI.vcxproj.filters new file mode 100644 index 00000000000000..ea223e30b23b71 --- /dev/null +++ b/panda/drivers/windows/ECUsim CLI/ECUsim CLI.vcxproj.filters @@ -0,0 +1,36 @@ + + + + + {4FC737F1-C7A5-4376-A066-2A32D752A2FF} + cpp;c;cc;cxx;def;odl;idl;hpj;bat;asm;asmx + + + {93995380-89BD-4b04-88EB-625FBE52EBFB} + h;hh;hpp;hxx;hm;inl;inc;xsd + + + {67DA6AB6-F800-4c08-8B7A-83BB121AAD01} + rc;ico;cur;bmp;dlg;rc2;rct;bin;rgs;gif;jpg;jpeg;jpe;resx;tiff;tif;png;wav;mfcribbon-ms + + + + + Header Files + + + Header Files + + + Header Files + + + + + Source Files + + + Source Files + + + \ No newline at end of file diff --git a/panda/drivers/windows/ECUsim CLI/stdafx.cpp b/panda/drivers/windows/ECUsim CLI/stdafx.cpp new file mode 100644 index 00000000000000..d4a23c3cf7b90a --- /dev/null +++ b/panda/drivers/windows/ECUsim CLI/stdafx.cpp @@ -0,0 +1,8 @@ +// stdafx.cpp : source file that includes just the standard includes +// ECUsim CLI.pch will be the pre-compiled header +// stdafx.obj will contain the pre-compiled type information + +#include "stdafx.h" + +// TODO: reference any additional headers you need in STDAFX.H +// and not in this file diff --git a/panda/drivers/windows/ECUsim CLI/stdafx.h b/panda/drivers/windows/ECUsim CLI/stdafx.h new file mode 100644 index 00000000000000..b005a839def248 --- /dev/null +++ b/panda/drivers/windows/ECUsim CLI/stdafx.h @@ -0,0 +1,15 @@ +// stdafx.h : include file for standard system include files, +// or project specific include files that are used frequently, but +// are changed infrequently +// + +#pragma once + +#include "targetver.h" + +#include +#include + + + +// TODO: reference additional headers your program requires here diff --git a/panda/drivers/windows/ECUsim CLI/targetver.h b/panda/drivers/windows/ECUsim CLI/targetver.h new file mode 100644 index 00000000000000..87c0086de751ba --- /dev/null +++ b/panda/drivers/windows/ECUsim CLI/targetver.h @@ -0,0 +1,8 @@ +#pragma once + +// Including SDKDDKVer.h defines the highest available Windows platform. + +// If you wish to build your application for a previous Windows platform, include WinSDKVer.h and +// set the _WIN32_WINNT macro to the platform you wish to support before including SDKDDKVer.h. + +#include diff --git a/panda/drivers/windows/ECUsim DLL/ECUsim DLL.vcxproj b/panda/drivers/windows/ECUsim DLL/ECUsim DLL.vcxproj new file mode 100644 index 00000000000000..93d75c14be1c7a --- /dev/null +++ b/panda/drivers/windows/ECUsim DLL/ECUsim DLL.vcxproj @@ -0,0 +1,197 @@ + + + + + Debug + Win32 + + + Release + Win32 + + + Debug + x64 + + + Release + x64 + + + + {96E0E646-EE76-444D-9A77-A0CD7F781DEB} + Win32Proj + ECUsimDLL + 10.0.16299.0 + + + + DynamicLibrary + true + v141 + Unicode + + + DynamicLibrary + false + v141 + true + Unicode + + + DynamicLibrary + true + v141 + Unicode + + + DynamicLibrary + false + v141 + true + Unicode + + + + + + + + + + + + + + + + + + + + + true + ecusim + $(SolutionDir)$(Configuration)_$(PlatformShortName)\ + + + true + ecusim + $(SolutionDir)$(Configuration)_$(PlatformShortName)\ + + + false + ecusim + $(SolutionDir)$(Configuration)_$(PlatformShortName)\ + + + false + ecusim + $(SolutionDir)$(Configuration)_$(PlatformShortName)\ + + + + Use + Level3 + Disabled + WIN32;_DEBUG;_WINDOWS;_USRDLL;ECUSIMDLL_EXPORTS;%(PreprocessorDefinitions) + true + %(AdditionalIncludeDirectories);$(SolutionDir) + + + Windows + true + kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);$(OutDir)panda.lib + + + + + Use + Level3 + Disabled + _DEBUG;_WINDOWS;_USRDLL;ECUSIMDLL_EXPORTS;%(PreprocessorDefinitions) + true + %(AdditionalIncludeDirectories);$(SolutionDir) + + + Windows + true + kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);$(OutDir)panda.lib + + + + + Level3 + Use + MaxSpeed + true + true + WIN32;NDEBUG;_WINDOWS;_USRDLL;ECUSIMDLL_EXPORTS;%(PreprocessorDefinitions) + true + %(AdditionalIncludeDirectories);$(SolutionDir) + + + Windows + true + true + true + kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);$(OutDir)panda.lib + + + + + Level3 + Use + MaxSpeed + true + true + NDEBUG;_WINDOWS;_USRDLL;ECUSIMDLL_EXPORTS;%(PreprocessorDefinitions) + true + %(AdditionalIncludeDirectories);$(SolutionDir) + + + Windows + true + true + true + kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);$(OutDir)panda.lib + + + + + + + + + + + false + + + false + + + false + + + false + + + + + + Create + Create + Create + Create + + + + + {5528aefb-638d-49af-b9d4-965154e7d531} + + + + + + \ No newline at end of file diff --git a/panda/drivers/windows/ECUsim DLL/ECUsim DLL.vcxproj.filters b/panda/drivers/windows/ECUsim DLL/ECUsim DLL.vcxproj.filters new file mode 100644 index 00000000000000..299d654451e182 --- /dev/null +++ b/panda/drivers/windows/ECUsim DLL/ECUsim DLL.vcxproj.filters @@ -0,0 +1,42 @@ + + + + + {4FC737F1-C7A5-4376-A066-2A32D752A2FF} + cpp;c;cc;cxx;def;odl;idl;hpj;bat;asm;asmx + + + {93995380-89BD-4b04-88EB-625FBE52EBFB} + h;hh;hpp;hxx;hm;inl;inc;xsd + + + {67DA6AB6-F800-4c08-8B7A-83BB121AAD01} + rc;ico;cur;bmp;dlg;rc2;rct;bin;rgs;gif;jpg;jpeg;jpe;resx;tiff;tif;png;wav;mfcribbon-ms + + + + + Header Files + + + Header Files + + + Header Files + + + Header Files + + + + + Source Files + + + Source Files + + + Source Files + + + \ No newline at end of file diff --git a/panda/drivers/windows/ECUsim DLL/ECUsim.cpp b/panda/drivers/windows/ECUsim DLL/ECUsim.cpp new file mode 100644 index 00000000000000..19f2bf360ead9d --- /dev/null +++ b/panda/drivers/windows/ECUsim DLL/ECUsim.cpp @@ -0,0 +1,261 @@ +#include "stdafx.h" +#include "ECUsim.h" + +ECUsim::ECUsim(std::string sn, unsigned long can_baud, bool ext_addr) : + doloop(TRUE), verbose(TRUE), can11b_enabled(TRUE), can29b_enabled(TRUE), ext_addr(ext_addr){ + this->panda = panda::Panda::openPanda(sn); + this->panda->set_can_speed_cbps(panda::PANDA_CAN1, can_baud / 100); //Don't pass in baud where baud%100 != 0 + this->panda->set_safety_mode(panda::SAFETY_ALLOUTPUT); + this->panda->set_can_loopback(FALSE); + this->panda->can_clear(panda::PANDA_CAN_RX); + + DWORD threadid; + this->thread_can = CreateThread(NULL, 0, _canthreadBootstrap, (LPVOID)this, 0, &threadid); +} + +ECUsim::~ECUsim() { + this->stop(); + this->join(); +} + +void ECUsim::stop() { + this->doloop = FALSE; +} + +void ECUsim::join() { + WaitForSingleObject(this->thread_can, INFINITE); +} + +DWORD WINAPI ECUsim::_canthreadBootstrap(LPVOID This) { + return ((ECUsim*)This)->can_recv_thread_function(); +} + +DWORD ECUsim::can_recv_thread_function() { + while (this->doloop) { + auto msgs = this->panda->can_recv(); + for (auto& msg : msgs) { + if (msg.is_receipt) continue; + if (msg.bus == 0 && !msg.is_receipt /*&& msg.len == 8*/ && msg.dat[0] >= 2) { + if (this->verbose) { + printf("Processing message (bus: %d; addr: %X; 29b: %d):\n ", msg.bus, msg.addr, msg.addr_29b); + for (int i = 0; i < msg.len; i++) printf("%02X ", msg.dat[i]); + printf("\n"); + } + this->_CAN_process_msg(msg); + } else { + if (this->verbose) { + printf("Rejecting message (bus: %d; addr: %X; 29b: %d):\n ", msg.bus, msg.addr, msg.addr_29b); + for (int i = 0; i < msg.len; i++) printf("%02X ", msg.dat[i]); + printf("\n"); + } + } + } + } + + return 0; +} + +BOOL ECUsim::_can_addr_matches(panda::PANDA_CAN_MSG& msg) { + if (this->can11b_enabled && !msg.addr_29b && (msg.addr == 0x7DF || (msg.addr & 0x7F8) == 0x7E0)) { + if (!this->ext_addr) { + return TRUE; + } else { + return msg.len >= 1 && msg.dat[0] == 0x13;//13 is an arbitrary address picked to test ext addresses + } + } + if (this->can29b_enabled && msg.addr_29b && ((msg.addr & 0x1FFF00FF) == 0x18DB00F1 || (msg.addr & 0x1FFF00FF) == 0x18da00f1)) { + if (!this->ext_addr) { + return TRUE; + } else { + return msg.len >= 1 && msg.dat[0] == 0x13;//13 is an arbitrary address picked to test ext addresses + } + } + return FALSE; +} + +void ECUsim::_CAN_process_msg(panda::PANDA_CAN_MSG& msg) { + std::string outmsg; + uint32_t outaddr; + uint8_t formatted_msg_buff[8]; + bool doreply = FALSE; + + if (this->_can_addr_matches(msg)) {// && msg.len == 8) { + uint8_t *dat = (this->ext_addr) ? &msg.dat[1] : &msg.dat[0]; + if ((dat[0] & 0xF0) == 0x10) { + printf("Got a multiframe write request\n"); + outaddr = (msg.addr_29b) ? 0x18DAF1EF : 0x7E8; + this->panda->can_send(outaddr, msg.addr_29b, (const uint8_t*)"\x30\x00\x00", 3, panda::PANDA_CAN1); + return; + } + + /////////// Check if Flow Control Msg + if ((dat[0] & 0xF0) == 0x30 && msg.len >= 3 && this->can_multipart_data.size() > 0) { + if (this->verbose) printf("More data requested\n"); + uint8_t block_size = dat[1], sep_time_min = dat[2]; + outaddr = (msg.addr == 0x7DF || msg.addr == 0x7E0) ? 0x7E8 : 0x18DAF1EF; //ext addr 5th byte is just always 0x13 for simplicity + + unsigned int msgnum = 1; + while (this->can_multipart_data.size()) { + unsigned int datalen = this->ext_addr ? + min(6, this->can_multipart_data.size()): //EXT ADDR VALUE + min(7, this->can_multipart_data.size()); //NORMAL ADDR VALUE + + unsigned int idx = 0; + if (this->ext_addr) + formatted_msg_buff[idx++] = 0x13; //EXT ADDR + formatted_msg_buff[idx++] = 0x20 | msgnum; + for (int i = 0; i < datalen; i++) { + formatted_msg_buff[i + idx] = this->can_multipart_data.front(); + this->can_multipart_data.pop(); + } + for (int i = datalen + idx; i < sizeof(formatted_msg_buff); i++) + formatted_msg_buff[i] = 0; + + if (this->verbose) { + printf("Multipart reply to %X.\n ", outaddr); + for (int i = 0; i < datalen + idx; i++) printf("%02X ", formatted_msg_buff[i]); + printf("\n"); + } + + this->panda->can_send(outaddr, msg.addr_29b, formatted_msg_buff, datalen + idx, panda::PANDA_CAN1); + msgnum = (msgnum + 1) % 0x10; + Sleep(10); + } + return; + } + + /////////// Normal message in + outmsg = this->process_obd_msg(dat[1], dat[2], doreply); + if (doreply) { + outaddr = (msg.addr_29b) ? 0x18DAF1EF : 0x7E8; + + if (outmsg.size() <= (this->ext_addr ? 4 : 5)) { + unsigned int idx = 0; + if(this->ext_addr) + formatted_msg_buff[idx++] = 0x13; //EXT ADDR + formatted_msg_buff[idx++] = outmsg.size() + 2; + formatted_msg_buff[idx++] = 0x40 | dat[1]; + formatted_msg_buff[idx++] = dat[2]; //PID + memcpy_s(&formatted_msg_buff[idx], sizeof(formatted_msg_buff) - idx, outmsg.c_str(), outmsg.size()); + for (int i = idx + outmsg.size(); i < 8; i++) + formatted_msg_buff[i] = 0; + + if (this->verbose) { + printf("Replying to %X.\n ", outaddr); + for (int i = 0; i < 8; i++) printf("%02X ", formatted_msg_buff[i]); + printf("\n"); + } + + this->panda->can_send(outaddr, msg.addr_29b, formatted_msg_buff, 8, panda::PANDA_CAN1); //outmsg.size() + 3 + } else { + uint8_t first_msg_len = this->ext_addr ? + min(2, outmsg.size() % 7) : //EXT ADDR VALUES + min(3, outmsg.size() % 7); //NORMAL ADDR VALUES + uint8_t payload_len = outmsg.size() + 3; + + unsigned int idx = 0; + if (this->ext_addr) + formatted_msg_buff[idx++] = 0x13; //EXT ADDR + formatted_msg_buff[idx++] = 0x10 | ((payload_len >> 8) & 0xF); + formatted_msg_buff[idx++] = payload_len & 0xFF; + formatted_msg_buff[idx++] = 0x40 | dat[1]; + formatted_msg_buff[idx++] = dat[2]; //PID + formatted_msg_buff[idx++] = 1; + memcpy_s(&formatted_msg_buff[idx], sizeof(formatted_msg_buff) - idx, outmsg.c_str(), first_msg_len); + + if (this->verbose) { + printf("Replying FIRST FRAME to %X.\n ", outaddr); + for (int i = 0; i < 8; i++) printf("%02X ", formatted_msg_buff[i]); + printf("\n"); + } + + this->panda->can_send(outaddr, msg.addr_29b, formatted_msg_buff, 8, panda::PANDA_CAN1); + for (int i = first_msg_len; i < outmsg.size(); i++) + this->can_multipart_data.push(outmsg[i]); + } + } + } +} + +std::string ECUsim::process_obd_msg(UCHAR mode, UCHAR pid, bool& return_data) { + std::string tmp; + return_data = TRUE; + + switch (mode) { + case 0x01: // Mode : Show current data + switch (pid) { + case 0x00: //List supported things + return "\xff\xff\xff\xfe"; //b"\xBE\x1F\xB8\x10" #Bitfield, random features + case 0x01: // Monitor Status since DTC cleared + return std::string("\x00\x00\x00\x00", 4); //Bitfield, random features + case 0x04: // Calculated engine load + return "\x2f"; + case 0x05: // Engine coolant temperature + return "\x3c"; + case 0x0B: // Intake manifold absolute pressure + return "\x90"; + case 0x0C: // Engine RPM + return "\x1A\xF8"; + case 0x0D: // Vehicle Speed + return "\x53"; + case 0x10: // MAF air flow rate + return "\x01\xA0"; + case 0x11: // Throttle Position + return "\x90"; + case 0x33: // Absolute Barometric Pressure + return "\x90"; + default: + return_data = FALSE; + return ""; + } + case 0x09: // Mode : Request vehicle information + switch (pid) { + case 0x02: // Show VIN + return "1D4GP00R55B123456"; + case 0xFC: // test long multi message.Ligned up for LIN responses + for (int i = 0; i < 80; i++) { + tmp += "\xAA\xAA"; + } + return tmp;//">BBH", 0xAA, 0xAA, num + 1) + case 0xFD: // test long multi message + for (int i = 0; i < 80; i++) { + tmp += "\xAA\xAA\xAA"; + tmp.push_back(i >> 24); + tmp.push_back((i >> 16) & 0xFF); + tmp.push_back((i >> 8) & 0xFF); + tmp.push_back(i & 0xFF); + } + return "\xAA\xAA\xAA" + tmp; + case 0xFE: // test very long multi message + tmp = "\xAA\xAA\xAA"; + for (int i = 0; i < 584; i++) { + tmp += "\xAA\xAA\xAA"; + tmp.push_back(i >> 24); + tmp.push_back((i >> 16) & 0xFF); + tmp.push_back((i >> 8) & 0xFF); + tmp.push_back(i & 0xFF); + } + return tmp + "\xAA"; + case 0xFF: + for (int i = 0; i < 584; i++) { + tmp += "\xAA\xAA\xAA\xAA\xAA"; + tmp.push_back(((i + 1) >> 8) & 0xFF); + tmp.push_back((i + 1) & 0xFF); + } + return std::string("\xAA\x00\x00", 3) + tmp; + default: + return_data = FALSE; + return ""; + } + case 0x3E: + if (pid == 0) { + return_data = TRUE; + return ""; + } + return_data = FALSE; + return ""; + default: + return_data = FALSE; + return ""; + } +} diff --git a/panda/drivers/windows/ECUsim DLL/ECUsim.h b/panda/drivers/windows/ECUsim DLL/ECUsim.h new file mode 100644 index 00000000000000..2f5fe0f7ad4865 --- /dev/null +++ b/panda/drivers/windows/ECUsim DLL/ECUsim.h @@ -0,0 +1,50 @@ +#pragma once + +#include +#include "panda_shared/panda.h" +#include + +// The following ifdef block is the standard way of creating macros which make exporting +// from a DLL simpler. All files within this DLL are compiled with the ECUSIMDLL_EXPORTS +// symbol defined on the command line. This symbol should not be defined on any project +// that uses this DLL. This way any other project whose source files include this file see +// ECUSIMDLL_API functions as being imported from a DLL, whereas this DLL sees symbols +// defined with this macro as being exported. +#ifdef ECUSIMDLL_EXPORTS +#define ECUSIMDLL_API __declspec(dllexport) +#else +#define ECUSIMDLL_API __declspec(dllimport) +#endif + +// This class is exported from the ECUsim DLL.dll +class ECUSIMDLL_API ECUsim { +public: + ECUsim(std::string sn, unsigned long can_baud, bool ext_addr = FALSE); + ECUsim(panda::Panda && p, unsigned long can_baud, bool ext_addr = FALSE); + ~ECUsim(); + + void stop(); + void join(); + + // Flag determines if verbose output is enabled + volatile bool verbose; + BOOL ext_addr; +private: + std::unique_ptr panda; + + static DWORD WINAPI _canthreadBootstrap(LPVOID This); + DWORD can_recv_thread_function(); + + BOOL _can_addr_matches(panda::PANDA_CAN_MSG & msg); + + void _CAN_process_msg(panda::PANDA_CAN_MSG & msg); + + std::string process_obd_msg(UCHAR mode, UCHAR pid, bool& return_data); + + HANDLE thread_can; + volatile bool doloop; + std::queue can_multipart_data; + + BOOL can11b_enabled; + BOOL can29b_enabled; +}; diff --git a/panda/drivers/windows/ECUsim DLL/dllmain.cpp b/panda/drivers/windows/ECUsim DLL/dllmain.cpp new file mode 100644 index 00000000000000..69b58914b3572b --- /dev/null +++ b/panda/drivers/windows/ECUsim DLL/dllmain.cpp @@ -0,0 +1,19 @@ +// dllmain.cpp : Defines the entry point for the DLL application. +#include "stdafx.h" + +BOOL APIENTRY DllMain( HMODULE hModule, + DWORD ul_reason_for_call, + LPVOID lpReserved + ) +{ + switch (ul_reason_for_call) + { + case DLL_PROCESS_ATTACH: + case DLL_THREAD_ATTACH: + case DLL_THREAD_DETACH: + case DLL_PROCESS_DETACH: + break; + } + return TRUE; +} + diff --git a/panda/drivers/windows/ECUsim DLL/stdafx.cpp b/panda/drivers/windows/ECUsim DLL/stdafx.cpp new file mode 100644 index 00000000000000..b4056ecd062c0d --- /dev/null +++ b/panda/drivers/windows/ECUsim DLL/stdafx.cpp @@ -0,0 +1,8 @@ +// stdafx.cpp : source file that includes just the standard includes +// ECUsim DLL.pch will be the pre-compiled header +// stdafx.obj will contain the pre-compiled type information + +#include "stdafx.h" + +// TODO: reference any additional headers you need in STDAFX.H +// and not in this file diff --git a/panda/drivers/windows/ECUsim DLL/stdafx.h b/panda/drivers/windows/ECUsim DLL/stdafx.h new file mode 100644 index 00000000000000..f3a07375c76623 --- /dev/null +++ b/panda/drivers/windows/ECUsim DLL/stdafx.h @@ -0,0 +1,16 @@ +// stdafx.h : include file for standard system include files, +// or project specific include files that are used frequently, but +// are changed infrequently +// + +#pragma once + +#include "targetver.h" + +#define WIN32_LEAN_AND_MEAN // Exclude rarely-used stuff from Windows headers +// Windows Header Files: +#include + + + +// TODO: reference additional headers your program requires here diff --git a/panda/drivers/windows/ECUsim DLL/targetver.h b/panda/drivers/windows/ECUsim DLL/targetver.h new file mode 100644 index 00000000000000..87c0086de751ba --- /dev/null +++ b/panda/drivers/windows/ECUsim DLL/targetver.h @@ -0,0 +1,8 @@ +#pragma once + +// Including SDKDDKVer.h defines the highest available Windows platform. + +// If you wish to build your application for a previous Windows platform, include WinSDKVer.h and +// set the _WIN32_WINNT macro to the platform you wish to support before including SDKDDKVer.h. + +#include diff --git a/panda/drivers/windows/README.md b/panda/drivers/windows/README.md new file mode 100644 index 00000000000000..06c7a51101914d --- /dev/null +++ b/panda/drivers/windows/README.md @@ -0,0 +1,144 @@ +``` + ;" ^; ;' ", +______/\\\\\\\\\\\____/\\\\\\\\\_______/\\\\\\\\\\\\\\\______/\\\\\\\\\\_____________/\\\____ ; s$$$$$$$s ; + _____\/////\\\///___/\\\///////\\\____\/\\\///////////_____/\\\///////\\\__________/\\\\\____ , ss$$$$$$$$$$s ,' + _________\/\\\_____\///______\//\\\___\/\\\_______________\///______/\\\_________/\\\/\\\____ ;s$$$$$$$$$$$$$$$ + _________\/\\\_______________/\\\/____\/\\\\\\\\\\\\_____________/\\\//________/\\\/\/\\\____ $$$$$$$$$$$$$$$$$$ + _________\/\\\____________/\\\//______\////////////\\\__________\////\\\_____/\\\/__\/\\\____ $$$$P""Y$$$Y""W$$$$$ + _________\/\\\_________/\\\//____________________\//\\\____________\//\\\__/\\\\\\\\\\\\\\\\_ $$$$ p"$$$"q $$$$$ + __/\\\___\/\\\_______/\\\/____________/\\\________\/\\\___/\\\______/\\\__\///////////\\\//__ $$$$ .$$$$$. $$$$ + _\//\\\\\\\\\_______/\\\\\\\\\\\\\\\_\//\\\\\\\\\\\\\/___\///\\\\\\\\\/_____________\/\\\____ _ $$$$$$$$$$$$$$$$ + __\/////////_______\///////////////___\/////////////_______\/////////_______________\///_____| | "Y$$$"*"$$$Y" + _ __ __ _ _ __ __| | __ _"$b.$$" + | '_ \ / _` | '_ \ / _` |/ _` | + | |_) | (_| | | | | (_| | (_| | + | .__/ \__,_|_| |_|\__,_|\__,_| + | | A comma.ai product. + |_| (Code by Jessy Diamond Exum) +``` + + +# Installing J2534 driver: + +[Download](https://github.com/commaai/panda/files/1742802/panda.J2534.driver.install.zip) + +Depending on what version of windows you are on, you may need to separately install the WinUSB driver (see next section). + +# Installing WinUSB driver: + +Installation automatically happens for Windows 8 and Windows 10 because the panda +firmware contains the USB descriptors necessary to auto-install the WinUSB driver. + +Windows 7 will not auto-install the WinUSB driver. You can use Zadig to install +the WinUSB driver. This software is not tested on anything before 7. + +More details here: +[WinUSB (Winusb.sys) Installation](https://docs.microsoft.com/en-us/windows-hardware/drivers/usbcon/winusb-installation) +[WCID Devices](https://github.com/pbatard/libwdi/wiki/WCID-Devices) +[Zadig for installing libusb compatible driver](https://github.com/pbatard/libwdi/wiki/Zadig) + +# Using J2534: + +After installing the J2534 drivers for the panda, you can do... nothing. +You first need to get a J2534 client that can load the drivers and talk to +the panda for you. + +A simple tool for testing J2534 drivers is DrewTech's 'J2534-1 Bus Analysis +Tool' available in the 'Other Support Applications' section of their +[Download Page](http://www.drewtech.com/downloads/). + +# What is J2534? + +J2534 is an API that tries to provide a consistent way to send/receive +messages over the many different protocols supported by the OBD II +port. The place this is perhaps most obvious, is sending data over +different protocols (each using unique packetizing methods) using the +same data format. + +For each PassThru Device that should be used with J2534 (in this case, +the panda), a 'driver' has to be written that can be loaded by a +client application wanting to send/receive data. + +A lot of J2534 has good ideas behind it, but the standard has some odd choices: + +* Platform Locked: Requires using the Windows Registry to find installed J2534 libraries/drivers. Drivers have to be DLLs. +* Architecture Locked: So far there is only support for x86. +* No device autodetect, and poor support for selecting from multiple devices. +* Constant vague language about important behavior (small differences between vendors). +* Most common differences become standard in later revisions. + +# Why use J2534 with the panda? + +J2534 is the only interface supported by most professional grade +vehicle diagnostics systems (such as HDS). These tools are useful for +diagnosing vehicles, as well as reverse engineering some lesser known +features. + +# What parts are supported with panda? + +- [ ] **J1850VPW** *(Outdated, and not physically supported by the panda)* +- [ ] **J1850PWM** *(Outdated, and not physically supported by the panda)* +- [X] **CAN** +- [X] **ISO15765** +- [ ] **ISO9141** *(This protocol could be implemented if 5 BAUD init support is added to the panda.)* +- [ ] **ISO14230/KWP2000** *(Could be supported with FAST init, 5baud init if panda adds support for 5bps serial)* + +# Building the Project: + +This project is developed with Visual Studio 2017, the Windows SDK, +and the Windows Driver Kit (WDK). + +The WDK is only required for creating the signed WinUSB inf file. The +WDK may also provide the headers for WinUSB. + +To build all the projects required for the installer, in Visual +Studio, select **Build->Batch Build.** In the project list select: + +- **"panda"** *Release|x86* +- **"panda"** *Release|x64* +- **"panda Driver Package"** Debug|x86 (Note this inf file works with x86/amd64). +- **"pandaJ2534DLL"** *Release|x86* + +The installer is generated with [NullSoft NSIS](http://nsis.sourceforge.net/Main_Page). +Use NSIS to run panda_install.nsi after building all the required projects. + +Before generating the installer, you must go to copy vscruntimeinfo.nsh.sample to +vscruntimeinfo.nsh and follow the instructions to bundle in the Visual Studio C +Runtime required by your version of Visual Studio. Without this runtime, the panda +code will not work, so without this file, the installer will refuse to build. + +# Developing: + +- Edit and merge pandaJ2534DLL\J2534register_x64.reg to register your development J2534 DLL. +- Add your output directory (panda\drivers\windows\Debug_x86) to your system PATH to avoid insanity. + +# ToDo Items: + +- Apply a style-guide and consistent naming convention for Classes/Functions/Variables. +- Send multiple messages (each with a different address) from a given connection at the same time. +- Implement ISO14230/KWP2000 FAST (LIN communication is already supported with the raw panda USB driver). +- Find more documentation about SW_CAN_PS (Single Wire CAN, aka GMLAN). +- Find example of client using a _PS version of a protocol (PS is pin select, and may support using different CAN buses). + + +# Known Issues: + +- ISO15765 Multi-frame TX: Hardware delays make transmission overshoot + STMIN by several milliseconds. This does not violate the requirements + of STMIN, it just means it is a little slower than it could be. + +- All Tx messages from a single Connection are serialized. This can be + relaxed to allow serialization of messages based on their address + (making multiple queues, effectively one queue per address). + +# Troubleshooting: +troubleshooting: +1. Install DrewTech J2534-1 Bus Analysis Tool +http://www.drewtech.com/downloads/tools/Drew%20Technologies%20Tool%20for%20J2534-1%20API%20v1.07.msi +2. Open DrewTech tool and make sure it shows "panda" as a device listed (this means registry settings are correct) +3. When DrewTech tool attempts to load the driver it will show an error if it fails +4. To figure out why the driver fails to load install Process Monitor and filter by the appropriate process name +https://docs.microsoft.com/en-us/sysinternals/downloads/procmon + +# Other: +Panda head ASCII art by dcau \ No newline at end of file diff --git a/panda/drivers/windows/docs/Message_Size.png b/panda/drivers/windows/docs/Message_Size.png new file mode 100644 index 00000000000000..3a20a2ef39fbdf Binary files /dev/null and b/panda/drivers/windows/docs/Message_Size.png differ diff --git a/panda/drivers/windows/docs/RxBits_defs.jpg b/panda/drivers/windows/docs/RxBits_defs.jpg new file mode 100644 index 00000000000000..db01f62c95dba3 Binary files /dev/null and b/panda/drivers/windows/docs/RxBits_defs.jpg differ diff --git a/panda/drivers/windows/docs/RxBits_valid.png b/panda/drivers/windows/docs/RxBits_valid.png new file mode 100644 index 00000000000000..6f7c4c326d9e0b Binary files /dev/null and b/panda/drivers/windows/docs/RxBits_valid.png differ diff --git a/panda/drivers/windows/docs/bus_init_signla.png b/panda/drivers/windows/docs/bus_init_signla.png new file mode 100644 index 00000000000000..9aa71faa274151 Binary files /dev/null and b/panda/drivers/windows/docs/bus_init_signla.png differ diff --git a/panda/drivers/windows/docs/connection_flags.png b/panda/drivers/windows/docs/connection_flags.png new file mode 100644 index 00000000000000..dd578a2cb9d7b3 Binary files /dev/null and b/panda/drivers/windows/docs/connection_flags.png differ diff --git a/panda/drivers/windows/docs/iso15765_ioctls.png b/panda/drivers/windows/docs/iso15765_ioctls.png new file mode 100644 index 00000000000000..7de4a118e0d11c Binary files /dev/null and b/panda/drivers/windows/docs/iso15765_ioctls.png differ diff --git a/panda/drivers/windows/docs/message_send.png b/panda/drivers/windows/docs/message_send.png new file mode 100644 index 00000000000000..112aab14cb060f Binary files /dev/null and b/panda/drivers/windows/docs/message_send.png differ diff --git a/panda/drivers/windows/docs/msg_filter_passfail.png b/panda/drivers/windows/docs/msg_filter_passfail.png new file mode 100644 index 00000000000000..4a91facb4538fb Binary files /dev/null and b/panda/drivers/windows/docs/msg_filter_passfail.png differ diff --git a/panda/drivers/windows/docs/other notes.txt b/panda/drivers/windows/docs/other notes.txt new file mode 100644 index 00000000000000..a066d2646557b1 --- /dev/null +++ b/panda/drivers/windows/docs/other notes.txt @@ -0,0 +1,347 @@ +When using the ISO 15765-4 protocol, only SingleFrame messages can be transmitted without a matching +flow control filter. Also, PCI bytes are transparently added by the API. See PassThruStartMsgFilter +and Appendix A for a discussion of flow control filters. + + + +PassThruReadMsgs +This function reads messages and indications from the receive buffer. All messages and indications shall +be read in the order that they occurred on the bus. If a transmit message generated a loopback message +and TxDone indication, the TxDone indication shall always be queued first. Except for loopback messages +and indications, no messages shall be queued for reception without matching a PASS_FILTER +(for non-ISO 15765) or FLOW_CONTROL filter (for ISO 15765). On ISO 15765, PCI bytes are transparently +removed by the API. If the function is successful, a value of STATUS_NOERROR is returned. + + +PassThruWriteMsgs +Write timeout (in milliseconds). When a value of 0 is specified, the function queues as +many of the specified messages as possible and returns immediately. When a value +greater than 0 is specified, the function will block until the Timeout has expired, an error +has occurred, or the desired number of messages have been transmitted on the vehicle +network. Even if the device can buffer only one packet at a time, this function shall be +able to send an arbitrary number of packets if a Timeout value is supplied. Since the +function returns early if all the messages have been sent, there is normally no penalty for +having a large timeout (several seconds). If the number of messages requested have +been written, the function shall not return ERR_TIMEOUT, even if the timeout value is +zero. + +When an ERR_TIMEOUT is returned, only the number of messages that were sent on +the vehicle network is known. The number of messages queued is unknown. Application +writers should avoid this ambiguity by using a Timeout value large enough to work on +slow devices and networks with arbitration delays. + + + +PassThruStartPeriodicMsg +This function will immediately queue the specified message for transmission, and repeat at the specified +interval. Periodic messages are limited in length to a single frame message of 12 bytes or less, including +header or CAN ID. Periodic messages shall have priority over messages queued with +PassThruWriteMsgs, but periodic messages must not violate bus idle timing parameters (e.g. P3_MIN). +Periodic messages shall generate TxDone indications (ISO 15765) and loopback messages (on any +protocol, if enabled). On ISO 15765, periodic messages can be sent during a multi-frame transmission or +reception. If the function is successful, a value of STATUS_NOERROR is returned. The Pass-Thru +device must support a minimum of ten periodic messages. + +PassThruDisconnect shall delete all periodic messages on that channel. PassThruClose shall delete all +periodic messages on all channels for the device. All periodic messages will be stopped on a +PassThruDisconnect for the associated protocol or a PassThruClose for the device. + + + +PASSTHRUSTARTMSGFILTER +This function starts filtering of incoming messages. If the function is successful, a value of +STATUS_NOERROR is returned. A minimum of ten message filters shall be supported by the interface +for each supported protocol. PassThruDisconnect shall delete all message filters on that channel. + +PassThruClose shall delete all filters on all channels for the device. Pattern and Mask messages shall +follow the protocol formats specified in Section 8. However, only the first twelve (12) bytes, including +header or CAN ID, are used by the filter. ERR_INVALID_MSG shall be returned if the filter length +exceeds 12. Note that this function does not clear any messages that may have been received and +queued before the filter was set. Users are cautioned to consider performing a CLEAR_RX_BUFFER +after starting a message filter to be sure that unwanted frames are purged from any receive buffers. + + + + + + + + +FILTER RELATED STUFF +For all protocols except ISO 15765: +• PASS_FILTERs and BLOCK_FILTERs will be applied to all received messages. They shall not be +applied to indications or loopback messages + +• FLOW_CONTROL_FILTERs must not be used and shall cause the interface to return +ERR_INVALID_FILTER_ID + +• Both pMaskMsg and pPatternMsg must have the same DataSize and TxFlags. Otherwise, the +interface shall return ERR_INVALID_MSG + +• The default filter behavior after PassThruConnect is to block all messages, which means no messages +will be placed in the receive queue until a PASS_FILTER has been set. Messages that match a +PASS_FILTER can still be blocked by a BLOCK_FILTER + +• Figure 16 and Figure 17 show how the message filtering mechanism operates + +For ISO 15765: +• PASS_FILTERs and BLOCK_FILTERs must not be used and shall cause the interface to return +ERR_INVALID_FILTER_ID + +• Filters shall not be applied to indications or loopback messages. When loopback is on, the original +message shall be copied to the receive queue upon the last segment being transmitted on the bus. + +• Non-segmented messages do not need to match a FLOW_CONTROL_FILTER. + +• No segmented messages can be transmitted without matching an appropriate FLOW_CONTROL_FILTER. +An appropriate filter is one in which the pFlowControlMsg CAN ID matches the messages to be +transmitted. Also, the ISO 15765_ADDR_TYPE (reference TxFlags in Section 8.7.3) bits must match. +If that bit is set, the first byte after the CAN IDs (the extended address) +must match too. + +• No message (segmented or unsegmented) shall be received without matching an appropriate +FLOW_CONTROL_FILTER. An appropriate filter is one in which the pPatternMsg CAN ID matches +the incoming message ID. If the ISO 15765_ADDR_TYPE (reference TxFlags in Section 8.7.3) bit is +set in the filter, the first byte after the CAN IDs (the extended address) must match too. + +• All 3 message pointers must have the same DataSize and TxFlags. Otherwise, the interface shall +return ERR_INVALID_MSG. + +• Both the pFlowControlMsg ID and the pPatternMsg ID must be unique (not match any IDs in any other +filters). The only exception is that pPatternMsg can equal pFlowControlMsg to allow for receiving +functionally addressed messages. In this case, only non-segmented messages can be received. + +• See Appendix A for a detailed description of flow control filter usage. + + + + +8.4 Format Checks for Messages Passed to the API +The vendor DLL shall validate all PASSTHRU_MSG structures, and return an ERR_INVALID_MSG in the following cases: +• DataSize violates Min Tx or Max Tx columns in Figure 42 + +• Source address (Data[3]) is different from the Node ID (Ioctl SET_CONFIG, Parameter NODE_ADDRESS) on J1850PWM + +• The header length field is incorrect for the number of bytes in the message on ISO14230 + +• The CAN_29_BIT flag of the message does not match the CAN_29_BIT flag passed to +PassThruConnect, unless the CAN_ID_BOTH bit was set on connect + +The vendor DLL shall return ERR_MSG_PROTOCOL_ID when the ProtocolID field in the message does +not match the Protocol ID specified when opening the channel. + + + +8.5 Conventions for Returning Messages from the API +When returning a message in PassThruReadMsg: +– DataSize shall tell the application how many bytes in the Data array are valid. ExtraDataIndex will be +the (non-zero) index of the last byte of the message. If ExtraDataIndex is not equal to DataSize there +are extra data bytes after the message. If loopback is on, RxStatus must be consulted to tell if the +message came via loopback. + +– DataSize will be in the range shown in the Min Rx and Max Rx columns of Figure 42. If the device +receives a message from the vehicle bus that is too long or too short, the message shall be discarded +with no error. + +– For received messages, ExtraDataIndex shall be equal to DataSize, except when the interface is +returning SAE J1850 PWM IFR bytes. In no case shall ExtraDataIndex be larger than DataSize. + +– When receiving a message on an SAE J1850 PWM channel, the message shall have any IFR bytes +appended. In this case, ExtraDataIndex shall be the index of the first IFR byte, and DataSize shall be +the total length of the original message plus all IFR bytes. For example, if there are two IFR bytes, +DataSize will be incremented by two, and ExtraDataIndex will be DataSize - 2. When loopback is on, +the loopback message shall contain any IFR bytes. + + + +8.6 Conventions for Retuning Indications from the API +When returning an indication in PassThruReadMsg: +– ExtraDataIndex must be zero + +– DataSize shall tell the application how many bytes in the Data array are valid + +– RxStatus must be consulted to determine the indication type (See Section 8.4). + +– A TxDone indication (ISO 15765 only) is generated by the DLL after a SingleFrame message is sent, +or the last frame of a multi-segment transmission is sent. DataSize shall be 4 (or 5 when the message +was using Extended Addressing). Data shall contain the CAN ID (and possible Extended Address) of +the message just sent. If loopback is on, the TxDone indication shall precede the loopback message in +the receive queue. + +– An RxBreak indication (SAE J2610/SCI and SAE J1850VPW only) is generated by the DLL if a break +is received. + +– An RxStart indication is generated by the DLL when starting to receive a message on ISO9141 or +ISO14230, or when receiving the FirstFrame signal of a multi-segment ISO 15765 message. + + + +9.1 Naming of Files +Each vendor will provide a different name implementation of the API DLL and a number of these +implementations could simultaneously reside on the same PC. No vendor shall name its implementation +“J2534.DLL”. All implementations shall have the string “32” suffixed to end of the name of the API DLL to +indicate 32-bit. For example, if the company name is “Vendor X” the name could be VENDRX32.DLL. + +For simplicity, an API DLL shall be named in accordance with the file allocation table (FAT) file system +naming convention (which allows up to eight characters for the file name and three characters for the +extension with no spaces anywhere). Note that, given this criteria, the major name of an API DLL can be +no greater than six characters. The OEM application can determine the name of the appropriate vendor’s +DLL using the Win32 Registry mechanism described in this section. + + + + +A.1 Flow Control Overview +ISO 15765-2 was designed to send blocks of up to 4095 bytes on top of the limited 8-byte payload of raw +CAN frames. If the data is small enough, it can fit in a single frame and be transmitted like a raw CAN +message with additional headers. Otherwise, the block is broken up into segments and becomes a +segmented transmission, generating CAN frames in both directions. For flexibility, the receiver of the +segments can control the rate at which the segments are sent. + +Each transmission is actually part of a conversation between two nodes. There is no discovery +mechanism for conversation partners. Therefore, each desired conversation must be pre-defined on each +side before the conversation can start. Conversations are symmetric, meaning that either side can send a +block of data to the other. A conversation can only have one transfer (in one direction) in progress at a +time. One transfer must complete before the next transfer (in the same or in a different direction) can +start. The device must support multiple transfers at once, as long as each one is part of a different +conversation. Raw CAN frames are not allowed when using ISO15765-2. + +A key feature of a conversation is that each side has a unique CAN ID, and each side uses their unique +CAN ID for all transmissions during the conversation. No other CAN IDs are part of the conversation. +Even though the useful data is only flowing in one direction, both sides are transmitting. One side is +sending the flow control message to pace the segments of data coming from the other side. + +For example, during OBD communication, a pass-thru device and an ECU might have a conversation. +The pass-thru device will use the "Tester1" physical CAN ID ($241), and the first ECU will use the +"ECU1" physical CAN ID ($641). During a multi-segment transfer, both sides will be transmitting using +only their respective IDs. It does not matter if the data is being sent by the ECU or by the Tester, the IDs +remain the same. + +It is important to understand the difference between OBD Requests/Responses and ISO 15765-2 +transfers. The OBD Request is transmitted from the Tester to the ECU using functional addressing. +Because segmented transfer is not possible on functional addresses, the message must fit in a single +frame. The OBD Response is a message from the ECU to the Tester using physical addressing. Unlike +other protocols, the responses are not sequential. In fact, the responses can overlap, as if each ECU +were having a private conversation with the Tester. Some of the responses may fit in a single frame, +while others will require a segmented transfer from the ECU to the tester. + + +A.2 Transmitting a Segmented Message +When PassThruWrite is called, the API will search the list of flow control filters, looking for a +pFlowControlMsg that matches the CAN ID (and possible extended address) of the message being sent. +Upon matching a filter, the pass-thru device will: + +• Start the ISO 15765 transfer by sending a FirstFrame on the bus. The CAN ID of this segment was +specified in both the message and the matching pFlowControlMsg. In our example, this is $241. + +• Wait for a FlowControl frame from the conversation partner. The CAN ID to look for is specified in the +corresponding pPatternMsg. In our example, this is $641. + +• Transmit the message data in ConsecutiveFrames according to the FlowControl frame’s instructions +for BS (BlockSize) and STmin (SeparationTime minimum). Again, the pass-thru device transmits using +CAN ID specified in pFlowControlMsg. In our example, this is $241. + +• Repeat the previous two steps as required. + +• When finished, the pass-thru device will place a TxDone indication in the API receive queue. The data +will contain the CAN ID specified in pFlowControlMsg. In our example, this is $241. + +• If loopback is on, the entire message sent will appear in the API receive queue with the +TX_MSG_TYPE bit set to 1 in RxStatus. The loopback shall not precede the TxDone indication. + +Before any multi-segment transfer can take place, the conversation must be set up on both sides. It’s +assumed that the ECU is already setup. The application is responsible for setting up the pass-thru device. +This setup must be done once (and only once) per conversation. The setup involves a single call to +PassThruStartMsgFilter, with the following parameters: + +A.2.2 Data Transmission +Once the conversation is set up, any number of messages (to the conversation partner) can be +transmitted using PassThruWriteMsg. The interface shall handle all aspects of the transfer, including +pacing (slowing) the transmission to the requirements of the receiver. + +When there are multiple conversations setup, the pass-thru device will search all of the flow control filters +for a matching pFlowControlMsg. If there is no match, the message cannot be sent because the pass- +thru device doesn’t know which partner will be pacing the conversation. + +When doing blocking writes, it is important to pick a timeout long enough to cover entire transfer, even if +the ECU is pacing things slowly. Otherwise PassThruWriteMsg will return with a timeout, even though the +transmission is proceeding normally. + + +A.3 Transmitting an Unsegmented Message +As a special case, transfers that fit in a single frame can be transmitted without setting up a conversation. +This is useful during an OBD Request, which is a functionally addressed message that is broadcast to all +ECUs. This message must be small enough to fit into a single frame (including headers) because it is not +possible to do one segmented transfer to multiple ECUs. + +When using functional addressing for an OBD Request, it is important to remember that there can be no +direct reply. Instead, each ECU will send their OBD Response using physical addressing to their +conversation partner (e.g. ECU1 to Tester1, ECU2 to Tester2) as defined by ISO 15765-4. The OBD +Response may be a segmented transfer, or it may be a single frame. + +In this case, no conversation setup is necessary. The call to PassThruWriteMsg is the same as above, +except that the DataSize must be 7 bytes or less (6 bytes or less if extended addressing is turned on). +The pass-thru device will automatically insert a PCI byte before transmission. + + +A.4 Receiving a Segmented Message +Message reception is asynchronous to the application. When a FirstFrame is seen on the bus, the pass- +thru device will search the list of flow control filters, looking for a pPatternMsg message with the same +CAN ID (and possible extended address) as the FirstFrame. Upon matching a filter, the pass-thru device will: + +• Place an RxStart indication in the API receive queue. This indication has the START_OF_MESSAGE +bit set in RxFlags. The message data will contain the CAN ID of the sender. In our example, this is +$641. DataSize will be 4 bytes (5 with extended addressing), and ExtraDataIndex will be zero. + +• Send a FlowControl frame to the conversation partner. The FlowStatus field shall be set to +ontinueToSend. The CAN ID of this segment comes from the filter’s corresponding +pFlowControlMsg. In our example, this CAN ID is $241. The BS (BlockSize) and STmin +(SeparationTime minimum) parameters default to zero, but can be changed with the SET_CONFIGIoctl. + +• Wait for the conversation partner to send C +onsecutiveFrames containing the actual data. The +partner’s CAN ID is specified in pPatternMsg. In our example, this CAN ID is $641. + +• Repeat as necessary until the entire block has been received. When finished, the pass-thru device will +put the assembled message into the API receive queue. The CAN ID of the assembled message will +be the CAN ID of the sender. In our example, this CAN ID is $641. + +If the FirstFrame does not match any flow control filters, then the message must be ignored by the +device. + +Segmented messages cause the API to generate an RxStart indication. This lets the application know +that the device has started message reception. It may take a while before message reception is +complete, especially if the application has increased BS and STmin. + +Once the transfer is complete, the entire message can be read like on any other protocol. Usually, +applications will call PassThruReadMsg again immediately after getting an RxStart indication. Application +writers should not assume that the complete message will always follow the RxStart indication. If multiple +conversations are setup, indications and messages from other conversations can be received in between +the RxStart indication and the actual message. The parameters for PassThruReadMsg are exactly the +same as in the previous section. The only difference is that the DataSize will be larger and +ExtraDataIndex will be non-zero. + + + +A.5 Receiving an Unsegmented Message +No messages can be received until a conversation is setup. Each conversation setup will receive +messages from exactly one CAN ID (and extended address if present). Because setup is bi-directional, +the same PassThruStartMsgFilter call used for transmission will allow for message reception. + +When a SingleFrame is seen on the bus, the pass-thru device will search the list of flow control filters, +looking for a pPatternMsg message with the same C +AN ID (and possible extended address) as the +SingleFrame. Upon matching a filter, the pass-thru device will strip the PCI byte and queue the packet for +reception. If the SingleFrame does not match a flow control filter, it must be discarded. + +The only difference between the previous cases is that single-frame messages do not generate an +RxStart indication. + + + + + + + + + diff --git a/panda/drivers/windows/docs/read_msg_flags.png b/panda/drivers/windows/docs/read_msg_flags.png new file mode 100644 index 00000000000000..6d0a1f87422713 Binary files /dev/null and b/panda/drivers/windows/docs/read_msg_flags.png differ diff --git a/panda/drivers/windows/docs/reginfo.txt b/panda/drivers/windows/docs/reginfo.txt new file mode 100644 index 00000000000000..03182832b21fa9 --- /dev/null +++ b/panda/drivers/windows/docs/reginfo.txt @@ -0,0 +1,2 @@ +#32 bit: HKEY_LOCAL_MACHINE\SOFTWARE\PassThruSupport +#64 bit: HKEY_LOCAL_MACHINE\SOFTWARE\WOW6432Node\PassThruSupport diff --git a/panda/drivers/windows/docs/start_msg_filter.png b/panda/drivers/windows/docs/start_msg_filter.png new file mode 100644 index 00000000000000..7cb1a7a4c8e742 Binary files /dev/null and b/panda/drivers/windows/docs/start_msg_filter.png differ diff --git a/panda/drivers/windows/docs/start_msg_filter2.png b/panda/drivers/windows/docs/start_msg_filter2.png new file mode 100644 index 00000000000000..54063a507427bc Binary files /dev/null and b/panda/drivers/windows/docs/start_msg_filter2.png differ diff --git a/panda/drivers/windows/docs/start_msg_filter3.png b/panda/drivers/windows/docs/start_msg_filter3.png new file mode 100644 index 00000000000000..ffc8e34820eec5 Binary files /dev/null and b/panda/drivers/windows/docs/start_msg_filter3.png differ diff --git a/panda/drivers/windows/docs/start_msg_filter4.png b/panda/drivers/windows/docs/start_msg_filter4.png new file mode 100644 index 00000000000000..9c21fb014d2349 Binary files /dev/null and b/panda/drivers/windows/docs/start_msg_filter4.png differ diff --git a/panda/drivers/windows/docs/timeout_info.txt b/panda/drivers/windows/docs/timeout_info.txt new file mode 100644 index 00000000000000..22cfa2c5d5c8e5 --- /dev/null +++ b/panda/drivers/windows/docs/timeout_info.txt @@ -0,0 +1,42 @@ +From focum information on NI hardware: https://forums.ni.com/t5/Automotive-and-Embedded-Networks/15765-2-with-NI-products/td-p/1454256 + +///////////////////////////////////////////////////////////////////// +Timeout Diag Command is the timeout in milliseconds the master +waits for the response to a diagnostic request message. The default is +1000 ms. + +Timeout FC (Bs) is the timeout in milliseconds the master waits +for a Flow Control frame after sending a First Frame or the last +Consecutive Frame of a block. The default is 250 ms. + +Timeout CF (Cr) is the timeout in milliseconds the master waits +for a Consecutive Frame in a multiframe response. The default is +250 ms. + +Receive Block Size (BS) is the number of Consecutive Frames the +slave sends in one block before waiting for the next Flow Control +frame. A value of 0 (default) means all Consecutive Frames are sent +in one run without interruption. + +Wait Time CF (STmin) defines the minimum time for the slave to +wait between sending two Consecutive Frames of a block. Values +from 0 to 127 are wait times in milliseconds. Values 241 to 249 +(Hex F1 to F9) mean wait times of 100 μs to 900 μs, respectively. +All other values are reserved. The default is 5 ms. + +Max Wait Frames (N_WFTmax) is the maximum number of WAIT +frames the master accepts before terminating the connection. The +default is 10. + + +There are no defined lower limits for these values; you can specify any +value down to 0. However, as you correctly pointed out, the timing is +done by Windows, and will be subject to the jitter introduced by the OS +which can easily be in the order of 10s of milliseconds. It is however +hard to give more accurate numbers as the actual jitter is dependent on +the workload of the computer +///////////////////////////////////////////////////////////////////// + +J2534 04.04 does not appear to have default adjustable parameters for +the timeout related fields. For now, these default values shall be used +in the Panda J2534 implementation. diff --git a/panda/drivers/windows/panda Driver Package/panda Driver Package.vcxproj b/panda/drivers/windows/panda Driver Package/panda Driver Package.vcxproj new file mode 100644 index 00000000000000..5b448e96a850f4 --- /dev/null +++ b/panda/drivers/windows/panda Driver Package/panda Driver Package.vcxproj @@ -0,0 +1,99 @@ + + + + + Debug + Win32 + + + Release + Win32 + + + + {BD34DB24-F5DC-4992-A74F-05FAF731ABED} + {a1357fe7-03e0-4d61-85f4-09c7ed38c0c1} + v4.5 + 12.0 + $driverCurrentWindowsConfigurationName$ Debug + Win32 + panda_Driver_Package + $(LatestTargetPlatformVersion) + + + + Windows10 + true + WindowsKernelModeDriver10.0 + Utility + Package + true + + + Windows10 + false + WindowsKernelModeDriver10.0 + Utility + Package + true + + + + + + + + + + + + DbgengRemoteDebugger + + + + False + False + True + + 133563 + $(SolutionDir)$(Configuration)_$(PlatformShortName)\ + + + + DbgengRemoteDebugger + + + + False + False + True + + 133563 + $(SolutionDir)$(Configuration)_$(PlatformShortName)\ + + + + + + + + + + + + + + $(KMDF_VERSION_MAJOR).$(KMDF_VERSION_MINOR) + + + + + + + $(KMDF_VERSION_MAJOR).$(KMDF_VERSION_MINOR) + + + + + + \ No newline at end of file diff --git a/panda/drivers/windows/panda Driver Package/panda Driver Package.vcxproj.filters b/panda/drivers/windows/panda Driver Package/panda Driver Package.vcxproj.filters new file mode 100644 index 00000000000000..b4cf07798166cf --- /dev/null +++ b/panda/drivers/windows/panda Driver Package/panda Driver Package.vcxproj.filters @@ -0,0 +1,14 @@ + + + + + {8E41214B-6785-4CFE-B992-037D68949A14} + inf;inv;inx;mof;mc; + + + + + Driver Files + + + \ No newline at end of file diff --git a/panda/drivers/windows/panda Driver Package/panda.inf b/panda/drivers/windows/panda Driver Package/panda.inf new file mode 100644 index 00000000000000..69390dcbc0616f Binary files /dev/null and b/panda/drivers/windows/panda Driver Package/panda.inf differ diff --git a/panda/drivers/windows/panda.ico b/panda/drivers/windows/panda.ico new file mode 100644 index 00000000000000..593a5cd33cb220 Binary files /dev/null and b/panda/drivers/windows/panda.ico differ diff --git a/panda/drivers/windows/panda.sln b/panda/drivers/windows/panda.sln new file mode 100644 index 00000000000000..39c8a63e28d23f --- /dev/null +++ b/panda/drivers/windows/panda.sln @@ -0,0 +1,92 @@ + +Microsoft Visual Studio Solution File, Format Version 12.00 +# Visual Studio 15 +VisualStudioVersion = 15.0.27130.2027 +MinimumVisualStudioVersion = 10.0.40219.1 +Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "pandaJ2534DLL", "pandaJ2534DLL\pandaJ2534DLL.vcxproj", "{A2BB18A5-F26B-48D6-BBB5-B83D64473C77}" +EndProject +Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "panda", "panda\panda.vcxproj", "{5528AEFB-638D-49AF-B9D4-965154E7D531}" +EndProject +Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "panda_playground", "panda_playground\panda_playground.vcxproj", "{691DB635-C272-4B98-897E-0505B970DCA9}" + ProjectSection(ProjectDependencies) = postProject + {5528AEFB-638D-49AF-B9D4-965154E7D531} = {5528AEFB-638D-49AF-B9D4-965154E7D531} + EndProjectSection +EndProject +Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "panda Driver Package", "panda Driver Package\panda Driver Package.vcxproj", "{BD34DB24-F5DC-4992-A74F-05FAF731ABED}" +EndProject +Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "Tests", "pandaJ2534DLL Test\pandaJ2534DLL Test.vcxproj", "{7912F978-B48C-4C5D-8BFD-5D1E22158E47}" +EndProject +Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "ECUsim DLL", "ECUsim DLL\ECUsim DLL.vcxproj", "{96E0E646-EE76-444D-9A77-A0CD7F781DEB}" +EndProject +Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "ECUsim CLI", "ECUsim CLI\ECUsim CLI.vcxproj", "{D99E2FCD-21A4-4065-949A-31E34E0E69D1}" +EndProject +Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "panda_shared", "panda_shared\panda_shared.vcxitems", "{0C843279-68C7-4679-AE51-9BC463D50D1C}" +EndProject +Global + GlobalSection(SharedMSBuildProjectFiles) = preSolution + panda_shared\panda_shared.vcxitems*{0c843279-68c7-4679-ae51-9bc463d50d1c}*SharedItemsImports = 9 + panda_shared\panda_shared.vcxitems*{5528aefb-638d-49af-b9d4-965154e7d531}*SharedItemsImports = 4 + panda_shared\panda_shared.vcxitems*{a2bb18a5-f26b-48d6-bbb5-b83d64473c77}*SharedItemsImports = 4 + EndGlobalSection + GlobalSection(SolutionConfigurationPlatforms) = preSolution + Debug|x64 = Debug|x64 + Debug|x86 = Debug|x86 + Release|x64 = Release|x64 + Release|x86 = Release|x86 + EndGlobalSection + GlobalSection(ProjectConfigurationPlatforms) = postSolution + {A2BB18A5-F26B-48D6-BBB5-B83D64473C77}.Debug|x64.ActiveCfg = Debug|Win32 + {A2BB18A5-F26B-48D6-BBB5-B83D64473C77}.Debug|x86.ActiveCfg = Debug|Win32 + {A2BB18A5-F26B-48D6-BBB5-B83D64473C77}.Debug|x86.Build.0 = Debug|Win32 + {A2BB18A5-F26B-48D6-BBB5-B83D64473C77}.Release|x64.ActiveCfg = Release|Win32 + {A2BB18A5-F26B-48D6-BBB5-B83D64473C77}.Release|x86.ActiveCfg = Release|Win32 + {A2BB18A5-F26B-48D6-BBB5-B83D64473C77}.Release|x86.Build.0 = Release|Win32 + {5528AEFB-638D-49AF-B9D4-965154E7D531}.Debug|x64.ActiveCfg = Debug|x64 + {5528AEFB-638D-49AF-B9D4-965154E7D531}.Debug|x64.Build.0 = Debug|x64 + {5528AEFB-638D-49AF-B9D4-965154E7D531}.Debug|x86.ActiveCfg = Debug|Win32 + {5528AEFB-638D-49AF-B9D4-965154E7D531}.Debug|x86.Build.0 = Debug|Win32 + {5528AEFB-638D-49AF-B9D4-965154E7D531}.Release|x64.ActiveCfg = Release|x64 + {5528AEFB-638D-49AF-B9D4-965154E7D531}.Release|x64.Build.0 = Release|x64 + {5528AEFB-638D-49AF-B9D4-965154E7D531}.Release|x86.ActiveCfg = Release|Win32 + {5528AEFB-638D-49AF-B9D4-965154E7D531}.Release|x86.Build.0 = Release|Win32 + {691DB635-C272-4B98-897E-0505B970DCA9}.Debug|x64.ActiveCfg = Debug|x64 + {691DB635-C272-4B98-897E-0505B970DCA9}.Debug|x64.Build.0 = Debug|x64 + {691DB635-C272-4B98-897E-0505B970DCA9}.Debug|x86.ActiveCfg = Debug|Win32 + {691DB635-C272-4B98-897E-0505B970DCA9}.Debug|x86.Build.0 = Debug|Win32 + {691DB635-C272-4B98-897E-0505B970DCA9}.Release|x64.ActiveCfg = Release|x64 + {691DB635-C272-4B98-897E-0505B970DCA9}.Release|x64.Build.0 = Release|x64 + {691DB635-C272-4B98-897E-0505B970DCA9}.Release|x86.ActiveCfg = Release|Win32 + {BD34DB24-F5DC-4992-A74F-05FAF731ABED}.Debug|x64.ActiveCfg = Debug|Win32 + {BD34DB24-F5DC-4992-A74F-05FAF731ABED}.Debug|x86.ActiveCfg = Debug|Win32 + {BD34DB24-F5DC-4992-A74F-05FAF731ABED}.Release|x64.ActiveCfg = Release|Win32 + {BD34DB24-F5DC-4992-A74F-05FAF731ABED}.Release|x86.ActiveCfg = Release|Win32 + {7912F978-B48C-4C5D-8BFD-5D1E22158E47}.Debug|x64.ActiveCfg = Debug|Win32 + {7912F978-B48C-4C5D-8BFD-5D1E22158E47}.Debug|x86.ActiveCfg = Debug|Win32 + {7912F978-B48C-4C5D-8BFD-5D1E22158E47}.Debug|x86.Build.0 = Debug|Win32 + {7912F978-B48C-4C5D-8BFD-5D1E22158E47}.Release|x64.ActiveCfg = Release|Win32 + {7912F978-B48C-4C5D-8BFD-5D1E22158E47}.Release|x86.ActiveCfg = Release|Win32 + {96E0E646-EE76-444D-9A77-A0CD7F781DEB}.Debug|x64.ActiveCfg = Debug|x64 + {96E0E646-EE76-444D-9A77-A0CD7F781DEB}.Debug|x64.Build.0 = Debug|x64 + {96E0E646-EE76-444D-9A77-A0CD7F781DEB}.Debug|x86.ActiveCfg = Debug|Win32 + {96E0E646-EE76-444D-9A77-A0CD7F781DEB}.Debug|x86.Build.0 = Debug|Win32 + {96E0E646-EE76-444D-9A77-A0CD7F781DEB}.Release|x64.ActiveCfg = Release|x64 + {96E0E646-EE76-444D-9A77-A0CD7F781DEB}.Release|x64.Build.0 = Release|x64 + {96E0E646-EE76-444D-9A77-A0CD7F781DEB}.Release|x86.ActiveCfg = Release|Win32 + {D99E2FCD-21A4-4065-949A-31E34E0E69D1}.Debug|x64.ActiveCfg = Debug|x64 + {D99E2FCD-21A4-4065-949A-31E34E0E69D1}.Debug|x64.Build.0 = Debug|x64 + {D99E2FCD-21A4-4065-949A-31E34E0E69D1}.Debug|x86.ActiveCfg = Debug|Win32 + {D99E2FCD-21A4-4065-949A-31E34E0E69D1}.Debug|x86.Build.0 = Debug|Win32 + {D99E2FCD-21A4-4065-949A-31E34E0E69D1}.Release|x64.ActiveCfg = Release|x64 + {D99E2FCD-21A4-4065-949A-31E34E0E69D1}.Release|x64.Build.0 = Release|x64 + {D99E2FCD-21A4-4065-949A-31E34E0E69D1}.Release|x86.ActiveCfg = Release|Win32 + EndGlobalSection + GlobalSection(SolutionProperties) = preSolution + HideSolutionNode = FALSE + EndGlobalSection + GlobalSection(ExtensibilityGlobals) = postSolution + SolutionGuid = {8AF3826E-406A-4F1C-BA80-B4D7FD4B52E1} + EndGlobalSection + GlobalSection(Performance) = preSolution + HasPerformanceSessions = true + EndGlobalSection +EndGlobal diff --git a/panda/drivers/windows/panda/dllmain.cpp b/panda/drivers/windows/panda/dllmain.cpp new file mode 100644 index 00000000000000..69b58914b3572b --- /dev/null +++ b/panda/drivers/windows/panda/dllmain.cpp @@ -0,0 +1,19 @@ +// dllmain.cpp : Defines the entry point for the DLL application. +#include "stdafx.h" + +BOOL APIENTRY DllMain( HMODULE hModule, + DWORD ul_reason_for_call, + LPVOID lpReserved + ) +{ + switch (ul_reason_for_call) + { + case DLL_PROCESS_ATTACH: + case DLL_THREAD_ATTACH: + case DLL_THREAD_DETACH: + case DLL_PROCESS_DETACH: + break; + } + return TRUE; +} + diff --git a/panda/drivers/windows/panda/main.cpp b/panda/drivers/windows/panda/main.cpp new file mode 100644 index 00000000000000..621c600b8238ae --- /dev/null +++ b/panda/drivers/windows/panda/main.cpp @@ -0,0 +1,79 @@ +#include "stdafx.h" + +#include + +LONG __cdecl +_tmain( + LONG Argc, + LPTSTR * Argv + ) +/*++ + +Routine description: + + Sample program that communicates with a USB device using WinUSB + +--*/ +{ + DEVICE_DATA deviceData; + HRESULT hr; + USB_DEVICE_DESCRIPTOR deviceDesc; + BOOL bResult; + BOOL noDevice; + ULONG lengthReceived; + + UNREFERENCED_PARAMETER(Argc); + UNREFERENCED_PARAMETER(Argv); + + // + // Find a device connected to the system that has WinUSB installed using our + // INF + // + hr = OpenDevice(&deviceData, &noDevice); + + if (FAILED(hr)) { + + if (noDevice) { + + printf(_T("Device not connected or driver not installed\n")); + + } else { + + printf(_T("Failed looking for device, HRESULT 0x%x\n"), hr); + } + + return 0; + } + + // + // Get device descriptor + // + bResult = WinUsb_GetDescriptor(deviceData.WinusbHandle, + USB_DEVICE_DESCRIPTOR_TYPE, + 0, + 0, + (PBYTE) &deviceDesc, + sizeof(deviceDesc), + &lengthReceived); + + if (FALSE == bResult || lengthReceived != sizeof(deviceDesc)) { + + printf(_T("Error among LastError %d or lengthReceived %d\n"), + FALSE == bResult ? GetLastError() : 0, + lengthReceived); + CloseDevice(&deviceData); + return 0; + } + + // + // Print a few parts of the device descriptor + // + printf(_T("Device found: VID_%04X&PID_%04X; bcdUsb %04X; path: %s\n"), + deviceDesc.idVendor, + deviceDesc.idProduct, + deviceDesc.bcdUSB, + deviceData.DevicePath); + + CloseDevice(&deviceData); + return 0; +} diff --git a/panda/drivers/windows/panda/panda.ico b/panda/drivers/windows/panda/panda.ico new file mode 100644 index 00000000000000..ff0e071f54f12f Binary files /dev/null and b/panda/drivers/windows/panda/panda.ico differ diff --git a/panda/drivers/windows/panda/panda.rc b/panda/drivers/windows/panda/panda.rc new file mode 100644 index 00000000000000..88cf9f76780799 Binary files /dev/null and b/panda/drivers/windows/panda/panda.rc differ diff --git a/panda/drivers/windows/panda/panda.vcxproj b/panda/drivers/windows/panda/panda.vcxproj new file mode 100644 index 00000000000000..22879c7cae8e2c --- /dev/null +++ b/panda/drivers/windows/panda/panda.vcxproj @@ -0,0 +1,189 @@ + + + + + Debug + Win32 + + + Release + Win32 + + + Debug + x64 + + + Release + x64 + + + + {5528AEFB-638D-49AF-B9D4-965154E7D531} + Win32Proj + panda + 10.0.16299.0 + + + + DynamicLibrary + true + v141 + Unicode + + + DynamicLibrary + false + v141 + true + Unicode + + + DynamicLibrary + true + v141 + Unicode + + + DynamicLibrary + false + v141 + true + Unicode + + + + + + + + + + + + + + + + + + + + + + true + $(SolutionDir)$(Configuration)_$(PlatformShortName)\ + + + true + $(SolutionDir)$(Configuration)_$(PlatformShortName)\ + + + false + $(SolutionDir)$(Configuration)_$(PlatformShortName)\ + + + false + $(SolutionDir)$(Configuration)_$(PlatformShortName)\ + + + + Use + Level3 + Disabled + WIN32;_DEBUG;_WINDOWS;_USRDLL;PANDA_EXPORTS;%(PreprocessorDefinitions) + true + false + + + Windows + true + kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);winusb.lib;setupapi.lib + + + + + Use + Level3 + Disabled + _DEBUG;_WINDOWS;_USRDLL;PANDA_EXPORTS;%(PreprocessorDefinitions) + true + + + Windows + true + kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);winusb.lib;setupapi.lib + + + + + Level3 + Use + MaxSpeed + true + true + WIN32;NDEBUG;_WINDOWS;_USRDLL;PANDA_EXPORTS;%(PreprocessorDefinitions) + true + + + Windows + true + true + true + kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);winusb.lib;setupapi.lib + + + + + Level3 + Use + MaxSpeed + true + true + NDEBUG;_WINDOWS;_USRDLL;PANDA_EXPORTS;%(PreprocessorDefinitions) + true + + + Windows + true + true + true + kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);winusb.lib;setupapi.lib + + + + + + + + + false + + + false + + + false + + + false + + + + + Create + Create + Create + Create + + + + + + + + + + + + \ No newline at end of file diff --git a/panda/drivers/windows/panda/panda.vcxproj.filters b/panda/drivers/windows/panda/panda.vcxproj.filters new file mode 100644 index 00000000000000..afddad6e8b7f97 --- /dev/null +++ b/panda/drivers/windows/panda/panda.vcxproj.filters @@ -0,0 +1,43 @@ + + + + + {4FC737F1-C7A5-4376-A066-2A32D752A2FF} + cpp;c;cc;cxx;def;odl;idl;hpj;bat;asm;asmx + + + {93995380-89BD-4b04-88EB-625FBE52EBFB} + h;hh;hpp;hxx;hm;inl;inc;xsd + + + {67DA6AB6-F800-4c08-8B7A-83BB121AAD01} + rc;ico;cur;bmp;dlg;rc2;rct;bin;rgs;gif;jpg;jpeg;jpe;resx;tiff;tif;png;wav;mfcribbon-ms + + + + + Header Files + + + Header Files + + + + + Source Files + + + Source Files + + + + + Resource Files + + + + + Resource Files + + + \ No newline at end of file diff --git a/panda/drivers/windows/panda/resource.h b/panda/drivers/windows/panda/resource.h new file mode 100644 index 00000000000000..bf006ff4b39308 Binary files /dev/null and b/panda/drivers/windows/panda/resource.h differ diff --git a/panda/drivers/windows/panda/stdafx.cpp b/panda/drivers/windows/panda/stdafx.cpp new file mode 100644 index 00000000000000..8793e09b40dfb5 --- /dev/null +++ b/panda/drivers/windows/panda/stdafx.cpp @@ -0,0 +1,8 @@ +// stdafx.cpp : source file that includes just the standard includes +// panda.pch will be the pre-compiled header +// stdafx.obj will contain the pre-compiled type information + +#include "stdafx.h" + +// TODO: reference any additional headers you need in STDAFX.H +// and not in this file diff --git a/panda/drivers/windows/panda/stdafx.h b/panda/drivers/windows/panda/stdafx.h new file mode 100644 index 00000000000000..cc3d3b96672b27 --- /dev/null +++ b/panda/drivers/windows/panda/stdafx.h @@ -0,0 +1,19 @@ +// stdafx.h : include file for standard system include files, +// or project specific include files that are used frequently, but +// are changed infrequently +// + +#pragma once + +#include "targetver.h" + +#ifndef WIN32_LEAN_AND_MEAN +#define WIN32_LEAN_AND_MEAN // Exclude rarely-used stuff from Windows headers +#endif +// Windows Header Files: +#include + +#include +#include +#include +#include diff --git a/panda/drivers/windows/pandaJ2534DLL Test/ECUsim_tests.cpp b/panda/drivers/windows/pandaJ2534DLL Test/ECUsim_tests.cpp new file mode 100644 index 00000000000000..8a9161475c90bd --- /dev/null +++ b/panda/drivers/windows/pandaJ2534DLL Test/ECUsim_tests.cpp @@ -0,0 +1,87 @@ +#include "stdafx.h" +#include "Loader4.h" +#include "pandaJ2534DLL/J2534_v0404.h" +#include "panda_shared/panda.h" +#include "Timer.h" +#include "ECUsim DLL\ECUsim.h" +#include "TestHelpers.h" + +using namespace Microsoft::VisualStudio::CppUnitTestFramework; + +namespace pandaWCUsimTest +{ + + TEST_CLASS(ECUsimTests) + { + public: + + TEST_METHOD(ECUsim_ISO15765_SingleFrameTx_29bStandardAddrPad500k) + { + ECUsim sim("", 500000); + auto p = getPanda(500); + + p->can_send(0x18daeff1, TRUE, (const uint8_t*)"\x02\x01\x00", 3, panda::PANDA_CAN1); + auto msg_recv = panda_recv_loop(p, 2); + check_panda_can_msg(msg_recv[0], 0, 0x18daeff1, TRUE, TRUE, std::string("\x02\x01\x00", 3), LINE_INFO()); + check_panda_can_msg(msg_recv[1], 0, 0x18daf1ef, TRUE, FALSE, std::string("\x06\x41\x00\xff\xff\xff\xfe\x00", 8), LINE_INFO()); + } + + TEST_METHOD(ECUsim_ISO15765_SingleFrameTx_29bStandardAddrPad250k) + { + ECUsim sim("", 250000); + auto p = getPanda(250); + + p->can_send(0x18daeff1, TRUE, (const uint8_t*)"\x02\x01\x00", 3, panda::PANDA_CAN1); + auto msg_recv = panda_recv_loop(p, 2); + check_panda_can_msg(msg_recv[0], 0, 0x18daeff1, TRUE, TRUE, std::string("\x02\x01\x00", 3), LINE_INFO()); + check_panda_can_msg(msg_recv[1], 0, 0x18daf1ef, TRUE, FALSE, std::string("\x06""\x41\x00""\xff\xff\xff\xfe""\x00", 8), LINE_INFO()); + } + + TEST_METHOD(ECUsim_ISO15765_SingleFrameTx_29bExtAddrPad500k) + { + ECUsim sim("", 500000, TRUE); + auto p = getPanda(500); + + p->can_send(0x18daeff1, TRUE, (const uint8_t*)"\x13""\x02\x01\x00", 4, panda::PANDA_CAN1); + auto msg_recv = panda_recv_loop(p, 2); + check_panda_can_msg(msg_recv[0], 0, 0x18daeff1, TRUE, TRUE, std::string("\x13""\x02\x01\x00", 4), LINE_INFO()); + check_panda_can_msg(msg_recv[1], 0, 0x18daf1ef, TRUE, FALSE, std::string("\x13""\x06""\x41\x00""\xff\xff\xff\xfe", 8), LINE_INFO()); + } + + TEST_METHOD(ECUsim_ISO15765_MultiFrameTx_29bStandardAddrPad500k) + { + ECUsim sim("", 500000); + auto p = getPanda(500); + + p->can_send(0x18daeff1, TRUE, (const uint8_t*)"\x02\x09\x02", 3, panda::PANDA_CAN1); + auto msg_recv = panda_recv_loop(p, 2); + check_panda_can_msg(msg_recv[0], 0, 0x18daeff1, TRUE, TRUE, std::string("\x02\x09\x02", 3), LINE_INFO()); + check_panda_can_msg(msg_recv[1], 0, 0x18daf1ef, TRUE, FALSE, std::string("\x10\x14""\x49\x02\x01""1D4", 8), LINE_INFO()); + + p->can_send(0x18daeff1, TRUE, (const uint8_t*)"\x30\x00\x00", 3, panda::PANDA_CAN1); + msg_recv = panda_recv_loop(p, 3); + check_panda_can_msg(msg_recv[0], 0, 0x18daeff1, TRUE, TRUE, std::string("\x30\x0\x0", 3), LINE_INFO()); + check_panda_can_msg(msg_recv[1], 0, 0x18daf1ef, TRUE, FALSE, std::string("\x21""GP00R55", 8), LINE_INFO()); + check_panda_can_msg(msg_recv[2], 0, 0x18daf1ef, TRUE, FALSE, std::string("\x22""B123456", 8), LINE_INFO()); + } + + TEST_METHOD(ECUsim_ISO15765_MultiFrameTx_29bExtAddrPad500k) + { + ECUsim sim("", 500000, TRUE); + auto p = getPanda(500); + + p->can_send(0x18daeff1, TRUE, (const uint8_t*)"\x13""\x02\x09\x02", 4, panda::PANDA_CAN1); + auto msg_recv = panda_recv_loop(p, 2); + check_panda_can_msg(msg_recv[0], 0, 0x18daeff1, TRUE, TRUE, std::string("\x13""\x02\x09\x02", 4), LINE_INFO()); + check_panda_can_msg(msg_recv[1], 0, 0x18daf1ef, TRUE, FALSE, std::string("\x13""\x10\x14""\x49\x02\x01""1D", 8), LINE_INFO()); + + p->can_send(0x18daeff1, TRUE, (const uint8_t*)"\x13""\x30\x00\x00", 4, panda::PANDA_CAN1); + msg_recv = panda_recv_loop(p, 4); + check_panda_can_msg(msg_recv[0], 0, 0x18daeff1, TRUE, TRUE, std::string("\x13""\x30\x0\x0", 4), LINE_INFO()); + check_panda_can_msg(msg_recv[1], 0, 0x18daf1ef, TRUE, FALSE, std::string("\x13""\x21""4GP00R", 8), LINE_INFO()); + check_panda_can_msg(msg_recv[2], 0, 0x18daf1ef, TRUE, FALSE, std::string("\x13""\x22""55B123", 8), LINE_INFO()); + check_panda_can_msg(msg_recv[3], 0, 0x18daf1ef, TRUE, FALSE, std::string("\x13""\x23""456", 5), LINE_INFO()); + } + }; + +} \ No newline at end of file diff --git a/panda/drivers/windows/pandaJ2534DLL Test/Loader4.cpp b/panda/drivers/windows/pandaJ2534DLL Test/Loader4.cpp new file mode 100644 index 00000000000000..f4a0b70fa596c2 --- /dev/null +++ b/panda/drivers/windows/pandaJ2534DLL Test/Loader4.cpp @@ -0,0 +1,240 @@ +// Loader4.cpp +// (c) 2005 National Control Systems, Inc. +// Portions (c) 2004 Drew Technologies, Inc. +// Dynamic J2534 v04.04 dll loader for VB + +// 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 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. + +// You should have received a copy of the GNU General Public License +// along with this program; if not, write to: +// the Free Software Foundation, Inc. +// 51 Franklin Street, Fifth Floor +// Boston, MA 02110-1301, USA + +// National Control Systems, Inc. +// 10737 Hamburg Rd +// Hamburg, MI 48139 +// 810-231-2901 + +// Drew Technologies, Inc. +// 7012 E.M -36, Suite 3B +// Whitmore Lake, MI 48189 +// 810-231-3171 + +#define STRICT +#include "stdafx.h" +#include +#include "Loader4.h" + +PTOPEN LocalOpen; +PTCLOSE LocalClose; +PTCONNECT LocalConnect; +PTDISCONNECT LocalDisconnect; +PTREADMSGS LocalReadMsgs; +PTWRITEMSGS LocalWriteMsgs; +PTSTARTPERIODICMSG LocalStartPeriodicMsg; +PTSTOPPERIODICMSG LocalStopPeriodicMsg; +PTSTARTMSGFILTER LocalStartMsgFilter; +PTSTOPMSGFILTER LocalStopMsgFilter; +PTSETPROGRAMMINGVOLTAGE LocalSetProgrammingVoltage; +PTREADVERSION LocalReadVersion; +PTGETLASTERROR LocalGetLastError; +PTIOCTL LocalIoctl; + +HINSTANCE hDLL = NULL; +//BOOL bIsCorrectVersion = FALSE; + +BOOL WINAPI DllMain(HINSTANCE hInstA, DWORD dwReason, LPVOID lpvReserved) +{ + switch (dwReason) { + case DLL_PROCESS_ATTACH: + // The DLL is being mapped into the process's address space + + case DLL_THREAD_ATTACH: + // A thread is being created + break; + + case DLL_THREAD_DETACH: + // A thread is exiting cleanly + break; + + case DLL_PROCESS_DETACH: + // The DLL is being unmapped from the process's address space + break; + } + + return TRUE; +} + + +long WINAPI LoadJ2534Dll(char *sLib) +{ + long lFuncList = 0; + + if (hDLL != NULL) UnloadJ2534Dll(); + hDLL = LoadLibraryA (sLib); + if (hDLL == NULL) return ERR_NO_DLL; + + LocalOpen = (PTOPEN)(GetProcAddress(hDLL, "PassThruOpen")); + if (LocalOpen == NULL) lFuncList = lFuncList | ERR_NO_PTOPEN; + + LocalClose = (PTCLOSE)(GetProcAddress(hDLL, "PassThruClose")); + if (LocalClose == NULL) lFuncList = lFuncList | ERR_NO_PTCLOSE; + + LocalConnect = (PTCONNECT)(GetProcAddress(hDLL,"PassThruConnect")); + if (LocalConnect == NULL) lFuncList = lFuncList | ERR_NO_PTCONNECT; + + LocalDisconnect = (PTDISCONNECT)(GetProcAddress(hDLL,"PassThruDisconnect")); + if (LocalDisconnect == NULL) lFuncList = lFuncList | ERR_NO_PTDISCONNECT; + + LocalReadMsgs = (PTREADMSGS)(GetProcAddress(hDLL,"PassThruReadMsgs")); + if (LocalReadMsgs == NULL) lFuncList = lFuncList | ERR_NO_PTREADMSGS; + + LocalWriteMsgs = (PTWRITEMSGS)(GetProcAddress(hDLL,"PassThruWriteMsgs")); + if (LocalWriteMsgs == NULL) lFuncList = lFuncList | ERR_NO_PTWRITEMSGS; + + LocalStartPeriodicMsg = (PTSTARTPERIODICMSG)(GetProcAddress(hDLL,"PassThruStartPeriodicMsg")); + if (LocalStartPeriodicMsg == NULL) lFuncList = lFuncList | ERR_NO_PTSTARTPERIODICMSG; + + LocalStopPeriodicMsg = (PTSTOPPERIODICMSG)(GetProcAddress(hDLL,"PassThruStopPeriodicMsg")); + if (LocalStopPeriodicMsg == NULL) lFuncList = lFuncList | ERR_NO_PTSTOPPERIODICMSG; + + LocalStartMsgFilter = (PTSTARTMSGFILTER)(GetProcAddress(hDLL,"PassThruStartMsgFilter")); + if (LocalStartPeriodicMsg == NULL) lFuncList = lFuncList | ERR_NO_PTSTARTMSGFILTER; + + LocalStopMsgFilter = (PTSTOPMSGFILTER)(GetProcAddress(hDLL,"PassThruStopMsgFilter")); + if (LocalStopMsgFilter == NULL) lFuncList = lFuncList | ERR_NO_PTSTOPMSGFILTER; + + LocalSetProgrammingVoltage = (PTSETPROGRAMMINGVOLTAGE)(GetProcAddress(hDLL,"PassThruSetProgrammingVoltage")); + if (LocalSetProgrammingVoltage == NULL) lFuncList = lFuncList | ERR_NO_PTSETPROGRAMMINGVOLTAGE; + + LocalReadVersion = (PTREADVERSION)(GetProcAddress(hDLL,"PassThruReadVersion")); + if (LocalReadVersion == NULL) lFuncList = lFuncList | ERR_NO_PTREADVERSION; + + LocalGetLastError = (PTGETLASTERROR)(GetProcAddress(hDLL,"PassThruGetLastError")); + if (LocalGetLastError == NULL) lFuncList = lFuncList | ERR_NO_PTGETLASTERROR; + + LocalIoctl = (PTIOCTL)(GetProcAddress(hDLL,"PassThruIoctl")); + if (LocalIoctl == NULL) lFuncList = lFuncList | ERR_NO_PTIOCTL; + + if (lFuncList == ERR_NO_FUNCTIONS) return ERR_WRONG_DLL_VER; + + return lFuncList; +} + +long WINAPI UnloadJ2534Dll() +{ + if (FreeLibrary(hDLL)) + { + hDLL = NULL; + LocalOpen = NULL; + LocalClose = NULL; + LocalConnect = NULL; + LocalDisconnect = NULL; + LocalReadMsgs = NULL; + LocalWriteMsgs = NULL; + LocalStartPeriodicMsg = NULL; + LocalStopPeriodicMsg = NULL; + LocalStartMsgFilter = NULL; + LocalStopMsgFilter = NULL; + LocalSetProgrammingVoltage = NULL; + LocalReadVersion = NULL; + LocalGetLastError = NULL; + LocalIoctl = NULL; + return 0; + } + return ERR_NO_DLL; +} + +long WINAPI PassThruOpen(void *pName, unsigned long *pDeviceID) +{ + if (LocalOpen == NULL) return ERR_FUNC_MISSING; + return LocalOpen(pName, pDeviceID); +} + +long WINAPI PassThruClose(unsigned long DeviceID) +{ + if (LocalOpen == NULL) return ERR_FUNC_MISSING; + return LocalClose(DeviceID); +} + +long WINAPI PassThruConnect(unsigned long DeviceID, unsigned long ProtocolID, unsigned long Flags, unsigned long Baudrate, unsigned long *pChannelID) +{ + if (LocalConnect == NULL) return ERR_FUNC_MISSING; + return LocalConnect(DeviceID, ProtocolID, Flags, Baudrate, pChannelID); +} + +long WINAPI PassThruDisconnect(unsigned long ChannelID) +{ + if (LocalDisconnect == NULL) return ERR_FUNC_MISSING; + return LocalDisconnect(ChannelID); +} + +long WINAPI PassThruReadMsgs(unsigned long ChannelID, PASSTHRU_MSG *pMsg, unsigned long *pNumMsgs, unsigned long Timeout) +{ + if (LocalReadMsgs == NULL) return ERR_FUNC_MISSING; + return LocalReadMsgs(ChannelID, pMsg, pNumMsgs, Timeout); +} + +long WINAPI PassThruWriteMsgs(unsigned long ChannelID, PASSTHRU_MSG *pMsg, unsigned long *pNumMsgs, unsigned long Timeout) +{ + if (LocalWriteMsgs == NULL) return ERR_FUNC_MISSING; + return LocalWriteMsgs(ChannelID, pMsg, pNumMsgs, Timeout); +} + +long WINAPI PassThruStartPeriodicMsg(unsigned long ChannelID, PASSTHRU_MSG *pMsg, unsigned long *pMsgID, unsigned long TimeInterval) +{ + if (LocalStartPeriodicMsg == NULL) return ERR_FUNC_MISSING; + return LocalStartPeriodicMsg(ChannelID, pMsg, pMsgID, TimeInterval); +} + +long WINAPI PassThruStopPeriodicMsg(unsigned long ChannelID, unsigned long MsgID) +{ + if (LocalStopPeriodicMsg == NULL) return ERR_FUNC_MISSING; + return LocalStopPeriodicMsg(ChannelID, MsgID); +} + +long WINAPI PassThruStartMsgFilter(unsigned long ChannelID, unsigned long FilterType, + PASSTHRU_MSG *pMaskMsg, PASSTHRU_MSG *pPatternMsg, PASSTHRU_MSG *pFlowControlMsg, unsigned long *pFilterID) +{ + if (LocalStartMsgFilter == NULL) return ERR_FUNC_MISSING; + return LocalStartMsgFilter(ChannelID, FilterType, pMaskMsg, pPatternMsg, pFlowControlMsg, pFilterID); +} + +long WINAPI PassThruStopMsgFilter(unsigned long ChannelID, unsigned long FilterID) +{ + if (LocalStopMsgFilter == NULL) return ERR_FUNC_MISSING; + return LocalStopMsgFilter(ChannelID, FilterID); +} + +long WINAPI PassThruSetProgrammingVoltage(unsigned long DeviceID, unsigned long PinNumber, unsigned long Voltage) +{ + if (LocalSetProgrammingVoltage == NULL) return ERR_FUNC_MISSING; + return LocalSetProgrammingVoltage(DeviceID, PinNumber, Voltage); +} + +long WINAPI PassThruReadVersion(unsigned long DeviceID, char *pFirmwareVersion, char *pDllVersion, char *pApiVersion) +{ + if (LocalReadVersion == NULL) return ERR_FUNC_MISSING; + return LocalReadVersion(DeviceID, pFirmwareVersion, pDllVersion, pApiVersion); +} + +long WINAPI PassThruGetLastError(char *pErrorDescription) +{ + if (LocalGetLastError == NULL) return ERR_FUNC_MISSING; + return LocalGetLastError(pErrorDescription); +} + +long WINAPI PassThruIoctl(unsigned long ChannelID, unsigned long IoctlID, void *pInput, void *pOutput) +{ + if (LocalIoctl == NULL) return ERR_FUNC_MISSING; + return LocalIoctl(ChannelID, IoctlID, pInput, pOutput); +} \ No newline at end of file diff --git a/panda/drivers/windows/pandaJ2534DLL Test/Loader4.h b/panda/drivers/windows/pandaJ2534DLL Test/Loader4.h new file mode 100644 index 00000000000000..9710144141e881 --- /dev/null +++ b/panda/drivers/windows/pandaJ2534DLL Test/Loader4.h @@ -0,0 +1,55 @@ +// Loader4.h +// (c) 2005 National Control Systems, Inc. +// Portions (c) 2004 Drew Technologies, Inc. + +// 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 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. + +// You should have received a copy of the GNU General Public License +// along with this program; if not, write to: +// the Free Software Foundation, Inc. +// 51 Franklin Street, Fifth Floor +// Boston, MA 02110-1301, USA + +// National Control Systems, Inc. +// 10737 Hamburg Rd +// Hamburg, MI 48139 +// 810-231-2901 + +// Drew Technologies, Inc. +// 7012 E.M -36, Suite 3B +// Whitmore Lake, MI 48189 +// 810-231-3171 + +#include "pandaJ2534DLL/J2534_v0404.h" + +//Other Functions +long WINAPI LoadJ2534Dll(char *); +long WINAPI UnloadJ2534Dll(); + +// NCS Returns of any functions not found +#define ERR_NO_PTOPEN 0x0001 +#define ERR_NO_PTCLOSE 0x0002 +#define ERR_NO_PTCONNECT 0x0004 +#define ERR_NO_PTDISCONNECT 0x0008 +#define ERR_NO_PTREADMSGS 0x0010 +#define ERR_NO_PTWRITEMSGS 0x0020 +#define ERR_NO_PTSTARTPERIODICMSG 0x0040 +#define ERR_NO_PTSTOPPERIODICMSG 0x0080 +#define ERR_NO_PTSTARTMSGFILTER 0x0100 +#define ERR_NO_PTSTOPMSGFILTER 0x0200 +#define ERR_NO_PTSETPROGRAMMINGVOLTAGE 0x0400 +#define ERR_NO_PTREADVERSION 0x0800 +#define ERR_NO_PTGETLASTERROR 0x1000 +#define ERR_NO_PTIOCTL 0x2000 +#define ERR_NO_FUNCTIONS 0x3fff +#define ERR_NO_DLL -1 +#define ERR_WRONG_DLL_VER -2 +#define ERR_FUNC_MISSING -3 diff --git a/panda/drivers/windows/pandaJ2534DLL Test/TestHelpers.cpp b/panda/drivers/windows/pandaJ2534DLL Test/TestHelpers.cpp new file mode 100644 index 00000000000000..1281eb9d616c43 --- /dev/null +++ b/panda/drivers/windows/pandaJ2534DLL Test/TestHelpers.cpp @@ -0,0 +1,254 @@ +#include "stdafx.h" +#include "TestHelpers.h" +#include "Loader4.h" +#include "pandaJ2534DLL/J2534_v0404.h" +#include "panda_shared/panda.h" +#include "Timer.h" + +using namespace Microsoft::VisualStudio::CppUnitTestFramework; + +void write_ioctl(unsigned int chanid, unsigned int param, unsigned int val, const __LineInfo* pLineInfo) { + SCONFIG config = { param, val }; + SCONFIG_LIST inconfig = { 1, &config }; + + Assert::AreEqual(STATUS_NOERROR, PassThruIoctl(chanid, SET_CONFIG, &inconfig, NULL), _T("Failed to set IOCTL."), pLineInfo); +} + +std::vector panda_recv_loop_loose(std::unique_ptr& p, unsigned int min_num, unsigned long timeout_ms) { + std::vector ret_messages; + Timer t = Timer(); + + while (t.getTimePassed() < timeout_ms) { + Sleep(10); + std::vectormsg_recv = p->can_recv(); + if (msg_recv.size() > 0) { + ret_messages.insert(std::end(ret_messages), std::begin(msg_recv), std::end(msg_recv)); + } + } + + Assert::IsTrue(min_num <= ret_messages.size(), _T("Received too few messages.")); + return ret_messages; +} + +std::vector panda_recv_loop(std::unique_ptr& p, unsigned int num_expected, unsigned long timeout_ms) { + std::vector ret_messages; + Timer t = Timer(); + + while (t.getTimePassed() < timeout_ms) { + Sleep(10); + std::vectormsg_recv = p->can_recv(); + if (msg_recv.size() > 0) { + ret_messages.insert(std::end(ret_messages), std::begin(msg_recv), std::end(msg_recv)); + } + if (ret_messages.size() >= num_expected) break; + } + + std::ostringstream stringStream; + + stringStream << "j2534_recv_loop Broke at " << t.getTimePassed() << " ms size is " << ret_messages.size() << std::endl; + + if (num_expected != ret_messages.size()) { + stringStream << "Incorrect number of messages received. Displaying the messages:" << std::endl; + for (auto msg : ret_messages) { + stringStream << " TS: " << msg.recv_time << "; Dat: "; + for (int i = 0; i < msg.len; i++) stringStream << std::hex << std::setw(2) << std::setfill('0') << int(msg.dat[i] & 0xFF) << " "; + stringStream << std::endl; + } + } + + Logger::WriteMessage(stringStream.str().c_str()); + + Assert::AreEqual(num_expected, ret_messages.size(), _T("Received wrong number of messages.")); + return ret_messages; +} + +void check_panda_can_msg(panda::PANDA_CAN_MSG& msgin, uint8_t bus, unsigned long addr, bool addr_29b, + bool is_receipt, std::string dat, const __LineInfo* pLineInfo) { + Assert::AreEqual(bus, msgin.bus, _T("Wrong msg bus"), pLineInfo); + Assert::AreEqual(addr, msgin.addr, _T("Wrong msg addr"), pLineInfo); + Assert::AreEqual(addr_29b, msgin.addr_29b, _T("Wrong msg 29b flag"), pLineInfo); + Assert::AreEqual(is_receipt, msgin.is_receipt, _T("Wrong msg receipt flag"), pLineInfo); + + std::ostringstream logmsg; + logmsg << "Expected Hex ("; + for (int i = 0; i < dat.size(); i++) logmsg << std::hex << std::setw(2) << std::setfill('0') << int(dat[i] & 0xFF) << " "; + logmsg << "); Actual Hex ("; + for (int i = 0; i < msgin.len; i++) logmsg << std::hex << std::setw(2) << std::setfill('0') << int(((char*)msgin.dat)[i] & 0xFF) << " "; + logmsg << ")"; + Logger::WriteMessage(logmsg.str().c_str()); + + Assert::AreEqual(dat.size(), msgin.len, _T("Wrong msg len"), pLineInfo); + Assert::AreEqual(dat, std::string((char*)msgin.dat, msgin.len), _T("Wrong msg payload"), pLineInfo); +} + +unsigned long J2534_start_periodic_msg_checked(unsigned long chanid, unsigned long ProtocolID, unsigned long TxFlags, unsigned long DataSize, + unsigned long ExtraDataIndex, const char * Data, unsigned long TimeInterval, const __LineInfo * pLineInfo) { + PASSTHRU_MSG msg = { ProtocolID, 0, TxFlags, 0, DataSize, ExtraDataIndex }; + memcpy_s(msg.Data, 4128, Data, DataSize); + unsigned long msgID; + Assert::AreEqual(STATUS_NOERROR, J2534_start_periodic_msg(chanid, ProtocolID, TxFlags, DataSize, + ExtraDataIndex, Data, TimeInterval, &msgID, pLineInfo), _T("Failed to start Periodic Message."), pLineInfo); + return msgID; +} + +unsigned long J2534_start_periodic_msg(unsigned long chanid, unsigned long ProtocolID, unsigned long TxFlags, unsigned long DataSize, + unsigned long ExtraDataIndex, const char * Data, unsigned long TimeInterval, unsigned long* msgID, const __LineInfo * pLineInfo) { + PASSTHRU_MSG msg = { ProtocolID, 0, TxFlags, 0, DataSize, ExtraDataIndex }; + memcpy_s(msg.Data, 4128, Data, DataSize); + return PassThruStartPeriodicMsg(chanid, &msg, msgID, TimeInterval); +} + +void J2534_send_msg_checked(unsigned long chanid, unsigned long ProtocolID, unsigned long RxStatus, unsigned long TxFlags, + unsigned long Timestamp, unsigned long DataSize, unsigned long ExtraDataIndex, const char* Data, const __LineInfo* pLineInfo) { + + PASSTHRU_MSG msg = { ProtocolID, RxStatus, TxFlags, Timestamp, DataSize, ExtraDataIndex }; + memcpy_s(msg.Data, 4128, Data, DataSize); + unsigned long msgcount = 1; + Assert::AreEqual(STATUS_NOERROR, PassThruWriteMsgs(chanid, &msg, &msgcount, 0), _T("Failed to write message."), pLineInfo); + Assert::AreEqual(1, msgcount, _T("Wrong message count after tx."), pLineInfo); +} + +long J2534_send_msg(unsigned long chanid, unsigned long ProtocolID, unsigned long RxStatus, unsigned long TxFlags, + unsigned long Timestamp, unsigned long DataSize, unsigned long ExtraDataIndex, const char* Data) { + + PASSTHRU_MSG msg = { ProtocolID, RxStatus, TxFlags, Timestamp, DataSize, ExtraDataIndex }; + memcpy_s(msg.Data, 4128, Data, DataSize); + unsigned long msgcount = 1; + return PassThruWriteMsgs(chanid, &msg, &msgcount, 0); +} + +//Allow more messages to come in than the min. +std::vector j2534_recv_loop_loose(unsigned int chanid, unsigned int min_num, unsigned long timeout_ms) { + std::vector ret_messages; + PASSTHRU_MSG recvbuff[4] = {}; + Timer t = Timer(); + + while (t.getTimePassed() < timeout_ms) { + unsigned long msgcount = 4; + unsigned int res = PassThruReadMsgs(chanid, recvbuff, &msgcount, 0); + if (res == ERR_BUFFER_EMPTY) continue; + Assert::IsFalse(msgcount > 4, _T("PassThruReadMsgs returned more data than the buffer could hold.")); + Assert::AreEqual(STATUS_NOERROR, res, _T("Failed to read message.")); + if (msgcount > 0) { + for (unsigned int i = 0; i < msgcount; i++) { + ret_messages.push_back(recvbuff[i]); + } + } + } + + Assert::IsTrue(min_num <= ret_messages.size(), _T("Received too few messages.")); + return ret_messages; +} + +std::vector j2534_recv_loop(unsigned int chanid, unsigned int num_expected, unsigned long timeout_ms) { + std::vector ret_messages; + PASSTHRU_MSG recvbuff[4] = {}; + Timer t = Timer(); + + while (t.getTimePassed() < timeout_ms) { + unsigned long msgcount = 4; + unsigned int res = PassThruReadMsgs(chanid, recvbuff, &msgcount, 0); + if (res == ERR_BUFFER_EMPTY) continue; + Assert::IsFalse(msgcount > 4, _T("PassThruReadMsgs returned more data than the buffer could hold.")); + Assert::AreEqual(STATUS_NOERROR, res, _T("Failed to read message.")); + if (msgcount > 0) { + for (unsigned int i = 0; i < msgcount; i++) { + ret_messages.push_back(recvbuff[i]); + } + } + if (ret_messages.size() >= num_expected) break; + } + + std::ostringstream stringStream; + stringStream << "j2534_recv_loop Broke at " << t.getTimePassed() << " ms size is " << ret_messages.size() << std::endl; + + if (num_expected != ret_messages.size()) { + stringStream << "Incorrect number of messages received. Displaying the messages:" << std::endl; + for (auto msg : ret_messages) { + stringStream << " TS: " << msg.Timestamp << "; Dat: "; + for (int i = 0; i < msg.DataSize; i++) stringStream << std::hex << std::setw(2) << std::setfill('0') << int(msg.Data[i] & 0xFF) << " "; + stringStream << std::endl; + } + } + + Logger::WriteMessage(stringStream.str().c_str()); + + Assert::AreEqual(num_expected, ret_messages.size(), _T("Received wrong number of messages.")); + return ret_messages; +} + +void check_J2534_can_msg(PASSTHRU_MSG& msgin, unsigned long ProtocolID, unsigned long RxStatus, unsigned long TxFlags, + unsigned long DataSize, unsigned long ExtraDataIndex, const char* Data, const __LineInfo* pLineInfo) { + Assert::AreEqual(DataSize, msgin.DataSize, _T("Wrong msg len"), pLineInfo); + + std::ostringstream logmsg; + logmsg << "Expected Hex ("; + for (int i = 0; i < DataSize; i++) logmsg << std::hex << std::setw(2) << std::setfill('0') << int(Data[i] & 0xFF) << " "; + logmsg << "); Actual Hex ("; + for (int i = 0; i < msgin.DataSize; i++) logmsg << std::hex << std::setw(2) << std::setfill('0') << int(((char*)msgin.Data)[i] & 0xFF) << " "; + logmsg << ")"; + Logger::WriteMessage(logmsg.str().c_str()); + Assert::AreEqual(std::string(Data, DataSize), std::string((char*)msgin.Data, msgin.DataSize), _T("Wrong msg payload"), pLineInfo); + + Assert::AreEqual(ProtocolID, msgin.ProtocolID, _T("Wrong msg protocol"), pLineInfo); + Assert::AreEqual(RxStatus, msgin.RxStatus, _T("Wrong msg receipt rxstatus"), pLineInfo); + Assert::AreEqual(TxFlags, msgin.TxFlags, _T("Wrong msg receipt txflag"), pLineInfo); + Assert::AreEqual(ExtraDataIndex, msgin.ExtraDataIndex, _T("Wrong msg ExtraDataIndex"), pLineInfo); +} + +unsigned long J2534_set_PASS_filter(unsigned long chanid, unsigned long ProtocolID, unsigned long tx, + unsigned long len, char* mask, char* pattern, const __LineInfo* pLineInfo) { + unsigned long filterid; + PASSTHRU_MSG mask_msg = { ProtocolID, 0, tx, 0, len, 0, 0 }; + PASSTHRU_MSG pattern_msg = { ProtocolID, 0, tx, 0, len, 0, 0 }; + memcpy(mask_msg.Data, mask, len); + memcpy(pattern_msg.Data, pattern, len); + Assert::AreEqual(STATUS_NOERROR, PassThruStartMsgFilter(chanid, PASS_FILTER, &mask_msg, &pattern_msg, NULL, &filterid), + _T("Failed to create filter."), pLineInfo); + return filterid; +} + +unsigned long J2534_set_BLOCK_filter(unsigned long chanid, unsigned long ProtocolID, unsigned long tx, + unsigned long len, char* mask, char* pattern, const __LineInfo* pLineInfo) { + unsigned long filterid; + PASSTHRU_MSG mask_msg = { ProtocolID, 0, tx, 0, len, 0, 0 }; + PASSTHRU_MSG pattern_msg = { ProtocolID, 0, tx, 0, len, 0, 0 }; + memcpy(mask_msg.Data, mask, len); + memcpy(pattern_msg.Data, pattern, len); + Assert::AreEqual(STATUS_NOERROR, PassThruStartMsgFilter(chanid, BLOCK_FILTER, &mask_msg, &pattern_msg, NULL, &filterid), + _T("Failed to create filter."), pLineInfo); + return filterid; +} + +unsigned long J2534_set_flowctrl_filter(unsigned long chanid, unsigned long tx, + unsigned long len, char* mask, char* pattern, char* flow, const __LineInfo* pLineInfo) { + unsigned long filterid; + PASSTHRU_MSG mask_msg = { ISO15765, 0, tx, 0, len, 0, 0 }; + PASSTHRU_MSG pattern_msg = { ISO15765, 0, tx, 0, len, 0, 0 }; + PASSTHRU_MSG flow_msg = { ISO15765, 0, tx, 0, len, 0, 0 }; + memcpy(mask_msg.Data, mask, len); + memcpy(pattern_msg.Data, pattern, len); + memcpy(flow_msg.Data, flow, len); + Assert::AreEqual(STATUS_NOERROR, PassThruStartMsgFilter(chanid, FLOW_CONTROL_FILTER, &mask_msg, &pattern_msg, &flow_msg, &filterid), + _T("Failed to create filter."), pLineInfo); + return filterid; +} + +std::unique_ptr getPanda(unsigned long kbaud, BOOL loopback) { + auto p = panda::Panda::openPanda(""); + Assert::IsTrue(p != nullptr, _T("Could not open raw panda device to test communication.")); + p->set_can_speed_kbps(panda::PANDA_CAN1, kbaud); + p->set_safety_mode(panda::SAFETY_ALLOUTPUT); + p->set_can_loopback(loopback); + p->can_clear(panda::PANDA_CAN_RX); + return p; +} + +std::vector checked_panda_send(std::unique_ptr& p, uint32_t addr, bool is_29b, + char* msg, uint8_t len, unsigned int num_expected, const __LineInfo* pLineInfo, unsigned long timeout_ms) { + Assert::IsTrue(p->can_send(addr, is_29b, (const uint8_t*)msg, len, panda::PANDA_CAN1), _T("Panda send says it failed."), pLineInfo); + auto panda_msg_recv = panda_recv_loop(p, 1 + num_expected, timeout_ms); + check_panda_can_msg(panda_msg_recv[0], 0, addr, is_29b, TRUE, std::string(msg, len), pLineInfo); + panda_msg_recv.erase(panda_msg_recv.begin()); + return panda_msg_recv; +} diff --git a/panda/drivers/windows/pandaJ2534DLL Test/TestHelpers.h b/panda/drivers/windows/pandaJ2534DLL Test/TestHelpers.h new file mode 100644 index 00000000000000..9df59d7b5e1ac0 --- /dev/null +++ b/panda/drivers/windows/pandaJ2534DLL Test/TestHelpers.h @@ -0,0 +1,48 @@ +#pragma once +#include "stdafx.h" +#include "pandaJ2534DLL/J2534_v0404.h" +#include "panda_shared/panda.h" + +using namespace Microsoft::VisualStudio::CppUnitTestFramework; + +extern void write_ioctl(unsigned int chanid, unsigned int param, unsigned int val, const __LineInfo* pLineInfo = NULL); + +extern std::vector panda_recv_loop_loose(std::unique_ptr& p, unsigned int min_num, unsigned long timeout_ms = 100); + +extern std::vector panda_recv_loop(std::unique_ptr& p, unsigned int num_expected, unsigned long timeout_ms = 100); + +extern void check_panda_can_msg(panda::PANDA_CAN_MSG& msgin, uint8_t bus, unsigned long addr, bool addr_29b, + bool is_receipt, std::string dat, const __LineInfo* pLineInfo = NULL); + +extern unsigned long J2534_start_periodic_msg_checked(unsigned long chanid, unsigned long ProtocolID, unsigned long TxFlags, unsigned long DataSize, + unsigned long ExtraDataIndex, const char * Data, unsigned long TimeInterval, const __LineInfo * pLineInfo); + +extern unsigned long J2534_start_periodic_msg(unsigned long chanid, unsigned long ProtocolID, unsigned long TxFlags, unsigned long DataSize, + unsigned long ExtraDataIndex, const char* Data, unsigned long TimeInterval, unsigned long* msgID, const __LineInfo* pLineInfo = NULL); + +extern void J2534_send_msg_checked(unsigned long chanid, unsigned long ProtocolID, unsigned long RxStatus, unsigned long TxFlags, + unsigned long Timestamp, unsigned long DataSize, unsigned long ExtraDataIndex, const char* Data, const __LineInfo* pLineInfo = NULL); + +extern long J2534_send_msg(unsigned long chanid, unsigned long ProtocolID, unsigned long RxStatus, unsigned long TxFlags, + unsigned long Timestamp, unsigned long DataSize, unsigned long ExtraDataIndex, const char* Data); + +extern std::vector j2534_recv_loop_loose(unsigned int chanid, unsigned int min_num, unsigned long timeout_ms = 100); + +extern std::vector j2534_recv_loop(unsigned int chanid, unsigned int num_expected, unsigned long timeout_ms = 100); + +extern void check_J2534_can_msg(PASSTHRU_MSG& msgin, unsigned long ProtocolID, unsigned long RxStatus, unsigned long TxFlags, + unsigned long DataSize, unsigned long ExtraDataIndex, const char* Data, const __LineInfo* pLineInfo = NULL); + +extern unsigned long J2534_set_PASS_filter(unsigned long chanid, unsigned long ProtocolID, unsigned long tx, + unsigned long len, char* mask, char* pattern, const __LineInfo* pLineInfo = NULL); + +extern unsigned long J2534_set_BLOCK_filter(unsigned long chanid, unsigned long ProtocolID, unsigned long tx, + unsigned long len, char* mask, char* pattern, const __LineInfo* pLineInfo = NULL); + +extern unsigned long J2534_set_flowctrl_filter(unsigned long chanid, unsigned long tx, + unsigned long len, char* mask, char* pattern, char* flow, const __LineInfo* pLineInfo = NULL); + +extern std::unique_ptr getPanda(unsigned long kbaud = 500, BOOL loopback = FALSE); + +extern std::vector checked_panda_send(std::unique_ptr& p, uint32_t addr, bool is_29b, + char* msg, uint8_t len, unsigned int num_expected=0, const __LineInfo* pLineInfo = NULL, unsigned long timeout_ms = 100); diff --git a/panda/drivers/windows/pandaJ2534DLL Test/Timer.cpp b/panda/drivers/windows/pandaJ2534DLL Test/Timer.cpp new file mode 100644 index 00000000000000..33d029e844a7a5 --- /dev/null +++ b/panda/drivers/windows/pandaJ2534DLL Test/Timer.cpp @@ -0,0 +1,21 @@ +#include "stdafx.h" +#include "Timer.h" + + +Timer::Timer() +{ + reset(); +} + +// gets the time elapsed from construction. +unsigned long long /*milliseconds*/ Timer::getTimePassed(){ + // get the new time + auto end = std::chrono::time_point_cast(clock::now()); + + // return the difference of the times + return (end - start).count(); +} + +void Timer::reset() { + start = std::chrono::time_point_cast(clock::now()); +} \ No newline at end of file diff --git a/panda/drivers/windows/pandaJ2534DLL Test/Timer.h b/panda/drivers/windows/pandaJ2534DLL Test/Timer.h new file mode 100644 index 00000000000000..cbf5579a5cfa4b --- /dev/null +++ b/panda/drivers/windows/pandaJ2534DLL Test/Timer.h @@ -0,0 +1,20 @@ +#pragma once +#include + +//Copied from https://stackoverflow.com/a/31488113 + +class Timer +{ + using clock = std::chrono::steady_clock; + using time_point_type = std::chrono::time_point < clock, std::chrono::milliseconds >; +public: + Timer(); + + // gets the time elapsed from construction. + unsigned long long /*milliseconds*/ getTimePassed(); + + void reset(); + +private: + time_point_type start; +}; \ No newline at end of file diff --git a/panda/drivers/windows/pandaJ2534DLL Test/j2534_tests.cpp b/panda/drivers/windows/pandaJ2534DLL Test/j2534_tests.cpp new file mode 100644 index 00000000000000..674569acccafd3 --- /dev/null +++ b/panda/drivers/windows/pandaJ2534DLL Test/j2534_tests.cpp @@ -0,0 +1,1602 @@ +#include "stdafx.h" +#include "Loader4.h" +#include "pandaJ2534DLL/J2534_v0404.h" +#include "panda_shared/panda.h" +#include "Timer.h" +#include "ECUsim DLL\ECUsim.h" +#include "TestHelpers.h" + +using namespace Microsoft::VisualStudio::CppUnitTestFramework; + +namespace pandaJ2534DLLTest +{ + TEST_CLASS(J2534DLLInitialization) + { + public: + + TEST_CLASS_CLEANUP(deinit) { + UnloadJ2534Dll(); + } + + TEST_METHOD(J2534_Driver_Init) + { + long err = LoadJ2534Dll("pandaJ2534_0404_32.dll"); + Assert::IsTrue(err == 0, _T("Library failed to load properly. Check the export names and library location.")); + } + + }; + + TEST_CLASS(J2534DeviceInitialization) + { + public: + + TEST_METHOD_INITIALIZE(init) { + LoadJ2534Dll("pandaJ2534_0404_32.dll"); + } + + TEST_METHOD_CLEANUP(deinit) { + if (didopen) { + PassThruClose(devid); + didopen = FALSE; + } + UnloadJ2534Dll(); + } + + TEST_METHOD(J2534_Device_OpenDevice__Empty) + { + Assert::AreEqual(STATUS_NOERROR, open_dev(""), _T("Failed to open device."), LINE_INFO()); + } + + TEST_METHOD(J2534_Device_OpenDevice__J2534_2) + { + Assert::AreEqual(STATUS_NOERROR, open_dev("J2534-2:"), _T("Failed to open device."), LINE_INFO()); + } + + TEST_METHOD(J2534_Device_OpenDevice__SN) + { + auto pandas_available = panda::Panda::listAvailablePandas(); + Assert::IsTrue(pandas_available.size() > 0, _T("No pandas detected.")); + + Assert::AreEqual(STATUS_NOERROR, open_dev(pandas_available[0].c_str()), _T("Failed to open device."), LINE_INFO()); + + auto pandas_available_2 = panda::Panda::listAvailablePandas(); + for (auto panda_sn : pandas_available_2) + Assert::AreNotEqual(panda_sn, pandas_available[0]); + } + + TEST_METHOD(J2534_Device_CloseDevice) + { + Assert::AreEqual(STATUS_NOERROR, open_dev(""), _T("Failed to open device."), LINE_INFO()); + Assert::AreEqual(STATUS_NOERROR, close_dev(devid), _T("Failed to close device."), LINE_INFO()); + Assert::AreEqual(ERR_INVALID_DEVICE_ID, PassThruClose(devid), _T("The 2nd close should have failed with ERR_INVALID_DEVICE_ID."), LINE_INFO()); + } + + TEST_METHOD(J2534_Device_ConnectDisconnect) + { + unsigned long chanid; + Assert::AreEqual(STATUS_NOERROR, open_dev(""), _T("Failed to open device."), LINE_INFO()); + Assert::AreEqual(STATUS_NOERROR, PassThruConnect(devid, CAN, 0, 500000, &chanid), _T("Failed to open channel."), LINE_INFO()); + + Assert::AreEqual(STATUS_NOERROR, PassThruDisconnect(chanid), _T("Failed to close channel."), LINE_INFO()); + Assert::AreEqual(ERR_INVALID_CHANNEL_ID, PassThruDisconnect(chanid), _T("The 2nd disconnect should have failed with ERR_INVALID_CHANNEL_ID."), LINE_INFO()); + } + + TEST_METHOD(J2534_Device_ConnectInvalidProtocol) + { + unsigned long chanid; + Assert::AreEqual(STATUS_NOERROR, open_dev(""), _T("Failed to open device."), LINE_INFO()); + Assert::AreEqual(ERR_INVALID_PROTOCOL_ID, PassThruConnect(devid, 999, 0, 500000, &chanid), + _T("Did not report ERR_INVALID_PROTOCOL_ID."), LINE_INFO()); + Assert::AreEqual(ERR_INVALID_CHANNEL_ID, PassThruDisconnect(chanid), _T("The channel should not have been created."), LINE_INFO()); + } + + bool didopen = FALSE; + unsigned long devid; + + unsigned long open_dev(const char* name, long assert_err = STATUS_NOERROR, TCHAR* failmsg = _T("Failed to open device.")) { + unsigned int res = PassThruOpen((void*)name, &devid); + if (res == STATUS_NOERROR) didopen = TRUE; + return res; + } + + unsigned long close_dev(unsigned long devid) { + unsigned long res = PassThruClose(devid); + if (res == STATUS_NOERROR) didopen = FALSE; + return res; + } + + }; + + TEST_CLASS(J2534DeviceCAN) + { + public: + + TEST_METHOD_INITIALIZE(init) { + LoadJ2534Dll("pandaJ2534_0404_32.dll"); + } + + TEST_METHOD_CLEANUP(deinit) { + if (didopen) { + PassThruClose(devid); + didopen = FALSE; + } + UnloadJ2534Dll(); + } + + //Test that the BAUD rate of a CAN connection can be changed. + TEST_METHOD(J2534_CAN_SetBaud) + { + auto chanid = J2534_open_and_connect("", CAN, 0, 500000, LINE_INFO()); + write_ioctl(chanid, LOOPBACK, TRUE, LINE_INFO()); // ENABLE J2534 ECHO/LOOPBACK + auto p = getPanda(250); + + J2534_send_msg_checked(chanid, CAN, 0, 0, 0, 4 + 2, 0, "\x0\x0\x3\xAB""HI", LINE_INFO()); + j2534_recv_loop(chanid, 0); + panda_recv_loop(p, 0); + + write_ioctl(chanid, DATA_RATE, 250000, LINE_INFO()); + + auto j2534_msg_recv = j2534_recv_loop(chanid, 1); + check_J2534_can_msg(j2534_msg_recv[0], CAN, TX_MSG_TYPE, 0, 4 + 2, 0, "\x0\x0\x3\xAB""HI", LINE_INFO()); + auto panda_msg_recv = panda_recv_loop(p, 1); + check_panda_can_msg(panda_msg_recv[0], 0, 0x3AB, FALSE, FALSE, "HI", LINE_INFO()); + } + + TEST_METHOD(J2534_CAN_11b_Tx) + { + auto chanid = J2534_open_and_connect("", CAN, 0, 500000, LINE_INFO()); + auto p = getPanda(500); + + J2534_send_msg_checked(chanid, CAN, 0, 0, 0, 6, 6, "\x0\x0\x3\xAB""HI", LINE_INFO()); + + std::vector msg_recv = panda_recv_loop(p, 1); + check_panda_can_msg(msg_recv[0], 0, 0x3AB, FALSE, FALSE, "HI", LINE_INFO()); + + j2534_recv_loop(chanid, 0, 50); // Check no message is returned (since loopback is off) + } + + TEST_METHOD(J2534_CAN_29b_Tx) + { + auto chanid = J2534_open_and_connect("", CAN, CAN_29BIT_ID, 500000, LINE_INFO()); + auto p = getPanda(500); + + Assert::AreEqual(ERR_INVALID_MSG, J2534_send_msg(chanid, CAN, 0, 0, 0, 6, 6, "\x0\x0\x3\xAB""HI"), _T("11b address should fail to tx."), LINE_INFO()); + J2534_send_msg_checked(chanid, CAN, 0, CAN_29BIT_ID, 0, 6, 6, "\x0\x0\x3\xAB""YO", LINE_INFO()); + + std::vector msg_recv = panda_recv_loop(p, 1); + check_panda_can_msg(msg_recv[0], 0, 0x3AB, TRUE, FALSE, "YO", LINE_INFO()); + } + + TEST_METHOD(J2534_CAN_11b29b_Tx) + { + auto chanid = J2534_open_and_connect("", CAN, CAN_ID_BOTH, 500000, LINE_INFO()); + auto p = getPanda(500); + + J2534_send_msg_checked(chanid, CAN, 0, 0, 0, 6, 6, "\x0\x0\x3\xAB""HI", LINE_INFO()); + J2534_send_msg_checked(chanid, CAN, 0, CAN_29BIT_ID, 0, 6, 6, "\x0\x0\x3\xAB""YO", LINE_INFO()); + + std::vector msg_recv = panda_recv_loop(p, 2); + check_panda_can_msg(msg_recv[0], 0, 0x3AB, FALSE, FALSE, "HI", LINE_INFO()); + check_panda_can_msg(msg_recv[1], 0, 0x3AB, TRUE, FALSE, "YO", LINE_INFO()); + } + + TEST_METHOD(J2534_CAN_TxEcho) + { + auto chanid = J2534_open_and_connect("", CAN, 0, 500000, LINE_INFO()); + auto p = getPanda(500); + + J2534_send_msg_checked(chanid, CAN, 0, 0, 0, 9, 9, "\x0\x0\x3\xAB""HIDOG", LINE_INFO()); + + auto msg_recv = panda_recv_loop(p, 1); + check_panda_can_msg(msg_recv[0], 0, 0x3AB, FALSE, FALSE, "HIDOG", LINE_INFO()); + + auto j2534_msg_recv = j2534_recv_loop(chanid, 0); + + ///////////////////////////////// + write_ioctl(chanid, LOOPBACK, TRUE, LINE_INFO()); // ENABLE J2534 ECHO/LOOPBACK + + J2534_send_msg_checked(chanid, CAN, 0, 0, 0, 7, 7, "\x0\x0\x3\xAB""SUP", LINE_INFO()); + + msg_recv = panda_recv_loop(p, 1); + check_panda_can_msg(msg_recv[0], 0, 0x3AB, FALSE, FALSE, "SUP", LINE_INFO()); + + j2534_msg_recv = j2534_recv_loop(chanid, 1); + check_J2534_can_msg(j2534_msg_recv[0], CAN, TX_MSG_TYPE, 0, 3 + 4, 0, "\x0\x0\x3\xAB""SUP", LINE_INFO()); + } + + TEST_METHOD(J2534_CAN_RxAndPassAllFilters) + { + auto chanid = J2534_open_and_connect("", CAN, 0, 500000, LINE_INFO()); + J2534_set_PASS_filter(chanid, CAN, 0, 4, "\x0\x0\x0\x0", "\x0\x0\x0\x0", LINE_INFO()); + auto p = getPanda(500); + + p->can_send(0x1FA, FALSE, (const uint8_t*)"ABCDE", 5, panda::PANDA_CAN1); + p->can_send(0x2AC, FALSE, (const uint8_t*)"HIJKL", 5, panda::PANDA_CAN1); + + auto j2534_msg_recv = j2534_recv_loop(chanid, 2); + check_J2534_can_msg(j2534_msg_recv[0], CAN, 0, 0, 5 + 4, 0, "\x0\x0\x1\xFA""ABCDE", LINE_INFO()); + check_J2534_can_msg(j2534_msg_recv[1], CAN, 0, 0, 5 + 4, 0, "\x0\x0\x2\xAC""HIJKL", LINE_INFO()); + } + + TEST_METHOD(J2534_CAN_RxAndLimitedPassFilter) + { + auto chanid = J2534_open_and_connect("", CAN, 0, 500000, LINE_INFO()); + J2534_set_PASS_filter(chanid, CAN, 0, 4, "\xFF\xFF\xFF\xFF", "\x0\x0\x02\xAC", LINE_INFO()); + auto p = getPanda(500); + + p->can_send(0x1FA, FALSE, (const uint8_t*)"ABCDE", 5, panda::PANDA_CAN1); + p->can_send(0x2AC, FALSE, (const uint8_t*)"HIJKL", 5, panda::PANDA_CAN1); + + auto j2534_msg_recv = j2534_recv_loop(chanid, 1); + check_J2534_can_msg(j2534_msg_recv[0], CAN, 0, 0, 5 + 4, 0, "\x0\x0\x2\xAC""HIJKL", LINE_INFO()); + } + + TEST_METHOD(J2534_CAN_RxAndPassBlockFilter) + { + auto chanid = J2534_open_and_connect("", CAN, 0, 500000, LINE_INFO()); + J2534_set_PASS_filter(chanid, CAN, 0, 4, "\x0\x0\x0\x0", "\x0\x0\x0\x0", LINE_INFO()); + J2534_set_BLOCK_filter(chanid, CAN, 0, 4, "\xFF\xFF\xFF\xFF", "\x0\x0\x02\xAC", LINE_INFO()); + auto p = getPanda(500); + + p->can_send(0x1FA, FALSE, (const uint8_t*)"ABCDE", 5, panda::PANDA_CAN1); + p->can_send(0x2AC, FALSE, (const uint8_t*)"HIJKL", 5, panda::PANDA_CAN1); + p->can_send(0x3FA, FALSE, (const uint8_t*)"MNOPQ", 5, panda::PANDA_CAN1); + + auto j2534_msg_recv = j2534_recv_loop(chanid, 2, 1000); + check_J2534_can_msg(j2534_msg_recv[0], CAN, 0, 0, 5 + 4, 0, "\x0\x0\x1\xFA""ABCDE", LINE_INFO()); + check_J2534_can_msg(j2534_msg_recv[1], CAN, 0, 0, 5 + 4, 0, "\x0\x0\x3\xFA""MNOPQ", LINE_INFO()); + } + + //Check that the order of the pass and block filter do not matter + TEST_METHOD(J2534_CAN_RxAndFilterBlockPass) + { + auto chanid = J2534_open_and_connect("", CAN, 0, 500000, LINE_INFO()); + J2534_set_BLOCK_filter(chanid, CAN, 0, 4, "\xFF\xFF\xFF\xFF", "\x0\x0\x02\xAC", LINE_INFO()); + J2534_set_PASS_filter(chanid, CAN, 0, 4, "\x0\x0\x0\x0", "\x0\x0\x0\x0", LINE_INFO()); + auto p = getPanda(500); + + p->can_send(0x1FA, FALSE, (const uint8_t*)"ABCDE", 5, panda::PANDA_CAN1); + p->can_send(0x2AC, FALSE, (const uint8_t*)"HIJKL", 5, panda::PANDA_CAN1); // Should not pass filter + p->can_send(0x3FA, FALSE, (const uint8_t*)"MNOPQ", 5, panda::PANDA_CAN1); + + auto j2534_msg_recv = j2534_recv_loop(chanid, 2, 2000); + check_J2534_can_msg(j2534_msg_recv[0], CAN, 0, 0, 5 + 4, 0, "\x0\x0\x1\xFA""ABCDE", LINE_INFO()); + check_J2534_can_msg(j2534_msg_recv[1], CAN, 0, 0, 5 + 4, 0, "\x0\x0\x3\xFA""MNOPQ", LINE_INFO()); + } + + //Check that the order of the pass and block filter do not matter + TEST_METHOD(J2534_CAN_RxAndFilterRemoval) + { + auto chanid = J2534_open_and_connect("", CAN, 0, 500000, LINE_INFO()); + auto filterid0 = J2534_set_BLOCK_filter(chanid, CAN, 0, 4, "\xFF\xFF\xFF\xFF", "\x0\x0\x02\xAC", LINE_INFO()); + auto filterid1 = J2534_set_PASS_filter(chanid, CAN, 0, 4, "\x0\x0\x0\x0", "\x0\x0\x0\x0", LINE_INFO()); + + Assert::AreEqual(STATUS_NOERROR, PassThruStopMsgFilter(chanid, filterid0), _T("Failed to delete filter."), LINE_INFO()); + + auto p = getPanda(500); + + p->can_send(0x1FA, FALSE, (const uint8_t*)"ABCDE", 5, panda::PANDA_CAN1); + p->can_send(0x2AC, FALSE, (const uint8_t*)"HIJKL", 5, panda::PANDA_CAN1); + p->can_send(0x3FA, FALSE, (const uint8_t*)"MNOPQ", 5, panda::PANDA_CAN1); + + auto j2534_msg_recv = j2534_recv_loop(chanid, 3, 1000); + check_J2534_can_msg(j2534_msg_recv[0], CAN, 0, 0, 5 + 4, 0, "\x0\x0\x1\xFA""ABCDE", LINE_INFO()); + check_J2534_can_msg(j2534_msg_recv[1], CAN, 0, 0, 5 + 4, 0, "\x0\x0\x2\xAC""HIJKL", LINE_INFO()); + check_J2534_can_msg(j2534_msg_recv[2], CAN, 0, 0, 5 + 4, 0, "\x0\x0\x3\xFA""MNOPQ", LINE_INFO()); + } + + //Check that the order of the pass and block filter do not matter + TEST_METHOD(J2534_CAN_RxWithTimeout) + { + auto chanid = J2534_open_and_connect("", CAN, 0, 500000, LINE_INFO()); + J2534_set_PASS_filter(chanid, CAN, 0, 4, "\x0\x0\x0\x0", "\x0\x0\x0\x0", LINE_INFO()); + auto p = getPanda(500); + + PASSTHRU_MSG recvbuff; + unsigned long msgcount = 1; + unsigned int res = PassThruReadMsgs(chanid, &recvbuff, &msgcount, 100); // Here is where we test the timeout + Assert::AreEqual(ERR_BUFFER_EMPTY, res, _T("No message should be found"), LINE_INFO()); + Assert::AreEqual(0, msgcount, _T("Received wrong number of messages.")); + + //TODO Test that the timings work right instead of just testing it doesn't crash. + } + + TEST_METHOD(J2534_CAN_Baud) + { + auto chanid = J2534_open_and_connect("", CAN, 0, 250000, LINE_INFO()); + auto p = getPanda(250); + + J2534_send_msg_checked(chanid, CAN, 0, 0, 0, 6, 6, "\x0\x0\x3\xAB""HI", LINE_INFO()); + + std::vector msg_recv = panda_recv_loop(p, 1); + check_panda_can_msg(msg_recv[0], 0, 0x3AB, FALSE, FALSE, "HI", LINE_INFO()); + } + + TEST_METHOD(J2534_CAN_PeriodicMessageStartStop) + { + auto chanid = J2534_open_and_connect("", CAN, 0, 500000, LINE_INFO()); + auto p = getPanda(500); + + auto msgid = J2534_start_periodic_msg_checked(chanid, CAN, 0, 6, 0, "\x0\x0\x3\xAB""HI", 100, LINE_INFO()); + + std::vector msg_recv = panda_recv_loop(p, 3, 250); + Assert::AreEqual(STATUS_NOERROR, PassThruStopPeriodicMsg(chanid, msgid), _T("Failed to delete filter."), LINE_INFO()); + check_panda_can_msg(msg_recv[0], 0, 0x3AB, FALSE, FALSE, "HI", LINE_INFO()); + check_panda_can_msg(msg_recv[1], 0, 0x3AB, FALSE, FALSE, "HI", LINE_INFO()); + check_panda_can_msg(msg_recv[2], 0, 0x3AB, FALSE, FALSE, "HI", LINE_INFO()); + + auto timediff_1_0 = msg_recv[1].recv_time - msg_recv[0].recv_time; + auto timediff_2_1 = msg_recv[2].recv_time - msg_recv[1].recv_time; + + std::ostringstream stringStream1; + stringStream1 << "times1: " << timediff_1_0 << ", " << timediff_2_1 << std::endl; + Logger::WriteMessage(stringStream1.str().c_str()); + + Assert::IsTrue(timediff_1_0 > 90000); + Assert::IsTrue(timediff_1_0 < 110000); + Assert::IsTrue(timediff_2_1 > 90000); + Assert::IsTrue(timediff_2_1 < 110000); + + msg_recv = panda_recv_loop(p, 0, 300); + } + + TEST_METHOD(J2534_CAN_PeriodicMessageMultipleStartStop) + { + auto chanid = J2534_open_and_connect("", CAN, 0, 500000, LINE_INFO()); + auto p = getPanda(500); + + auto msgid0 = J2534_start_periodic_msg_checked(chanid, CAN, 0, 6, 0, "\x0\x0\x3\xAB""HI", 100, LINE_INFO()); + auto msgid1 = J2534_start_periodic_msg_checked(chanid, CAN, 0, 6, 0, "\x0\x0\x1\x23""YO", 80, LINE_INFO()); + + std::vector msg_recv = panda_recv_loop(p, 9, 370); + Assert::AreEqual(STATUS_NOERROR, PassThruStopPeriodicMsg(chanid, msgid0), _T("Failed to delete filter."), LINE_INFO()); + Assert::AreEqual(STATUS_NOERROR, PassThruStopPeriodicMsg(chanid, msgid1), _T("Failed to delete filter."), LINE_INFO()); + //time diagram. 10 ms per character. * is send event. : is termination of periodic messages. + //*---------*---------*---------*-----:----* HI + //*-------*-------*-------*-------*---:----* YO + check_panda_can_msg(msg_recv[0], 0, 0x3AB, FALSE, FALSE, "HI", LINE_INFO()); + check_panda_can_msg(msg_recv[1], 0, 0x123, FALSE, FALSE, "YO", LINE_INFO()); + check_panda_can_msg(msg_recv[2], 0, 0x123, FALSE, FALSE, "YO", LINE_INFO()); + check_panda_can_msg(msg_recv[3], 0, 0x3AB, FALSE, FALSE, "HI", LINE_INFO()); + check_panda_can_msg(msg_recv[4], 0, 0x123, FALSE, FALSE, "YO", LINE_INFO()); + check_panda_can_msg(msg_recv[5], 0, 0x3AB, FALSE, FALSE, "HI", LINE_INFO()); + check_panda_can_msg(msg_recv[6], 0, 0x123, FALSE, FALSE, "YO", LINE_INFO()); + check_panda_can_msg(msg_recv[7], 0, 0x3AB, FALSE, FALSE, "HI", LINE_INFO()); + check_panda_can_msg(msg_recv[8], 0, 0x123, FALSE, FALSE, "YO", LINE_INFO()); + + auto timediff_HI_3_0 = msg_recv[3].recv_time - msg_recv[0].recv_time; + auto timediff_HI_5_3 = msg_recv[5].recv_time - msg_recv[3].recv_time; + auto timediff_HI_7_5 = msg_recv[7].recv_time - msg_recv[5].recv_time; + + auto timediff_YO_2_1 = msg_recv[2].recv_time - msg_recv[1].recv_time; + auto timediff_YO_4_2 = msg_recv[4].recv_time - msg_recv[2].recv_time; + auto timediff_YO_6_4 = msg_recv[6].recv_time - msg_recv[4].recv_time; + auto timediff_YO_8_6 = msg_recv[8].recv_time - msg_recv[6].recv_time; + + std::ostringstream stringStreamHi; + stringStreamHi << "HiTimes: " << timediff_HI_3_0 << ", " << timediff_HI_5_3 << ", " << timediff_HI_7_5 << std::endl; + Logger::WriteMessage(stringStreamHi.str().c_str()); + + std::ostringstream stringStreamYo; + stringStreamYo << "HiTimes: " << timediff_YO_2_1 << ", " << timediff_YO_4_2 << ", " << timediff_YO_6_4 << ", " << timediff_YO_8_6 << std::endl; + Logger::WriteMessage(stringStreamYo.str().c_str()); + + Assert::IsTrue(timediff_HI_3_0 > 90000); + Assert::IsTrue(timediff_HI_3_0 < 110000); + Assert::IsTrue(timediff_HI_5_3 > 90000); + Assert::IsTrue(timediff_HI_5_3 < 110000); + Assert::IsTrue(timediff_HI_7_5 > 90000); + Assert::IsTrue(timediff_HI_7_5 < 110000); + + Assert::IsTrue(timediff_YO_2_1 > 80000-10000); + Assert::IsTrue(timediff_YO_2_1 < 80000+1000); + Assert::IsTrue(timediff_YO_4_2 > 80000 - 10000); + Assert::IsTrue(timediff_YO_4_2 < 80000 + 10000); + Assert::IsTrue(timediff_YO_6_4 > 80000 - 10000); + Assert::IsTrue(timediff_YO_6_4 < 80000 + 10000); + Assert::IsTrue(timediff_YO_8_6 > 80000 - 10000); + Assert::IsTrue(timediff_YO_8_6 < 80000 + 10000); + + msg_recv = panda_recv_loop(p, 0, 300); + } + + TEST_METHOD(J2534_CAN_PeriodicMessageStartStop_Loopback) + { + auto chanid = J2534_open_and_connect("", CAN, 0, 500000, LINE_INFO()); + write_ioctl(chanid, LOOPBACK, TRUE, LINE_INFO()); // ENABLE J2534 ECHO/LOOPBACK + auto p = getPanda(500); + auto msgid = J2534_start_periodic_msg_checked(chanid, CAN, 0, 6, 0, "\x0\x0\x3\xAB""HI", 100, LINE_INFO()); + + std::vector msg_recv = panda_recv_loop(p, 3, 250); + Assert::AreEqual(STATUS_NOERROR, PassThruStopPeriodicMsg(chanid, msgid), _T("Failed to delete filter."), LINE_INFO()); + check_panda_can_msg(msg_recv[0], 0, 0x3AB, FALSE, FALSE, "HI", LINE_INFO()); + check_panda_can_msg(msg_recv[1], 0, 0x3AB, FALSE, FALSE, "HI", LINE_INFO()); + check_panda_can_msg(msg_recv[2], 0, 0x3AB, FALSE, FALSE, "HI", LINE_INFO()); + + auto j2534_msg_recv = j2534_recv_loop(chanid, 3); + check_J2534_can_msg(j2534_msg_recv[0], CAN, TX_MSG_TYPE, 0, 6, 0, "\x0\x0\x3\xAB""HI", LINE_INFO()); + check_J2534_can_msg(j2534_msg_recv[1], CAN, TX_MSG_TYPE, 0, 6, 0, "\x0\x0\x3\xAB""HI", LINE_INFO()); + check_J2534_can_msg(j2534_msg_recv[2], CAN, TX_MSG_TYPE, 0, 6, 0, "\x0\x0\x3\xAB""HI", LINE_INFO()); + + auto timediff_1_0 = j2534_msg_recv[1].Timestamp - j2534_msg_recv[0].Timestamp; + auto timediff_2_1 = j2534_msg_recv[2].Timestamp - j2534_msg_recv[1].Timestamp; + + std::ostringstream stringStream1; + stringStream1 << "times1: " << timediff_1_0 << ", " << timediff_2_1 << std::endl; + Logger::WriteMessage(stringStream1.str().c_str()); + + Assert::IsTrue(timediff_1_0 > 90000); + Assert::IsTrue(timediff_1_0 < 110000); + Assert::IsTrue(timediff_2_1 > 90000); + Assert::IsTrue(timediff_2_1 < 110000); + + msg_recv = panda_recv_loop(p, 0, 300); + } + + TEST_METHOD(J2534_CAN_PeriodicMessageWithTx) + { + auto chanid = J2534_open_and_connect("", CAN, 0, 500000, LINE_INFO()); + auto p = getPanda(500); + auto msgid = J2534_start_periodic_msg_checked(chanid, CAN, 0, 6, 0, "\x0\x0\x3\xAB""HI", 100, LINE_INFO()); + + J2534_send_msg(chanid, CAN, 0, 0, 0, 7, 0, "\x0\x0\x3\xAB""LOL"); + + std::vector msg_recv = panda_recv_loop(p, 4, 250); + Assert::AreEqual(STATUS_NOERROR, PassThruStopPeriodicMsg(chanid, msgid), _T("Failed to delete filter."), LINE_INFO()); + check_panda_can_msg(msg_recv[0], 0, 0x3AB, FALSE, FALSE, "HI", LINE_INFO()); + check_panda_can_msg(msg_recv[1], 0, 0x3AB, FALSE, FALSE, "LOL", LINE_INFO());//Staggered write inbetween multiple scheduled TXs + check_panda_can_msg(msg_recv[2], 0, 0x3AB, FALSE, FALSE, "HI", LINE_INFO()); + check_panda_can_msg(msg_recv[3], 0, 0x3AB, FALSE, FALSE, "HI", LINE_INFO()); + + auto timediff_2_0 = msg_recv[2].recv_time - msg_recv[0].recv_time; + auto timediff_3_2 = msg_recv[3].recv_time - msg_recv[2].recv_time; + + std::ostringstream stringStream1; + stringStream1 << "times1: " << timediff_2_0 << ", " << timediff_3_2 << std::endl; + Logger::WriteMessage(stringStream1.str().c_str()); + + Assert::IsTrue(timediff_2_0 > 90000); + Assert::IsTrue(timediff_2_0 < 110000); + Assert::IsTrue(timediff_3_2 > 90000); + Assert::IsTrue(timediff_3_2 < 110000); + + msg_recv = panda_recv_loop(p, 0, 300); + } + + TEST_METHOD(J2534_CAN_BaudInvalid) + { + unsigned long chanid; + Assert::AreEqual(STATUS_NOERROR, open_dev(""), _T("Failed to open device."), LINE_INFO()); + Assert::AreEqual(ERR_INVALID_BAUDRATE, PassThruConnect(devid, CAN, 0, 6000000, &chanid), _T("Baudrate should have been invalid."), LINE_INFO()); + Assert::AreEqual(ERR_INVALID_BAUDRATE, PassThruConnect(devid, CAN, 0, 200, &chanid), _T("Baudrate should have been invalid."), LINE_INFO()); + Assert::AreEqual(ERR_INVALID_BAUDRATE, PassThruConnect(devid, CAN, 0, 250010, &chanid), _T("Baudrate should have been invalid."), LINE_INFO()); + } + + bool didopen = FALSE; + unsigned long devid; + + unsigned long open_dev(const char* name, long assert_err = STATUS_NOERROR, TCHAR* failmsg = _T("Failed to open device.")) { + unsigned int res = PassThruOpen((void*)name, &devid); + if (res == STATUS_NOERROR) didopen = TRUE; + return res; + } + + unsigned long J2534_open_and_connect(const char* name, unsigned long ProtocolID, unsigned long Flags, unsigned long bps, const __LineInfo* pLineInfo = NULL) { + unsigned long chanid; + Assert::AreEqual(STATUS_NOERROR, open_dev(name), _T("Failed to open device."), pLineInfo); + Assert::AreEqual(STATUS_NOERROR, PassThruConnect(devid, ProtocolID, Flags, bps, &chanid), _T("Failed to open channel."), pLineInfo); + write_ioctl(chanid, LOOPBACK, FALSE, LINE_INFO()); // DISABLE J2534 ECHO/LOOPBACK + return chanid; + } + + }; + + TEST_CLASS(J2534DeviceISO15765) + { + public: + + TEST_METHOD_INITIALIZE(init) { + LoadJ2534Dll("pandaJ2534_0404_32.dll"); + } + + TEST_METHOD_CLEANUP(deinit) { + if (didopen) { + PassThruClose(devid); + didopen = FALSE; + } + UnloadJ2534Dll(); + } + + //Test that the BAUD rate of a ISO15765 connection can be changed. + TEST_METHOD(J2534_ISO15765_SetBaud) + { + auto chanid = J2534_open_and_connect("", ISO15765, 0, 500000, LINE_INFO()); + write_ioctl(chanid, LOOPBACK, TRUE, LINE_INFO()); // ENABLE J2534 ECHO/LOOPBACK + auto p = getPanda(250); + + J2534_send_msg_checked(chanid, ISO15765, 0, 0, 0, 4 + 2, 0, "\x0\x0\x3\xAB""HI", LINE_INFO()); + j2534_recv_loop(chanid, 0); + panda_recv_loop(p, 0); + + write_ioctl(chanid, DATA_RATE, 250000, LINE_INFO()); + + auto j2534_msg_recv = j2534_recv_loop(chanid, 2); + check_J2534_can_msg(j2534_msg_recv[0], ISO15765, TX_INDICATION, 0, 4, 0, "\x0\x0\x3\xAB", LINE_INFO()); + check_J2534_can_msg(j2534_msg_recv[1], ISO15765, TX_MSG_TYPE, 0, 4 + 2, 0, "\x0\x0\x3\xAB""HI", LINE_INFO()); + auto panda_msg_recv = panda_recv_loop(p, 1); + check_panda_can_msg(panda_msg_recv[0], 0, 0x3AB, FALSE, FALSE, "\x2""HI", LINE_INFO()); + } + + ///////////////////// Tests checking things don't send/receive ///////////////////// + + //Check tx PASSES and rx FAIL WITHOUT a filter. 29 bit. NO Filter. NoPadding. STD address. Single Frame. + TEST_METHOD(J2534_ISO15765_PassTxFailRx_29b_NoFilter_NoPad_STD_SF) + { + auto chanid = J2534_open_and_connect("", ISO15765, CAN_29BIT_ID, 500000, LINE_INFO()); + auto p = getPanda(500); + + //TX: works because all single frame writes should work (with or without a flow contorl filter) + J2534_send_msg_checked(chanid, ISO15765, 0, CAN_29BIT_ID, 0, 11, 0, "\x18\xda\xef\xf1""TX_TEST", LINE_INFO()); + auto j2534_msg_recv = j2534_recv_loop(chanid, 1); + check_J2534_can_msg(j2534_msg_recv[0], ISO15765, CAN_29BIT_ID | TX_INDICATION, 0, 4, 0, "\x18\xda\xef\xf1", LINE_INFO()); + + auto panda_msg_recv = panda_recv_loop(p, 1); + check_panda_can_msg(panda_msg_recv[0], 0, 0x18DAEFF1, TRUE, FALSE, "\x07""TX_TEST", LINE_INFO()); + + //RX: Reads require a flow control filter, and should fail without one. + checked_panda_send(p, 0x18DAF1EF, TRUE, "\x06\x41\x00\xff\xff\xff\xfe", 7, 0, LINE_INFO()); + j2534_recv_loop(chanid, 0); + } + + //Check tx and rx FAIL WITHOUT a filter. 29 bit. NO Filter. NoPadding. STD address. First Frame. + TEST_METHOD(J2534_ISO15765_FailTxRx_29b_NoFilter_NoPad_STD_FF) + { + auto chanid = J2534_open_and_connect("", ISO15765, CAN_29BIT_ID, 500000, LINE_INFO()); + auto p = getPanda(500); + + //TX + Assert::AreEqual(ERR_NO_FLOW_CONTROL, J2534_send_msg(chanid, ISO15765, 0, CAN_29BIT_ID, 0, 12, 0, "\x18\xda\xef\xf1\xA1\xB2\xC3\xD4\xE5\xF6\x09\x1A"), + _T("Should fail to tx without a filter."), LINE_INFO()); + j2534_recv_loop(chanid, 0); + panda_recv_loop(p, 0); + + //RX; Send full response and check didn't receive flow control from J2534 device + checked_panda_send(p, 0x18DAF1EF, TRUE, "\x10\x14\x49\x02\x01""1D4", 8, 0, LINE_INFO()); + checked_panda_send(p, 0x18DAF1EF, TRUE, "\x21""GP00R55", 8, 0, LINE_INFO()); + checked_panda_send(p, 0x18DAF1EF, TRUE, "\x22""B123456", 8, 0, LINE_INFO()); + j2534_recv_loop(chanid, 0);//Check a full message is not accepted. + } + + //Check tx PASSES and rx FAIL with a MISMATCHED filter. 29 bit. Mismatch Filter. NoPadding. STD address. Single Frame. + TEST_METHOD(J2534_ISO15765_PassTxFailRx_29b_MismatchFilter_NoPad_STD_SF) + { + auto chanid = J2534_open_and_connect("", ISO15765, CAN_29BIT_ID, 500000, LINE_INFO()); + J2534_set_flowctrl_filter(chanid, CAN_29BIT_ID, 4, "\xff\xff\xff\xff", "\x18\xda\xf1\xef", "\x18\xda\xef\xf1", LINE_INFO()); + auto p = getPanda(500); + + //TX: works because all single frame writes should work (with or without a flow contorl filter) + J2534_send_msg_checked(chanid, ISO15765, 0, CAN_29BIT_ID, 0, 6, 0, "\x18\xda\xe0\xf1""\x11\x22", LINE_INFO()); + auto j2534_msg_recv = j2534_recv_loop(chanid, 1); + check_J2534_can_msg(j2534_msg_recv[0], ISO15765, CAN_29BIT_ID | TX_INDICATION, 0, 4, 0, "\x18\xda\xe0\xf1", LINE_INFO()); + + auto panda_msg_recv = panda_recv_loop(p, 1); + check_panda_can_msg(panda_msg_recv[0], 0, 0x18DAE0F1, TRUE, FALSE, "\x02""\x11\x22", LINE_INFO()); + + //RX. Send ISO15765 single frame to device. Address still doesn't match filter, so should not be received. + checked_panda_send(p, 0x18DAF1E0, TRUE, "\x06\x41\x00\xff\xff\xff\xfe", 7, 0, LINE_INFO()); + j2534_recv_loop(chanid, 0); + } + + //Check tx and rx FAIL with a MISMATCHED filter. 29 bit. Mismatch Filter. NoPadding. STD address. First Frame. + TEST_METHOD(J2534_ISO15765_FailTxRx_29b_MismatchFilter_NoPad_STD_FF) + { + auto chanid = J2534_open_and_connect("", ISO15765, CAN_29BIT_ID, 500000, LINE_INFO()); + J2534_set_flowctrl_filter(chanid, CAN_29BIT_ID, 4, "\xff\xff\xff\xff", "\x18\xda\xf1\xef", "\x18\xda\xef\xf1", LINE_INFO()); + auto p = getPanda(500); + + //TX + Assert::AreEqual(ERR_NO_FLOW_CONTROL, J2534_send_msg(chanid, ISO15765, 0, CAN_29BIT_ID, 0, 12, 0, "\x18\xda\xe0\xf1""USELESS STUFF"), + _T("Should fail to tx without a filter."), LINE_INFO()); + j2534_recv_loop(chanid, 0); + panda_recv_loop(p, 0); + + //RX; Send a full response and check didn't receive flow control from J2534 device + checked_panda_send(p, 0x18DAF1E0, TRUE, "\x10\x14\x49\x02\x01""1D4", 8, 0, LINE_INFO()); + checked_panda_send(p, 0x18DAF1E0, TRUE, "\x21""GP00R55", 8, 0, LINE_INFO()); + checked_panda_send(p, 0x18DAF1E0, TRUE, "\x22""B123456", 8, 0, LINE_INFO()); + j2534_recv_loop(chanid, 0);//Check a full message is not accepted. + } + + //Check tx FAILS with a MISMATCHED filter 29bit flag. 29 bit. Mismatch Filter. NoPadding. STD address. Single Frame. + TEST_METHOD(J2534_ISO15765_FailTxRx_29b_MismatchFilterFlag29b_NoPad_STD_SF) + { + auto chanid = J2534_open_and_connect("", ISO15765, CAN_29BIT_ID, 500000, LINE_INFO()); + J2534_set_flowctrl_filter(chanid, CAN_29BIT_ID, 4, "\xff\xff\xff\xff", "\x0\x0\x1\xab", "\x0\x0\x1\xcd", LINE_INFO()); + auto p = getPanda(500); + + //TX + Assert::AreEqual(ERR_INVALID_MSG, J2534_send_msg(chanid, ISO15765, 0, 0, 0, 6, 0, "\x0/x0/x1/xcd\x01\x00"), + _T("mismatched address should fail to tx."), LINE_INFO()); + j2534_recv_loop(chanid, 0); + panda_recv_loop(p, 0); + + //RX. Send ISO15765 single frame to device. Address still doesn't match filter, so should not be received. + checked_panda_send(p, 0x1ab, FALSE, "\x06\x41\x00\xff\xff\xff\xfe", 7, 0, LINE_INFO()); + j2534_recv_loop(chanid, 0); + } + + ///////////////////// Tests checking things actually send/receive. Standard Addressing ///////////////////// + + //Check rx passes with filter. 29 bit. Good Filter. NoPadding. STD address. Single Frame. + TEST_METHOD(J2534_ISO15765_SuccessRx_29b_Filter_NoPad_STD_SF) + { + auto chanid = J2534_open_and_connect("", ISO15765, CAN_29BIT_ID, 500000, LINE_INFO()); + J2534_set_flowctrl_filter(chanid, CAN_29BIT_ID, 4, "\xff\xff\xff\xff", "\x18\xda\xf1\xef", "\x18\xda\xef\xf1", LINE_INFO()); + auto p = getPanda(500); + + checked_panda_send(p, 0x18DAF1EF, TRUE, "\x07""ABCD123", 8, 0, LINE_INFO()); + + auto j2534_msg_recv = j2534_recv_loop(chanid, 1); + check_J2534_can_msg(j2534_msg_recv[0], ISO15765, CAN_29BIT_ID, 0, 11, 11, "\x18\xda\xf1\xef""ABCD123", LINE_INFO()); + } + + //Check tx passes with filter. 29 bit. Good Filter. NoPadding. STD address. Single Frame. + TEST_METHOD(J2534_ISO15765_SuccessTx_29b_Filter_NoPad_STD_SF) + { + auto chanid = J2534_open_and_connect("", ISO15765, CAN_29BIT_ID, 500000, LINE_INFO()); + J2534_set_flowctrl_filter(chanid, CAN_29BIT_ID, 4, "\xff\xff\xff\xff", "\x18\xda\xf1\xef", "\x18\xda\xef\xf1", LINE_INFO()); + auto p = getPanda(500); + + J2534_send_msg_checked(chanid, ISO15765, 0, CAN_29BIT_ID, 0, 11, 0, "\x18\xda\xef\xf1""TX_TEST", LINE_INFO()); + auto j2534_msg_recv = j2534_recv_loop(chanid, 1); + check_J2534_can_msg(j2534_msg_recv[0], ISO15765, CAN_29BIT_ID | TX_INDICATION, 0, 4, 0, "\x18\xda\xef\xf1", LINE_INFO()); + + auto panda_msg_recv = panda_recv_loop(p, 1); + check_panda_can_msg(panda_msg_recv[0], 0, 0x18DAEFF1, TRUE, FALSE, "\x07""TX_TEST", LINE_INFO()); + } + + //Check tx passes with filter. 29 bit. Good Filter. NoPadding. STD address. Single Frame. Loopback. + TEST_METHOD(J2534_ISO15765_SuccessTx_29b_Filter_NoPad_STD_SF_LOOPBACK) + { + auto chanid = J2534_open_and_connect("", ISO15765, CAN_29BIT_ID, 500000, LINE_INFO()); + J2534_set_flowctrl_filter(chanid, CAN_29BIT_ID, 4, "\xff\xff\xff\xff", "\x18\xda\xf1\xef", "\x18\xda\xef\xf1", LINE_INFO()); + write_ioctl(chanid, LOOPBACK, TRUE, LINE_INFO()); + auto p = getPanda(500); + + J2534_send_msg_checked(chanid, ISO15765, 0, CAN_29BIT_ID, 0, 11, 0, "\x18\xda\xef\xf1""TX_TEST", LINE_INFO()); + auto j2534_msg_recv = j2534_recv_loop(chanid, 2); + check_J2534_can_msg(j2534_msg_recv[0], ISO15765, CAN_29BIT_ID | TX_INDICATION, 0, 4, 0, "\x18\xda\xef\xf1", LINE_INFO()); + check_J2534_can_msg(j2534_msg_recv[1], ISO15765, CAN_29BIT_ID | TX_MSG_TYPE, 0, 11, 0, "\x18\xda\xef\xf1""TX_TEST", LINE_INFO()); + + auto panda_msg_recv = panda_recv_loop(p, 1); + check_panda_can_msg(panda_msg_recv[0], 0, 0x18DAEFF1, TRUE, FALSE, "\x07""TX_TEST", LINE_INFO()); + } + + //Check rx passes with filter. 29 bit. Good Filter. NoPadding. STD address. Multi Frame. + TEST_METHOD(J2534_ISO15765_SuccessRx_29b_Filter_NoPad_STD_FFCF) + { + auto chanid = J2534_open_and_connect("", ISO15765, CAN_29BIT_ID, 500000, LINE_INFO()); + J2534_set_flowctrl_filter(chanid, CAN_29BIT_ID, 4, "\xff\xff\xff\xff", "\x18\xda\xf1\xef", "\x18\xda\xef\xf1", LINE_INFO()); + auto p = getPanda(500); + + //Send first frame, then check we get a flow control frame + auto panda_msg_recv = checked_panda_send(p, 0x18DAF1EF, TRUE, "\x10\x13""ninete", 8, 1, LINE_INFO()); + check_panda_can_msg(panda_msg_recv[0], 0, 0x18DAEFF1, TRUE, FALSE, std::string("\x30\x00\x00", 3), LINE_INFO()); + + //Check first frame is registered with J2534 + auto j2534_msg_recv = j2534_recv_loop(chanid, 1); + check_J2534_can_msg(j2534_msg_recv[0], ISO15765, CAN_29BIT_ID | START_OF_MESSAGE, 0, 4, 0, "\x18\xda\xf1\xef", LINE_INFO()); + + //Send the rest of the message + checked_panda_send(p, 0x18DAF1EF, TRUE, "\x21""en byte", 8, 0, LINE_INFO()); + checked_panda_send(p, 0x18DAF1EF, TRUE, "\x22""s here", 7, 0, LINE_INFO()); + + //Check J2534 constructed the whole message + j2534_msg_recv = j2534_recv_loop(chanid, 1); + check_J2534_can_msg(j2534_msg_recv[0], ISO15765, CAN_29BIT_ID, 0, 4 + 0x13, 4 + 0x13, "\x18\xda\xf1\xef""nineteen bytes here", LINE_INFO()); + } + + //Check multi frame tx passes with filter. 29 bit. Good Filter. NoPadding. STD address. Multi Frame. + TEST_METHOD(J2534_ISO15765_SuccessTx_29b_Filter_NoPad_STD_FFCF) + { + auto chanid = J2534_open_and_connect("", ISO15765, CAN_29BIT_ID, 500000, LINE_INFO()); + J2534_set_flowctrl_filter(chanid, CAN_29BIT_ID, 4, "\xff\xff\xff\xff", "\x18\xda\xf1\xef", "\x18\xda\xef\xf1", LINE_INFO()); + auto p = getPanda(500); + + J2534_send_msg_checked(chanid, ISO15765, 0, CAN_29BIT_ID, 0, 14, 0, "\x18\xda\xef\xf1""\xAA\xBB\xCC\xDD\xEE\xFF\x11\x22\x33\x44", LINE_INFO()); + auto j2534_msg_recv = j2534_recv_loop(chanid, 0); // No TxDone msg until after the final tx frame is sent + + auto panda_msg_recv = panda_recv_loop(p, 1); + check_panda_can_msg(panda_msg_recv[0], 0, 0x18DAEFF1, TRUE, FALSE, "\x10\x0A""\xAA\xBB\xCC\xDD\xEE\xFF", LINE_INFO()); + + panda_msg_recv = checked_panda_send(p, 0x18DAF1EF, TRUE, "\x30\x0\x0", 3, 1, LINE_INFO()); + check_panda_can_msg(panda_msg_recv[0], 0, 0x18DAEFF1, TRUE, FALSE, "\x21""\x11\x22\x33\x44", LINE_INFO()); + + j2534_msg_recv = j2534_recv_loop(chanid, 1); + check_J2534_can_msg(j2534_msg_recv[0], ISO15765, CAN_29BIT_ID | TX_INDICATION, 0, 4, 0, "\x18\xda\xef\xf1", LINE_INFO()); + } + + //Check rx passes with filter. 11 bit. Good Filter. NoPadding. STD address. Single Frame. + TEST_METHOD(J2534_ISO15765_SuccessRx_11b_Filter_NoPad_STD_SF) + { + auto chanid = J2534_open_and_connect("", ISO15765, 0, 500000, LINE_INFO()); + J2534_set_flowctrl_filter(chanid, 0, 4, "\xff\xff\xff\xff", "\x0\x0\x1\xab", "\x0\x0\x1\xcd", LINE_INFO()); + auto p = getPanda(500); + + checked_panda_send(p, 0x1ab, FALSE, "\x07""ABCD123", 8, 0, LINE_INFO()); + + auto j2534_msg_recv = j2534_recv_loop(chanid, 1); + check_J2534_can_msg(j2534_msg_recv[0], ISO15765, 0, 0, 11, 11, "\x0\x0\x1\xab""ABCD123", LINE_INFO()); + } + + //Check tx passes with filter. 11 bit. Good Filter. NoPadding. STD address. Single Frame. + TEST_METHOD(J2534_ISO15765_SuccessTx_11b_Filter_NoPad_STD_SF) + { + auto chanid = J2534_open_and_connect("", ISO15765, 0, 500000, LINE_INFO()); + J2534_set_flowctrl_filter(chanid, 0, 4, "\xff\xff\xff\xff", "\x0\x0\x1\xab", "\x0\x0\x1\xcd", LINE_INFO()); + auto p = getPanda(500); + + J2534_send_msg_checked(chanid, ISO15765, 0, 0, 0, 11, 0, "\x0\x0\x1\xcd""TX_TEST", LINE_INFO()); + auto j2534_msg_recv = j2534_recv_loop(chanid, 1); + check_J2534_can_msg(j2534_msg_recv[0], ISO15765, TX_INDICATION, 0, 4, 0, "\x0\x0\x1\xcd", LINE_INFO()); + + auto panda_msg_recv = panda_recv_loop(p, 1); + check_panda_can_msg(panda_msg_recv[0], 0, 0x1CD, FALSE, FALSE, "\x07""TX_TEST", LINE_INFO()); + } + + //Check tx passes with filter multiple times. 29 bit. Good Filter. NoPadding. STD address. Multiple Single Frames. + TEST_METHOD(J2534_ISO15765_SuccessTx_29b_Filter_NoPad_STD_MultipleSF) + { + auto chanid = J2534_open_and_connect("", ISO15765, CAN_29BIT_ID, 500000, LINE_INFO()); + J2534_set_flowctrl_filter(chanid, CAN_29BIT_ID, 4, "\xff\xff\xff\xff", "\x18\xda\xf1\xef", "\x18\xda\xef\xf1", LINE_INFO()); + write_ioctl(chanid, LOOPBACK, TRUE, LINE_INFO()); + auto p = getPanda(500); + + J2534_send_msg_checked(chanid, ISO15765, 0, CAN_29BIT_ID, 0, 11, 0, "\x18\xda\xef\xf1""TX_TEST", LINE_INFO()); + J2534_send_msg_checked(chanid, ISO15765, 0, CAN_29BIT_ID, 0, 9, 0, "\x18\xda\xef\xf1""HELLO", LINE_INFO()); + auto j2534_msg_recv = j2534_recv_loop(chanid, 4); + check_J2534_can_msg(j2534_msg_recv[0], ISO15765, CAN_29BIT_ID | TX_INDICATION, 0, 4, 0, "\x18\xda\xef\xf1", LINE_INFO()); + check_J2534_can_msg(j2534_msg_recv[1], ISO15765, CAN_29BIT_ID | TX_MSG_TYPE, 0, 11, 0, "\x18\xda\xef\xf1""TX_TEST", LINE_INFO()); + check_J2534_can_msg(j2534_msg_recv[2], ISO15765, CAN_29BIT_ID | TX_INDICATION, 0, 4, 0, "\x18\xda\xef\xf1", LINE_INFO()); + check_J2534_can_msg(j2534_msg_recv[3], ISO15765, CAN_29BIT_ID | TX_MSG_TYPE, 0, 9, 0, "\x18\xda\xef\xf1""HELLO", LINE_INFO()); + + auto panda_msg_recv = panda_recv_loop(p, 2); + check_panda_can_msg(panda_msg_recv[0], 0, 0x18DAEFF1, TRUE, FALSE, "\x07""TX_TEST", LINE_INFO()); + check_panda_can_msg(panda_msg_recv[1], 0, 0x18DAEFF1, TRUE, FALSE, "\x05""HELLO", LINE_INFO()); + } + + //Check that receiver's flow control block size requests are respected. 29 bit. Good Filter. NoPadding. STD address. Multiple Frames with multiple flow control. + TEST_METHOD(J2534_ISO15765_SuccessTx_29b_Filter_NoPad_STD_MF_FLOWCONTROLBlockSize) + { + auto chanid = J2534_open_and_connect("", ISO15765, CAN_29BIT_ID, 500000, LINE_INFO()); + J2534_set_flowctrl_filter(chanid, CAN_29BIT_ID, 4, "\xff\xff\xff\xff", "\x18\xda\xf1\xef", "\x18\xda\xef\xf1", LINE_INFO()); + auto p = getPanda(500); + + J2534_send_msg_checked(chanid, ISO15765, 0, CAN_29BIT_ID, 0, 4 + 52, 0, "\x18\xda\xef\xf1""AABBCCDDEEFFGGHHIIJJKKLLMMNNOOPPQQRRSSTTUUVVWWXXYYZZ", LINE_INFO()); + + auto panda_msg_recv = panda_recv_loop(p, 1); + check_panda_can_msg(panda_msg_recv[0], 0, 0x18DAEFF1, TRUE, FALSE, "\x10\x34""AABBCC", LINE_INFO()); + + // [flow_status, block_size, st_min] + panda_msg_recv = checked_panda_send(p, 0x18DAF1EF, TRUE, "\x30\x01\x00", 3, 1, LINE_INFO()); + check_panda_can_msg(panda_msg_recv[0], 0, 0x18DAEFF1, TRUE, FALSE, "\x21""DDEEFFG", LINE_INFO()); + + panda_msg_recv = checked_panda_send(p, 0x18DAF1EF, TRUE, "\x30\x02\x00", 3, 2, LINE_INFO()); + check_panda_can_msg(panda_msg_recv[0], 0, 0x18DAEFF1, TRUE, FALSE, "\x22""GHHIIJJ", LINE_INFO()); + check_panda_can_msg(panda_msg_recv[1], 0, 0x18DAEFF1, TRUE, FALSE, "\x23""KKLLMMN", LINE_INFO()); + + panda_msg_recv = checked_panda_send(p, 0x18DAF1EF, TRUE, "\x30\x01\x00", 3, 1, LINE_INFO()); + check_panda_can_msg(panda_msg_recv[0], 0, 0x18DAEFF1, TRUE, FALSE, "\x24""NOOPPQQ", LINE_INFO()); + + panda_msg_recv = checked_panda_send(p, 0x18DAF1EF, TRUE, "\x30\x00\x00", 3, 3, LINE_INFO()); + check_panda_can_msg(panda_msg_recv[0], 0, 0x18DAEFF1, TRUE, FALSE, "\x25""RRSSTTU", LINE_INFO()); + check_panda_can_msg(panda_msg_recv[1], 0, 0x18DAEFF1, TRUE, FALSE, "\x26""UVVWWXX", LINE_INFO()); + check_panda_can_msg(panda_msg_recv[2], 0, 0x18DAEFF1, TRUE, FALSE, "\x27""YYZZ", LINE_INFO()); + + auto j2534_msg_recv = j2534_recv_loop(chanid, 1); + check_J2534_can_msg(j2534_msg_recv[0], ISO15765, CAN_29BIT_ID | TX_INDICATION, 0, 4, 0, "\x18\xda\xef\xf1", LINE_INFO()); + } + + //Check that receiver's flow control separation time requests are respected. 29 bit. Good Filter. NoPadding. STD address. Multiple Frames with multiple flow control. + TEST_METHOD(J2534_ISO15765_SuccessTx_29b_Filter_NoPad_STD_MF_FLOWCONTROLSTMinMultiFc) + { + auto chanid = J2534_open_and_connect("", ISO15765, CAN_29BIT_ID, 500000, LINE_INFO()); + J2534_set_flowctrl_filter(chanid, CAN_29BIT_ID, 4, "\xff\xff\xff\xff", "\x18\xda\xf1\xef", "\x18\xda\xef\xf1", LINE_INFO()); + auto p = getPanda(500); + + J2534_send_msg_checked(chanid, ISO15765, 0, CAN_29BIT_ID, 0, 4 + 52, 0, "\x18\xda\xef\xf1""AABBCCDDEEFFGGHHIIJJKKLLMMNNOOPPQQRRSSTTUUVVWWXXYYZZ", LINE_INFO()); + + auto panda_msg_recv = panda_recv_loop(p, 1); + check_panda_can_msg(panda_msg_recv[0], 0, 0x18DAEFF1, TRUE, FALSE, "\x10\x34""AABBCC", LINE_INFO()); + + // [flow_status, block_size, st_min] + panda_msg_recv = checked_panda_send(p, 0x18DAF1EF, TRUE, "\x30\x03\x0A", 3, 3, LINE_INFO()); + check_panda_can_msg(panda_msg_recv[0], 0, 0x18DAEFF1, TRUE, FALSE, "\x21""DDEEFFG", LINE_INFO()); + check_panda_can_msg(panda_msg_recv[1], 0, 0x18DAEFF1, TRUE, FALSE, "\x22""GHHIIJJ", LINE_INFO()); + check_panda_can_msg(panda_msg_recv[2], 0, 0x18DAEFF1, TRUE, FALSE, "\x23""KKLLMMN", LINE_INFO()); + auto timediff0_1_0 = panda_msg_recv[1].recv_time - panda_msg_recv[0].recv_time; + auto timediff0_2_1 = panda_msg_recv[2].recv_time - panda_msg_recv[1].recv_time; + + std::ostringstream stringStream0; + stringStream0 << "times0: " << timediff0_1_0 << ", " << timediff0_2_1 << std::endl; + Logger::WriteMessage(stringStream0.str().c_str()); + + Assert::IsTrue(timediff0_1_0 > 10000); + Assert::IsTrue(timediff0_1_0 < 32000);//Flexible, but trying to make sure things don't just all lag for a second or something + Assert::IsTrue(timediff0_2_1 > 10000); + Assert::IsTrue(timediff0_2_1 < 32000); + + panda_msg_recv = checked_panda_send(p, 0x18DAF1EF, TRUE, "\x30\x04\x20", 3, 4, LINE_INFO(), 500); + check_panda_can_msg(panda_msg_recv[0], 0, 0x18DAEFF1, TRUE, FALSE, "\x24""NOOPPQQ", LINE_INFO()); + check_panda_can_msg(panda_msg_recv[1], 0, 0x18DAEFF1, TRUE, FALSE, "\x25""RRSSTTU", LINE_INFO()); + check_panda_can_msg(panda_msg_recv[2], 0, 0x18DAEFF1, TRUE, FALSE, "\x26""UVVWWXX", LINE_INFO()); + check_panda_can_msg(panda_msg_recv[3], 0, 0x18DAEFF1, TRUE, FALSE, "\x27""YYZZ", LINE_INFO()); + auto timediff1_1_0 = panda_msg_recv[1].recv_time - panda_msg_recv[0].recv_time; + auto timediff1_2_1 = panda_msg_recv[2].recv_time - panda_msg_recv[1].recv_time; + auto timediff1_3_2 = panda_msg_recv[3].recv_time - panda_msg_recv[2].recv_time; + + std::ostringstream stringStream1; + stringStream1 << "times1: " << timediff1_1_0 << ", " << timediff1_2_1 << ", " << timediff1_3_2 << std::endl; + Logger::WriteMessage(stringStream1.str().c_str()); + + Assert::IsTrue(timediff1_1_0 > 32000); + Assert::IsTrue(timediff1_2_1 > 32000); + Assert::IsTrue(timediff1_3_2 > 32000); + + auto j2534_msg_recv = j2534_recv_loop(chanid, 1); + check_J2534_can_msg(j2534_msg_recv[0], ISO15765, CAN_29BIT_ID | TX_INDICATION, 0, 4, 0, "\x18\xda\xef\xf1", LINE_INFO()); + } + + //Check that receiver's flow control separation time requests are respected 2. 29 bit. Good Filter. NoPadding. STD address. Multiple Frames with one flow control. + TEST_METHOD(J2534_ISO15765_SuccessTx_29b_Filter_NoPad_STD_MF_FLOWCONTROLSTMinSingleFc) + { + auto chanid = J2534_open_and_connect("", ISO15765, CAN_29BIT_ID, 500000, LINE_INFO()); + J2534_set_flowctrl_filter(chanid, CAN_29BIT_ID, 4, "\xff\xff\xff\xff", "\x18\xda\xf1\xef", "\x18\xda\xef\xf1", LINE_INFO()); + auto p = getPanda(500); + + J2534_send_msg_checked(chanid, ISO15765, 0, CAN_29BIT_ID, 0, 4 + 52, 0, "\x18\xda\xef\xf1""AABBCCDDEEFFGGHHIIJJKKLLMMNNOOPPQQRRSSTTUUVVWWXXYYZZ", LINE_INFO()); + + auto panda_msg_recv = panda_recv_loop(p, 1); + check_panda_can_msg(panda_msg_recv[0], 0, 0x18DAEFF1, TRUE, FALSE, "\x10\x34""AABBCC", LINE_INFO()); + + // [flow_status, block_size, st_min] + panda_msg_recv = checked_panda_send(p, 0x18DAF1EF, TRUE, "\x30\x07\x0A", 3, 7, LINE_INFO(), 500); + check_panda_can_msg(panda_msg_recv[0], 0, 0x18DAEFF1, TRUE, FALSE, "\x21""DDEEFFG", LINE_INFO()); + check_panda_can_msg(panda_msg_recv[1], 0, 0x18DAEFF1, TRUE, FALSE, "\x22""GHHIIJJ", LINE_INFO()); + check_panda_can_msg(panda_msg_recv[2], 0, 0x18DAEFF1, TRUE, FALSE, "\x23""KKLLMMN", LINE_INFO()); + check_panda_can_msg(panda_msg_recv[3], 0, 0x18DAEFF1, TRUE, FALSE, "\x24""NOOPPQQ", LINE_INFO()); + check_panda_can_msg(panda_msg_recv[4], 0, 0x18DAEFF1, TRUE, FALSE, "\x25""RRSSTTU", LINE_INFO()); + check_panda_can_msg(panda_msg_recv[5], 0, 0x18DAEFF1, TRUE, FALSE, "\x26""UVVWWXX", LINE_INFO()); + check_panda_can_msg(panda_msg_recv[6], 0, 0x18DAEFF1, TRUE, FALSE, "\x27""YYZZ", LINE_INFO()); + + auto timediff_1_0 = panda_msg_recv[1].recv_time - panda_msg_recv[0].recv_time; + auto timediff_2_1 = panda_msg_recv[2].recv_time - panda_msg_recv[1].recv_time; + auto timediff_3_2 = panda_msg_recv[3].recv_time - panda_msg_recv[2].recv_time; + auto timediff_4_3 = panda_msg_recv[4].recv_time - panda_msg_recv[3].recv_time; + auto timediff_5_4 = panda_msg_recv[5].recv_time - panda_msg_recv[4].recv_time; + auto timediff_6_5 = panda_msg_recv[6].recv_time - panda_msg_recv[5].recv_time; + + std::ostringstream stringStream1; + stringStream1 << "times1: " << timediff_1_0 << ", " << timediff_2_1 << ", " << timediff_3_2 << + ", " << timediff_4_3 << ", " << timediff_5_4 << ", " << timediff_6_5 << std::endl; + Logger::WriteMessage(stringStream1.str().c_str()); + + Assert::IsTrue(timediff_1_0 > 10000); + Assert::IsTrue(timediff_2_1 > 10000); + Assert::IsTrue(timediff_3_2 > 10000); + Assert::IsTrue(timediff_4_3 > 10000); + Assert::IsTrue(timediff_5_4 > 10000); + Assert::IsTrue(timediff_6_5 > 10000); + } + + //Check that tx works for messages with more than 16 frames. 29 bit. Good Filter. NoPadding. STD address. Large multiframe message. + TEST_METHOD(J2534_ISO15765_SuccessTx_29b_Filter_NoPad_STD_MF_LotsOfFrames) + { + auto chanid = J2534_open_and_connect("", ISO15765, CAN_29BIT_ID, 500000, LINE_INFO()); + J2534_set_flowctrl_filter(chanid, CAN_29BIT_ID, 4, "\xff\xff\xff\xff", "\x18\xda\xf1\xef", "\x18\xda\xef\xf1", LINE_INFO()); + auto p = getPanda(500); + + J2534_send_msg_checked(chanid, ISO15765, 0, CAN_29BIT_ID, 0, 4 + 125, 0, + "\x18\xda\xef\xf1" + "AABBCC""DDEEFFG""GHHIIJJ""KKLLMMN""NOOPPQQ""RRSSTTU""UVVWWXX""YYZZ112""2334455""6677889" + "900abcd""efghijk""lmnopqr""stuvwxy""z!@#$%^""&*()_+-""=`~ABCD""EFGHIJK", LINE_INFO()); + + auto panda_msg_recv = panda_recv_loop(p, 1); + check_panda_can_msg(panda_msg_recv[0], 0, 0x18DAEFF1, TRUE, FALSE, "\x10\x7D""AABBCC", LINE_INFO()); + + // [flow_status, block_size, st_min] + panda_msg_recv = checked_panda_send(p, 0x18DAF1EF, TRUE, "\x30\x00\x00", 3, 17, LINE_INFO(), 1000); + check_panda_can_msg(panda_msg_recv[0], 0, 0x18DAEFF1, TRUE, FALSE, "\x21""DDEEFFG", LINE_INFO()); + check_panda_can_msg(panda_msg_recv[1], 0, 0x18DAEFF1, TRUE, FALSE, "\x22""GHHIIJJ", LINE_INFO()); + check_panda_can_msg(panda_msg_recv[2], 0, 0x18DAEFF1, TRUE, FALSE, "\x23""KKLLMMN", LINE_INFO()); + check_panda_can_msg(panda_msg_recv[3], 0, 0x18DAEFF1, TRUE, FALSE, "\x24""NOOPPQQ", LINE_INFO()); + check_panda_can_msg(panda_msg_recv[4], 0, 0x18DAEFF1, TRUE, FALSE, "\x25""RRSSTTU", LINE_INFO()); + check_panda_can_msg(panda_msg_recv[5], 0, 0x18DAEFF1, TRUE, FALSE, "\x26""UVVWWXX", LINE_INFO()); + check_panda_can_msg(panda_msg_recv[6], 0, 0x18DAEFF1, TRUE, FALSE, "\x27""YYZZ112", LINE_INFO()); + check_panda_can_msg(panda_msg_recv[7], 0, 0x18DAEFF1, TRUE, FALSE, "\x28""2334455", LINE_INFO()); + check_panda_can_msg(panda_msg_recv[8], 0, 0x18DAEFF1, TRUE, FALSE, "\x29""6677889", LINE_INFO()); + check_panda_can_msg(panda_msg_recv[9], 0, 0x18DAEFF1, TRUE, FALSE, "\x2A""900abcd", LINE_INFO()); + check_panda_can_msg(panda_msg_recv[10], 0, 0x18DAEFF1, TRUE, FALSE, "\x2B""efghijk", LINE_INFO()); + check_panda_can_msg(panda_msg_recv[11], 0, 0x18DAEFF1, TRUE, FALSE, "\x2C""lmnopqr", LINE_INFO()); + check_panda_can_msg(panda_msg_recv[12], 0, 0x18DAEFF1, TRUE, FALSE, "\x2D""stuvwxy", LINE_INFO()); + check_panda_can_msg(panda_msg_recv[13], 0, 0x18DAEFF1, TRUE, FALSE, "\x2E""z!@#$%^", LINE_INFO()); + check_panda_can_msg(panda_msg_recv[14], 0, 0x18DAEFF1, TRUE, FALSE, "\x2F""&*()_+-", LINE_INFO()); + check_panda_can_msg(panda_msg_recv[15], 0, 0x18DAEFF1, TRUE, FALSE, "\x20""=`~ABCD", LINE_INFO()); + check_panda_can_msg(panda_msg_recv[16], 0, 0x18DAEFF1, TRUE, FALSE, "\x21""EFGHIJK", LINE_INFO()); + + auto j2534_msg_recv = j2534_recv_loop(chanid, 1); + check_J2534_can_msg(j2534_msg_recv[0], ISO15765, CAN_29BIT_ID | TX_INDICATION, 0, 4, 0, "\x18\xda\xef\xf1", LINE_INFO()); + } + + //Check tx passes with filter multiple times. 29 bit. Good Filter. NoPadding. STD address. Multiple Single Frames. + TEST_METHOD(J2534_ISO15765_SuccessTx_29b_Filter_NoPad_STD_MultipleMFSF) + { + auto chanid = J2534_open_and_connect("", ISO15765, CAN_29BIT_ID, 500000, LINE_INFO()); + J2534_set_flowctrl_filter(chanid, CAN_29BIT_ID, 4, "\xff\xff\xff\xff", "\x18\xda\xf1\xef", "\x18\xda\xef\xf1", LINE_INFO()); + write_ioctl(chanid, LOOPBACK, TRUE, LINE_INFO()); + auto p = getPanda(500); + + J2534_send_msg_checked(chanid, ISO15765, 0, CAN_29BIT_ID, 0, 4 + 23, 0, "\x18\xda\xef\xf1""Long data because I can", LINE_INFO()); + J2534_send_msg_checked(chanid, ISO15765, 0, CAN_29BIT_ID, 0, 9, 0, "\x18\xda\xef\xf1""HELLO", LINE_INFO()); + + auto panda_msg_recv = panda_recv_loop(p, 1); + check_panda_can_msg(panda_msg_recv[0], 0, 0x18DAEFF1, TRUE, FALSE, "\x10\x17""Long d", LINE_INFO()); + + panda_msg_recv = checked_panda_send(p, 0x18DAF1EF, TRUE, "\x30\x00\x00", 3, 4, LINE_INFO()); + check_panda_can_msg(panda_msg_recv[0], 0, 0x18DAEFF1, TRUE, FALSE, "\x21""ata bec", LINE_INFO()); + check_panda_can_msg(panda_msg_recv[1], 0, 0x18DAEFF1, TRUE, FALSE, "\x22""ause I ", LINE_INFO()); + check_panda_can_msg(panda_msg_recv[2], 0, 0x18DAEFF1, TRUE, FALSE, "\x23""can", LINE_INFO()); + check_panda_can_msg(panda_msg_recv[3], 0, 0x18DAEFF1, TRUE, FALSE, "\x05""HELLO", LINE_INFO()); + + auto j2534_msg_recv = j2534_recv_loop(chanid, 4); + check_J2534_can_msg(j2534_msg_recv[0], ISO15765, CAN_29BIT_ID | TX_INDICATION, 0, 4, 0, "\x18\xda\xef\xf1", LINE_INFO()); + check_J2534_can_msg(j2534_msg_recv[1], ISO15765, CAN_29BIT_ID | TX_MSG_TYPE, 0, 4 + 23, 0, "\x18\xda\xef\xf1""Long data because I can", LINE_INFO()); + check_J2534_can_msg(j2534_msg_recv[2], ISO15765, CAN_29BIT_ID | TX_INDICATION, 0, 4, 0, "\x18\xda\xef\xf1", LINE_INFO()); + check_J2534_can_msg(j2534_msg_recv[3], ISO15765, CAN_29BIT_ID | TX_MSG_TYPE, 0, 4 + 5, 0, "\x18\xda\xef\xf1""HELLO", LINE_INFO()); + } + + //Check tx passes after message timeout. 29 bit. Good Filter. NoPadding. STD address. Multiple Frame timeout then Single Frame. + TEST_METHOD(J2534_ISO15765_SuccessTx_29b_Filter_NoPad_STD_MFTimeoutSFSuccess) + { + auto chanid = J2534_open_and_connect("", ISO15765, CAN_29BIT_ID, 500000, LINE_INFO()); + J2534_set_flowctrl_filter(chanid, CAN_29BIT_ID, 4, "\xff\xff\xff\xff", "\x18\xda\xf1\xef", "\x18\xda\xef\xf1", LINE_INFO()); + write_ioctl(chanid, LOOPBACK, TRUE, LINE_INFO()); + auto p = getPanda(500); + + J2534_send_msg_checked(chanid, ISO15765, 0, CAN_29BIT_ID, 0, 4 + 23, 0, "\x18\xda\xef\xf1""Long data because I can", LINE_INFO()); + J2534_send_msg_checked(chanid, ISO15765, 0, CAN_29BIT_ID, 0, 9, 0, "\x18\xda\xef\xf1""HELLO", LINE_INFO()); + + auto panda_msg_recv = panda_recv_loop(p, 2, 1000); + check_panda_can_msg(panda_msg_recv[0], 0, 0x18DAEFF1, TRUE, FALSE, "\x10\x17""Long d", LINE_INFO()); //First Frame. Not replying so it needs to time out. + check_panda_can_msg(panda_msg_recv[1], 0, 0x18DAEFF1, TRUE, FALSE, "\x05""HELLO", LINE_INFO()); //Reply to the next message. + + auto j2534_msg_recv = j2534_recv_loop(chanid, 2); + check_J2534_can_msg(j2534_msg_recv[0], ISO15765, CAN_29BIT_ID | TX_INDICATION, 0, 4, 0, "\x18\xda\xef\xf1", LINE_INFO()); + check_J2534_can_msg(j2534_msg_recv[1], ISO15765, CAN_29BIT_ID | TX_MSG_TYPE, 0, 4 + 5, 0, "\x18\xda\xef\xf1""HELLO", LINE_INFO()); + } + + //Check tx passes after mid-message timeout. 29 bit. Good Filter. NoPadding. STD address. Multiple Frame mid-timeout then Single Frame. + TEST_METHOD(J2534_ISO15765_SuccessTx_29b_Filter_NoPad_STD_MFMidTimeoutSFSuccess) + { + auto chanid = J2534_open_and_connect("", ISO15765, CAN_29BIT_ID, 500000, LINE_INFO()); + J2534_set_flowctrl_filter(chanid, CAN_29BIT_ID, 4, "\xff\xff\xff\xff", "\x18\xda\xf1\xef", "\x18\xda\xef\xf1", LINE_INFO()); + write_ioctl(chanid, LOOPBACK, TRUE, LINE_INFO()); + auto p = getPanda(500); + + J2534_send_msg_checked(chanid, ISO15765, 0, CAN_29BIT_ID, 0, 4 + 23, 0, "\x18\xda\xef\xf1""Long data because I can", LINE_INFO()); + J2534_send_msg_checked(chanid, ISO15765, 0, CAN_29BIT_ID, 0, 9, 0, "\x18\xda\xef\xf1""HELLO", LINE_INFO()); + + auto panda_msg_recv = panda_recv_loop(p, 1); + check_panda_can_msg(panda_msg_recv[0], 0, 0x18DAEFF1, TRUE, FALSE, "\x10\x17""Long d", LINE_INFO()); //First Frame. Not replying so it needs to time out. + + panda_msg_recv = checked_panda_send(p, 0x18DAF1EF, TRUE, "\x30\x01\x00", 3, 2, LINE_INFO(), 1000);//Start a conversation + check_panda_can_msg(panda_msg_recv[0], 0, 0x18DAEFF1, TRUE, FALSE, "\x21""ata bec", LINE_INFO());//Check passthru device sent more data, but don't reply to it + check_panda_can_msg(panda_msg_recv[1], 0, 0x18DAEFF1, TRUE, FALSE, "\x05""HELLO", LINE_INFO()); //Reply to the next message. + + auto j2534_msg_recv = j2534_recv_loop(chanid, 2); + check_J2534_can_msg(j2534_msg_recv[0], ISO15765, CAN_29BIT_ID | TX_INDICATION, 0, 4, 0, "\x18\xda\xef\xf1", LINE_INFO()); + check_J2534_can_msg(j2534_msg_recv[1], ISO15765, CAN_29BIT_ID | TX_MSG_TYPE, 0, 4 + 5, 0, "\x18\xda\xef\xf1""HELLO", LINE_INFO()); + } + + //Check slow tx passes without hitting FC timeout. 29 bit. Good Filter. NoPadding. STD address. Long STmin, catches if FC timeout applies before needed. + TEST_METHOD(J2534_ISO15765_SuccessTx_29b_Filter_NoPad_STD_SLOWMF) + { + auto chanid = J2534_open_and_connect("", ISO15765, CAN_29BIT_ID, 500000, LINE_INFO()); + J2534_set_flowctrl_filter(chanid, CAN_29BIT_ID, 4, "\xff\xff\xff\xff", "\x18\xda\xf1\xef", "\x18\xda\xef\xf1", LINE_INFO()); + write_ioctl(chanid, LOOPBACK, TRUE, LINE_INFO()); + auto p = getPanda(500); + + J2534_send_msg_checked(chanid, ISO15765, 0, CAN_29BIT_ID, 0, 4 + 48, 0, "\x18\xda\xef\xf1""AABBCCDDEEFFGGHHIIJJKKLLMMNNOOPPQQRRSSTTUUVVWWXX", LINE_INFO()); + + auto panda_msg_recv = panda_recv_loop(p, 1); + check_panda_can_msg(panda_msg_recv[0], 0, 0x18DAEFF1, TRUE, FALSE, "\x10\x30""AABBCC", LINE_INFO()); + + panda_msg_recv = checked_panda_send(p, 0x18DAF1EF, TRUE, "\x30\x06\x7F", 3, 6, LINE_INFO(), 3000);//Start a conversation... but slow. FC timeout is 250 ms. + check_panda_can_msg(panda_msg_recv[0], 0, 0x18DAEFF1, TRUE, FALSE, "\x21""DDEEFFG", LINE_INFO());//Check this convo doesn't trigger that timeout. + check_panda_can_msg(panda_msg_recv[1], 0, 0x18DAEFF1, TRUE, FALSE, "\x22""GHHIIJJ", LINE_INFO()); + check_panda_can_msg(panda_msg_recv[2], 0, 0x18DAEFF1, TRUE, FALSE, "\x23""KKLLMMN", LINE_INFO()); + check_panda_can_msg(panda_msg_recv[3], 0, 0x18DAEFF1, TRUE, FALSE, "\x24""NOOPPQQ", LINE_INFO()); + check_panda_can_msg(panda_msg_recv[4], 0, 0x18DAEFF1, TRUE, FALSE, "\x25""RRSSTTU", LINE_INFO());//Some of these should fail to recv if there is an issue. + check_panda_can_msg(panda_msg_recv[5], 0, 0x18DAEFF1, TRUE, FALSE, "\x26""UVVWWXX", LINE_INFO()); + + auto j2534_msg_recv = j2534_recv_loop(chanid, 2); + check_J2534_can_msg(j2534_msg_recv[0], ISO15765, CAN_29BIT_ID | TX_INDICATION, 0, 4, 0, "\x18\xda\xef\xf1", LINE_INFO()); + check_J2534_can_msg(j2534_msg_recv[1], ISO15765, CAN_29BIT_ID | TX_MSG_TYPE, 0, 4 + 48, 0, "\x18\xda\xef\xf1""AABBCCDDEEFFGGHHIIJJKKLLMMNNOOPPQQRRSSTTUUVVWWXX", LINE_INFO()); + } + + //Check MF tx can be sent along side of a periodic message. 29 bit. Good Filter. NoPadding. STD address. Long STmin, checks that MF tx and periodic TX don't break each other. + TEST_METHOD(J2534_ISO15765_SuccessTx_29b_Filter_NoPad_STD_SLOWMF_WithPeriodicMsg) + { + auto chanid = J2534_open_and_connect("", ISO15765, CAN_29BIT_ID, 500000, LINE_INFO()); + J2534_set_flowctrl_filter(chanid, CAN_29BIT_ID, 4, "\xff\xff\xff\xff", "\x18\xda\xf1\xef", "\x18\xda\xef\xf1", LINE_INFO()); + write_ioctl(chanid, LOOPBACK, TRUE, LINE_INFO()); + auto p = getPanda(500); + + //Timing diagram of this test. + //* is a periodic msg transfer; F is first frame, L is Flow control, C is Consecutive Frame. + // *~~~~~~~*~~~~~~~*~~~~~~~* (The alignment here is unimportant. The exact order is not checked. + //F C----C----C----C----C----C (100 ms between Cs) + // L + + auto msgid = J2534_start_periodic_msg_checked(chanid, ISO15765, CAN_29BIT_ID, 6, 0, "\x18\xda\xef\xf1""HI", 130, LINE_INFO()); + J2534_send_msg_checked(chanid, ISO15765, 0, CAN_29BIT_ID, 0, 4 + 48, 0, "\x18\xda\xef\xf1""AABBCCDDEEFFGGHHIIJJKKLLMMNNOOPPQQRRSSTTUUVVWWXX", LINE_INFO()); + + auto panda_msg_recv = panda_recv_loop(p, 2); + check_panda_can_msg(panda_msg_recv[0], 0, 0x18DAEFF1, TRUE, FALSE, "\x02""HI", LINE_INFO()); + check_panda_can_msg(panda_msg_recv[1], 0, 0x18DAEFF1, TRUE, FALSE, "\x10\x30""AABBCC", LINE_INFO()); + + Assert::IsTrue(p->can_send(0x18DAF1EF, TRUE, (const uint8_t*)"\x30\x06\x64", 3, panda::PANDA_CAN1), _T("Panda send says it failed."), LINE_INFO()); + + Timer t_permsg = Timer(); + Timer t_MFmsg = Timer(); + unsigned int MFframesReceived = 0; + unsigned int PeriodicMsgReceived = 1; //Because of the first panda_recv_loop above. + std::array const mfMsgExpectedParts{ "\x21""DDEEFFG", "\x22""GHHIIJJ", "\x23""KKLLMMN", "\x24""NOOPPQQ", "\x25""RRSSTTU", "\x26""UVVWWXX" }; + + while (TRUE) { + std::vectormsg_recv = p->can_recv(); + for (auto msg : msg_recv) { + if (msg.is_receipt) continue; + if ((msg.dat[0] & 0xf0) == 0x20) { + Assert::AreEqual(mfMsgExpectedParts[MFframesReceived], std::string((const char*)msg.dat, msg.len), _T("Got wrong part of MF msg."), LINE_INFO()); + MFframesReceived++; + t_MFmsg.reset(); + } else if (std::string((const char*)msg.dat, msg.len) == "\x02HI") { + PeriodicMsgReceived++; + t_permsg.reset(); + } else { + Assert::IsTrue(FALSE, _T("Got impossible message. Something is very wrong. Check other tests."), LINE_INFO()); + } + } + + if (MFframesReceived >= 6) break; + Assert::IsTrue(300 > t_permsg.getTimePassed(), _T("Timed out waiting for periodic msessage frame."), LINE_INFO()); + Assert::IsTrue(300 > t_MFmsg.getTimePassed(), _T("Timed out waiting for multiframe msessage frame."), LINE_INFO()); + + if (msg_recv.size() == 0) + Sleep(10); + } + + //Stop the periodic message and grab any data it may have sent since we last checked. + //Not sure if this is needed. + Assert::AreEqual(STATUS_NOERROR, PassThruStopPeriodicMsg(chanid, msgid), _T("Failed to delete filter."), LINE_INFO()); + auto extra_panda_msg = panda_recv_loop_loose(p, 0, 200); + for (auto msg : extra_panda_msg) { + if (std::string((const char*)msg.dat, msg.len) == "\x02HI") { + PeriodicMsgReceived++; + Logger::WriteMessage("Received extra periodic message."); + } else { + Assert::IsTrue(FALSE, _T("Got impossible message. Something is very wrong. Check other tests."), LINE_INFO()); + } + } + + Assert::IsTrue(PeriodicMsgReceived > 3, _T("Did not receive enough periodic messages. Likely canceled or delayed."), LINE_INFO()); + + std::ostringstream stringStream; + stringStream << "PeriodicMsgReceived = " << PeriodicMsgReceived << std::endl; + Logger::WriteMessage(stringStream.str().c_str()); + + unsigned int periodicTxIndicationCount = 0; + unsigned int TxIndicationCount = 0; + auto j2534_msg_recv = j2534_recv_loop(chanid, 2 + (PeriodicMsgReceived * 2)); + for (int i = 0; i < PeriodicMsgReceived + 1; i++) { + check_J2534_can_msg(j2534_msg_recv[(i * 2) + 0], ISO15765, CAN_29BIT_ID | TX_INDICATION, 0, 4, 0, "\x18\xda\xef\xf1", LINE_INFO()); + switch (j2534_msg_recv[(i * 2) + 1].DataSize) { + case 4 + 2: + check_J2534_can_msg(j2534_msg_recv[(i * 2) + 1], ISO15765, CAN_29BIT_ID | TX_MSG_TYPE, 0, 4 + 2, 0, "\x18\xda\xef\xf1""HI", LINE_INFO()); + break; + case 4 + 48: + check_J2534_can_msg(j2534_msg_recv[(i * 2) + 1], ISO15765, CAN_29BIT_ID | TX_MSG_TYPE, 0, 4 + 48, 0, "\x18\xda\xef\xf1""AABBCCDDEEFFGGHHIIJJKKLLMMNNOOPPQQRRSSTTUUVVWWXX", LINE_INFO()); + break; + default: + Assert::IsTrue(FALSE, _T("Got unexpected data!"), LINE_INFO()); + } + } + + Assert::AreNotEqual(PeriodicMsgReceived, periodicTxIndicationCount, _T("Wrong number of periodic msgs reported by passthru device."), LINE_INFO()); + Assert::AreNotEqual(1, TxIndicationCount, _T("Wrong number of TX msgs reported by passthru device."), LINE_INFO()); + } + + ///////////////////// Tests checking things break or recover during send/receive ///////////////////// + + //Check rx FAILS when frame is dropped. 29 bit. Good Filter. NoPadding. STD address. Multi Frame. + TEST_METHOD(J2534_ISO15765_FailRx_29b_Filter_NoPad_STD_FFCF_DropFrame) + { + auto chanid = J2534_open_and_connect("", ISO15765, CAN_29BIT_ID, 500000, LINE_INFO()); + J2534_set_flowctrl_filter(chanid, CAN_29BIT_ID, 4, "\xff\xff\xff\xff", "\x18\xda\xf1\xef", "\x18\xda\xef\xf1", LINE_INFO()); + auto p = getPanda(500); + + //Send first frame, then check we get a flow control frame + auto panda_msg_recv = checked_panda_send(p, 0x18DAF1EF, TRUE, "\x10\x13""ninete", 8, 1, LINE_INFO()); + check_panda_can_msg(panda_msg_recv[0], 0, 0x18DAEFF1, TRUE, FALSE, std::string("\x30\x00\x00", 3), LINE_INFO()); + + //Check first frame is registered with J2534 + auto j2534_msg_recv = j2534_recv_loop(chanid, 1); + check_J2534_can_msg(j2534_msg_recv[0], ISO15765, CAN_29BIT_ID | START_OF_MESSAGE, 0, 4, 0, "\x18\xda\xf1\xef", LINE_INFO()); + + //Send the rest of the message + //Missing the 2nd frame "\x21""en byte" + checked_panda_send(p, 0x18DAF1EF, TRUE, "\x22""s here", 7, 0, LINE_INFO()); + + //Check J2534 DOES NOT construct the incomplete message + j2534_recv_loop(chanid, 0); + } + + //Check rx ignores frames that arrive out of order. 29 bit. Good Filter. NoPadding. STD address. Multi Frame. + TEST_METHOD(J2534_ISO15765_PassRx_29b_Filter_NoPad_STD_FFCF_FrameNumSkip) + { + auto chanid = J2534_open_and_connect("", ISO15765, CAN_29BIT_ID, 500000, LINE_INFO()); + J2534_set_flowctrl_filter(chanid, CAN_29BIT_ID, 4, "\xff\xff\xff\xff", "\x18\xda\xf1\xef", "\x18\xda\xef\xf1", LINE_INFO()); + auto p = getPanda(500); + + //Send first frame, then check we get a flow control frame + auto panda_msg_recv = checked_panda_send(p, 0x18DAF1EF, TRUE, "\x10\x13""ABCDEF", 8, 1, LINE_INFO()); + check_panda_can_msg(panda_msg_recv[0], 0, 0x18DAEFF1, TRUE, FALSE, std::string("\x30\x00\x00", 3), LINE_INFO()); + + //Check first frame is registered with J2534 + auto j2534_msg_recv = j2534_recv_loop(chanid, 1); + check_J2534_can_msg(j2534_msg_recv[0], ISO15765, CAN_29BIT_ID | START_OF_MESSAGE, 0, 4, 0, "\x18\xda\xf1\xef", LINE_INFO()); + + //Send the rest of the message + checked_panda_send(p, 0x18DAF1EF, TRUE, "\x22""XXXXXX", 7, 0, LINE_INFO()); + checked_panda_send(p, 0x18DAF1EF, TRUE, "\x21""GHIJKLM", 8, 0, LINE_INFO()); + checked_panda_send(p, 0x18DAF1EF, TRUE, "\x23""ZZZZZZ", 7, 0, LINE_INFO()); + checked_panda_send(p, 0x18DAF1EF, TRUE, "\x22""NOPQRS", 7, 0, LINE_INFO()); + + //Check J2534 constructa the complete message from the correctly numbered frames. + j2534_msg_recv = j2534_recv_loop(chanid, 1); + check_J2534_can_msg(j2534_msg_recv[0], ISO15765, CAN_29BIT_ID, 0, 4 + 0x13, 4 + 0x13, "\x18\xda\xf1\xef""ABCDEFGHIJKLMNOPQRS", LINE_INFO()); + } + + //Check Single Frame rx RESETS ongoing multiframe transmission. 29 bit. Good Filter. NoPadding. STD address. Multi Frame. + TEST_METHOD(J2534_ISO15765_PassRx_29b_Filter_NoPad_STD_SFRxResetsMFRx) + { + auto chanid = J2534_open_and_connect("", ISO15765, CAN_29BIT_ID, 500000, LINE_INFO()); + J2534_set_flowctrl_filter(chanid, CAN_29BIT_ID, 4, "\xff\xff\xff\xff", "\x18\xda\xf1\xef", "\x18\xda\xef\xf1", LINE_INFO()); + auto p = getPanda(500); + + //Send first frame, then check we get a flow control frame + auto panda_msg_recv = checked_panda_send(p, 0x18DAF1EF, TRUE, "\x10\x13""ABCDEF", 8, 1, LINE_INFO()); + check_panda_can_msg(panda_msg_recv[0], 0, 0x18DAEFF1, TRUE, FALSE, std::string("\x30\x00\x00", 3), LINE_INFO()); + + //Check first frame is registered with J2534 + auto j2534_msg_recv = j2534_recv_loop(chanid, 1); + check_J2534_can_msg(j2534_msg_recv[0], ISO15765, CAN_29BIT_ID | START_OF_MESSAGE, 0, 4, 0, "\x18\xda\xf1\xef", LINE_INFO()); + + //Send the next part of the message multi message + checked_panda_send(p, 0x18DAF1EF, TRUE, "\x21""GHIJKLM", 8, 0, LINE_INFO()); + + //ABORTING MESSAGE + //Send a NEW single frame message and check the J2534 device gets it (but not the original message it was receiving. + checked_panda_send(p, 0x18DAF1EF, TRUE, "\x06""ABC123", 7, 0, LINE_INFO()); + j2534_msg_recv = j2534_recv_loop(chanid, 1); + check_J2534_can_msg(j2534_msg_recv[0], ISO15765, CAN_29BIT_ID, 0, 10, 10, "\x18\xda\xf1\xef""ABC123", LINE_INFO()); + + //Resume sending the old message, and check th eJ2534 device didn't get a message. + checked_panda_send(p, 0x18DAF1EF, TRUE, "\x22""NOPQRS", 7, 0, LINE_INFO()); + j2534_recv_loop(chanid, 0); + } + + //The documentation says that a s ingle channel can not send and receive messages trhough a + //single conversation (flow control filter) at the same time. However, the required behavior + //when this is detected is not described. This test was my best understanding of how it was + //wanted, but I no longer see the point. For now I am disabling it. + /*//Check Single Frame tx RESETS ongoing multiframe rx transmission. 29 bit. Good Filter. NoPadding. STD address. Multi Frame. + TEST_METHOD(J2534_ISO15765_PassRx_29b_Filter_NoPad_STD_SFTxResetsMFRx) + { + auto chanid = J2534_open_and_connect("", ISO15765, CAN_29BIT_ID, 500000, LINE_INFO()); + J2534_set_flowctrl_filter(chanid, CAN_29BIT_ID, 4, "\xff\xff\xff\xff", "\x18\xda\xf1\xef", "\x18\xda\xef\xf1", LINE_INFO()); + auto p = getPanda(500); + + //Send first frame, then check we get a flow control frame + auto panda_msg_recv = checked_panda_send(p, 0x18DAF1EF, TRUE, "\x10\x13""ABCDEF", 8, 1, LINE_INFO()); + check_panda_can_msg(panda_msg_recv[0], 0, 0x18DAEFF1, TRUE, FALSE, std::string("\x30\x00\x00", 3), LINE_INFO()); + + //Check first frame is registered with J2534 + auto j2534_msg_recv = j2534_recv_loop(chanid, 1); + check_J2534_can_msg(j2534_msg_recv[0], ISO15765, CAN_29BIT_ID | START_OF_MESSAGE, 0, 4, 0, "\x18\xda\xf1\xef", LINE_INFO()); + + //Send the next part of the message multi message + checked_panda_send(p, 0x18DAF1EF, TRUE, "\x21""GHIJKLM", 8, 0, LINE_INFO()); + j2534_recv_loop(chanid, 0); + + //ABORTING MESSAGE + //Send a NEW single frame message and check the J2534 device gets it (but not the original message it was receiving. + J2534_send_msg_checked(chanid, ISO15765, 0, CAN_29BIT_ID, 0, 11, 0, "\x18\xda\xef\xf1""TX_TEST", LINE_INFO()); + j2534_msg_recv = j2534_recv_loop(chanid, 1); + check_J2534_can_msg(j2534_msg_recv[0], ISO15765, CAN_29BIT_ID | TX_INDICATION, 0, 4, 0, "\x18\xda\xef\xf1", LINE_INFO()); + + panda_msg_recv = panda_recv_loop(p, 1); + check_panda_can_msg(panda_msg_recv[0], 0, 0x18DAEFF1, TRUE, FALSE, "\x07""TX_TEST", LINE_INFO()); + /////////////////////////// + + //Resume sending the old message, and check th eJ2534 device didn't get a message. + checked_panda_send(p, 0x18DAF1EF, TRUE, "\x22""NOPQRS", 7, 0, LINE_INFO()); + j2534_recv_loop(chanid, 0); + }*/ + + //TODO check rx is cleared by tx (multi). Or not.... read above note. + + //Check multiframe rx RESETS ongoing multiframe transmission. 29 bit. Good Filter. NoPadding. STD address. Multi Frame. + TEST_METHOD(J2534_ISO15765_PassRx_29b_Filter_NoPad_STD_FFCF_MFRxResetsMFRx) + { + auto chanid = J2534_open_and_connect("", ISO15765, CAN_29BIT_ID, 500000, LINE_INFO()); + J2534_set_flowctrl_filter(chanid, CAN_29BIT_ID, 4, "\xff\xff\xff\xff", "\x18\xda\xf1\xef", "\x18\xda\xef\xf1", LINE_INFO()); + auto p = getPanda(500); + + //Send first frame, then check we get a flow control frame + auto panda_msg_recv = checked_panda_send(p, 0x18DAF1EF, TRUE, "\x10\x13""ABCDEF", 8, 1, LINE_INFO()); + check_panda_can_msg(panda_msg_recv[0], 0, 0x18DAEFF1, TRUE, FALSE, std::string("\x30\x00\x00", 3), LINE_INFO()); + + //Check first frame is registered with J2534 + auto j2534_msg_recv = j2534_recv_loop(chanid, 1); + check_J2534_can_msg(j2534_msg_recv[0], ISO15765, CAN_29BIT_ID | START_OF_MESSAGE, 0, 4, 0, "\x18\xda\xf1\xef", LINE_INFO()); + + //Send the next part of the multi message A + checked_panda_send(p, 0x18DAF1EF, TRUE, "\x21""GHIJKLM", 8, 0, LINE_INFO()); + + //ABORTING MESSAGE A + //Send a NEW multi frame message (B) and check the J2534 device gets it (but not the original message it was receiving. + //Send first frame, then check we get a flow control frame + panda_msg_recv = checked_panda_send(p, 0x18DAF1EF, TRUE, "\x10\x13""ninete", 8, 1, LINE_INFO()); + check_panda_can_msg(panda_msg_recv[0], 0, 0x18DAEFF1, TRUE, FALSE, std::string("\x30\x00\x00", 3), LINE_INFO()); + + //Check first frame is registered with J2534 + j2534_msg_recv = j2534_recv_loop(chanid, 1); + check_J2534_can_msg(j2534_msg_recv[0], ISO15765, CAN_29BIT_ID | START_OF_MESSAGE, 0, 4, 0, "\x18\xda\xf1\xef", LINE_INFO()); + + //Send the rest of the message + checked_panda_send(p, 0x18DAF1EF, TRUE, "\x21""en byte", 8, 0, LINE_INFO()); + checked_panda_send(p, 0x18DAF1EF, TRUE, "\x22""s here", 7, 0, LINE_INFO()); + + //Check J2534 constructed the whole message + j2534_msg_recv = j2534_recv_loop(chanid, 1); + check_J2534_can_msg(j2534_msg_recv[0], ISO15765, CAN_29BIT_ID, 0, 4 + 0x13, 4 + 0x13, "\x18\xda\xf1\xef""nineteen bytes here", LINE_INFO()); + //////////////////////// End sending B + + //Resume sending the multi message A, and check th eJ2534 device didn't get a message. + checked_panda_send(p, 0x18DAF1EF, TRUE, "\x22""NOPQRS", 7, 0, LINE_INFO()); + j2534_recv_loop(chanid, 0); + } + + //Check rx fails gracefully if final CF of MF rx is too short. 29 bit. Good Filter. NoPadding. STD address. Multi Frame. + TEST_METHOD(J2534_ISO15765_FailRxFinalCFTooShort_29b_Filter_NoPad_STD_FFCF) + { + auto chanid = J2534_open_and_connect("", ISO15765, CAN_29BIT_ID, 500000, LINE_INFO()); + J2534_set_flowctrl_filter(chanid, CAN_29BIT_ID, 4, "\xff\xff\xff\xff", "\x18\xda\xf1\xef", "\x18\xda\xef\xf1", LINE_INFO()); + auto p = getPanda(500); + + //Send first frame, then check we get a flow control frame + auto panda_msg_recv = checked_panda_send(p, 0x18DAF1EF, TRUE, "\x10\x13""ninete", 8, 1, LINE_INFO()); + check_panda_can_msg(panda_msg_recv[0], 0, 0x18DAEFF1, TRUE, FALSE, std::string("\x30\x00\x00", 3), LINE_INFO()); + + //Check first frame is registered with J2534 + auto j2534_msg_recv = j2534_recv_loop(chanid, 1); + check_J2534_can_msg(j2534_msg_recv[0], ISO15765, CAN_29BIT_ID | START_OF_MESSAGE, 0, 4, 0, "\x18\xda\xf1\xef", LINE_INFO()); + + //Send the rest of the message + checked_panda_send(p, 0x18DAF1EF, TRUE, "\x21""en byte", 8, 0, LINE_INFO()); + checked_panda_send(p, 0x18DAF1EF, TRUE, "\x22""s her", 6, 0, LINE_INFO()); //The transaction should reset here because more data could have been sent. + checked_panda_send(p, 0x18DAF1EF, TRUE, "\x23""e", 2, 0, LINE_INFO()); + + //Check J2534 constructed the whole message + j2534_msg_recv = j2534_recv_loop(chanid, 0); + } + + //Check rx fails gracefully if first frame is too short. 29 bit. Good Filter. NoPadding. STD address. Multi Frame. + TEST_METHOD(J2534_ISO15765_FailRxFFTooShort_29b_Filter_NoPad_STD_FFCF) + { + auto chanid = J2534_open_and_connect("", ISO15765, CAN_29BIT_ID, 500000, LINE_INFO()); + J2534_set_flowctrl_filter(chanid, CAN_29BIT_ID, 4, "\xff\xff\xff\xff", "\x18\xda\xf1\xef", "\x18\xda\xef\xf1", LINE_INFO()); + auto p = getPanda(500); + + //Send first frame, then check we get a flow control frame. The transaction should reset immediately because more data could have been sent in this frame. + checked_panda_send(p, 0x18DAF1EF, TRUE, "\x10\x13""ninet", 7, 0, LINE_INFO()); + j2534_recv_loop(chanid, 0); + + //Send the rest of the message + checked_panda_send(p, 0x18DAF1EF, TRUE, "\x21""een byt", 8, 0, LINE_INFO()); + checked_panda_send(p, 0x18DAF1EF, TRUE, "\x22""es here", 8, 0, LINE_INFO()); + + //Check J2534 constructed the whole message + j2534_recv_loop(chanid, 0); + } + + //Check MF tx will stop upon receiving a flow control ABORT. 29 bit. Good Filter. NoPadding. STD address. Large STmin, then abort, then send SF. + TEST_METHOD(J2534_ISO15765_SuccessTx_29b_Filter_NoPad_STD__MF_FCAbort_SF) + { + auto chanid = J2534_open_and_connect("", ISO15765, CAN_29BIT_ID, 500000, LINE_INFO()); + J2534_set_flowctrl_filter(chanid, CAN_29BIT_ID, 4, "\xff\xff\xff\xff", "\x18\xda\xf1\xef", "\x18\xda\xef\xf1", LINE_INFO()); + write_ioctl(chanid, LOOPBACK, TRUE, LINE_INFO()); + auto p = getPanda(500); + + J2534_send_msg_checked(chanid, ISO15765, 0, CAN_29BIT_ID, 0, 4 + 48, 0, "\x18\xda\xef\xf1""AABBCCDDEEFFGGHHIIJJKKLLMMNNOOPPQQRRSSTTUUVVWWXX", LINE_INFO()); + + auto panda_msg_recv = panda_recv_loop(p, 1); + check_panda_can_msg(panda_msg_recv[0], 0, 0x18DAEFF1, TRUE, FALSE, "\x10\x30""AABBCC", LINE_INFO()); + + panda_msg_recv = checked_panda_send(p, 0x18DAF1EF, TRUE, "\x30\x02\x20", 3, 2, LINE_INFO());//Start a conversation. FC timeout is 32 ms. + check_panda_can_msg(panda_msg_recv[0], 0, 0x18DAEFF1, TRUE, FALSE, "\x21""DDEEFFG", LINE_INFO()); + check_panda_can_msg(panda_msg_recv[1], 0, 0x18DAEFF1, TRUE, FALSE, "\x22""GHHIIJJ", LINE_INFO()); + + panda_msg_recv = checked_panda_send(p, 0x18DAF1EF, TRUE, "\x32\x0\x0", 3, 0, LINE_INFO());//Abort the conversation + + J2534_send_msg_checked(chanid, ISO15765, 0, CAN_29BIT_ID, 0, 4 + 4, 0, "\x18\xda\xef\xf1""SUP!", LINE_INFO()); + + auto j2534_msg_recv = j2534_recv_loop(chanid, 2); + check_J2534_can_msg(j2534_msg_recv[0], ISO15765, CAN_29BIT_ID | TX_INDICATION, 0, 4, 0, "\x18\xda\xef\xf1", LINE_INFO()); + check_J2534_can_msg(j2534_msg_recv[1], ISO15765, CAN_29BIT_ID | TX_MSG_TYPE, 0, 4 + 4, 0, "\x18\xda\xef\xf1""SUP!", LINE_INFO()); + } + + //Check MF tx will stop upon receiving a flow control ABORT during valid blocksize. 29 bit. Good Filter. NoPadding. STD address. Large STmin, then mid tx abort, then send SF. + TEST_METHOD(J2534_ISO15765_SuccessTx_29b_Filter_NoPad_STD__MF_FCMixTXAbort_SF) + { + auto chanid = J2534_open_and_connect("", ISO15765, CAN_29BIT_ID, 500000, LINE_INFO()); + J2534_set_flowctrl_filter(chanid, CAN_29BIT_ID, 4, "\xff\xff\xff\xff", "\x18\xda\xf1\xef", "\x18\xda\xef\xf1", LINE_INFO()); + write_ioctl(chanid, LOOPBACK, TRUE, LINE_INFO()); + auto p = getPanda(500); + + J2534_send_msg_checked(chanid, ISO15765, 0, CAN_29BIT_ID, 0, 4 + 48, 0, "\x18\xda\xef\xf1""AABBCCDDEEFFGGHHIIJJKKLLMMNNOOPPQQRRSSTTUUVVWWXX", LINE_INFO()); + + auto panda_msg_recv = panda_recv_loop(p, 1); + check_panda_can_msg(panda_msg_recv[0], 0, 0x18DAEFF1, TRUE, FALSE, "\x10\x30""AABBCC", LINE_INFO()); + + panda_msg_recv = checked_panda_send(p, 0x18DAF1EF, TRUE, "\x30\x06\x7F", 3, 1, LINE_INFO(), 200);//Start a conversation. FC timeout is 127 ms. + check_panda_can_msg(panda_msg_recv[0], 0, 0x18DAEFF1, TRUE, FALSE, "\x21""DDEEFFG", LINE_INFO()); + + panda_msg_recv = checked_panda_send(p, 0x18DAF1EF, TRUE, "\x32\x0\x0", 3, 0, LINE_INFO());//Abort the conversation + panda_recv_loop(p, 0, 200); + + J2534_send_msg_checked(chanid, ISO15765, 0, CAN_29BIT_ID, 0, 4 + 4, 0, "\x18\xda\xef\xf1""SUP!", LINE_INFO()); + + auto j2534_msg_recv = j2534_recv_loop(chanid, 2); + check_J2534_can_msg(j2534_msg_recv[0], ISO15765, CAN_29BIT_ID | TX_INDICATION, 0, 4, 0, "\x18\xda\xef\xf1", LINE_INFO()); + check_J2534_can_msg(j2534_msg_recv[1], ISO15765, CAN_29BIT_ID | TX_MSG_TYPE, 0, 4 + 4, 0, "\x18\xda\xef\xf1""SUP!", LINE_INFO()); + } + + //Check slow tx can be stalled past timeout with CF WAIT frames. 29 bit. Good Filter. NoPadding. STD address. MF tx that would timeout without WAIT frames. + TEST_METHOD(J2534_ISO15765_SuccessTx_29b_Filter_NoPad_STD_MFWithWaitFrames) + { + auto chanid = J2534_open_and_connect("", ISO15765, CAN_29BIT_ID, 500000, LINE_INFO()); + J2534_set_flowctrl_filter(chanid, CAN_29BIT_ID, 4, "\xff\xff\xff\xff", "\x18\xda\xf1\xef", "\x18\xda\xef\xf1", LINE_INFO()); + write_ioctl(chanid, LOOPBACK, TRUE, LINE_INFO()); + write_ioctl(chanid, ISO15765_WFT_MAX, 10, LINE_INFO()); + auto p = getPanda(500); + + J2534_send_msg_checked(chanid, ISO15765, 0, CAN_29BIT_ID, 0, 4 + 48, 0, "\x18\xda\xef\xf1""AABBCCDDEEFFGGHHIIJJKKLLMMNNOOPPQQRRSSTTUUVVWWXX", LINE_INFO()); + + auto panda_msg_recv = panda_recv_loop(p, 1); + check_panda_can_msg(panda_msg_recv[0], 0, 0x18DAEFF1, TRUE, FALSE, "\x10\x30""AABBCC", LINE_INFO()); + + panda_msg_recv = checked_panda_send(p, 0x18DAF1EF, TRUE, "\x30\x02\x40", 3, 2, LINE_INFO(), 3000);//Start a conversation. FC timeout is 250 ms. + check_panda_can_msg(panda_msg_recv[0], 0, 0x18DAEFF1, TRUE, FALSE, "\x21""DDEEFFG", LINE_INFO()); + check_panda_can_msg(panda_msg_recv[1], 0, 0x18DAEFF1, TRUE, FALSE, "\x22""GHHIIJJ", LINE_INFO()); + + checked_panda_send(p, 0x18DAF1EF, TRUE, "\x31\x0\x0", 3, 0, LINE_INFO(), 100);//Delay the conversation. + Sleep(100); + checked_panda_send(p, 0x18DAF1EF, TRUE, "\x31\x0\x0", 3, 0, LINE_INFO(), 100);//Delay the conversation. + Sleep(100); + checked_panda_send(p, 0x18DAF1EF, TRUE, "\x31\x0\x0", 3, 0, LINE_INFO(), 100);//Delay the conversation. + Sleep(100); + checked_panda_send(p, 0x18DAF1EF, TRUE, "\x31\x0\x0", 3, 0, LINE_INFO(), 100);//Delay the conversation. + Sleep(100); + + panda_msg_recv = checked_panda_send(p, 0x18DAF1EF, TRUE, "\x30\x0\x0", 3, 4, LINE_INFO(), 3000);//Start a conversation. FC timeout is 250 ms. + check_panda_can_msg(panda_msg_recv[0], 0, 0x18DAEFF1, TRUE, FALSE, "\x23""KKLLMMN", LINE_INFO()); + check_panda_can_msg(panda_msg_recv[1], 0, 0x18DAEFF1, TRUE, FALSE, "\x24""NOOPPQQ", LINE_INFO()); + check_panda_can_msg(panda_msg_recv[2], 0, 0x18DAEFF1, TRUE, FALSE, "\x25""RRSSTTU", LINE_INFO());//Some of these should fail to recv if there is an issue. + check_panda_can_msg(panda_msg_recv[3], 0, 0x18DAEFF1, TRUE, FALSE, "\x26""UVVWWXX", LINE_INFO()); + + auto j2534_msg_recv = j2534_recv_loop(chanid, 2); + check_J2534_can_msg(j2534_msg_recv[0], ISO15765, CAN_29BIT_ID | TX_INDICATION, 0, 4, 0, "\x18\xda\xef\xf1", LINE_INFO()); + check_J2534_can_msg(j2534_msg_recv[1], ISO15765, CAN_29BIT_ID | TX_MSG_TYPE, 0, 4 + 48, 0, "\x18\xda\xef\xf1""AABBCCDDEEFFGGHHIIJJKKLLMMNNOOPPQQRRSSTTUUVVWWXX", LINE_INFO()); + } + + //Check slow tx can be stalled past timeout with CF WAIT frames during normal TX. 29 bit. Good Filter. NoPadding. STD address. Stalling working MF tx. + TEST_METHOD(J2534_ISO15765_SuccessTx_29b_Filter_NoPad_STD_MFWithMidTXWaitFrames) + { + auto chanid = J2534_open_and_connect("", ISO15765, CAN_29BIT_ID, 500000, LINE_INFO()); + J2534_set_flowctrl_filter(chanid, CAN_29BIT_ID, 4, "\xff\xff\xff\xff", "\x18\xda\xf1\xef", "\x18\xda\xef\xf1", LINE_INFO()); + write_ioctl(chanid, LOOPBACK, TRUE, LINE_INFO()); + write_ioctl(chanid, ISO15765_WFT_MAX, 10, LINE_INFO()); + auto p = getPanda(500); + + J2534_send_msg_checked(chanid, ISO15765, 0, CAN_29BIT_ID, 0, 4 + 48, 0, "\x18\xda\xef\xf1""AABBCCDDEEFFGGHHIIJJKKLLMMNNOOPPQQRRSSTTUUVVWWXX", LINE_INFO()); + + auto panda_msg_recv = panda_recv_loop(p, 1); + check_panda_can_msg(panda_msg_recv[0], 0, 0x18DAEFF1, TRUE, FALSE, "\x10\x30""AABBCC", LINE_INFO()); + + panda_msg_recv = checked_panda_send(p, 0x18DAF1EF, TRUE, "\x30\x06\x64", 3, 2, LINE_INFO(), 120);//Start a conversation. STmin 100. FC timeout is 250 ms. + check_panda_can_msg(panda_msg_recv[0], 0, 0x18DAEFF1, TRUE, FALSE, "\x21""DDEEFFG", LINE_INFO()); + check_panda_can_msg(panda_msg_recv[1], 0, 0x18DAEFF1, TRUE, FALSE, "\x22""GHHIIJJ", LINE_INFO()); + + panda_msg_recv = checked_panda_send(p, 0x18DAF1EF, TRUE, "\x31\x0\x0", 3, 0, LINE_INFO(), 100);//Delay the conversation. + Sleep(100); + panda_msg_recv = checked_panda_send(p, 0x18DAF1EF, TRUE, "\x31\x0\x0", 3, 0, LINE_INFO(), 100);//Delay the conversation. + Sleep(100); + panda_msg_recv = checked_panda_send(p, 0x18DAF1EF, TRUE, "\x31\x0\x0", 3, 0, LINE_INFO(), 100);//Delay the conversation. + Sleep(100); + panda_msg_recv = checked_panda_send(p, 0x18DAF1EF, TRUE, "\x31\x0\x0", 3, 0, LINE_INFO(), 100);//Delay the conversation. + Sleep(100); + + panda_msg_recv = checked_panda_send(p, 0x18DAF1EF, TRUE, "\x30\x0\x0", 3, 4, LINE_INFO(), 3000);//Start a conversation. FC timeout is 250 ms. + check_panda_can_msg(panda_msg_recv[0], 0, 0x18DAEFF1, TRUE, FALSE, "\x23""KKLLMMN", LINE_INFO()); + check_panda_can_msg(panda_msg_recv[1], 0, 0x18DAEFF1, TRUE, FALSE, "\x24""NOOPPQQ", LINE_INFO()); + check_panda_can_msg(panda_msg_recv[2], 0, 0x18DAEFF1, TRUE, FALSE, "\x25""RRSSTTU", LINE_INFO());//Some of these should fail to recv if there is an issue. + check_panda_can_msg(panda_msg_recv[3], 0, 0x18DAEFF1, TRUE, FALSE, "\x26""UVVWWXX", LINE_INFO()); + + auto j2534_msg_recv = j2534_recv_loop(chanid, 2); + check_J2534_can_msg(j2534_msg_recv[0], ISO15765, CAN_29BIT_ID | TX_INDICATION, 0, 4, 0, "\x18\xda\xef\xf1", LINE_INFO()); + check_J2534_can_msg(j2534_msg_recv[1], ISO15765, CAN_29BIT_ID | TX_MSG_TYPE, 0, 4 + 48, 0, "\x18\xda\xef\xf1""AABBCCDDEEFFGGHHIIJJKKLLMMNNOOPPQQRRSSTTUUVVWWXX", LINE_INFO()); + } + + //Check that too many WAIT frames will abort the transfer. 29 bit. Good Filter. NoPadding. STD address. Too much stalling causes abort. + TEST_METHOD(J2534_ISO15765_SuccessTx_29b_Filter_NoPad_STD_MFTooManyWaitFrames) + { + auto chanid = J2534_open_and_connect("", ISO15765, CAN_29BIT_ID, 500000, LINE_INFO()); + J2534_set_flowctrl_filter(chanid, CAN_29BIT_ID, 4, "\xff\xff\xff\xff", "\x18\xda\xf1\xef", "\x18\xda\xef\xf1", LINE_INFO()); + write_ioctl(chanid, LOOPBACK, TRUE, LINE_INFO()); + write_ioctl(chanid, ISO15765_WFT_MAX, 2, LINE_INFO()); + auto p = getPanda(500); + + J2534_send_msg_checked(chanid, ISO15765, 0, CAN_29BIT_ID, 0, 4 + 48, 0, "\x18\xda\xef\xf1""AABBCCDDEEFFGGHHIIJJKKLLMMNNOOPPQQRRSSTTUUVVWWXX", LINE_INFO()); + + auto panda_msg_recv = panda_recv_loop(p, 1); + check_panda_can_msg(panda_msg_recv[0], 0, 0x18DAEFF1, TRUE, FALSE, "\x10\x30""AABBCC", LINE_INFO()); + + panda_msg_recv = checked_panda_send(p, 0x18DAF1EF, TRUE, "\x30\x02\x64", 3, 2, LINE_INFO(), 120);//Start a conversation. STmin 100. FC timeout is 250 ms. + check_panda_can_msg(panda_msg_recv[0], 0, 0x18DAEFF1, TRUE, FALSE, "\x21""DDEEFFG", LINE_INFO()); + check_panda_can_msg(panda_msg_recv[1], 0, 0x18DAEFF1, TRUE, FALSE, "\x22""GHHIIJJ", LINE_INFO()); + + panda_msg_recv = checked_panda_send(p, 0x18DAF1EF, TRUE, "\x31\x0\x0", 3, 0, LINE_INFO(), 100);//Delay the conversation. + Sleep(100); + panda_msg_recv = checked_panda_send(p, 0x18DAF1EF, TRUE, "\x31\x0\x0", 3, 0, LINE_INFO(), 100);//Delay the conversation. + Sleep(100); + + panda_msg_recv = checked_panda_send(p, 0x18DAF1EF, TRUE, "\x30\x02\x64", 3, 2, LINE_INFO(), 120);//Resume the conversation. + check_panda_can_msg(panda_msg_recv[0], 0, 0x18DAEFF1, TRUE, FALSE, "\x23""KKLLMMN", LINE_INFO()); + check_panda_can_msg(panda_msg_recv[1], 0, 0x18DAEFF1, TRUE, FALSE, "\x24""NOOPPQQ", LINE_INFO()); + + panda_msg_recv = checked_panda_send(p, 0x18DAF1EF, TRUE, "\x31\x0\x0", 3, 0, LINE_INFO(), 100);//Delay the conversation. + Sleep(100); + panda_msg_recv = checked_panda_send(p, 0x18DAF1EF, TRUE, "\x31\x0\x0", 3, 0, LINE_INFO(), 100);//Delay the conversation. + Sleep(100); + + //Should not resume because the conversation has been delayed too long. + panda_msg_recv = checked_panda_send(p, 0x18DAF1EF, TRUE, "\x30\x0\x0", 3, 0, LINE_INFO(), 300); + + //Send a SF message to check the tubes are not clogged. + J2534_send_msg_checked(chanid, ISO15765, 0, CAN_29BIT_ID, 0, 4 + 4, 0, "\x18\xda\xef\xf1""SUP!", LINE_INFO()); + + auto j2534_msg_recv = j2534_recv_loop(chanid, 2); + check_J2534_can_msg(j2534_msg_recv[0], ISO15765, CAN_29BIT_ID | TX_INDICATION, 0, 4, 0, "\x18\xda\xef\xf1", LINE_INFO()); + check_J2534_can_msg(j2534_msg_recv[1], ISO15765, CAN_29BIT_ID | TX_MSG_TYPE, 0, 4 + 4, 0, "\x18\xda\xef\xf1""SUP!", LINE_INFO()); + } + + ///////////////////// Tests checking things actually send/receive. Ext 5 byte Addressing ///////////////////// + + //Check rx passes with filter. 29 bit. Good Filter. NoPadding. EXT address. Single Frame. + TEST_METHOD(J2534_ISO15765_SuccessRx_29b_Filter_NoPad_EXT_SF) + { + auto chanid = J2534_open_and_connect("", ISO15765, CAN_29BIT_ID, 500000, LINE_INFO()); + J2534_set_flowctrl_filter(chanid, CAN_29BIT_ID | ISO15765_ADDR_TYPE, 5, "\xff\xff\xff\xff\xff", "\x18\xda\xf1\xef\x13", "\x18\xda\xef\xf1\x13", LINE_INFO()); + auto p = getPanda(500); + + checked_panda_send(p, 0x18DAF1EF, TRUE, "\x13""\x06""ABC123", 8, 0, LINE_INFO()); + + auto j2534_msg_recv = j2534_recv_loop(chanid, 1); + check_J2534_can_msg(j2534_msg_recv[0], ISO15765, CAN_29BIT_ID | ISO15765_ADDR_TYPE, 0, 11, 11, "\x18\xda\xf1\xef\x13""ABC123", LINE_INFO()); + } + + //Check tx passes with filter. 29 bit. Good Filter. NoPadding. EXT address. Single Frame. + TEST_METHOD(J2534_ISO15765_SuccessTx_29b_Filter_NoPad_EXT_SF) + { + auto chanid = J2534_open_and_connect("", ISO15765, CAN_29BIT_ID, 500000, LINE_INFO()); + J2534_set_flowctrl_filter(chanid, CAN_29BIT_ID | ISO15765_ADDR_TYPE, 5, "\xff\xff\xff\xff\xff", "\x18\xda\xf1\xef\x13", "\x18\xda\xef\xf1\x13", LINE_INFO()); + auto p = getPanda(500); + + J2534_send_msg_checked(chanid, ISO15765, 0, CAN_29BIT_ID | ISO15765_ADDR_TYPE, 0, 11, 0, "\x18\xda\xef\xf1\x13""DERP!!", LINE_INFO()); + auto j2534_msg_recv = j2534_recv_loop(chanid, 1); + check_J2534_can_msg(j2534_msg_recv[0], ISO15765, CAN_29BIT_ID | TX_INDICATION | ISO15765_ADDR_TYPE, 0, 5, 0, "\x18\xda\xef\xf1\x13", LINE_INFO()); + + auto panda_msg_recv = panda_recv_loop(p, 1); + check_panda_can_msg(panda_msg_recv[0], 0, 0x18DAEFF1, TRUE, FALSE, "\x13""\x06""DERP!!", LINE_INFO()); + } + + //Check rx passes with filter. 29 bit. Good Filter. NoPadding. EXT address. Multi Frame. + TEST_METHOD(J2534_ISO15765_SuccessRx_29b_Filter_NoPad_EXT_FFCF) + { + auto chanid = J2534_open_and_connect("", ISO15765, CAN_29BIT_ID, 500000, LINE_INFO()); + J2534_set_flowctrl_filter(chanid, CAN_29BIT_ID | ISO15765_ADDR_TYPE, 5, "\xff\xff\xff\xff\xff", "\x18\xda\xf1\xef\x13", "\x18\xda\xef\xf1\x13", LINE_INFO()); + auto p = getPanda(500); + + //Send first frame, then check we get a flow control frame + Assert::IsTrue(p->can_send(0x18DAF1EF, TRUE, (const uint8_t*)"\x13""\x10\x13""ninet", 8, panda::PANDA_CAN1), _T("Panda send says it failed."), LINE_INFO()); + + //Check first frame is registered with J2534 + auto j2534_msg_recv = j2534_recv_loop(chanid, 1); + check_J2534_can_msg(j2534_msg_recv[0], ISO15765, CAN_29BIT_ID | START_OF_MESSAGE | ISO15765_ADDR_TYPE, 0, 5, 0, "\x18\xda\xf1\xef\x13", LINE_INFO()); + + auto panda_msg_recv = panda_recv_loop(p, 2); + check_panda_can_msg(panda_msg_recv[0], 0, 0x18DAF1EF, TRUE, TRUE, std::string("\x13""\x10\x13""ninet", 8), LINE_INFO()); + check_panda_can_msg(panda_msg_recv[1], 0, 0x18DAEFF1, TRUE, FALSE, std::string("\x13""\x30\x00\x00", 4), LINE_INFO()); + + //Send the rest of the message + checked_panda_send(p, 0x18DAF1EF, TRUE, "\x13""\x21""een by", 8, 0, LINE_INFO()); + checked_panda_send(p, 0x18DAF1EF, TRUE, "\x13""\x22""tes he", 8, 0, LINE_INFO()); + checked_panda_send(p, 0x18DAF1EF, TRUE, "\x13""\x23""re", 8, 0, LINE_INFO()); + + //Check J2534 constructed the whole message + j2534_msg_recv = j2534_recv_loop(chanid, 1); + check_J2534_can_msg(j2534_msg_recv[0], ISO15765, CAN_29BIT_ID | ISO15765_ADDR_TYPE, 0, 5 + 0x13, 5 + 0x13, "\x18\xda\xf1\xef\x13""nineteen bytes here", LINE_INFO()); + } + + //Check tx passes with filter. 29 bit. Good Filter. NoPadding. EXT address. Multi Frame. + /*TEST_METHOD(J2534_ISO15765_SuccessTx_29b_Filter_NoPad_EXT_FFCF) + { //TODO when TX works with flow control}*/ + + ///////////////////// Tests checking things break or recover during send/receive. Ext 5 byte Addressing ///////////////////// + + //Check rx FAILS when frame is dropped. 29 bit. Good Filter. NoPadding. STD address. Multi Frame. + TEST_METHOD(J2534_ISO15765_FailRx_29b_Filter_NoPad_EXT_FFCF_DropFrame) + { + auto chanid = J2534_open_and_connect("", ISO15765, CAN_29BIT_ID, 500000, LINE_INFO()); + J2534_set_flowctrl_filter(chanid, CAN_29BIT_ID | ISO15765_ADDR_TYPE, 5, "\xff\xff\xff\xff\xff", "\x18\xda\xf1\xef\x13", "\x18\xda\xef\xf1\x13", LINE_INFO()); + auto p = getPanda(500); + + //Send first frame, then check we get a flow control frame + auto panda_msg_recv = checked_panda_send(p, 0x18DAF1EF, TRUE, "\x13\x10\x13""ninet", 8, 1, LINE_INFO()); + check_panda_can_msg(panda_msg_recv[0], 0, 0x18DAEFF1, TRUE, FALSE, std::string("\x13\x30\x00\x00", 4), LINE_INFO()); + + //Check first frame is registered with J2534 + auto j2534_msg_recv = j2534_recv_loop(chanid, 1); + check_J2534_can_msg(j2534_msg_recv[0], ISO15765, CAN_29BIT_ID | START_OF_MESSAGE | ISO15765_ADDR_TYPE, 0, 5, 0, "\x18\xda\xf1\xef\x13", LINE_INFO()); + + //Send the rest of the message + //Missing the 2nd frame "\x13""\x21""een by" + checked_panda_send(p, 0x18DAF1EF, TRUE, "\x13""\x22""tes he", 8, 0, LINE_INFO()); + checked_panda_send(p, 0x18DAF1EF, TRUE, "\x13""\x23""re", 8, 0, LINE_INFO()); + + //Check J2534 DOES NOT construct the incomplete message + j2534_recv_loop(chanid, 0); + } + + bool didopen = FALSE; + unsigned long devid; + + unsigned long open_dev(const char* name, long assert_err = STATUS_NOERROR, TCHAR* failmsg = _T("Failed to open device.")) { + unsigned int res = PassThruOpen((void*)name, &devid); + if (res == STATUS_NOERROR) didopen = TRUE; + return res; + } + + unsigned long J2534_open_and_connect(const char* name, unsigned long ProtocolID, unsigned long Flags, unsigned long bps, const __LineInfo* pLineInfo = NULL) { + unsigned long chanid; + Assert::AreEqual(STATUS_NOERROR, open_dev(name), _T("Failed to open device."), pLineInfo); + Assert::AreEqual(STATUS_NOERROR, PassThruConnect(devid, ProtocolID, Flags, bps, &chanid), _T("Failed to open channel."), pLineInfo); + write_ioctl(chanid, LOOPBACK, FALSE, LINE_INFO()); // DISABLE J2534 ECHO/LOOPBACK + return chanid; + } + + }; +} diff --git a/panda/drivers/windows/pandaJ2534DLL Test/pandaJ2534DLL Test.vcxproj b/panda/drivers/windows/pandaJ2534DLL Test/pandaJ2534DLL Test.vcxproj new file mode 100644 index 00000000000000..f19c743461d661 --- /dev/null +++ b/panda/drivers/windows/pandaJ2534DLL Test/pandaJ2534DLL Test.vcxproj @@ -0,0 +1,122 @@ + + + + + Debug + Win32 + + + Release + Win32 + + + + {7912F978-B48C-4C5D-8BFD-5D1E22158E47} + Win32Proj + pandaJ2534DLLTest + 10.0.16299.0 + Tests + + + + DynamicLibrary + true + v141 + Unicode + false + + + DynamicLibrary + false + v141 + true + Unicode + false + + + + + + + + + + + + + + + true + $(SolutionDir)$(Configuration)_$(PlatformShortName)\ + + + true + $(SolutionDir)$(Configuration)_$(PlatformShortName)\ + + + + Use + Level3 + Disabled + $(VCInstallDir)UnitTest\include;%(AdditionalIncludeDirectories);$(SolutionDir) + WIN32;_DEBUG;%(PreprocessorDefinitions) + true + + + Windows + $(VCInstallDir)UnitTest\lib;%(AdditionalLibraryDirectories) + kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);$(OutDir)panda.lib + + + + + Level3 + Use + MaxSpeed + true + true + $(VCInstallDir)UnitTest\include;%(AdditionalIncludeDirectories);$(SolutionDir) + WIN32;NDEBUG;%(PreprocessorDefinitions) + true + + + Windows + true + true + $(VCInstallDir)UnitTest\lib;%(AdditionalLibraryDirectories) + kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);$(OutDir)panda.lib + + + + + + + + + + + + + + + + + Create + Create + + + + + + + + {96e0e646-ee76-444d-9a77-a0cd7f781deb} + + + {a2bb18a5-f26b-48d6-bbb5-b83d64473c77} + + + + + + \ No newline at end of file diff --git a/panda/drivers/windows/pandaJ2534DLL Test/pandaJ2534DLL Test.vcxproj.filters b/panda/drivers/windows/pandaJ2534DLL Test/pandaJ2534DLL Test.vcxproj.filters new file mode 100644 index 00000000000000..476ce458d35534 --- /dev/null +++ b/panda/drivers/windows/pandaJ2534DLL Test/pandaJ2534DLL Test.vcxproj.filters @@ -0,0 +1,63 @@ + + + + + {4FC737F1-C7A5-4376-A066-2A32D752A2FF} + cpp;c;cc;cxx;def;odl;idl;hpj;bat;asm;asmx + + + {93995380-89BD-4b04-88EB-625FBE52EBFB} + h;hh;hpp;hxx;hm;inl;inc;xsd + + + {67DA6AB6-F800-4c08-8B7A-83BB121AAD01} + rc;ico;cur;bmp;dlg;rc2;rct;bin;rgs;gif;jpg;jpeg;jpe;resx;tiff;tif;png;wav;mfcribbon-ms + + + + + Header Files + + + Header Files + + + Header Files + + + Header Files + + + Header Files + + + Header Files + + + Header Files + + + + + Source Files + + + Source Files + + + Source Files + + + Source Files + + + Source Files + + + Source Files + + + Source Files + + + \ No newline at end of file diff --git a/panda/drivers/windows/pandaJ2534DLL Test/panda_tests.cpp b/panda/drivers/windows/pandaJ2534DLL Test/panda_tests.cpp new file mode 100644 index 00000000000000..51b0bfcf2f60b5 --- /dev/null +++ b/panda/drivers/windows/pandaJ2534DLL Test/panda_tests.cpp @@ -0,0 +1,187 @@ +#include "stdafx.h" +#include "panda_shared/panda.h" +#include "TestHelpers.h" + +#include + +using namespace Microsoft::VisualStudio::CppUnitTestFramework; +using namespace panda; + +namespace pandaTestNative +{ + TEST_CLASS(DeviceDiscovery) + { + public: + + TEST_METHOD(Panda_DevDiscover_ListDevices) + { + auto pandas_available = Panda::listAvailablePandas(); + Assert::IsTrue(pandas_available.size() > 0, _T("No pandas were found.")); + for (auto sn : pandas_available) { + Assert::IsTrue(sn.size() == 24, _T("panda Serial Number not 24 characters long.")); + } + } + + TEST_METHOD(Panda_DevDiscover_OpenFirstDevice) + { + auto pandas_available = Panda::listAvailablePandas(); + Assert::IsTrue(pandas_available.size() > 0, _T("No pandas were found.")); + + auto p1 = Panda::openPanda(pandas_available[0]); + Assert::IsFalse(p1 == nullptr, _T("Could not open panda.")); + } + + TEST_METHOD(Panda_DevDiscover_OpenDeviceNoName) + { + auto pandas_available = Panda::listAvailablePandas(); + Assert::IsTrue(pandas_available.size() > 0, _T("No pandas were found.")); + + auto p1 = Panda::openPanda(""); + Assert::IsFalse(p1 == nullptr, _T("Could not open panda.")); + Assert::IsTrue(p1->get_usb_sn() == pandas_available[0], _T("Could not open panda.")); + } + + TEST_METHOD(Panda_DevDiscover_OpenDeviceUnavailable) + { + auto p1 = Panda::openPanda("ZZZZZZZZZZZZZZZZZZZZZZZZ"); + Assert::IsTrue(p1 == nullptr, _T("Invalid sn still worked.")); + } + + TEST_METHOD(Panda_DevDiscover_WillNotOpenAlreadyOpenedDevice) + { + auto pandas_available = Panda::listAvailablePandas(); + Assert::IsTrue(pandas_available.size() > 0, _T("No pandas were found.")); + + auto p1 = Panda::openPanda(pandas_available[0]); + Assert::IsFalse(p1 == nullptr, _T("Could not open panda.")); + + auto p2 = Panda::openPanda(pandas_available[0]); + Assert::IsTrue(p2 == nullptr, _T("Opened an already open panda.")); + } + + TEST_METHOD(Panda_DevDiscover_OpenedDeviceNotListed) + { + auto pandas_available = Panda::listAvailablePandas(); + Assert::IsTrue(pandas_available.size() > 0, _T("No pandas were found.")); + + auto p1 = Panda::openPanda(pandas_available[0]); + Assert::IsFalse(p1 == nullptr, _T("Could not open panda.")); + + auto pandas_available2 = Panda::listAvailablePandas(); + for (auto sn : pandas_available2) { + Assert::IsFalse(p1->get_usb_sn() == sn, _T("Opened panda appears in list of available pandas.")); + } + + } + }; + + TEST_CLASS(CANOperations) + { + public: + + TEST_METHOD(Panda_CAN_Echo) + { + auto p0 = getPanda(500, TRUE); + + uint32_t addr = 0xAA; + bool is_29b = FALSE; + uint8_t candata[8]; + + for (auto canbus : { PANDA_CAN1, PANDA_CAN2, PANDA_CAN3 }) { + uint8_t len = (rand() % 8) + 1; + for (size_t i = 0; i < len; i++) + candata[i] = rand() % 256; + + p0->can_send(addr, is_29b, candata, len, canbus); + Sleep(10); + + auto can_msgs = p0->can_recv(); + + Assert::AreEqual(2, can_msgs.size(), _T("Received the wrong number of CAN messages."), LINE_INFO()); + + for (auto msg : can_msgs) { + Assert::IsTrue(msg.addr == addr, _T("Wrong addr.")); + Assert::IsTrue(msg.bus == canbus, _T("Wrong bus.")); + Assert::IsTrue(msg.len == len, _T("Wrong len.")); + Assert::AreEqual(memcmp(msg.dat, candata, msg.len), 0, _T("Received CAN data not equal")); + for (int i = msg.len; i < 8; i++) + Assert::IsTrue(msg.dat[i] == 0, _T("Received CAN data not trailed by 0s")); + } + + Assert::IsTrue(can_msgs[0].is_receipt, _T("Didn't get receipt.")); + Assert::IsFalse(can_msgs[1].is_receipt, _T("Didn't get echo.")); + } + } + + TEST_METHOD(Panda_CAN_ChangeBaud) + { + auto p0 = getPanda(250); + auto p1 = getPanda(500); + + p0->can_send(0xAA, FALSE, (const uint8_t*)"\x1\x2\x3\x4\x5\x6\x7\x8", 8, panda::PANDA_CAN1); + panda_recv_loop(p0, 0); + panda_recv_loop(p1, 0); + + p0->set_can_speed_kbps(panda::PANDA_CAN1, 500); + + auto panda_msg_recv = panda_recv_loop(p0, 1); + check_panda_can_msg(panda_msg_recv[0], 0, 0xAA, FALSE, TRUE, "\x1\x2\x3\x4\x5\x6\x7\x8", LINE_INFO()); + panda_msg_recv = panda_recv_loop(p1, 1); + check_panda_can_msg(panda_msg_recv[0], 0, 0xAA, FALSE, FALSE, "\x1\x2\x3\x4\x5\x6\x7\x8", LINE_INFO()); + + ////////////////// + + p0->set_can_speed_kbps(panda::PANDA_CAN1, 250); + p0->can_send(0xC4, FALSE, (const uint8_t*)"\xA\B\xC\xD\xE\xF\x10\x11", 8, panda::PANDA_CAN1); + panda_recv_loop(p0, 0); + panda_recv_loop(p1, 0); + + p1->set_can_speed_kbps(panda::PANDA_CAN1, 250); + + panda_msg_recv = panda_recv_loop(p0, 1); + check_panda_can_msg(panda_msg_recv[0], 0, 0xC4, FALSE, TRUE, "\xA\B\xC\xD\xE\xF\x10\x11", LINE_INFO()); + panda_msg_recv = panda_recv_loop(p1, 1); + check_panda_can_msg(panda_msg_recv[0], 0, 0xC4, FALSE, FALSE, "\xA\B\xC\xD\xE\xF\x10\x11", LINE_INFO()); + } + + TEST_METHOD(Panda_CAN_ClearClears) + { + auto p0 = getPanda(500, TRUE); + p0->can_send(0xAA, FALSE, (const uint8_t*)"\x0\x1\x2\x3\x4\x5\x6\x7", 8, panda::PANDA_CAN1); + Sleep(100); + p0->can_clear(PANDA_CAN_RX); + + auto can_msgs = p0->can_recv(); + Assert::IsTrue(can_msgs.size() == 0, _T("Received messages after a clear.")); + } + }; + + TEST_CLASS(SerialOperations) + { + public: + + TEST_METHOD(Panda_LIN_Echo) + { + auto p0 = getPanda(500); + + for (auto lin_port : { SERIAL_LIN1, SERIAL_LIN2 }) { + p0->serial_clear(lin_port); + + for (int i = 0; i < 10; i++) { + uint8_t len = (rand() % LIN_MSG_MAX_LEN) + 1; + std::string lindata; + lindata.reserve(len); + + for (size_t j = 0; j < len; j++) + lindata += (const char)(rand() % 256); + + p0->serial_write(lin_port, lindata.c_str(), len); + Sleep(10); + + auto retdata = p0->serial_read(lin_port); + Assert::AreEqual(retdata, lindata); + } + } + } + }; +} \ No newline at end of file diff --git a/panda/drivers/windows/pandaJ2534DLL Test/stdafx.cpp b/panda/drivers/windows/pandaJ2534DLL Test/stdafx.cpp new file mode 100644 index 00000000000000..84a1f0aaf34351 --- /dev/null +++ b/panda/drivers/windows/pandaJ2534DLL Test/stdafx.cpp @@ -0,0 +1,8 @@ +// stdafx.cpp : source file that includes just the standard includes +// pandaJ2534DLL Test.pch will be the pre-compiled header +// stdafx.obj will contain the pre-compiled type information + +#include "stdafx.h" + +// TODO: reference any additional headers you need in STDAFX.H +// and not in this file diff --git a/panda/drivers/windows/pandaJ2534DLL Test/stdafx.h b/panda/drivers/windows/pandaJ2534DLL Test/stdafx.h new file mode 100644 index 00000000000000..1ac8bd8dcc42c9 --- /dev/null +++ b/panda/drivers/windows/pandaJ2534DLL Test/stdafx.h @@ -0,0 +1,14 @@ +#pragma once + +#include "targetver.h" + +#define WIN32_LEAN_AND_MEAN // Exclude rarely-used stuff from Windows headers +// Windows Header Files: +#include +#include + +// Headers for CppUnitTest +#include "CppUnitTest.h" +#include //Used for formatting in TestHelpers.cpp +#include +#include diff --git a/panda/drivers/windows/pandaJ2534DLL Test/targetver.h b/panda/drivers/windows/pandaJ2534DLL Test/targetver.h new file mode 100644 index 00000000000000..87c0086de751ba --- /dev/null +++ b/panda/drivers/windows/pandaJ2534DLL Test/targetver.h @@ -0,0 +1,8 @@ +#pragma once + +// Including SDKDDKVer.h defines the highest available Windows platform. + +// If you wish to build your application for a previous Windows platform, include WinSDKVer.h and +// set the _WIN32_WINNT macro to the platform you wish to support before including SDKDDKVer.h. + +#include diff --git a/panda/drivers/windows/pandaJ2534DLL/Action.h b/panda/drivers/windows/pandaJ2534DLL/Action.h new file mode 100644 index 00000000000000..e9721c2eda9f29 --- /dev/null +++ b/panda/drivers/windows/pandaJ2534DLL/Action.h @@ -0,0 +1,57 @@ +#pragma once +#include + +#include "J2534Frame.h" + +class J2534Connection; + +/** +An Action represents a unit of work that can be scheduled for execution at a later time. +Actions are not guaranteed to be run at their specified time, but a best effort is made. +An Action will never execute early, but can execute later depending on what is in the +queus. +Many different operations are based on this base class. Instead of making a thread, +consider if the work can be offloaded to the Task Queue. +*/ +class Action +{ +public: + Action( + std::weak_ptr connection, + std::chrono::microseconds delay + ) : connection(connection), delay(delay) { }; + + Action( + std::weak_ptr connection + ) : connection(connection), delay(std::chrono::microseconds(0)) { }; + + //The function called by the task runner when this action is to be invoked. + virtual void execute() = 0; + + //Reschedule this Action for now(). + void scheduleImmediate() { + expire = std::chrono::steady_clock::now(); + } + + //Reschedule this Action relative to its last expiration time. + void scheduleDelay() { + expire += this->delay; + } + + //Reschedule this action {delay} after now(). + void scheduleImmediateDelay() { + expire = std::chrono::steady_clock::now() + this->delay; + } + + //Reschedule this Action based on a specific base time. + void schedule(std::chrono::time_point starttine, BOOL adddelayed) { + this->expire = starttine; + if (adddelayed) + expire += this->delay; + } + + std::weak_ptr connection; + std::chrono::microseconds delay; + //The timestamp at which point this Action is ready to be executed. + std::chrono::time_point expire; +}; diff --git a/panda/drivers/windows/pandaJ2534DLL/J2534Connection.cpp b/panda/drivers/windows/pandaJ2534DLL/J2534Connection.cpp new file mode 100644 index 00000000000000..aa364b0f8a323c --- /dev/null +++ b/panda/drivers/windows/pandaJ2534DLL/J2534Connection.cpp @@ -0,0 +1,283 @@ +#include "stdafx.h" +#include "J2534Connection.h" +#include "Timer.h" + +J2534Connection::J2534Connection( + std::shared_ptr panda_dev, + unsigned long ProtocolID, + unsigned long Flags, + unsigned long BaudRate +) : panda_dev(panda_dev), ProtocolID(ProtocolID), Flags(Flags), BaudRate(BaudRate), port(0) { } + +unsigned long J2534Connection::validateTxMsg(PASSTHRU_MSG* msg) { + if (msg->DataSize < this->getMinMsgLen() || msg->DataSize > this->getMaxMsgLen()) + return ERR_INVALID_MSG; + return STATUS_NOERROR; +} + +long J2534Connection::PassThruReadMsgs(PASSTHRU_MSG *pMsg, unsigned long *pNumMsgs, unsigned long Timeout) { + //Timeout of 0 means return immediately. Non zero means WAIT for that time then return. Dafuk. + long err_code = STATUS_NOERROR; + Timer t = Timer(); + + unsigned long msgnum = 0; + while (msgnum < *pNumMsgs) { + if (Timeout > 0 && t.getTimePassed() >= Timeout) { + err_code = ERR_TIMEOUT; + break; + } + + //Synchronized won't work where we have to break out of a loop + messageRxBuff_mutex.lock(); + if (this->messageRxBuff.empty()) { + messageRxBuff_mutex.unlock(); + if (Timeout == 0) + break; + Sleep(2); + continue; + } + + auto msg_in = this->messageRxBuff.front(); + this->messageRxBuff.pop(); + messageRxBuff_mutex.unlock(); + + PASSTHRU_MSG *msg_out = &pMsg[msgnum++]; + msg_out->ProtocolID = this->ProtocolID; + msg_out->DataSize = msg_in.Data.size(); + memcpy(msg_out->Data, msg_in.Data.c_str(), msg_in.Data.size()); + msg_out->Timestamp = msg_in.Timestamp; + msg_out->RxStatus = msg_in.RxStatus; + msg_out->ExtraDataIndex = msg_in.ExtraDataIndex; + msg_out->TxFlags = 0; + if (msgnum == *pNumMsgs) break; + } + + if (msgnum == 0) + err_code = ERR_BUFFER_EMPTY; + *pNumMsgs = msgnum; + return err_code; +} + +long J2534Connection::PassThruWriteMsgs(PASSTHRU_MSG *pMsg, unsigned long *pNumMsgs, unsigned long Timeout) { + //There doesn't seem to be much reason to implement the timeout here. + for (int msgnum = 0; msgnum < *pNumMsgs; msgnum++) { + PASSTHRU_MSG* msg = &pMsg[msgnum]; + if (msg->ProtocolID != this->ProtocolID) { + *pNumMsgs = msgnum; + return ERR_MSG_PROTOCOL_ID; + } + + auto retcode = this->validateTxMsg(msg); + if (retcode != STATUS_NOERROR) { + *pNumMsgs = msgnum; + return retcode; + } + + auto msgtx = this->parseMessageTx(*pMsg); + if (msgtx != nullptr) //Nullptr is supported for unimplemented connection types. + this->schedultMsgTx(std::dynamic_pointer_cast(msgtx)); + } + return STATUS_NOERROR; +} + +//The docs say that a device has to support 10 periodic messages, though more is ok. +//It is easier to store them on the connection, so 10 per connection it is. +long J2534Connection::PassThruStartPeriodicMsg(PASSTHRU_MSG *pMsg, unsigned long *pMsgID, unsigned long TimeInterval) { + if (pMsg->DataSize < getMinMsgLen() || pMsg->DataSize > getMaxMsgSingleFrameLen()) return ERR_INVALID_MSG; + if (pMsg->ProtocolID != this->ProtocolID) return ERR_MSG_PROTOCOL_ID; + if (TimeInterval < 5 || TimeInterval > 65535) return ERR_INVALID_TIME_INTERVAL; + + for (int i = 0; i < this->periodicMessages.size(); i++) { + if (periodicMessages[i] != nullptr) continue; + + *pMsgID = i; + auto msgtx = this->parseMessageTx(*pMsg); + if (msgtx != nullptr) { + periodicMessages[i] = std::make_shared(std::chrono::microseconds(TimeInterval*1000), msgtx); + periodicMessages[i]->scheduleImmediate(); + if (auto panda_dev = this->getPandaDev()) { + panda_dev->insertActionIntoTaskList(periodicMessages[i]); + } + } + return STATUS_NOERROR; + } + return ERR_EXCEEDED_LIMIT; +} + +long J2534Connection::PassThruStopPeriodicMsg(unsigned long MsgID) { + if (MsgID >= this->periodicMessages.size() || this->periodicMessages[MsgID] == nullptr) + return ERR_INVALID_MSG_ID; + this->periodicMessages[MsgID]->cancel(); + this->periodicMessages[MsgID] = nullptr; + return STATUS_NOERROR; +} + +long J2534Connection::PassThruStartMsgFilter(unsigned long FilterType, PASSTHRU_MSG *pMaskMsg, PASSTHRU_MSG *pPatternMsg, + PASSTHRU_MSG *pFlowControlMsg, unsigned long *pFilterID) { + for (int i = 0; i < this->filters.size(); i++) { + if (filters[i] == nullptr) { + try { + auto newfilter = std::make_shared(this, FilterType, pMaskMsg, pPatternMsg, pFlowControlMsg); + for (int check_idx = 0; check_idx < filters.size(); check_idx++) { + if (filters[check_idx] == nullptr) continue; + if (filters[check_idx] == newfilter) { + filters[i] = nullptr; + return ERR_NOT_UNIQUE; + } + } + *pFilterID = i; + filters[i] = newfilter; + return STATUS_NOERROR; + } catch (int e) { + return e; + } + } + } + return ERR_EXCEEDED_LIMIT; +} + +long J2534Connection::PassThruStopMsgFilter(unsigned long FilterID) { + if (FilterID >= this->filters.size() || this->filters[FilterID] == nullptr) + return ERR_INVALID_FILTER_ID; + this->filters[FilterID] = nullptr; + return STATUS_NOERROR; +} + +long J2534Connection::PassThruIoctl(unsigned long IoctlID, void *pInput, void *pOutput) { + return STATUS_NOERROR; +} + +long J2534Connection::init5b(SBYTE_ARRAY* pInput, SBYTE_ARRAY* pOutput) { return ERR_FAILED; } +long J2534Connection::initFast(PASSTHRU_MSG* pInput, PASSTHRU_MSG* pOutput) { return ERR_FAILED; } +long J2534Connection::clearTXBuff() { + if (auto panda_ps = this->panda_dev.lock()) { + synchronized(staged_writes_lock) { + this->txbuff = {}; + panda_ps->panda->can_clear(panda::PANDA_CAN1_TX); + } + } + return STATUS_NOERROR; +} +long J2534Connection::clearRXBuff() { + if (auto panda_ps = this->panda_dev.lock()) { + synchronized(messageRxBuff_mutex) { + this->messageRxBuff = {}; + panda_ps->panda->can_clear(panda::PANDA_CAN_RX); + } + } + return STATUS_NOERROR; +} +long J2534Connection::clearPeriodicMsgs() { + for (int i = 0; i < this->periodicMessages.size(); i++) { + if (periodicMessages[i] == nullptr) continue; + this->periodicMessages[i]->cancel(); + this->periodicMessages[i] = nullptr; + } + + return STATUS_NOERROR; +} +long J2534Connection::clearMsgFilters() { + for (auto& filter : this->filters) filter = nullptr; + return STATUS_NOERROR; +} + +void J2534Connection::setBaud(unsigned long baud) { + this->BaudRate = baud; +} + +void J2534Connection::schedultMsgTx(std::shared_ptr msgout) { + if (auto panda_ps = this->panda_dev.lock()) { + synchronized(staged_writes_lock) { + this->txbuff.push(msgout); + panda_ps->registerConnectionTx(shared_from_this()); + } + } +} + +void J2534Connection::rescheduleExistingTxMsgs() { + if (auto panda_ps = this->panda_dev.lock()) { + synchronized(staged_writes_lock) { + panda_ps->unstallConnectionTx(shared_from_this()); + } + } +} + +//Works well as long as the protocol doesn't support flow control. +void J2534Connection::processMessage(const J2534Frame& msg) { + FILTER_RESULT filter_res = FILTER_RESULT_NEUTRAL; + + for (auto filter : this->filters) { + if (filter == nullptr) continue; + FILTER_RESULT current_check_res = filter->check(msg); + if (current_check_res == FILTER_RESULT_BLOCK) return; + if (current_check_res == FILTER_RESULT_PASS) filter_res = FILTER_RESULT_PASS; + } + + if (filter_res == FILTER_RESULT_PASS) { + addMsgToRxQueue(msg); + } +} + +void J2534Connection::processIOCTLSetConfig(unsigned long Parameter, unsigned long Value) { + switch (Parameter) { + case DATA_RATE: // 5-500000 + this->setBaud(Value); + break; + case LOOPBACK: // 0 (OFF), 1 (ON) [0] + this->loopback = (Value != 0); + break; + case ISO15765_WFT_MAX: + break; + case NODE_ADDRESS: // J1850PWM Related (Not supported by panda). HDS requires these to 'work'. + case NETWORK_LINE: + case P1_MIN: // A bunch of stuff relating to ISO9141 and ISO14230 that the panda + case P1_MAX: // currently doesn't support. Don't let HDS know we can't use these. + case P2_MIN: + case P2_MAX: + case P3_MIN: + case P3_MAX: + case P4_MIN: + case P4_MAX: + case W0: + case W1: + case W2: + case W3: + case W4: + case W5: + case TIDLE: + case TINIL: + case TWUP: + case PARITY: + case T1_MAX: // SCI related options. The panda does not appear to support this + case T2_MAX: + case T3_MAX: + case T4_MAX: + case T5_MAX: + break; // Just smile and nod. + default: + printf("Got unknown SET code %X\n", Parameter); + } + + // reserved parameters usually mean special equiptment is required + if (Parameter >= 0x20) { + throw ERR_NOT_SUPPORTED; + } +} + +unsigned long J2534Connection::processIOCTLGetConfig(unsigned long Parameter) { + switch (Parameter) { + case DATA_RATE: + return this->getBaud(); + case LOOPBACK: + return this->loopback; + break; + case BIT_SAMPLE_POINT: + return 80; + case SYNC_JUMP_WIDTH: + return 15; + default: + // HDS rarely reads off values through ioctl GET_CONFIG, but it often + // just wants the call to pass without erroring, so just don't do anything. + printf("Got unknown code %X\n", Parameter); + } +} diff --git a/panda/drivers/windows/pandaJ2534DLL/J2534Connection.h b/panda/drivers/windows/pandaJ2534DLL/J2534Connection.h new file mode 100644 index 00000000000000..70f25a1063f09f --- /dev/null +++ b/panda/drivers/windows/pandaJ2534DLL/J2534Connection.h @@ -0,0 +1,141 @@ +#pragma once +#include "panda_shared/panda.h" +#include "J2534_v0404.h" +#include "synchronize.h" +#include "J2534Frame.h" +#include "PandaJ2534Device.h" +#include "J2534MessageFilter.h" +#include "MessagePeriodic.h" + +class J2534Frame; +class Action; +class PandaJ2534Device; +class J2534MessageFilter; + +#define check_bmask(num, mask)(((num) & mask) == mask) + +/** +Class representing a generic J2534 Connection created by PassThruConnect, +and is associated with a channelID given to the J2534 API user. +Subclasses implement specific J2534 supported protocols. +*/ +class J2534Connection : public std::enable_shared_from_this { + friend class PandaJ2534Device; + +public: + J2534Connection( + std::shared_ptr panda_dev, + unsigned long ProtocolID, + unsigned long Flags, + unsigned long BaudRate + ); + virtual ~J2534Connection() {}; + + //J2534 API functions + + virtual long PassThruReadMsgs(PASSTHRU_MSG *pMsg, unsigned long *pNumMsgs, unsigned long Timeout); + long PassThruWriteMsgs(PASSTHRU_MSG *pMsg, unsigned long *pNumMsgs, unsigned long Timeout); + virtual long PassThruStartPeriodicMsg(PASSTHRU_MSG *pMsg, unsigned long *pMsgID, unsigned long TimeInterval); + virtual long PassThruStopPeriodicMsg(unsigned long MsgID); + + virtual long PassThruStartMsgFilter(unsigned long FilterType, PASSTHRU_MSG *pMaskMsg, PASSTHRU_MSG *pPatternMsg, + PASSTHRU_MSG *pFlowControlMsg, unsigned long *pFilterID); + + virtual long PassThruStopMsgFilter(unsigned long FilterID); + virtual long PassThruIoctl(unsigned long IoctlID, void *pInput, void *pOutput); + + //Functions for parsing messages to be send with PassThruWriteMsgs. + + virtual unsigned long validateTxMsg(PASSTHRU_MSG* msg); + virtual std::shared_ptr parseMessageTx(PASSTHRU_MSG& msg) { return nullptr; }; + + //IOCTL functions + + long init5b(SBYTE_ARRAY* pInput, SBYTE_ARRAY* pOutput); + long initFast(PASSTHRU_MSG* pInput, PASSTHRU_MSG* pOutput); + long clearTXBuff(); + long clearRXBuff(); + long clearPeriodicMsgs(); + long clearMsgFilters(); + + virtual void setBaud(unsigned long baud); + + unsigned long getBaud() { + return this->BaudRate; + } + + unsigned long getProtocol() { + return this->ProtocolID; + }; + + virtual bool isProtoCan() { + return FALSE; + } + + //Port is used in a protocol specific way to differentiate tranceivers. + unsigned long getPort() { + return this->port; + } + + virtual void processIOCTLSetConfig(unsigned long Parameter, unsigned long Value); + + virtual unsigned long processIOCTLGetConfig(unsigned long Parameter); + + //Called when the passthru device has received a message for this connection + //Loopback messages are processed separately. + virtual void processMessage(const J2534Frame& msg); + + //Limitations on message size. Override in every subclass. + + virtual unsigned long getMinMsgLen() { + return 1; + } + + virtual unsigned long getMaxMsgLen() { + return 4128; + } + + virtual unsigned long getMaxMsgSingleFrameLen() { + return 12; + } + + //Add an Action to the Task Queue for future processing. + //The task should be set its expire time before being submitted. + void schedultMsgTx(std::shared_ptr msgout); + + void rescheduleExistingTxMsgs(); + + std::shared_ptr getPandaDev() { + if (auto panda_dev_sp = this->panda_dev.lock()) + return panda_dev_sp; + return nullptr; + } + + //Add a message to the queue read by PassThruReadMsgs(). + void addMsgToRxQueue(const J2534Frame& frame) { + synchronized(messageRxBuff_mutex) { + messageRxBuff.push(frame); + } + } + + bool loopback = FALSE; + +protected: + unsigned long ProtocolID; + unsigned long Flags; + unsigned long BaudRate; + unsigned long port; + + std::weak_ptr panda_dev; + + Mutex messageRxBuff_mutex; + std::queue messageRxBuff; + + std::array, 10> filters; + std::queue> txbuff; + + std::array, 10> periodicMessages; + +private: + Mutex staged_writes_lock; +}; diff --git a/panda/drivers/windows/pandaJ2534DLL/J2534Connection_CAN.cpp b/panda/drivers/windows/pandaJ2534DLL/J2534Connection_CAN.cpp new file mode 100644 index 00000000000000..342616900d0e39 --- /dev/null +++ b/panda/drivers/windows/pandaJ2534DLL/J2534Connection_CAN.cpp @@ -0,0 +1,41 @@ +#include "stdafx.h" +#include "J2534Connection_CAN.h" +#include "MessageTx_CAN.h" +#include "Timer.h" + +J2534Connection_CAN::J2534Connection_CAN( + std::shared_ptr panda_dev, + unsigned long ProtocolID, + unsigned long Flags, + unsigned long BaudRate + ) : J2534Connection(panda_dev, ProtocolID, Flags, BaudRate) { + this->port = 0; + + if (BaudRate % 100 || BaudRate < 10000 || BaudRate > 5000000) + throw ERR_INVALID_BAUDRATE; + + panda_dev->panda->set_can_speed_cbps(panda::PANDA_CAN1, BaudRate/100); +}; + +unsigned long J2534Connection_CAN::validateTxMsg(PASSTHRU_MSG* msg) { + if ((msg->DataSize < this->getMinMsgLen() || msg->DataSize > this->getMaxMsgLen() || + (val_is_29bit(msg->TxFlags) != this->_is_29bit() && !check_bmask(this->Flags, CAN_ID_BOTH)))) + return ERR_INVALID_MSG; + return STATUS_NOERROR; +} + +std::shared_ptr J2534Connection_CAN::parseMessageTx(PASSTHRU_MSG& msg) { + return std::dynamic_pointer_cast(std::make_shared(shared_from_this(), msg)); +} + +void J2534Connection_CAN::setBaud(unsigned long BaudRate) { + if (auto panda_dev = this->getPandaDev()) { + if (BaudRate % 100 || BaudRate < 10000 || BaudRate > 5000000) + throw ERR_NOT_SUPPORTED; + + panda_dev->panda->set_can_speed_cbps(panda::PANDA_CAN1, (uint16_t)(BaudRate / 100)); + return J2534Connection::setBaud(BaudRate); + } else { + throw ERR_DEVICE_NOT_CONNECTED; + } +} diff --git a/panda/drivers/windows/pandaJ2534DLL/J2534Connection_CAN.h b/panda/drivers/windows/pandaJ2534DLL/J2534Connection_CAN.h new file mode 100644 index 00000000000000..3971351eea369a --- /dev/null +++ b/panda/drivers/windows/pandaJ2534DLL/J2534Connection_CAN.h @@ -0,0 +1,43 @@ +#pragma once + +#include "J2534Connection.h" +#include "panda_shared/panda.h" + +#define val_is_29bit(num) check_bmask(num, CAN_29BIT_ID) + +class J2534Connection_CAN : public J2534Connection { +public: + J2534Connection_CAN( + std::shared_ptr panda_dev, + unsigned long ProtocolID, + unsigned long Flags, + unsigned long BaudRate + ); + + virtual unsigned long validateTxMsg(PASSTHRU_MSG* msg); + + virtual std::shared_ptr parseMessageTx(PASSTHRU_MSG& pMsg); + + virtual void setBaud(unsigned long baud); + + virtual unsigned long getMinMsgLen() { + return 4; + } + + virtual unsigned long getMaxMsgLen() { + return 12; + } + + virtual unsigned long getMaxMsgSingleFrameLen() { + return 12; + } + + virtual bool isProtoCan() { + return TRUE; + } + + bool _is_29bit() { + return (this->Flags & CAN_29BIT_ID) == CAN_29BIT_ID; + } + +}; \ No newline at end of file diff --git a/panda/drivers/windows/pandaJ2534DLL/J2534Connection_ISO15765.cpp b/panda/drivers/windows/pandaJ2534DLL/J2534Connection_ISO15765.cpp new file mode 100644 index 00000000000000..a83f6f433135f2 --- /dev/null +++ b/panda/drivers/windows/pandaJ2534DLL/J2534Connection_ISO15765.cpp @@ -0,0 +1,232 @@ +#include "stdafx.h" +#include "J2534Connection_ISO15765.h" +#include "Timer.h" +#include "constants_ISO15765.h" +#include + +J2534Connection_ISO15765::J2534Connection_ISO15765( + std::shared_ptr panda_dev, + unsigned long ProtocolID, + unsigned long Flags, + unsigned long BaudRate +) : J2534Connection(panda_dev, ProtocolID, Flags, BaudRate), wftMax(0) { + this->port = 0; + + if (BaudRate % 100 || BaudRate < 10000 || BaudRate > 5000000) + throw ERR_INVALID_BAUDRATE; + + panda_dev->panda->set_can_speed_cbps(panda::PANDA_CAN1, (uint16_t)(BaudRate / 100)); +} + +unsigned long J2534Connection_ISO15765::validateTxMsg(PASSTHRU_MSG* msg) { + if ((msg->DataSize < this->getMinMsgLen() + (msg_is_extaddr(msg) ? 1 : 0) || + msg->DataSize > this->getMaxMsgLen() + (msg_is_extaddr(msg) ? 1 : 0) || + (val_is_29bit(msg->TxFlags) != this->_is_29bit() && !check_bmask(this->Flags, CAN_ID_BOTH)))) + return ERR_INVALID_MSG; + + int fid = get_matching_out_fc_filter_id(std::string((const char*)msg->Data, msg->DataSize), msg->TxFlags, 0xFFFFFFFF); + if (msg->DataSize > getMaxMsgSingleFrameLen() && fid == -1) return ERR_NO_FLOW_CONTROL; //11 bytes (4 for CANid, 7 payload) is max length of input frame. + + return STATUS_NOERROR; +} + +std::shared_ptr J2534Connection_ISO15765::parseMessageTx(PASSTHRU_MSG& msg) { + int fid = get_matching_out_fc_filter_id(std::string((const char*)msg.Data, msg.DataSize), msg.TxFlags, 0xFFFFFFFF); + if (msg.DataSize > getMaxMsgSingleFrameLen() && fid == -1) 1; + + return std::dynamic_pointer_cast( + std::make_shared(shared_from_this(), msg, (fid == -1) ? nullptr : this->filters[fid]) + ); +} + +//https://happilyembedded.wordpress.com/2016/02/15/can-multiple-frame-transmission/ +void J2534Connection_ISO15765::processMessage(const J2534Frame& msg) { + if (msg.ProtocolID != CAN) return; + + int fid = get_matching_in_fc_filter_id(msg, this->Flags); + if (fid == -1) return; + + auto filter = this->filters[fid]; + bool is_ext_addr = check_bmask(filter->flags, ISO15765_ADDR_TYPE); + uint8_t addrlen = is_ext_addr ? 5 : 4; + + switch (msg_get_type(msg, addrlen)) { + case FRAME_FLOWCTRL: + { + if (this->txbuff.size() == 0) + return; + if (msg.Data.size() < addrlen + 3) return; + uint8_t flow_status = msg.Data[addrlen] & 0x0F; + uint8_t block_size = msg.Data[addrlen + 1]; + uint8_t st_min = msg.Data[addrlen + 2]; + + auto txConvo = std::static_pointer_cast(this->txbuff.front()); + switch (flow_status) { + case FLOWCTRL_CONTINUE: { + if (st_min > 0xF9) break; + if (st_min >= 0xf1 && st_min <= 0xf9) { + txConvo->flowControlContinue(block_size, std::chrono::microseconds((st_min & 0x0F) * 100)); + } else if(st_min <= 0x7f) { + txConvo->flowControlContinue(block_size, std::chrono::microseconds(st_min * 1000)); + } else { + break; + } + txConvo->scheduleImmediate(); + this->rescheduleExistingTxMsgs(); + break; + } + case FLOWCTRL_WAIT: + txConvo->flowControlWait(this->wftMax); + break; + case FLOWCTRL_ABORT: + txConvo->flowControlAbort(); + break; + } + break; + } + case FRAME_SINGLE: + { + this->rxConversations[fid] = nullptr; //Reset any current transaction. + + if (is_ext_addr) { + if ((msg.Data[5] & 0x0F) > 6) return; + } else { + if ((msg.Data[4] & 0x0F) > 7) return; + } + + J2534Frame outframe(ISO15765, msg.RxStatus, 0, msg.Timestamp); + if (msg.Data.size() != 8 && check_bmask(this->Flags, ISO15765_FRAME_PAD)) + outframe.RxStatus |= ISO15765_PADDING_ERROR; + if (is_ext_addr) + outframe.RxStatus |= ISO15765_ADDR_TYPE; + outframe.Data = msg.Data.substr(0, addrlen) + msg.Data.substr(addrlen + 1, msg.Data[addrlen]); + outframe.ExtraDataIndex = outframe.Data.size(); + + addMsgToRxQueue(outframe); + break; + } + case FRAME_FIRST: + { + if (msg.Data.size() < 12) { + //A frame was received that could have held more data. + //No examples of this protocol show that happening, so + //it will be assumed that it is grounds to reset rx. + this->rxConversations[fid] = nullptr; + return; + } + + J2534Frame outframe(ISO15765, msg.RxStatus | START_OF_MESSAGE, 0, msg.Timestamp); + if (is_ext_addr) + outframe.RxStatus |= ISO15765_ADDR_TYPE; + outframe.Data = msg.Data.substr(0, addrlen); + + addMsgToRxQueue(outframe); + + this->rxConversations[fid] = std::make_shared( + ((msg.Data[addrlen] & 0x0F) << 8) | msg.Data[addrlen + 1], + msg.Data.substr(addrlen + 2, 12 - (addrlen + 2)), + msg.RxStatus, filter); + + //TODO maybe the flow control should also be scheduled in the TX list. + //Doing it this way because the filter can be 5 bytes in ext address mode. + std::string flowfilter = filter->get_flowctrl(); + uint32_t flow_addr = (((uint8_t)flowfilter[0]) << 24) | ((uint8_t)(flowfilter[1]) << 16) | ((uint8_t)(flowfilter[2]) << 8) | ((uint8_t)flowfilter[3]); + + std::string flowstrlresp; + if (flowfilter.size() > 4) + flowstrlresp += flowfilter[4]; + flowstrlresp += std::string("\x30\x00\x00", 3); + if (check_bmask(filter->flags, ISO15765_FRAME_PAD)) { + flowstrlresp += std::string(8 - flowstrlresp.size(), '\x00'); + } + + if (auto panda_dev_sp = this->panda_dev.lock()) { + panda_dev_sp->panda->can_send(flow_addr, val_is_29bit(msg.RxStatus), (const uint8_t *)flowstrlresp.c_str(), (uint8_t)flowstrlresp.size(), panda::PANDA_CAN1); + } + break; + } + case FRAME_CONSEC: + { + auto& convo = this->rxConversations[fid]; + if (convo == nullptr) return; + + if (!convo->rx_add_frame(msg.Data[addrlen], (is_ext_addr ? 6 : 7), msg.Data.substr(addrlen + 1))) { + //Delete this conversation. + convo = nullptr; + return; + } + + std::string final_msg; + if (convo->flush_result(final_msg)) { + convo = nullptr; + J2534Frame outframe(ISO15765, msg.RxStatus, 0, msg.Timestamp); + if (is_ext_addr) + outframe.RxStatus |= ISO15765_ADDR_TYPE; + outframe.Data = msg.Data.substr(0, addrlen) + final_msg; + outframe.ExtraDataIndex = outframe.Data.size(); + + addMsgToRxQueue(outframe); + } + break; + } + } +} + +void J2534Connection_ISO15765::setBaud(unsigned long BaudRate) { + if (auto panda_dev = this->getPandaDev()) { + if (BaudRate % 100 || BaudRate < 10000 || BaudRate > 5000000) + throw ERR_NOT_SUPPORTED; + + panda_dev->panda->set_can_speed_cbps(panda::PANDA_CAN1, (uint16_t)(BaudRate / 100)); + return J2534Connection::setBaud(BaudRate); + } else { + throw ERR_DEVICE_NOT_CONNECTED; + } +} + +long J2534Connection_ISO15765::PassThruStartMsgFilter(unsigned long FilterType, PASSTHRU_MSG *pMaskMsg, PASSTHRU_MSG *pPatternMsg, + PASSTHRU_MSG *pFlowControlMsg, unsigned long *pFilterID) { + + if (FilterType != FLOW_CONTROL_FILTER) return ERR_INVALID_FILTER_ID; + return J2534Connection::PassThruStartMsgFilter(FilterType, pMaskMsg, pPatternMsg, pFlowControlMsg, pFilterID); +} + +int J2534Connection_ISO15765::get_matching_out_fc_filter_id(const std::string& msgdata, unsigned long flags, unsigned long flagmask) { + for (unsigned int i = 0; i < this->filters.size(); i++) { + if (this->filters[i] == nullptr) continue; + auto filter = this->filters[i]->get_flowctrl(); + if (filter == msgdata.substr(0, filter.size()) && + (this->filters[i]->flags & flagmask) == (flags & flagmask)) + return i; + } + return -1; +} + +int J2534Connection_ISO15765::get_matching_in_fc_filter_id(const J2534Frame& msg, unsigned long flagmask) { + for (unsigned int i = 0; i < this->filters.size(); i++) { + if (this->filters[i] == nullptr) continue; + if (this->filters[i]->check(msg) == FILTER_RESULT_MATCH && + (this->filters[i]->flags & flagmask) == (msg.RxStatus & flagmask)) + return i; + } + return -1; +} + +void J2534Connection_ISO15765::processIOCTLSetConfig(unsigned long Parameter, unsigned long Value) { + switch (Parameter) { + case ISO15765_WFT_MAX: + this->wftMax = Value; + break; + default: + J2534Connection::processIOCTLSetConfig(Parameter, Value); + } +} + +unsigned long J2534Connection_ISO15765::processIOCTLGetConfig(unsigned long Parameter) { + switch (Parameter) { + case ISO15765_WFT_MAX: + return this->wftMax; + default: + return J2534Connection::processIOCTLGetConfig(Parameter); + } +} diff --git a/panda/drivers/windows/pandaJ2534DLL/J2534Connection_ISO15765.h b/panda/drivers/windows/pandaJ2534DLL/J2534Connection_ISO15765.h new file mode 100644 index 00000000000000..beb9f012e09976 --- /dev/null +++ b/panda/drivers/windows/pandaJ2534DLL/J2534Connection_ISO15765.h @@ -0,0 +1,65 @@ +#pragma once +#include +#include "J2534Connection.h" +#include "J2534Connection_CAN.h" +#include "MessageTx_ISO15765.h" +#include "MessageRx.h" + +class MessageTx_ISO15765; + +typedef struct { + std::string dispatched_msg; + std::string remaining_payload; +} PRESTAGED_WRITE; + +class J2534Connection_ISO15765 : public J2534Connection { +public: + J2534Connection_ISO15765( + std::shared_ptr panda_dev, + unsigned long ProtocolID, + unsigned long Flags, + unsigned long BaudRate + ); + + virtual long PassThruStartMsgFilter(unsigned long FilterType, PASSTHRU_MSG * pMaskMsg, PASSTHRU_MSG * pPatternMsg, PASSTHRU_MSG * pFlowControlMsg, unsigned long * pFilterID); + + int get_matching_out_fc_filter_id(const std::string & msgdata, unsigned long flags, unsigned long flagmask); + + int get_matching_in_fc_filter_id(const J2534Frame& msg, unsigned long flagmask); + + virtual unsigned long validateTxMsg(PASSTHRU_MSG* msg); + + virtual std::shared_ptr parseMessageTx(PASSTHRU_MSG& msg); + + virtual void processMessage(const J2534Frame& msg); + + virtual void setBaud(unsigned long baud); + + virtual void processIOCTLSetConfig(unsigned long Parameter, unsigned long Value); + + virtual unsigned long processIOCTLGetConfig(unsigned long Parameter); + + virtual unsigned long getMinMsgLen() { + return 4; + } + + virtual unsigned long getMaxMsgLen() { + return 4099; + }; + + virtual unsigned long getMaxMsgSingleFrameLen() { + return 11; + } + + virtual bool _is_29bit() { + return (this->Flags & CAN_29BIT_ID) == CAN_29BIT_ID; + } + + virtual bool isProtoCan() { + return TRUE; + } + +private: + std::array, 10> rxConversations; + unsigned int wftMax; +}; diff --git a/panda/drivers/windows/pandaJ2534DLL/J2534Frame.h b/panda/drivers/windows/pandaJ2534DLL/J2534Frame.h new file mode 100644 index 00000000000000..2549216b6f1fac --- /dev/null +++ b/panda/drivers/windows/pandaJ2534DLL/J2534Frame.h @@ -0,0 +1,48 @@ +#pragma once +#include "J2534_v0404.h" +#include "panda_shared/panda.h" + +/*A move convenient container for J2534 Messages than the static buffer provided by default.*/ +class J2534Frame { +public: + J2534Frame(unsigned long ProtocolID, unsigned long RxStatus=0, unsigned long TxFlags=0, unsigned long Timestamp=0) : + ProtocolID(ProtocolID), RxStatus(RxStatus), TxFlags(TxFlags), Timestamp(Timestamp), ExtraDataIndex(0), Data("") { }; + + J2534Frame(const panda::PANDA_CAN_MSG& msg_in) { + ProtocolID = CAN; + ExtraDataIndex = msg_in.len + 4; + Data.reserve(msg_in.len + 4); + Data += msg_in.addr >> 24; + Data += (msg_in.addr >> 16) & 0xFF; + Data += (msg_in.addr >> 8) & 0xFF; + Data += msg_in.addr & 0xFF; + Data += std::string((char*)&msg_in.dat, msg_in.len); + Timestamp = msg_in.recv_time; + RxStatus = (msg_in.addr_29b ? CAN_29BIT_ID : 0) | + (msg_in.is_receipt ? TX_MSG_TYPE : 0); + } + + J2534Frame(const PASSTHRU_MSG& msg) { + this->ProtocolID = msg.ProtocolID; + this->RxStatus = msg.RxStatus; + this->TxFlags = msg.TxFlags; + this->Timestamp = msg.Timestamp; + this->ExtraDataIndex = msg.ExtraDataIndex; + this->Data = std::string((const char*)msg.Data, msg.DataSize); + } + + J2534Frame() { + this->ProtocolID = 0; + this->RxStatus = 0; + this->TxFlags = 0; + this->Timestamp = 0; + this->ExtraDataIndex = 0; + } + + unsigned long ProtocolID; + unsigned long RxStatus; + unsigned long TxFlags; + unsigned long Timestamp; + unsigned long ExtraDataIndex; + std::string Data; +}; \ No newline at end of file diff --git a/panda/drivers/windows/pandaJ2534DLL/J2534MessageFilter.cpp b/panda/drivers/windows/pandaJ2534DLL/J2534MessageFilter.cpp new file mode 100644 index 00000000000000..2d19e1f4e5a63a --- /dev/null +++ b/panda/drivers/windows/pandaJ2534DLL/J2534MessageFilter.cpp @@ -0,0 +1,104 @@ +#include "stdafx.h" +#include "J2534MessageFilter.h" +#include "J2534Frame.h" + +J2534MessageFilter::J2534MessageFilter( + J2534Connection *const conn, + unsigned int filtertype, + PASSTHRU_MSG *pMaskMsg, + PASSTHRU_MSG *pPatternMsg, + PASSTHRU_MSG *pFlowControlMsg +) : filtertype(filtertype), flags(0), conn(conn) { + switch (filtertype) { + case PASS_FILTER: + case BLOCK_FILTER: + if (pMaskMsg == NULL || pPatternMsg == NULL) + throw ERR_NULL_PARAMETER; + if (pFlowControlMsg != NULL) + throw ERR_INVALID_FILTER_ID; + if (pMaskMsg->DataSize != pPatternMsg->DataSize) + throw ERR_INVALID_MSG; + break; + case FLOW_CONTROL_FILTER: + if (conn->getProtocol() != ISO15765) throw ERR_MSG_PROTOCOL_ID; //CHECK + if (pFlowControlMsg == NULL || pMaskMsg == NULL || pPatternMsg == NULL) + throw ERR_NULL_PARAMETER; + break; + default: + throw ERR_INVALID_MSG; + } + + if (!(conn->getMinMsgLen() < pMaskMsg->DataSize || pMaskMsg->DataSize < conn->getMaxMsgLen())) + throw ERR_INVALID_MSG; + if (conn->getProtocol() != pMaskMsg->ProtocolID) + throw ERR_MSG_PROTOCOL_ID; + this->maskMsg = std::string((char*)pMaskMsg->Data, pMaskMsg->DataSize); + + if (!(conn->getMinMsgLen() < pPatternMsg->DataSize || pPatternMsg->DataSize < conn->getMaxMsgLen())) + throw ERR_INVALID_MSG; + if (conn->getProtocol() != pPatternMsg->ProtocolID) + throw ERR_MSG_PROTOCOL_ID; + this->patternMsg = std::string((char*)pPatternMsg->Data, pPatternMsg->DataSize); + if (this->maskMsg.size() != this->patternMsg.size()) + throw ERR_INVALID_MSG; + + if (pFlowControlMsg) { + if (!(conn->getMinMsgLen() < pFlowControlMsg->DataSize || pFlowControlMsg->DataSize < conn->getMaxMsgLen())) + throw ERR_INVALID_MSG; + if (conn->getProtocol() != pFlowControlMsg->ProtocolID) + throw ERR_MSG_PROTOCOL_ID; + if (pMaskMsg->TxFlags != pPatternMsg->TxFlags || pMaskMsg->TxFlags != pFlowControlMsg->TxFlags) + throw ERR_INVALID_MSG; + if(pFlowControlMsg->TxFlags & ~(ISO15765_FRAME_PAD | CAN_29BIT_ID | ISO15765_ADDR_TYPE)) + throw ERR_INVALID_MSG; + if ((pFlowControlMsg->TxFlags & ISO15765_ADDR_TYPE) == ISO15765_ADDR_TYPE) { + if(pFlowControlMsg->DataSize != 5) + throw ERR_INVALID_MSG; + } else { + if (pFlowControlMsg->DataSize != 4) + throw ERR_INVALID_MSG; + } + this->flowCtrlMsg = std::string((char*)pFlowControlMsg->Data, pFlowControlMsg->DataSize); + if (this->flowCtrlMsg.size() != this->patternMsg.size()) + throw ERR_INVALID_MSG; + this->flags = pFlowControlMsg->TxFlags; + } +} + +bool J2534MessageFilter::operator ==(const J2534MessageFilter &b) const { + if (this->filtertype != b.filtertype) return FALSE; + if (this->maskMsg != b.maskMsg) return FALSE; + if (this->patternMsg != b.patternMsg) return FALSE; + if (this->flowCtrlMsg != b.flowCtrlMsg) return FALSE; + if (this->flags != b.flags) return FALSE; + return TRUE; +} + +FILTER_RESULT J2534MessageFilter::check(const J2534Frame& msg) { + bool matches = TRUE; + if (msg.Data.size() < this->maskMsg.size()) { + matches = FALSE; + } else { + for (int i = 0; i < this->maskMsg.size(); i++) { + if (this->patternMsg[i] != (msg.Data[i] & this->maskMsg[i])) { + matches = FALSE; + break; + } + } + } + + switch (this->filtertype) { + case PASS_FILTER: + return matches ? FILTER_RESULT_PASS : FILTER_RESULT_NEUTRAL; + case BLOCK_FILTER: + return matches ? FILTER_RESULT_BLOCK: FILTER_RESULT_NEUTRAL; + case FLOW_CONTROL_FILTER: + return matches ? FILTER_RESULT_MATCH : FILTER_RESULT_NOMATCH; + default: + throw std::out_of_range("Filtertype should not be able to be anything but PASS, BLOCK, or FLOW_CONTROL"); + } +} + +std::string J2534MessageFilter::get_flowctrl() { + return std::string(this->flowCtrlMsg); +} diff --git a/panda/drivers/windows/pandaJ2534DLL/J2534MessageFilter.h b/panda/drivers/windows/pandaJ2534DLL/J2534MessageFilter.h new file mode 100644 index 00000000000000..c5e9a68390b1bf --- /dev/null +++ b/panda/drivers/windows/pandaJ2534DLL/J2534MessageFilter.h @@ -0,0 +1,47 @@ +#pragma once +#include "J2534_v0404.h" +#include "J2534Connection.h" +#include "J2534Frame.h" + +typedef enum { + FILTER_RESULT_BLOCK, + FILTER_RESULT_NEUTRAL, + FILTER_RESULT_PASS, + FILTER_RESULT_NOMATCH = FILTER_RESULT_BLOCK, + FILTER_RESULT_MATCH = FILTER_RESULT_PASS, +} FILTER_RESULT; + +//Forward declare +class J2534Connection; + +/* Represents a J2534 Message Filter created by PassThruStartMsgFilter. + +J2534 uses filters to sort out messages in a simple and sane way. Except for +flow control filters. J2534 v04.04 uses filters to manage 'conversations' in +protocols that support flow control like ISO15765. The whole solution is a +hack, and J2534 v05.00 greatly simplifies this concept. But we are using +v04.04 so, here we are. +*/ +class J2534MessageFilter { +public: + J2534MessageFilter( + J2534Connection *const conn, + unsigned int filtertype, + PASSTHRU_MSG *pMaskMsg, + PASSTHRU_MSG *pPatternMsg, + PASSTHRU_MSG *pFlowControlMsg + ); + + bool J2534MessageFilter::operator ==(const J2534MessageFilter &b) const; + + FILTER_RESULT check(const J2534Frame& msg); + std::string get_flowctrl(); + + unsigned long flags; + J2534Connection *const conn; +private: + unsigned int filtertype; + std::string maskMsg; + std::string patternMsg; + std::string flowCtrlMsg; +}; \ No newline at end of file diff --git a/panda/drivers/windows/pandaJ2534DLL/J2534_v0404.h b/panda/drivers/windows/pandaJ2534DLL/J2534_v0404.h new file mode 100644 index 00000000000000..7cccf6b429a515 --- /dev/null +++ b/panda/drivers/windows/pandaJ2534DLL/J2534_v0404.h @@ -0,0 +1,428 @@ +// +// Copyright (c) 2015-2016 DashLogic, Inc. +// All Rights Reserved. +// +// http://www.dashlogic.com +// sales@dashlogic.com +// +// Redistribution and use in source and binary forms, with or without +// modification, including use for commercial purposes, are permitted +// provided that the following conditions are met: +// +// 1. Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// +// 2. Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in +// the documentation and/or other materials provided with the +// distribution. +// +// 3. Neither the name of the copyright holder nor the names of its +// contributors may be used to endorse or promote products derived +// from this software without specific prior written permission. +// +// 4. Redistributions of any form whatsoever must retain the following +// acknowledgment: 'This product includes software developed by +// "DashLogic, Inc." (http://www.dashlogic.com/).' +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, 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. +// + + +// +// Formatting: +// Indents: Use tabs only (1 tab per indent) +// Tab Size: 4 spaces +// +// File Revision: +// $Rev: 5216 $ +// $Date: 2016-03-15 09:32:34 -0600 (Tue, 15 Mar 2016) $ +// + +#pragma once + +#ifdef PANDAJ2534DLL_EXPORTS +#define PANDAJ2534DLL_API extern "C" __declspec(dllexport) +#else +#define PANDAJ2534DLL_API +//__declspec(dllimport) +#endif + +// +// Platform-specific Defines: +// +// PTAPI: Define this yourself if you want a specific calling +// convention or other modifiers on the Pass-Thru API +// functions. Typically, on Windows, PTAPI will be defined +// as WINAPI, which enables the __stdcall convention. +// +#define PTAPI __stdcall //WINAPI + +// +// J2534-1 v04.04 ProtocolID Values +// +#define J1850VPW 0x01 +#define J1850PWM 0x02 +#define ISO9141 0x03 +#define ISO14230 0x04 +#define CAN 0x05 +#define ISO15765 0x06 +#define SCI_A_ENGINE 0x07 +#define SCI_A_TRANS 0x08 +#define SCI_B_ENGINE 0x09 +#define SCI_B_TRANS 0x0A + + +// +// J2534-2 ProtocolID Values +// +#define J1850VPW_PS 0x00008000 +#define J1850PWM_PS 0x00008001 +#define ISO9141_PS 0x00008002 +#define ISO14230_PS 0x00008003 +#define CAN_PS 0x00008004 +#define ISO15765_PS 0x00008005 +#define J2610_PS 0x00008006 +#define SW_ISO15765_PS 0x00008007 +#define SW_CAN_PS 0x00008008 +#define GM_UART_PS 0x00008009 +#define CAN_CH1 0x00009000 +#define CAN_CH2 (CAN_CH1 + 1) +#define CAN_CH128 (CAN_CH1 + 127) +#define J1850VPW_CH1 0x00009080 +#define J1850VPW_CH2 (J1850VPW_CH1 + 1) +#define J1850VPW_CH128 (J1850VPW_CH1 + 127) +#define J1850PWM_CH1 0x00009160 +#define J1850PWM_CH2 (J1850PWM_CH1 + 1) +#define J1850PWM_CH128 (J1850PWM_CH1 + 127) +#define ISO9141_CH1 0x00009240 +#define ISO9141_CH2 (ISO9141_CH1 + 1) +#define ISO9141_CH128 (ISO9141_CH1 + 127) +#define ISO14230_CH1 0x00009320 +#define ISO14230_CH2 (ISO14230_CH1 + 1) +#define ISO14230_CH128 (ISO14230_CH1 + 127) +#define ISO15765_CH1 0x00009400 +#define ISO15765_CH2 (ISO15765_CH1 + 1) +#define ISO15765_CH128 (ISO15765_CH1 + 127) +#define SW_CAN_CAN_CH1 0x00009480 +#define SW_CAN_CAN_CH2 (SW_CAN_CAN_CH1 + 1) +#define SW_CAN_CAN_CH128 (SW_CAN_CAN_CH1 + 127) +#define SW_CAN_ISO15765_CH1 0x00009560 +#define SW_CAN_ISO15765_CH2 (SW_CAN_ISO15765_CH1 + 1) +#define SW_CAN_ISO15765_CH128 (SW_CAN_ISO15765_CH1 + 127) +#define J2610_CH1 0x00009640 +#define J2610_CH2 (J2610_CH1 + 1) +#define J2610_CH128 (J2610_CH1 + 127) +#define ANALOG_IN_CH1 0x0000C000 +#define ANALOG_IN_CH2 0x0000C001 +#define ANALOG_IN_CH32 0x0000C01F + + +// +// J2534-1 v04.04 Error Values +// +#define STATUS_NOERROR 0x00 // Function call successful. +#define ERR_NOT_SUPPORTED 0x01 // Device cannot support requested functionality mandated in J2534. Device is not fully SAE J2534 compliant. +#define ERR_INVALID_CHANNEL_ID 0x02 // Invalid ChannelID value. +#define ERR_INVALID_PROTOCOL_ID 0x03 // Invalid or unsupported ProtocolID, or there is a resource conflict (i.e. trying to connect to multiple mutually exclusive protocols such as J1850PWM and J1850VPW, or CAN and SCI, etc.). +#define ERR_NULL_PARAMETER 0x04 // NULL pointer supplied where a valid pointer is required. +#define ERR_INVALID_IOCTL_VALUE 0x05 // Invalid value for Ioctl parameter. +#define ERR_INVALID_FLAGS 0x06 // Invalid flag values. +#define ERR_FAILED 0x07 // Undefined error, use PassThruGetLastError() for text description. +#define ERR_DEVICE_NOT_CONNECTED 0x08 // Unable to communicate with device. +#define ERR_TIMEOUT 0x09 // Read or write timeout: + // PassThruReadMsgs() - No message available to read or could not read the specified number of messages. The actual number of messages read is placed in . + // PassThruWriteMsgs() - Device could not write the specified number of messages. The actual number of messages sent on the vehicle network is placed in . +#define ERR_INVALID_MSG 0x0A // Invalid message structure pointed to by pMsg. +#define ERR_INVALID_TIME_INTERVAL 0x0B // Invalid TimeInterval value. +#define ERR_EXCEEDED_LIMIT 0x0C // Exceeded maximum number of message IDs or allocated space. +#define ERR_INVALID_MSG_ID 0x0D // Invalid MsgID value. +#define ERR_DEVICE_IN_USE 0x0E // Device is currently open. +#define ERR_INVALID_IOCTL_ID 0x0F // Invalid IoctlID value. +#define ERR_BUFFER_EMPTY 0x10 // Protocol message buffer empty, no messages available to read. +#define ERR_BUFFER_FULL 0x11 // Protocol message buffer full. All the messages specified may not have been transmitted. +#define ERR_BUFFER_OVERFLOW 0x12 // Indicates a buffer overflow occurred and messages were lost. +#define ERR_PIN_INVALID 0x13 // Invalid pin number, pin number already in use, or voltage already applied to a different pin. +#define ERR_CHANNEL_IN_USE 0x14 // Channel number is currently connected. +#define ERR_MSG_PROTOCOL_ID 0x15 // Protocol type in the message does not match the protocol associated with the Channel ID +#define ERR_INVALID_FILTER_ID 0x16 // Invalid Filter ID value. +#define ERR_NO_FLOW_CONTROL 0x17 // No flow control filter set or matched (for ProtocolID ISO15765 only). +#define ERR_NOT_UNIQUE 0x18 // A CAN ID in pPatternMsg or pFlowControlMsg matches either ID in an existing FLOW_CONTROL_FILTER +#define ERR_INVALID_BAUDRATE 0x19 // The desired baud rate cannot be achieved within the tolerance specified in SAE J2534-1 Section 6.5 +#define ERR_INVALID_DEVICE_ID 0x1A // Device ID invalid. + + +// +// J2534-1 v04.04 Connect Flags +// +#define CAN_29BIT_ID 0x0100 +#define ISO9141_NO_CHECKSUM 0x0200 +#define CAN_ID_BOTH 0x0800 +#define ISO9141_K_LINE_ONLY 0x1000 + + +// +// J2534-1 v04.04 Filter Type Values +// +#define PASS_FILTER 0x00000001 +#define BLOCK_FILTER 0x00000002 +#define FLOW_CONTROL_FILTER 0x00000003 + + +// +// J2534-1 v04.04 Programming Voltage Pin Numbers +// +#define AUXILIARY_OUTPUT_PIN 0 +#define SAE_J1962_CONNECTOR_PIN_6 6 +#define SAE_J1962_CONNECTOR_PIN_9 9 +#define SAE_J1962_CONNECTOR_PIN_11 11 +#define SAE_J1962_CONNECTOR_PIN_12 12 +#define SAE_J1962_CONNECTOR_PIN_13 13 +#define SAE_J1962_CONNECTOR_PIN_14 14 +#define SAE_J1962_CONNECTOR_PIN_15 15 // Short to ground only + + +// +// J2534-1 v04.04 Programming Voltage Values +// +#define SHORT_TO_GROUND 0xFFFFFFFE +#define VOLTAGE_OFF 0xFFFFFFFF + + +// +// J2534-1 v04.04 API Version Values +// +#define J2534_APIVER_FEBRUARY_2002 "02.02" +#define J2534_APIVER_NOVEMBER_2004 "04.04" + + +// +// J2534-1 v04.04 IOCTL ID Values +// +#define GET_CONFIG 0x01 // pInput = SCONFIG_LIST, pOutput = NULL +#define SET_CONFIG 0x02 // pInput = SCONFIG_LIST, pOutput = NULL +#define READ_VBATT 0x03 // pInput = NULL, pOutput = unsigned long +#define FIVE_BAUD_INIT 0x04 // pInput = SBYTE_ARRAY, pOutput = SBYTE_ARRAY +#define FAST_INIT 0x05 // pInput = PASSTHRU_MSG, pOutput = PASSTHRU_MSG +#define CLEAR_TX_BUFFER 0x07 // pInput = NULL, pOutput = NULL +#define CLEAR_RX_BUFFER 0x08 // pInput = NULL, pOutput = NULL +#define CLEAR_PERIODIC_MSGS 0x09 // pInput = NULL, pOutput = NULL +#define CLEAR_MSG_FILTERS 0x0A // pInput = NULL, pOutput = NULL +#define CLEAR_FUNCT_MSG_LOOKUP_TABLE 0x0B // pInput = NULL, pOutput = NULL +#define ADD_TO_FUNCT_MSG_LOOKUP_TABLE 0x0C // pInput = SBYTE_ARRAY, pOutput = NULL +#define DELETE_FROM_FUNCT_MSG_LOOKUP_TABLE 0x0D // pInput = SBYTE_ARRAY, pOutput = NULL +#define READ_PROG_VOLTAGE 0x0E // pInput = NULL, pOutput = unsigned long + + +// +// J2534-2 IOCTL ID Values +// +#define SW_CAN_HS 0x00008000 // pInput = NULL, pOutput = NULL +#define SW_CAN_NS 0x00008001 // pInput = NULL, pOutput = NULL +#define SET_POLL_RESPONSE 0x00008002 // pInput = SBYTE_ARRAY, pOutput = NULL +#define BECOME_MASTER 0x00008003 // pInput = unsigned char, pOutput = NULL + + +// +// J2534-1 v04.04 Configuration Parameter Values +// Default value is enclosed in square brackets "[" and "]" +// +#define DATA_RATE 0x01 // 5-500000 +#define LOOPBACK 0x03 // 0 (OFF), 1 (ON) [0] +#define NODE_ADDRESS 0x04 // J1850PWM: 0x00-0xFF +#define NETWORK_LINE 0x05 // J1850PWM: 0 (BUS_NORMAL), 1 (BUS_PLUS), 2 (BUS_MINUS) [0] +#define P1_MIN 0x06 // ISO9141 or ISO14230: Not used by interface +#define P1_MAX 0x07 // ISO9141 or ISO14230: 0x1-0xFFFF (.5 ms per bit) [40 (20ms)] +#define P2_MIN 0x08 // ISO9141 or ISO14230: Not used by interface +#define P2_MAX 0x09 // ISO9141 or ISO14230: Not used by interface +#define P3_MIN 0x0A // ISO9141 or ISO14230: 0x0-0xFFFF (.5 ms per bit) [110 (55ms)] +#define P3_MAX 0x0B // ISO9141 or ISO14230: Not used by interface +#define P4_MIN 0x0C // ISO9141 or ISO14230: 0x0-0xFFFF (.5 ms per bit) [10 (5ms)] +#define P4_MAX 0x0D // ISO9141 or ISO14230: Not used by interface +#define W0 0x19 // ISO9141: 0x0-0xFFFF (1 ms per bit) [300] +#define W1 0x0E // ISO9141 or ISO14230: 0x0-0xFFFF (1 ms per bit) [300] +#define W2 0x0F // ISO9141 or ISO14230: 0x0-0xFFFF (1 ms per bit) [20] +#define W3 0x10 // ISO9141 or ISO14230: 0x0-0xFFFF (1 ms per bit) [20] +#define W4 0x11 // ISO9141 or ISO14230: 0x0-0xFFFF (1 ms per bit) [50] +#define W5 0x12 // ISO9141 or ISO14230: 0x0-0xFFFF (1 ms per bit) [300] +#define TIDLE 0x13 // ISO9141 or ISO14230: 0x0-0xFFFF (1 ms per bit) [300] +#define TINIL 0x14 // ISO9141 or ISO14230: 0x0-0xFFFF (1 ms per bit) [25] +#define TWUP 0x15 // ISO9141 or ISO14230: 0x0-0xFFFF (1 ms per bit) [50] +#define PARITY 0x16 // ISO9141 or ISO14230: 0 (NO_PARITY), 1 (ODD_PARITY), 2 (EVEN_PARITY) [0] +#define BIT_SAMPLE_POINT 0x17 // CAN: 0-100 (1% per bit) [80] +#define SYNC_JUMP_WIDTH 0x18 // CAN: 0-100 (1% per bit) [15] +#define T1_MAX 0x1A // SCI: 0x0-0xFFFF (1 ms per bit) [20] +#define T2_MAX 0x1B // SCI: 0x0-0xFFFF (1 ms per bit) [100] +#define T3_MAX 0x24 // SCI: 0x0-0xFFFF (1 ms per bit) [50] +#define T4_MAX 0x1C // SCI: 0x0-0xFFFF (1 ms per bit) [20] +#define T5_MAX 0x1D // SCI: 0x0-0xFFFF (1 ms per bit) [100] +#define ISO15765_BS 0x1E // ISO15765: 0x0-0xFF [0] +#define ISO15765_STMIN 0x1F // ISO15765: 0x0-0xFF [0] +#define ISO15765_BS_TX 0x22 // ISO15765: 0x0-0xFF,0xFFFF [0xFFFF] +#define ISO15765_STMIN_TX 0x23 // ISO15765: 0x0-0xFF,0xFFFF [0xFFFF] +#define DATA_BITS 0x20 // ISO9141 or ISO14230: 0 (8 data bits), 1 (7 data bits) [0] +#define FIVE_BAUD_MOD 0x21 // ISO9141 or ISO14230: 0 (ISO 9141-2/14230-4), 1 (Inv KB2), 2 (Inv Addr), 3 (ISO 9141) [0] +#define ISO15765_WFT_MAX 0x25 // ISO15765: 0x0-0xFF [0] + + +// +// J2534-2 Configuration Parameter Values +// Default value is enclosed in square brackets "[" and "]" +// +#define CAN_MIXED_FORMAT 0x00008000 // See #defines below. [0] +#define J1962_PINS 0x00008001 // 0xPPSS PP: 0x00-0x10 SS: 0x00-0x10 PP!=SS, except 0x0000. Exclude pins 4, 5, and 16. [0] +#define SW_CAN_HS_DATA_RATE 0x00008010 // SWCAN: 5-500000 [83333] +#define SW_CAN_SPEEDCHANGE_ENABLE 0x00008011 // SWCAN: 0 (DISABLE_SPDCHANGE), 1 (ENABLE_SPDCHANGE) [0] +#define SW_CAN_RES_SWITCH 0x00008012 // SWCAN: 0 (DISCONNECT_RESISTOR), 1 (CONNECT_RESISTOR), 2 (AUTO_ RESISTOR) [0] +#define ACTIVE_CHANNELS 0x00008020 // ANALOG: 0-0xFFFFFFFF +#define SAMPLE_RATE 0x00008021 // ANALOG: 0-0xFFFFFFFF [0] (high bit changes meaning from samples/sec to seconds/sample) +#define SAMPLES_PER_READING 0x00008022 // ANALOG: 1-0xFFFFFFFF [1] +#define READINGS_PER_MSG 0x00008023 // ANALOG: 1-0x00000408 (1 - 1032) [1] +#define AVERAGING_METHOD 0x00008024 // ANALOG: 0-0xFFFFFFFF [0] +#define SAMPLE_RESOLUTION 0x00008025 // ANALOG READ-ONLY: 0x1-0x20 (1 - 32) +#define INPUT_RANGE_LOW 0x00008026 // ANALOG READ-ONLY: 0x80000000-0x7FFFFFFF (-2147483648-2147483647) +#define INPUT_RANGE_HIGH 0x00008027 // ANALOG READ-ONLY: 0x80000000-0x7FFFFFFF (-2147483648-2147483647) + + +// +// J2534-2 Mixed-Mode/Format CAN Definitions +// +#define CAN_MIXED_FORMAT_OFF 0 // Messages will be treated as ISO 15765 ONLY. +#define CAN_MIXED_FORMAT_ON 1 // Messages will be treated as either ISO 15765 or an unformatted CAN frame. +#define CAN_MIXED_FORMAT_ALL_FRAMES 2 // Messages will be treated as ISO 15765, an unformatted CAN frame, or both. + + +// +// J2534-2 Analog Channel Averaging Method Definitions +// +#define SIMPLE_AVERAGE 0x00000000 // Simple arithmetic mean +#define MAX_LIMIT_AVERAGE 0x00000001 // Choose the biggest value +#define MIN_LIMIT_AVERAGE 0x00000002 // Choose the lowest value +#define MEDIAN_AVERAGE 0x00000003 // Choose arithmetic median + + +// +// J2534-1 v04.04 RxStatus Definitions +// +#define TX_MSG_TYPE 0x0001 +#define START_OF_MESSAGE 0x0002 +#define RX_BREAK 0x0004 +#define TX_INDICATION 0x0008 +#define ISO15765_PADDING_ERROR 0x0010 +#define ISO15765_ADDR_TYPE 0x0080 +//#define CAN_29BIT_ID 0x0100 // Defined above + + +// +// J2534-2 RxStatus Definitions +// +#define SW_CAN_HV_RX 0x00010000 // SWCAN Channels Only +#define SW_CAN_HS_RX 0x00020000 // SWCAN Channels Only +#define SW_CAN_NS_RX 0x00040000 // SWCAN Channels Only +#define OVERFLOW_ 0x00010000 // Analog Input Channels Only + + +// +// J2534-1 v04.04 TxFlags Definitions +// +#define ISO15765_FRAME_PAD 0x0040 +//#define ISO15765_ADDR_TYPE 0x0080 // Defined above +//#define CAN_29BIT_ID 0x0100 // Defined above +#define WAIT_P3_MIN_ONLY 0x0200 +#define SCI_MODE 0x400000 +#define SCI_TX_VOLTAGE 0x800000 + + +// +// J2534-2 TxFlags Definitions +// +#define SW_CAN_HV_TX 0x00000400 + + +// +// J2534-1 v04.04 Structure Definitions +// +typedef struct +{ + unsigned long Parameter; // Name of parameter + unsigned long Value; // Value of the parameter +} SCONFIG; + + +typedef struct +{ + unsigned long NumOfParams; // Number of SCONFIG elements + SCONFIG* ConfigPtr; // Array of SCONFIG +} SCONFIG_LIST; + + +typedef struct +{ + unsigned long NumOfBytes; // Number of bytes in the array + unsigned char* BytePtr; // Array of bytes +} SBYTE_ARRAY; + + +typedef struct +{ + unsigned long ProtocolID; + unsigned long RxStatus; + unsigned long TxFlags; + unsigned long Timestamp; + unsigned long DataSize; + unsigned long ExtraDataIndex; + unsigned char Data[4128]; +} PASSTHRU_MSG; + +// +// J2534-1 v04.04 Function Prototypes +// +PANDAJ2534DLL_API long PTAPI PassThruOpen(void *pName, unsigned long *pDeviceID); +PANDAJ2534DLL_API long PTAPI PassThruClose(unsigned long DeviceID); +PANDAJ2534DLL_API long PTAPI PassThruConnect(unsigned long DeviceID, unsigned long ProtocolID, unsigned long Flags, unsigned long BaudRate, unsigned long *pChannelID); +PANDAJ2534DLL_API long PTAPI PassThruDisconnect(unsigned long ChannelID); +PANDAJ2534DLL_API long PTAPI PassThruReadMsgs(unsigned long ChannelID, PASSTHRU_MSG *pMsg, unsigned long *pNumMsgs, unsigned long Timeout); +PANDAJ2534DLL_API long PTAPI PassThruWriteMsgs(unsigned long ChannelID, PASSTHRU_MSG *pMsg, unsigned long *pNumMsgs, unsigned long Timeout); +PANDAJ2534DLL_API long PTAPI PassThruStartPeriodicMsg(unsigned long ChannelID, PASSTHRU_MSG *pMsg, unsigned long *pMsgID, unsigned long TimeInterval); +PANDAJ2534DLL_API long PTAPI PassThruStopPeriodicMsg(unsigned long ChannelID, unsigned long MsgID); +PANDAJ2534DLL_API long PTAPI PassThruStartMsgFilter(unsigned long ChannelID, unsigned long FilterType, PASSTHRU_MSG *pMaskMsg, PASSTHRU_MSG *pPatternMsg, PASSTHRU_MSG *pFlowControlMsg, unsigned long *pFilterID); +PANDAJ2534DLL_API long PTAPI PassThruStopMsgFilter(unsigned long ChannelID, unsigned long FilterID); +PANDAJ2534DLL_API long PTAPI PassThruSetProgrammingVoltage(unsigned long DeviceID, unsigned long PinNumber, unsigned long Voltage); +PANDAJ2534DLL_API long PTAPI PassThruReadVersion(unsigned long DeviceID, char *pFirmwareVersion, char *pDllVersion, char *pApiVersion); +PANDAJ2534DLL_API long PTAPI PassThruGetLastError(char *pErrorDescription); +PANDAJ2534DLL_API long PTAPI PassThruIoctl(unsigned long ChannelID, unsigned long IoctlID, void *pInput, void *pOutput); + + +// +// J2534-1 v04.04 Function Typedefs +// These function typedefs allow simpler use of the J2534 API by +// allowing you to do things like this: +// PTCONNECT pPassThruConnectFunc = GetProcAddress(hModule, "PassThruConnect"); +// if (pPassThruConnectFunc == NULL) +// return FALSE; +// pPassThruConnectFunc(DeviceID, CAN, CAN_29BIT_ID, 500000, &ChannelID); +// +typedef long (PTAPI *PTOPEN)(void *pName, unsigned long *pDeviceID); +typedef long (PTAPI *PTCLOSE)(unsigned long DeviceID); +typedef long (PTAPI *PTCONNECT)(unsigned long DeviceID, unsigned long ProtocolID, unsigned long Flags, unsigned long BaudRate, unsigned long *pChannelID); +typedef long (PTAPI *PTDISCONNECT)(unsigned long ChannelID); +typedef long (PTAPI *PTREADMSGS)(unsigned long ChannelID, PASSTHRU_MSG *pMsg, unsigned long *pNumMsgs, unsigned long Timeout); +typedef long (PTAPI *PTWRITEMSGS)(unsigned long ChannelID, PASSTHRU_MSG *pMsg, unsigned long *pNumMsgs, unsigned long Timeout); +typedef long (PTAPI *PTSTARTPERIODICMSG)(unsigned long ChannelID, PASSTHRU_MSG *pMsg, unsigned long *pMsgID, unsigned long TimeInterval); +typedef long (PTAPI *PTSTOPPERIODICMSG)(unsigned long ChannelID, unsigned long MsgID); +typedef long (PTAPI *PTSTARTMSGFILTER)(unsigned long ChannelID, unsigned long FilterType, PASSTHRU_MSG *pMaskMsg, PASSTHRU_MSG *pPatternMsg, PASSTHRU_MSG *pFlowControlMsg, unsigned long *pFilterID); +typedef long (PTAPI *PTSTOPMSGFILTER)(unsigned long ChannelID, unsigned long FilterID); +typedef long (PTAPI *PTSETPROGRAMMINGVOLTAGE)(unsigned long DeviceID, unsigned long PinNumber, unsigned long Voltage); +typedef long (PTAPI *PTREADVERSION)(unsigned long DeviceID, char *pFirmwareVersion, char *pDllVersion, char *pApiVersion); +typedef long (PTAPI *PTGETLASTERROR)(char *pErrorDescription); +typedef long (PTAPI *PTIOCTL)(unsigned long ChannelID, unsigned long IoctlID, void *pInput, void *pOutput); diff --git a/panda/drivers/windows/pandaJ2534DLL/J2534register_x64.reg b/panda/drivers/windows/pandaJ2534DLL/J2534register_x64.reg new file mode 100644 index 00000000000000..120ab391c7bb4d Binary files /dev/null and b/panda/drivers/windows/pandaJ2534DLL/J2534register_x64.reg differ diff --git a/panda/drivers/windows/pandaJ2534DLL/MessagePeriodic.cpp b/panda/drivers/windows/pandaJ2534DLL/MessagePeriodic.cpp new file mode 100644 index 00000000000000..0c3416e0daf09f --- /dev/null +++ b/panda/drivers/windows/pandaJ2534DLL/MessagePeriodic.cpp @@ -0,0 +1,30 @@ +#include "stdafx.h" +#include "MessagePeriodic.h" +#include "J2534Connection.h" + +MessagePeriodic::MessagePeriodic( + std::chrono::microseconds delay, + std::shared_ptr msg +) : Action(msg->connection, delay), msg(msg), runyet(FALSE), active(TRUE) { }; + +void MessagePeriodic::execute() { + if (!this->active) return; + if (this->runyet) { + if (msg->isFinished()) { + msg->reset(); + msg->execute(); + } + } else { + this->runyet = TRUE; + msg->execute(); + } + + if (auto conn_sp = this->connection.lock()) { + if (auto panda_dev_sp = conn_sp->getPandaDev()) { + //Scheduling must be relative to now incase there was a long stall that + //would case it to be super far behind and try to catch up forever. + this->scheduleImmediateDelay(); + panda_dev_sp->insertActionIntoTaskList(shared_from_this()); + } + } +} diff --git a/panda/drivers/windows/pandaJ2534DLL/MessagePeriodic.h b/panda/drivers/windows/pandaJ2534DLL/MessagePeriodic.h new file mode 100644 index 00000000000000..40132565c11fc0 --- /dev/null +++ b/panda/drivers/windows/pandaJ2534DLL/MessagePeriodic.h @@ -0,0 +1,33 @@ +#pragma once +#include "Action.h" +#include "MessageTx.h" + +class J2534Connection; + +/* A message that is resent on a given period. Created with calls to PassThruStartPeriodicMessage. + +Instead of making each J2534 protocol implementation have to implement periodic message +functionality, this class takes a message to be sent, and passes along the execute call +to the message, then reschedules itself. +*/ +class MessagePeriodic : public Action, public std::enable_shared_from_this +{ +public: + MessagePeriodic( + std::chrono::microseconds delay, + std::shared_ptr msg + ); + + virtual void execute(); + + void cancel() { + this->active = FALSE; + } + +protected: + std::shared_ptr msg; + +private: + BOOL runyet; + BOOL active; +}; diff --git a/panda/drivers/windows/pandaJ2534DLL/MessageRx.h b/panda/drivers/windows/pandaJ2534DLL/MessageRx.h new file mode 100644 index 00000000000000..e22278d4d0a934 --- /dev/null +++ b/panda/drivers/windows/pandaJ2534DLL/MessageRx.h @@ -0,0 +1,61 @@ +#pragma once + +class MessageRx +{ +public: + MessageRx( + unsigned long size, + std::string piece, + unsigned long rxFlags, + std::shared_ptr filter + ) : expected_size(size & 0xFFF), flags(rxFlags) { + msg.reserve(expected_size); + msg = piece; + next_part = 1; + }; + + bool rx_add_frame(uint8_t pci_byte, unsigned int max_packet_size, const std::string piece) { + if ((pci_byte & 0x0F) != this->next_part) { + //TODO: Maybe this should instantly fail the transaction. + return TRUE; + } + + this->next_part = (this->next_part + 1) % 0x10; + unsigned int payload_len = min(expected_size - msg.size(), max_packet_size); + if (piece.size() < payload_len) { + //A frame was received that could have held more data. + //No examples of this protocol show that happening, so + //it will be assumed that it is grounds to reset rx. + return FALSE; + } + msg += piece.substr(0, payload_len); + + return TRUE; + } + + unsigned int bytes_remaining() { + return this->expected_size - this->msg.size(); + } + + bool is_ready() { + return this->msg.size() == this->expected_size; + } + + bool flush_result(std::string& final_msg) { + if (this->msg.size() == this->expected_size) { + final_msg = this->msg; + return TRUE; + } + return FALSE; + } + + uint8_t getNextConsecutiveFrameId() { + return this->next_part++; + } + + std::weak_ptr filter; + unsigned long flags; + unsigned long expected_size; + std::string msg; + unsigned char next_part; +}; diff --git a/panda/drivers/windows/pandaJ2534DLL/MessageTx.h b/panda/drivers/windows/pandaJ2534DLL/MessageTx.h new file mode 100644 index 00000000000000..5315fa058faf60 --- /dev/null +++ b/panda/drivers/windows/pandaJ2534DLL/MessageTx.h @@ -0,0 +1,25 @@ +#pragma once +#include "Action.h" +#include "J2534Frame.h" + +class J2534Connection; + +class MessageTx : public Action, public std::enable_shared_from_this +{ +public: + MessageTx( + std::weak_ptr connection_in, + PASSTHRU_MSG& to_send + ) : Action(connection_in), fullmsg(to_send) { }; + + virtual BOOL checkTxReceipt(J2534Frame frame) = 0; + + virtual BOOL isFinished() = 0; + + virtual BOOL txReady() = 0; + + virtual void reset() = 0; + +protected: + J2534Frame fullmsg; +}; \ No newline at end of file diff --git a/panda/drivers/windows/pandaJ2534DLL/MessageTxTimeout.cpp b/panda/drivers/windows/pandaJ2534DLL/MessageTxTimeout.cpp new file mode 100644 index 00000000000000..2e21ba3ce121cd --- /dev/null +++ b/panda/drivers/windows/pandaJ2534DLL/MessageTxTimeout.cpp @@ -0,0 +1,43 @@ +#include "stdafx.h" +#include "J2534Connection.h" +#include "MessageTxTimeout.h" + +MessageTxTimeoutable::MessageTxTimeoutable( + std::weak_ptr connection, + PASSTHRU_MSG& to_send +) : MessageTx(connection, to_send), recvCount(0) { }; + +void MessageTxTimeoutable::scheduleTimeout(std::chrono::microseconds timeoutus) { + if (auto conn_sp = this->connection.lock()) { + if (auto panda_dev_sp = conn_sp->getPandaDev()) { + auto timeoutobj = std::make_shared(std::static_pointer_cast(shared_from_this()), timeoutus); + panda_dev_sp->scheduleAction(std::static_pointer_cast(timeoutobj), TRUE); + } + } +} + +void MessageTxTimeoutable::scheduleTimeout(unsigned long timeoutus) { + scheduleTimeout(std::chrono::microseconds(timeoutus)); +} + + + +MessageTxTimeout::MessageTxTimeout( + std::shared_ptr msg, + std::chrono::microseconds timeout +) : Action(msg->connection), msg(msg), lastRecvCount(msg->getRecvCount()) { + delay = timeout; +}; + +MessageTxTimeout::MessageTxTimeout( + std::shared_ptr msg, + unsigned long timeout +) : MessageTxTimeout(msg, std::chrono::microseconds(timeout * 1000)) { }; + +void MessageTxTimeout::execute() { + if (auto msg_sp = this->msg.lock()) { + if (msg_sp->getRecvCount() == this->lastRecvCount) { + msg_sp->onTimeout(); + } + } +} diff --git a/panda/drivers/windows/pandaJ2534DLL/MessageTxTimeout.h b/panda/drivers/windows/pandaJ2534DLL/MessageTxTimeout.h new file mode 100644 index 00000000000000..a9c878468cfd6e --- /dev/null +++ b/panda/drivers/windows/pandaJ2534DLL/MessageTxTimeout.h @@ -0,0 +1,52 @@ +#pragma once +#include "Action.h" +#include "MessageTx.h" + +class MessageTxTimeout; + +/* A special type of MessageTx for multipart messages that supports being canceled with a timeout.*/ +class MessageTxTimeoutable : public MessageTx +{ +public: + MessageTxTimeoutable( + std::weak_ptr connection, + PASSTHRU_MSG& to_send + ); + + unsigned long getRecvCount() { + return recvCount; + } + + virtual void onTimeout() = 0; + +protected: + unsigned long recvCount; + + void scheduleTimeout(std::chrono::microseconds timeoutus); + + void scheduleTimeout(unsigned long timeoutus); +}; + + +/* An Action that cancels MessageTxTimeoutableif the Timeout Actoin executes +before the MessageTxTimeoutableif renews its timeout. +*/ +class MessageTxTimeout : public Action +{ +public: + MessageTxTimeout( + std::shared_ptr msg, + std::chrono::microseconds timeout + ); + + MessageTxTimeout( + std::shared_ptr msg, + unsigned long timeout + ); + + virtual void execute(); + +private: + std::weak_ptr msg; + unsigned long lastRecvCount; +}; diff --git a/panda/drivers/windows/pandaJ2534DLL/MessageTx_CAN.cpp b/panda/drivers/windows/pandaJ2534DLL/MessageTx_CAN.cpp new file mode 100644 index 00000000000000..8217ce539a1a54 --- /dev/null +++ b/panda/drivers/windows/pandaJ2534DLL/MessageTx_CAN.cpp @@ -0,0 +1,44 @@ +#include "stdafx.h" +#include "MessageTx_CAN.h" +#include "J2534Connection_CAN.h" + +MessageTx_CAN::MessageTx_CAN( + std::shared_ptr connection_in, + PASSTHRU_MSG& to_send +) : MessageTx(connection_in, to_send), sentyet(FALSE), txInFlight(FALSE) {}; + +void MessageTx_CAN::execute() { + uint32_t addr = ((uint8_t)fullmsg.Data[0]) << 24 | ((uint8_t)fullmsg.Data[1]) << 16 | + ((uint8_t)fullmsg.Data[2]) << 8 | ((uint8_t)fullmsg.Data[3]); + + if (auto conn_sp = std::static_pointer_cast(this->connection.lock())) { + if (auto panda_dev_sp = conn_sp->getPandaDev()) { + auto payload = fullmsg.Data.substr(4); + if (panda_dev_sp->panda->can_send(addr, check_bmask(this->fullmsg.TxFlags, CAN_29BIT_ID), + (const uint8_t*)payload.c_str(), (uint8_t)payload.size(), panda::PANDA_CAN1) == FALSE) { + return; + } + this->txInFlight = TRUE; + this->sentyet = TRUE; + panda_dev_sp->txMsgsAwaitingEcho.push(shared_from_this()); + } + } +} + +//Returns TRUE if receipt is consumed by the msg, FALSE otherwise. +BOOL MessageTx_CAN::checkTxReceipt(J2534Frame frame) { + if (txReady()) return FALSE; + if (frame.Data == fullmsg.Data && ((this->fullmsg.TxFlags & CAN_29BIT_ID) == (frame.RxStatus & CAN_29BIT_ID))) { + txInFlight = FALSE; + if (auto conn_sp = std::static_pointer_cast(this->connection.lock())) + if (conn_sp->loopback) + conn_sp->addMsgToRxQueue(frame); + return TRUE; + } + return FALSE; +} + +void MessageTx_CAN::reset() { + sentyet = FALSE; + txInFlight = FALSE; +} diff --git a/panda/drivers/windows/pandaJ2534DLL/MessageTx_CAN.h b/panda/drivers/windows/pandaJ2534DLL/MessageTx_CAN.h new file mode 100644 index 00000000000000..afac75ef8116c2 --- /dev/null +++ b/panda/drivers/windows/pandaJ2534DLL/MessageTx_CAN.h @@ -0,0 +1,33 @@ +#pragma once +#include +#include "MessageTx.h" + +class J2534Connection; + +class MessageTx_CAN : public MessageTx +{ +public: + MessageTx_CAN( + std::shared_ptr connection_in, + PASSTHRU_MSG& to_send + ); + + virtual void execute(); + + //Returns TRUE if receipt is consumed by the msg, FALSE otherwise. + virtual BOOL checkTxReceipt(J2534Frame frame); + + virtual BOOL isFinished() { + return !txInFlight && sentyet; + }; + + virtual BOOL txReady() { + return !sentyet; + }; + + virtual void reset(); + +private: + BOOL sentyet; + BOOL txInFlight; +}; diff --git a/panda/drivers/windows/pandaJ2534DLL/MessageTx_ISO15765.cpp b/panda/drivers/windows/pandaJ2534DLL/MessageTx_ISO15765.cpp new file mode 100644 index 00000000000000..023088d3c61ea6 --- /dev/null +++ b/panda/drivers/windows/pandaJ2534DLL/MessageTx_ISO15765.cpp @@ -0,0 +1,180 @@ +#include "stdafx.h" +#include "MessageTx_ISO15765.h" +#include "constants_ISO15765.h" + +//in microseconsa +#define TIMEOUT_FC 250000 //Flow Control +#define TIMEOUT_CF 250000 //Consecutive Frames + +MessageTx_ISO15765::MessageTx_ISO15765( + std::shared_ptr connection_in, + PASSTHRU_MSG& to_send, + std::shared_ptr filter +) : MessageTxTimeoutable(connection_in, to_send), filter(filter), frames_sent(0), +consumed_count(0), txInFlight(FALSE), sendAll(FALSE), block_size(0), numWaitFrames(0), didtimeout(FALSE), issuspended(FALSE){ + + CANid = ((uint8_t)fullmsg.Data[0]) << 24 | ((uint8_t)fullmsg.Data[1]) << 16 | + ((uint8_t)fullmsg.Data[2]) << 8 | ((uint8_t)fullmsg.Data[3]); + + payload = fullmsg.Data.substr(addressLength()); + + if (check_bmask(fullmsg.TxFlags, ISO15765_ADDR_TYPE)) + data_prefix = fullmsg.Data[4]; + + if (payload.size() <= (7 - data_prefix.size())) { + isMultipart = FALSE; + auto framepayload = data_prefix + std::string(1, (char)payload.size()) + payload; + if (check_bmask(this->fullmsg.TxFlags, ISO15765_FRAME_PAD)) + framepayload += std::string(8 - framepayload.size(), '\x00'); + framePayloads.push_back(framepayload); + } else { + isMultipart = TRUE; + unsigned long first_payload_len = 6 - data_prefix.size(); // 5 or 6 + std::string framepayload = data_prefix + + (char)(0x10 | ((payload.size() >> 8) & 0xF)) + + (char)(payload.size() & 0xFF) + + payload.substr(0, first_payload_len); + framePayloads.push_back(framepayload); + + unsigned int pktnum = 1; + uint8_t CFDatSize = 7 - data_prefix.size(); + while (TRUE) { + framepayload = data_prefix + (char)(0x20 | (pktnum % 0x10)) + + payload.substr(first_payload_len + (CFDatSize * (pktnum-1)), CFDatSize); + + if (check_bmask(this->fullmsg.TxFlags, ISO15765_FRAME_PAD)) + framepayload += std::string(8 - framepayload.size(), '\x00'); + framePayloads.push_back(framepayload); + if (first_payload_len + (CFDatSize * pktnum) >= payload.size()) break; + pktnum++; + } + + } +}; + +unsigned int MessageTx_ISO15765::addressLength() { + return check_bmask(fullmsg.TxFlags, ISO15765_ADDR_TYPE) ? 5 : 4; +} + +void MessageTx_ISO15765::execute() { + if (didtimeout || issuspended) return; + if (this->frames_sent >= this->framePayloads.size()) return; + if (block_size == 0 && !sendAll && this->frames_sent > 0) return; + if (block_size > 0 && !sendAll) block_size--; + + if (auto conn_sp = this->connection.lock()) { + if (auto panda_dev_sp = conn_sp->getPandaDev()) { + auto& outFramePayload = this->framePayloads[this->frames_sent]; + if (panda_dev_sp->panda->can_send(this->CANid, check_bmask(this->fullmsg.TxFlags, CAN_29BIT_ID), + (const uint8_t*)outFramePayload.c_str(), (uint8_t)outFramePayload.size(), panda::PANDA_CAN1) == FALSE) { + return; + } + + this->txInFlight = TRUE; + this->frames_sent++; + panda_dev_sp->txMsgsAwaitingEcho.push(shared_from_this()); + } + } +} + +//Returns TRUE if receipt is consumed by the msg, FALSE otherwise. +BOOL MessageTx_ISO15765::checkTxReceipt(J2534Frame frame) { + if (!txInFlight) return FALSE; + if (frame.Data.size() >= addressLength() + 1 && (frame.Data[addressLength()] & 0xF0) == FRAME_FLOWCTRL) return FALSE; + + if (frame.Data == fullmsg.Data.substr(0, 4) + framePayloads[frames_sent - 1] && + ((this->fullmsg.TxFlags & CAN_29BIT_ID) == (frame.RxStatus & CAN_29BIT_ID))) { //Check receipt is expected + txInFlight = FALSE; //Received the expected receipt. Allow another msg to be sent. + + if (this->recvCount == 0 && this->framePayloads.size() > 1) + scheduleTimeout(TIMEOUT_FC); + + if (frames_sent == framePayloads.size()) { //Check message done + if (auto conn_sp = std::static_pointer_cast(this->connection.lock())) { + unsigned long flags = (filter == nullptr) ? fullmsg.TxFlags : this->filter->flags; + + J2534Frame outframe(ISO15765); + outframe.Timestamp = frame.Timestamp; + outframe.RxStatus = TX_MSG_TYPE | TX_INDICATION | (flags & (ISO15765_ADDR_TYPE | CAN_29BIT_ID)); + outframe.Data = frame.Data.substr(0, addressLength()); + conn_sp->addMsgToRxQueue(outframe); + + if (conn_sp->loopback) { + J2534Frame outframe(ISO15765); + outframe.Timestamp = frame.Timestamp; + outframe.RxStatus = TX_MSG_TYPE | (flags & (ISO15765_ADDR_TYPE | CAN_29BIT_ID)); + outframe.Data = this->fullmsg.Data; + conn_sp->addMsgToRxQueue(outframe); + } + + } //TODO what if fails + } else { + //Restart timeout if we are waiting for a flow control frame. + //FC frames are required when we are not sending all, the + //current block_size batch has not been sent, a FC message has + //already been received (differentiating from first frame), the + //message is not finished, and there is more than one frame in + //the message. + if (block_size == 0 && recvCount != 0 && !sendAll && !this->isFinished() && this->framePayloads.size() > 1) + scheduleTimeout(TIMEOUT_CF); + } + return TRUE; + } + return FALSE; +} + +BOOL MessageTx_ISO15765::isFinished() { + return this->frames_sent == this->framePayloads.size() && !txInFlight; +} + +BOOL MessageTx_ISO15765::txReady() { + return block_size > 0 || sendAll || this->frames_sent == 0; +} + +void MessageTx_ISO15765::reset() { + frames_sent = 0; + consumed_count = 0; + block_size = 0; + txInFlight = FALSE; + sendAll = FALSE; + numWaitFrames = 0; + didtimeout = FALSE; +} + +void MessageTx_ISO15765::onTimeout() { + didtimeout = TRUE; + if (auto conn_sp = std::static_pointer_cast(this->connection.lock())) { + if (auto panda_dev_sp = conn_sp->getPandaDev()) { + panda_dev_sp->removeConnectionTopAction(conn_sp, shared_from_this()); + } + } +} + +void MessageTx_ISO15765::flowControlContinue(uint8_t block_size, std::chrono::microseconds separation_time) { + this->issuspended = FALSE; + this->block_size = block_size; + this->delay = separation_time; + this->sendAll = block_size == 0; + this->recvCount++; +} + +void MessageTx_ISO15765::flowControlWait(unsigned long N_WFTmax) { + this->issuspended = TRUE; + this->recvCount++; + this->numWaitFrames++; + this->sendAll = FALSE; + this->block_size = block_size; + this->delay = std::chrono::microseconds(0); + //Docs are vague on if 0 means NO WAITS ALLOWED or NO LIMIT TO WAITS. + //It is less likely to cause issue if NO LIMIT is assumed. + if (N_WFTmax > 0 && this->numWaitFrames > N_WFTmax) { + this->onTimeout(); //Trigger self destruction of message. + } else { + scheduleTimeout(TIMEOUT_FC); + } +} + +void MessageTx_ISO15765::flowControlAbort() { + this->recvCount++; //Invalidate future timeout actions. + this->onTimeout(); //Trigger self destruction of message. +} diff --git a/panda/drivers/windows/pandaJ2534DLL/MessageTx_ISO15765.h b/panda/drivers/windows/pandaJ2534DLL/MessageTx_ISO15765.h new file mode 100644 index 00000000000000..0113edb8f96fd3 --- /dev/null +++ b/panda/drivers/windows/pandaJ2534DLL/MessageTx_ISO15765.h @@ -0,0 +1,54 @@ +#pragma once +#include "MessageTxTimeout.h" +#include "J2534Connection_ISO15765.h" + +class J2534Connection_ISO15765; + +/** +A specialized message type that can handle J2534 single and multi +frame (with flow control) writes. +*/ +class MessageTx_ISO15765 : public MessageTxTimeoutable +{ +public: + MessageTx_ISO15765( + std::shared_ptr connection, + PASSTHRU_MSG& to_send, + std::shared_ptr filter + ); + + unsigned int addressLength(); + + virtual void execute(); + + virtual BOOL checkTxReceipt(J2534Frame frame); + + virtual BOOL isFinished(); + + virtual BOOL txReady(); + + virtual void reset(); + + virtual void onTimeout(); + + //Functions for ISO15765 flow control + + void MessageTx_ISO15765::flowControlContinue(uint8_t block_size, std::chrono::microseconds separation_time); + void MessageTx_ISO15765::flowControlWait(unsigned long N_WFTmax); + void MessageTx_ISO15765::flowControlAbort(); + + std::shared_ptr filter; + unsigned long frames_sent; + unsigned long consumed_count; + uint8_t block_size; + unsigned long CANid; + std::string data_prefix; + std::string payload; + BOOL isMultipart; + std::vector framePayloads; + BOOL txInFlight; + BOOL sendAll; + unsigned int numWaitFrames; + BOOL didtimeout; + BOOL issuspended; +}; diff --git a/panda/drivers/windows/pandaJ2534DLL/PandaJ2534Device.cpp b/panda/drivers/windows/pandaJ2534DLL/PandaJ2534Device.cpp new file mode 100644 index 00000000000000..1b961579e079ab --- /dev/null +++ b/panda/drivers/windows/pandaJ2534DLL/PandaJ2534Device.cpp @@ -0,0 +1,238 @@ +#include "stdafx.h" +#include "PandaJ2534Device.h" +#include "J2534Frame.h" + +PandaJ2534Device::PandaJ2534Device(std::unique_ptr new_panda) : txInProgress(FALSE) { + this->panda = std::move(new_panda); + + this->panda->set_esp_power(FALSE); + this->panda->set_safety_mode(panda::SAFETY_ALLOUTPUT); + this->panda->set_can_loopback(FALSE); + this->panda->set_alt_setting(0); + + this->thread_kill_event = CreateEvent(NULL, TRUE, FALSE, NULL); + + DWORD canListenThreadID; + this->can_recv_handle = CreateThread(NULL, 0, _can_recv_threadBootstrap, (LPVOID)this, 0, &canListenThreadID); + + DWORD canProcessThreadID; + this->can_process_handle = CreateThread(NULL, 0, _can_process_threadBootstrap, (LPVOID)this, 0, &canProcessThreadID); + + DWORD flowControlSendThreadID; + this->flow_control_wakeup_event = CreateEvent(NULL, TRUE, FALSE, NULL); + this->flow_control_thread_handle = CreateThread(NULL, 0, _msg_tx_threadBootstrap, (LPVOID)this, 0, &flowControlSendThreadID); +}; + +PandaJ2534Device::~PandaJ2534Device() { + SetEvent(this->thread_kill_event); + DWORD res = WaitForSingleObject(this->can_recv_handle, INFINITE); + CloseHandle(this->can_recv_handle); + + res = WaitForSingleObject(this->can_process_handle, INFINITE); + CloseHandle(this->can_process_handle); + + res = WaitForSingleObject(this->flow_control_thread_handle, INFINITE); + CloseHandle(this->flow_control_thread_handle); + + CloseHandle(this->flow_control_wakeup_event); + CloseHandle(this->thread_kill_event); +} + +std::shared_ptr PandaJ2534Device::openByName(std::string sn) { + auto p = panda::Panda::openPanda(""); + if (p == nullptr) + return nullptr; + return std::unique_ptr(new PandaJ2534Device(std::move(p))); +} + +DWORD PandaJ2534Device::closeChannel(unsigned long ChannelID) { + if (this->connections.size() <= ChannelID) return ERR_INVALID_CHANNEL_ID; + if (this->connections[ChannelID] == nullptr) return ERR_INVALID_CHANNEL_ID; + this->connections[ChannelID] = nullptr; + return STATUS_NOERROR; +} + +DWORD PandaJ2534Device::addChannel(std::shared_ptr& conn, unsigned long* channel_id) { + int channel_index = -1; + for (unsigned int i = 0; i < this->connections.size(); i++) + if (this->connections[i] == nullptr) { + channel_index = i; + break; + } + + if (channel_index == -1) { + if (this->connections.size() == 0xFFFF) //channelid max 16 bits + return ERR_FAILED; //Too many channels + this->connections.push_back(nullptr); + channel_index = this->connections.size() - 1; + } + + this->connections[channel_index] = conn; + + *channel_id = channel_index; + return STATUS_NOERROR; +} + +DWORD PandaJ2534Device::can_recv_thread() { + this->panda->can_clear(panda::PANDA_CAN_RX); + this->panda->can_rx_q_push(this->thread_kill_event); + + return 0; +} + +DWORD PandaJ2534Device::can_process_thread() { + panda::PANDA_CAN_MSG msg_recv[CAN_RX_MSG_LEN]; + + while (true) { + if (!WaitForSingleObject(this->thread_kill_event, 0)) { + break; + } + + int count = 0; + this->panda->can_rx_q_pop(msg_recv, count); + if (count == 0) { + continue; + } + + for (int i = 0; i < count; i++) { + auto msg_in = msg_recv[i]; + J2534Frame msg_out(msg_in); + + if (msg_in.is_receipt) { + synchronized(task_queue_mutex) { + if (txMsgsAwaitingEcho.size() > 0) { + auto msgtx = txMsgsAwaitingEcho.front(); + if (auto conn = msgtx->connection.lock()) { + if (conn->isProtoCan() && conn->getPort() == msg_in.bus) { + if (msgtx->checkTxReceipt(msg_out)) { + //Things to check: + // Frame not for this msg: Drop frame and alert. Error? + // Frame is for this msg, more tx frames required after a FC frame: Wait for FC frame to come and trigger next tx. + // Frame is for this msg, more tx frames required: Schedule next tx frame. + // Frame is for this msg, and is the final frame of the msg: Let conn process full msg, If another msg from this conn is available, register it. + txMsgsAwaitingEcho.pop(); //Remove the TX object and schedule record. + + if (msgtx->isFinished()) { + this->removeConnectionTopAction(conn, msgtx); + } else { + if (msgtx->txReady()) { //Not finished, ready to send next frame. + msgtx->schedule(msg_in.recv_time_point, TRUE); + this->insertActionIntoTaskList(msgtx); + } else { + //Not finished, but next frame not ready (maybe waiting for flow control). + //Do not schedule more messages from this connection. + //this->ConnTxSet.erase(conn); + //Removing this means new messages queued can kickstart the queue and overstep the current message. + } + } + } + } + } else { + //Connection has died. Clear out the tx entry from device records. + txMsgsAwaitingEcho.pop(); + this->ConnTxSet.erase(conn); //connection is already dead, no need to schedule future tx msgs. + } + } + } + } else { + for (auto& conn : this->connections) + if (conn != nullptr && conn->isProtoCan() && conn->getPort() == msg_in.bus) + conn->processMessage(msg_out); + } + } + } + + return 0; +} + +DWORD PandaJ2534Device::msg_tx_thread() { + const HANDLE subscriptions[] = { this->flow_control_wakeup_event, this->thread_kill_event }; + DWORD sleepDuration = INFINITE; + while (TRUE) { + DWORD res = WaitForMultipleObjects(2, subscriptions, FALSE, sleepDuration); + if (res == WAIT_OBJECT_0 + 1) return 0; + if (res != WAIT_OBJECT_0 && res != WAIT_TIMEOUT) { + printf("Got an unexpected wait result in flow_control_write_thread. Res: %d; GetLastError: %d\n. Terminating thread.", res, GetLastError()); + return 0; + } + ResetEvent(this->flow_control_wakeup_event); + + while (TRUE) { + synchronized(task_queue_mutex) { //implemented with for loop. Consumes breaks. + if (this->task_queue.size() == 0) { + sleepDuration = INFINITE; + goto break_flow_ctrl_loop; + } + if (std::chrono::steady_clock::now() >= this->task_queue.front()->expire) { + auto task = this->task_queue.front(); //Get the scheduled tx record. + this->task_queue.pop_front(); + task->execute(); + } else { //Ran out of things that need to be sent now. Sleep! + auto time_diff = std::chrono::duration_cast + (this->task_queue.front()->expire - std::chrono::steady_clock::now()); + sleepDuration = max(1, time_diff.count()); + goto break_flow_ctrl_loop; + } + } + } + break_flow_ctrl_loop: + continue; + } + return 0; +} + +//Place the Action in the task queue based on the Action's expiration time, +//then signal the thread that processes actions. +void PandaJ2534Device::insertActionIntoTaskList(std::shared_ptr action) { + synchronized(task_queue_mutex) { + auto iter = this->task_queue.begin(); + for (; iter != this->task_queue.end(); iter++) { + if (action->expire < (*iter)->expire) break; + } + this->task_queue.insert(iter, action); + } + SetEvent(this->flow_control_wakeup_event); +} + +void PandaJ2534Device::scheduleAction(std::shared_ptr msg, BOOL startdelayed) { + if(startdelayed) + msg->scheduleImmediateDelay(); + else + msg->scheduleImmediate(); + this->insertActionIntoTaskList(msg); +} + +void PandaJ2534Device::registerConnectionTx(std::shared_ptr conn) { + synchronized(connTXSet_mutex) { + auto ret = this->ConnTxSet.insert(conn); + if (ret.second == FALSE) return; //Conn already exists. + this->scheduleAction(conn->txbuff.front()); + } +} + +void PandaJ2534Device::unstallConnectionTx(std::shared_ptr conn) { + synchronized(connTXSet_mutex) { + auto ret = this->ConnTxSet.insert(conn); + if (ret.second == TRUE) return; //Conn already exists. + this->insertActionIntoTaskList(conn->txbuff.front()); + } +} + +void PandaJ2534Device::removeConnectionTopAction(std::shared_ptr conn, std::shared_ptr msg) { + synchronized(task_queue_mutex) { + if (conn->txbuff.size() == 0) + return; + if (conn->txbuff.front() != msg) + return; + conn->txbuff.pop(); //Remove the top TX message from the connection tx queue. + + //Remove the connection from the active connection list if no more messages are scheduled with this connection. + if (conn->txbuff.size() == 0) { + //Update records showing the connection no longer has a tx record scheduled. + this->ConnTxSet.erase(conn); + } else { + //Add the next scheduled tx from this conn + this->scheduleAction(conn->txbuff.front()); + } + } +} diff --git a/panda/drivers/windows/pandaJ2534DLL/PandaJ2534Device.h b/panda/drivers/windows/pandaJ2534DLL/PandaJ2534Device.h new file mode 100644 index 00000000000000..32004ffba5ea14 --- /dev/null +++ b/panda/drivers/windows/pandaJ2534DLL/PandaJ2534Device.h @@ -0,0 +1,83 @@ +#pragma once +#include +#include +#include +#include +#include +#include "J2534_v0404.h" +#include "panda_shared/panda.h" +#include "synchronize.h" +#include "Action.h" +#include "MessageTx.h" +#include "J2534Connection.h" + +class J2534Connection; +class Action; +class MessageTx; + +/** +Class representing a physical panda adapter. Instances are created by +PassThruOpen in the J2534 API. A Device can create one or more +J2534Connections. +*/ +class PandaJ2534Device { +public: + PandaJ2534Device(std::unique_ptr new_panda); + + ~PandaJ2534Device(); + + static std::shared_ptr openByName(std::string sn); + + DWORD closeChannel(unsigned long ChannelID); + DWORD addChannel(std::shared_ptr& conn, unsigned long* channel_id); + + std::unique_ptr panda; + std::vector> connections; + + //Place the Action in the task queue based on the Action's expiration time, + //then signal the thread that processes actions. + void insertActionIntoTaskList(std::shared_ptr action); + + void scheduleAction(std::shared_ptr msg, BOOL startdelayed=FALSE); + + void registerConnectionTx(std::shared_ptr conn); + + //Resume sending messages from the provided Connection's TX queue. + void unstallConnectionTx(std::shared_ptr conn); + + //Cleans up several queues after a message completes, is canceled, or otherwise goes away. + void removeConnectionTopAction(std::shared_ptr conn, std::shared_ptr msg); + + //Messages that have been sent on the wire will be echoed by the panda when + //transmission is complete. This tracks what is still waiting to hear an echo. + std::queue> txMsgsAwaitingEcho; + +private: + HANDLE thread_kill_event; + + HANDLE can_recv_handle; + static DWORD WINAPI _can_recv_threadBootstrap(LPVOID This) { + return ((PandaJ2534Device*)This)->can_recv_thread(); + } + DWORD can_recv_thread(); + + HANDLE can_process_handle; + static DWORD WINAPI _can_process_threadBootstrap(LPVOID This) { + return ((PandaJ2534Device*)This)->can_process_thread(); + } + DWORD can_process_thread(); + + HANDLE flow_control_wakeup_event; + HANDLE flow_control_thread_handle; + static DWORD WINAPI _msg_tx_threadBootstrap(LPVOID This) { + return ((PandaJ2534Device*)This)->msg_tx_thread(); + } + DWORD msg_tx_thread(); + std::list> task_queue; + Mutex task_queue_mutex; + + std::queue> ConnTxQueue; + std::set> ConnTxSet; + Mutex connTXSet_mutex; + BOOL txInProgress; +}; diff --git a/panda/drivers/windows/pandaJ2534DLL/Timer.cpp b/panda/drivers/windows/pandaJ2534DLL/Timer.cpp new file mode 100644 index 00000000000000..2f20f888eeef83 --- /dev/null +++ b/panda/drivers/windows/pandaJ2534DLL/Timer.cpp @@ -0,0 +1,17 @@ +#include "stdafx.h" +#include "Timer.h" + + +Timer::Timer() +{ + start = std::chrono::time_point_cast(clock::now()); +} + +// gets the time elapsed from construction. +unsigned long long /*milliseconds*/ Timer::getTimePassed(){ + // get the new time + auto end = std::chrono::time_point_cast(clock::now()); + + // return the difference of the times + return (end - start).count(); +} \ No newline at end of file diff --git a/panda/drivers/windows/pandaJ2534DLL/Timer.h b/panda/drivers/windows/pandaJ2534DLL/Timer.h new file mode 100644 index 00000000000000..d4888fc5e6dd55 --- /dev/null +++ b/panda/drivers/windows/pandaJ2534DLL/Timer.h @@ -0,0 +1,18 @@ +#pragma once +#include + +//Copied from https://stackoverflow.com/a/31488113 + +class Timer +{ + using clock = std::chrono::steady_clock; + using time_point_type = std::chrono::time_point < clock, std::chrono::milliseconds >; +public: + Timer(); + + // gets the time elapsed from construction. + unsigned long long /*milliseconds*/ getTimePassed(); + +private: + time_point_type start; +}; \ No newline at end of file diff --git a/panda/drivers/windows/pandaJ2534DLL/constants_ISO15765.h b/panda/drivers/windows/pandaJ2534DLL/constants_ISO15765.h new file mode 100644 index 00000000000000..86928f1436c996 --- /dev/null +++ b/panda/drivers/windows/pandaJ2534DLL/constants_ISO15765.h @@ -0,0 +1,20 @@ +#pragma once + +#define msg_is_extaddr(msg) check_bmask(msg->TxFlags, ISO15765_ADDR_TYPE) +#define msg_is_padded(msg) check_bmask(msg->TxFlags, ISO15765_FRAME_PAD) + +#define FRAME_SINGLE 0x00 +#define FRAME_FIRST 0x10 +#define FRAME_CONSEC 0x20 +#define FRAME_FLOWCTRL 0x30 + +#define FLOWCTRL_CONTINUE 0 +#define FLOWCTRL_WAIT 1 +#define FLOWCTRL_ABORT 2 + +#define msg_get_type(msg, addrlen) ((msg).Data[addrlen] & 0xF0) + +#define is_single(msg, addrlen) (msg_get_type(msg, addrlen) == FRAME_SINGLE) +#define is_first(msg, addrlen) (msg_get_type(msg, addrlen) == FRAME_FIRST) +#define is_consecutive(msg, addrlen) (msg_get_type(msg, addrlen) == FRAME_CONSEC) +#define is_flowctrl(msg, addrlen) (msg_get_type(msg, addrlen) == FRAME_FLOWCTRL) \ No newline at end of file diff --git a/panda/drivers/windows/pandaJ2534DLL/dllmain.cpp b/panda/drivers/windows/pandaJ2534DLL/dllmain.cpp new file mode 100644 index 00000000000000..d4122e0b1dda9c --- /dev/null +++ b/panda/drivers/windows/pandaJ2534DLL/dllmain.cpp @@ -0,0 +1,22 @@ +// dllmain.cpp : Defines the entry point for the DLL application. +#include "dllmain.h" + +HMODULE thisdll; + +BOOL APIENTRY DllMain( HMODULE hModule, + DWORD ul_reason_for_call, + LPVOID lpReserved + ) +{ + thisdll = hModule; + + switch (ul_reason_for_call) + { + case DLL_PROCESS_ATTACH: + case DLL_THREAD_ATTACH: + case DLL_THREAD_DETACH: + case DLL_PROCESS_DETACH: + break; + } + return TRUE; +} diff --git a/panda/drivers/windows/pandaJ2534DLL/dllmain.h b/panda/drivers/windows/pandaJ2534DLL/dllmain.h new file mode 100644 index 00000000000000..f49819e2c40aa1 --- /dev/null +++ b/panda/drivers/windows/pandaJ2534DLL/dllmain.h @@ -0,0 +1,4 @@ +#pragma once +#include "stdafx.h" + +extern HMODULE thisdll; diff --git a/panda/drivers/windows/pandaJ2534DLL/pandaJ2534DLL.cpp b/panda/drivers/windows/pandaJ2534DLL/pandaJ2534DLL.cpp new file mode 100644 index 00000000000000..096e4419883928 --- /dev/null +++ b/panda/drivers/windows/pandaJ2534DLL/pandaJ2534DLL.cpp @@ -0,0 +1,430 @@ +// pandaJ2534DLL.cpp : Defines the exported functions for the DLL application. +// Protocol derived from the following sites (which shall be referred to as The Protocol Reference #). +// https://web.archive.org/web/20130805013326/https://tunertools.com/prodimages/DrewTech/Manuals/PassThru_API-1.pdf +// http://web.archive.org/web/20170910063536/http://www.tiecar.net/downloads/SAE_J2534_2002.pdf + +#include "stdafx.h" +#include "J2534_v0404.h" +#include "panda_shared/panda.h" +#include "J2534Connection.h" +#include "J2534Connection_CAN.h" +#include "J2534Connection_ISO15765.h" +#include "PandaJ2534Device.h" +#include "dllmain.h" + +// A quick way to avoid the name mangling that __stdcall liked to do +#define EXPORT comment(linker, "/EXPORT:" __FUNCTION__ "=" __FUNCDNAME__) + +std::vector> pandas; + +int J25334LastError = 0; + +std::string GetProductAndVersion(TCHAR* szFilename)//std::string & strProductName, std::string & strProductVersion) +{ + // allocate a block of memory for the version info + DWORD dummy; + DWORD dwSize = GetFileVersionInfoSize(szFilename, &dummy); + if (dwSize == 0) { + return "error"; + } + std::vector data(dwSize); + + // load the version info + if (!GetFileVersionInfo(szFilename, NULL, dwSize, &data[0])) { + return "error"; + } + + // get the name and version strings + LPVOID pvProductName = NULL; + unsigned int iProductNameLen = 0; + LPVOID pvProductVersion = NULL; + unsigned int iProductVersionLen = 0; + + // 040904b0 is a language id. + if (!VerQueryValueA(&data[0], "\\StringFileInfo\\040904b0\\ProductName", &pvProductName, &iProductNameLen) || + !VerQueryValueA(&data[0], "\\StringFileInfo\\040904b0\\ProductVersion", &pvProductVersion, &iProductVersionLen)) { + return "error"; + } + + std::string ver_str = std::string((char*)pvProductVersion, iProductVersionLen-1); + std::string prod_str = std::string((char*)pvProductName, iProductNameLen-1); + std::string full_ver = prod_str + std::string(": ") + ver_str; + return full_ver; +} + +long ret_code(long code) { + J25334LastError = code; + return code; +} + +#define EXTRACT_DID(CID) ((CID & 0xFFFF) - 1) +#define EXTRACT_CID(CID) ((CID >> 16) & 0xFFFF) + +long check_valid_DeviceID(unsigned long DeviceID) { + uint16_t dev_id = EXTRACT_DID(DeviceID); + if (pandas.size() <= dev_id || pandas[dev_id] == nullptr) + return ret_code(ERR_INVALID_DEVICE_ID); + return ret_code(STATUS_NOERROR); +} + +long check_valid_ChannelID(unsigned long ChannelID) { + uint16_t dev_id = EXTRACT_DID(ChannelID); + uint16_t con_id = EXTRACT_CID(ChannelID); + + if (pandas.size() <= dev_id || pandas[dev_id] == nullptr) + return ret_code(ERR_INVALID_CHANNEL_ID); + + if (pandas[dev_id]->connections.size() <= con_id) return ret_code(ERR_INVALID_CHANNEL_ID); + if (pandas[dev_id]->connections[con_id] == nullptr) return ret_code(ERR_DEVICE_NOT_CONNECTED); + + return ret_code(STATUS_NOERROR); +} + +//Do not call without checking if the device/channel id exists first. +#define get_device(DeviceID) (pandas[EXTRACT_DID(DeviceID)]) +#define get_channel(ChannelID) (get_device(ChannelID)->connections[EXTRACT_CID(ChannelID)]) + +PANDAJ2534DLL_API long PTAPI PassThruOpen(void *pName, unsigned long *pDeviceID) { + #pragma EXPORT + if (pDeviceID == NULL) return ret_code(ERR_NULL_PARAMETER); + std::string sn = (pName == NULL) ? "" : std::string((char*)pName); + if (sn == "J2534-2:") + sn = ""; + + auto new_panda = PandaJ2534Device::openByName(sn); + if (new_panda == nullptr) { + if(sn == "" && pandas.size() == 1) + return ret_code(ERR_DEVICE_IN_USE); + for (auto& pn : pandas) { + if (pn->panda->get_usb_sn() == sn) + return ret_code(ERR_DEVICE_IN_USE); + } + return ret_code(ERR_DEVICE_NOT_CONNECTED); + } + + int panda_index = -1; + for (unsigned int i = 0; i < pandas.size(); i++) + if (pandas[i] == nullptr) { + panda_index = i; + pandas[panda_index] = std::move(new_panda); + break; + } + + if (panda_index == -1) { + if(pandas.size() == 0xFFFF) //device id will be 16 bit to fit channel next to it. + return ret_code(ERR_FAILED); //Too many pandas. Off the endangered species list. + pandas.push_back(std::move(new_panda)); + panda_index = pandas.size()-1; + } + + *pDeviceID = panda_index + 1; // TIS doesn't like it when ID == 0 + return ret_code(STATUS_NOERROR); +} +PANDAJ2534DLL_API long PTAPI PassThruClose(unsigned long DeviceID) { + #pragma EXPORT + if (check_valid_DeviceID(DeviceID) != STATUS_NOERROR) return J25334LastError; + get_device(DeviceID) = nullptr; + return ret_code(STATUS_NOERROR); +} +PANDAJ2534DLL_API long PTAPI PassThruConnect(unsigned long DeviceID, unsigned long ProtocolID, + unsigned long Flags, unsigned long BaudRate, unsigned long *pChannelID) { + #pragma EXPORT + if (pChannelID == NULL) return ret_code(ERR_NULL_PARAMETER); + if (check_valid_DeviceID(DeviceID) != STATUS_NOERROR) return J25334LastError; + auto& panda = get_device(DeviceID); + + std::shared_ptr conn; + + //TODO check if channel can be made + try { + switch (ProtocolID) { + //SW seems to refer to Single Wire. https://www.nxp.com/files-static/training_pdf/20451_BUS_COMM_WBT.pdf + //SW_ protocols may be touched on here: https://www.iso.org/obp/ui/#iso:std:iso:22900:-2:ed-1:v1:en + //case J1850VPW: // These protocols are outdated and will not be supported. HDS wants them to not fail to open. + //case J1850PWM: // ^-- it appears HDS no longer needs this, and TIS needs it disabled --^ + //case J1850VPW_PS: + //case J1850PWM_PS: + case ISO9141: //This protocol could be implemented if 5 BAUD init support is added to the panda. + case ISO9141_PS: + case ISO14230: //Only supporting Fast init until panda adds support for 5 BAUD init. + case ISO14230_PS: + conn = std::make_shared(panda, ProtocolID, Flags, BaudRate); + break; + case CAN: + case CAN_PS: + //case SW_CAN_PS: + conn = std::make_shared(panda, ProtocolID, Flags, BaudRate); + break; + case ISO15765: + case ISO15765_PS: + conn = std::make_shared(panda, ProtocolID, Flags, BaudRate); + break; + //case SW_ISO15765_PS: // SW = Single Wire. GMLAN is a SW CAN protocol + //case GM_UART_PS: // PS = Pin Select. Handles different ports. + //Looks like SCI based protocols may not be compatible with the panda: + //http://mdhmotors.com/can-communications-vehicle-network-protocols/3/ + //case SCI_A_ENGINE: + //case SCI_A_TRANS: + //case SCI_B_ENGINE: + //case SCI_B_TRANS: + //case J2610_PS: + default: + return ret_code(ERR_INVALID_PROTOCOL_ID); + } + } catch (int e) { + return ret_code(e); + } + + unsigned long channel_index; + unsigned long err = panda->addChannel(conn, &channel_index); + if (err == STATUS_NOERROR) + *pChannelID = (channel_index << 16) | DeviceID; + + return ret_code(err); +} +PANDAJ2534DLL_API long PTAPI PassThruDisconnect(unsigned long ChannelID) { + #pragma EXPORT + unsigned long res = check_valid_DeviceID(ChannelID); + if (res == ERR_INVALID_DEVICE_ID) return ret_code(ERR_INVALID_CHANNEL_ID); + if (res != STATUS_NOERROR) return J25334LastError; + return ret_code(get_device(ChannelID)->closeChannel(EXTRACT_CID(ChannelID))); +} +PANDAJ2534DLL_API long PTAPI PassThruReadMsgs(unsigned long ChannelID, PASSTHRU_MSG *pMsg, + unsigned long *pNumMsgs, unsigned long Timeout) { + #pragma EXPORT + if (pMsg == NULL || pNumMsgs == NULL) return ret_code(ERR_NULL_PARAMETER); + if (check_valid_ChannelID(ChannelID) != STATUS_NOERROR) return J25334LastError; + return ret_code(get_channel(ChannelID)->PassThruReadMsgs(pMsg, pNumMsgs, Timeout)); +} +PANDAJ2534DLL_API long PTAPI PassThruWriteMsgs(unsigned long ChannelID, PASSTHRU_MSG *pMsg, unsigned long *pNumMsgs, unsigned long Timeout) { + #pragma EXPORT + if (pMsg == NULL || pNumMsgs == NULL) return ret_code(ERR_NULL_PARAMETER); + if (check_valid_ChannelID(ChannelID) != STATUS_NOERROR) return J25334LastError; + return ret_code(get_channel(ChannelID)->PassThruWriteMsgs(pMsg, pNumMsgs, Timeout)); +} +PANDAJ2534DLL_API long PTAPI PassThruStartPeriodicMsg(unsigned long ChannelID, PASSTHRU_MSG *pMsg, unsigned long *pMsgID, unsigned long TimeInterval) { + #pragma EXPORT + if (pMsg == NULL || pMsgID == NULL) return ret_code(ERR_NULL_PARAMETER); + if (check_valid_ChannelID(ChannelID) != STATUS_NOERROR) return J25334LastError; + return ret_code(get_channel(ChannelID)->PassThruStartPeriodicMsg(pMsg, pMsgID, TimeInterval)); +} +PANDAJ2534DLL_API long PTAPI PassThruStopPeriodicMsg(unsigned long ChannelID, unsigned long MsgID) { + #pragma EXPORT + if (check_valid_ChannelID(ChannelID) != STATUS_NOERROR) return J25334LastError; + return ret_code(get_channel(ChannelID)->PassThruStopPeriodicMsg(MsgID)); +} +PANDAJ2534DLL_API long PTAPI PassThruStartMsgFilter(unsigned long ChannelID, unsigned long FilterType, PASSTHRU_MSG *pMaskMsg, + PASSTHRU_MSG *pPatternMsg, PASSTHRU_MSG *pFlowControlMsg, unsigned long *pFilterID) { + #pragma EXPORT + if (FilterType != PASS_FILTER && FilterType != BLOCK_FILTER && FilterType != FLOW_CONTROL_FILTER) return ret_code(ERR_NULL_PARAMETER); + if (!pFilterID || (!pMaskMsg && !pPatternMsg && !pFlowControlMsg)) return ret_code(ERR_NULL_PARAMETER); + if (check_valid_ChannelID(ChannelID) != STATUS_NOERROR) return J25334LastError; + return ret_code(get_channel(ChannelID)->PassThruStartMsgFilter(FilterType, pMaskMsg, pPatternMsg, pFlowControlMsg, pFilterID)); +} +PANDAJ2534DLL_API long PTAPI PassThruStopMsgFilter(unsigned long ChannelID, unsigned long FilterID) { + #pragma EXPORT + if (check_valid_ChannelID(ChannelID) != STATUS_NOERROR) return J25334LastError; + return ret_code(get_channel(ChannelID)->PassThruStopMsgFilter(FilterID)); +} +PANDAJ2534DLL_API long PTAPI PassThruSetProgrammingVoltage(unsigned long DeviceID, unsigned long PinNumber, unsigned long Voltage) { + #pragma EXPORT + //Unused + if (check_valid_DeviceID(DeviceID) != STATUS_NOERROR) return J25334LastError; + auto& panda = get_device(DeviceID); + + switch (Voltage) { + case SHORT_TO_GROUND: + break; + case VOLTAGE_OFF: + break; + default: + if (!(5000 <= Voltage && Voltage <= 20000)) + return ret_code(ERR_NOT_SUPPORTED); + break; + } + + return ret_code(STATUS_NOERROR); +} +PANDAJ2534DLL_API long PTAPI PassThruReadVersion(unsigned long DeviceID, char *pFirmwareVersion, char *pDllVersion, char *pApiVersion) { + #pragma EXPORT + if (!pFirmwareVersion || !pDllVersion || !pApiVersion) return ret_code(ERR_NULL_PARAMETER); + if (check_valid_DeviceID(DeviceID) != STATUS_NOERROR) return J25334LastError; + + auto& panda = get_device(DeviceID); + auto fw_version = panda->panda->get_version(); + strcpy_s(pFirmwareVersion, 80, fw_version.c_str()); + + std::string j2534dll_ver; + TCHAR pandalib_filename[MAX_PATH + 1] = { 0 }; + if (GetModuleFileName(thisdll, pandalib_filename, MAX_PATH) == 0) { + j2534dll_ver = "error"; + } else { + j2534dll_ver = GetProductAndVersion(pandalib_filename); + } + std::string fullver = "(" + j2534dll_ver + ")"; + strcpy_s(pDllVersion, 80, fullver.c_str()); + + strcpy_s(pApiVersion, 80, J2534_APIVER_NOVEMBER_2004); + return ret_code(STATUS_NOERROR); +} +PANDAJ2534DLL_API long PTAPI PassThruGetLastError(char *pErrorDescription) { + #pragma EXPORT + if (pErrorDescription == NULL) return ret_code(ERR_NULL_PARAMETER); + switch (J25334LastError) { + case STATUS_NOERROR: + strcpy_s(pErrorDescription, 80, "Function call successful."); + break; + case ERR_NOT_SUPPORTED: + strcpy_s(pErrorDescription, 80, "Device cannot support requested functionality mandated in J2534."); + break; + case ERR_INVALID_CHANNEL_ID: + strcpy_s(pErrorDescription, 80, "Invalid ChannelID value."); + break; + case ERR_INVALID_PROTOCOL_ID: + strcpy_s(pErrorDescription, 80, "Invalid or unsupported ProtocolID, or resource conflict."); + break; + case ERR_NULL_PARAMETER: + strcpy_s(pErrorDescription, 80, "NULL pointer supplied where a valid pointer is required."); + break; + case ERR_INVALID_IOCTL_VALUE: + strcpy_s(pErrorDescription, 80, "Invalid value for Ioctl parameter."); + break; + case ERR_INVALID_FLAGS: + strcpy_s(pErrorDescription, 80, "Invalid flag values."); + break; + case ERR_FAILED: + strcpy_s(pErrorDescription, 80, "Undefined error."); + break; + case ERR_DEVICE_NOT_CONNECTED: + strcpy_s(pErrorDescription, 80, "Unable to communicate with device."); + break; + case ERR_TIMEOUT: + strcpy_s(pErrorDescription, 80, "Read or write timeout:"); + // PassThruReadMsgs() - No message available to read or could not read the specified number of messages. The actual number of messages read is placed in . + // PassThruWriteMsgs() - Device could not write the specified number of messages. The actual number of messages sent on the vehicle network is placed in . + break; + case ERR_INVALID_MSG: + strcpy_s(pErrorDescription, 80, "Invalid message structure pointed to by pMsg."); + break; + case ERR_INVALID_TIME_INTERVAL: + strcpy_s(pErrorDescription, 80, "Invalid TimeInterval value."); + break; + case ERR_EXCEEDED_LIMIT: + strcpy_s(pErrorDescription, 80, "Exceeded maximum number of message IDs or allocated space."); + break; + case ERR_INVALID_MSG_ID: + strcpy_s(pErrorDescription, 80, "Invalid MsgID value."); + break; + case ERR_DEVICE_IN_USE: + strcpy_s(pErrorDescription, 80, "Device is currently open."); + break; + case ERR_INVALID_IOCTL_ID: + strcpy_s(pErrorDescription, 80, "Invalid IoctlID value."); + break; + case ERR_BUFFER_EMPTY: + strcpy_s(pErrorDescription, 80, "Protocol message buffer empty."); + break; + case ERR_BUFFER_FULL: + strcpy_s(pErrorDescription, 80, "Protocol message buffer full. Messages may have been lost."); + break; + case ERR_BUFFER_OVERFLOW: + strcpy_s(pErrorDescription, 80, "A buffer overflow occurred and messages were lost."); + break; + case ERR_PIN_INVALID: + strcpy_s(pErrorDescription, 80, "Invalid pin number, or pin number already in use."); + break; + case ERR_CHANNEL_IN_USE: + strcpy_s(pErrorDescription, 80, "Channel number is currently connected."); + break; + case ERR_MSG_PROTOCOL_ID: + strcpy_s(pErrorDescription, 80, "The Message's Protocol does not match the Channel's protocol."); + break; + case ERR_INVALID_FILTER_ID: + strcpy_s(pErrorDescription, 80, "Invalid Filter ID value."); + break; + case ERR_NO_FLOW_CONTROL: + strcpy_s(pErrorDescription, 80, "No flow control filter set or matched."); + break; + case ERR_NOT_UNIQUE: + strcpy_s(pErrorDescription, 80, "This filter already exists."); + break; + case ERR_INVALID_BAUDRATE: + strcpy_s(pErrorDescription, 80, "The desired baud rate cannot be achieved within SAE tolerance."); + break; + case ERR_INVALID_DEVICE_ID: + strcpy_s(pErrorDescription, 80, "Device ID invalid."); + break; + } + return ret_code(STATUS_NOERROR); +} +PANDAJ2534DLL_API long PTAPI PassThruIoctl(unsigned long ChannelID, unsigned long IoctlID, + void *pInput, void *pOutput) { + #pragma EXPORT + if (check_valid_ChannelID(ChannelID) != STATUS_NOERROR) return J25334LastError; + auto& dev_entry = get_device(ChannelID); + //get_channel(ChannelID) + + switch (IoctlID) { + case GET_CONFIG: + { + SCONFIG_LIST *inconfig = (SCONFIG_LIST*)pInput; + if (inconfig == NULL) + return ret_code(ERR_NULL_PARAMETER); + for (unsigned int i = 0; i < inconfig->NumOfParams; i++) { + try { + inconfig->ConfigPtr[i].Value = get_channel(ChannelID)->processIOCTLGetConfig(inconfig->ConfigPtr[i].Parameter); + } catch (int e) { + return ret_code(e); + } + } + break; + } + case SET_CONFIG: + { + SCONFIG_LIST *inconfig = (SCONFIG_LIST*)pInput; + if (inconfig == NULL) + return ret_code(ERR_NULL_PARAMETER); + for (unsigned int i = 0; i < inconfig->NumOfParams; i++) { + try { + get_channel(ChannelID)->processIOCTLSetConfig(inconfig->ConfigPtr[i].Parameter, inconfig->ConfigPtr[i].Value); + } catch (int e) { + return ret_code(e); + } + } + break; + } + case READ_VBATT: + panda::PANDA_HEALTH health = dev_entry->panda->get_health(); + *(unsigned long*)pOutput = health.voltage; + break; + case FIVE_BAUD_INIT: + if (!pInput || !pOutput) return ret_code(ERR_NULL_PARAMETER); + return ret_code(get_channel(ChannelID)->init5b((SBYTE_ARRAY*)pInput, (SBYTE_ARRAY*)pOutput)); + case FAST_INIT: + if (!pInput || !pOutput) return ret_code(ERR_NULL_PARAMETER); + return ret_code(get_channel(ChannelID)->initFast((PASSTHRU_MSG*)pInput, (PASSTHRU_MSG*)pOutput)); + case CLEAR_TX_BUFFER: + return ret_code(get_channel(ChannelID)->clearTXBuff()); + case CLEAR_RX_BUFFER: + return ret_code(get_channel(ChannelID)->clearRXBuff()); + case CLEAR_PERIODIC_MSGS: + return ret_code(get_channel(ChannelID)->clearPeriodicMsgs()); + case CLEAR_MSG_FILTERS: + return ret_code(get_channel(ChannelID)->clearMsgFilters()); + case CLEAR_FUNCT_MSG_LOOKUP_TABLE: // LOOKUP TABLE IS RELATED TO J1850 PWM. Unsupported. + if (!pInput) return ret_code(ERR_NULL_PARAMETER); + return ret_code(STATUS_NOERROR); + case ADD_TO_FUNCT_MSG_LOOKUP_TABLE: // LOOKUP TABLE IS RELATED TO J1850 PWM. Unsupported. + if (!pInput) return ret_code(ERR_NULL_PARAMETER); + return ret_code(STATUS_NOERROR); + case DELETE_FROM_FUNCT_MSG_LOOKUP_TABLE: // LOOKUP TABLE IS RELATED TO J1850 PWM. Unsupported. + return ret_code(STATUS_NOERROR); + case READ_PROG_VOLTAGE: + *(unsigned long*)pOutput = 0; + break; + default: + printf("Got unknown IIOCTL %X\n", IoctlID); + } + + return ret_code(STATUS_NOERROR); +} diff --git a/panda/drivers/windows/pandaJ2534DLL/pandaJ2534DLL.rc b/panda/drivers/windows/pandaJ2534DLL/pandaJ2534DLL.rc new file mode 100644 index 00000000000000..e359044825257c Binary files /dev/null and b/panda/drivers/windows/pandaJ2534DLL/pandaJ2534DLL.rc differ diff --git a/panda/drivers/windows/pandaJ2534DLL/pandaJ2534DLL.vcxproj b/panda/drivers/windows/pandaJ2534DLL/pandaJ2534DLL.vcxproj new file mode 100644 index 00000000000000..fd5eac56dd4d4a --- /dev/null +++ b/panda/drivers/windows/pandaJ2534DLL/pandaJ2534DLL.vcxproj @@ -0,0 +1,148 @@ + + + + + Debug + Win32 + + + Release + Win32 + + + + {A2BB18A5-F26B-48D6-BBB5-B83D64473C77} + Win32Proj + pandaJ2534DLL + 10.0.16299.0 + + + + DynamicLibrary + true + v141 + Unicode + + + DynamicLibrary + false + v141 + true + Unicode + + + + + + + + + + + + + + + + true + $(SolutionDir)$(Configuration)_$(PlatformShortName)\ + pandaJ2534_0404_32 + + + false + $(SolutionDir)$(Configuration)_$(PlatformShortName)\ + pandaJ2534_0404_32 + + + + Use + Level3 + Disabled + WIN32;_DEBUG;_WINDOWS;_USRDLL;PANDAJ2534DLL_EXPORTS;%(PreprocessorDefinitions) + true + $(SolutionDir); + + + Windows + true + kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);version.lib;winusb.lib;setupapi.lib + + + + + Level3 + Use + MaxSpeed + true + true + WIN32;NDEBUG;_WINDOWS;_USRDLL;PANDAJ2534DLL_EXPORTS;%(PreprocessorDefinitions) + true + $(SolutionDir); + + + Windows + true + true + true + kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);version.lib;winusb.lib;setupapi.lib + + + + + + + + + + + + + + + + + + + + + + + + + + + + + false + + + false + + + + + + + + + + + + + + + Create + Create + + + + + + + + + + + + + \ No newline at end of file diff --git a/panda/drivers/windows/pandaJ2534DLL/pandaJ2534DLL.vcxproj.filters b/panda/drivers/windows/pandaJ2534DLL/pandaJ2534DLL.vcxproj.filters new file mode 100644 index 00000000000000..57f7cefb081e74 --- /dev/null +++ b/panda/drivers/windows/pandaJ2534DLL/pandaJ2534DLL.vcxproj.filters @@ -0,0 +1,155 @@ + + + + + {4FC737F1-C7A5-4376-A066-2A32D752A2FF} + cpp;c;cc;cxx;def;odl;idl;hpj;bat;asm;asmx + + + {93995380-89BD-4b04-88EB-625FBE52EBFB} + h;hh;hpp;hxx;hm;inl;inc;xsd + + + {67DA6AB6-F800-4c08-8B7A-83BB121AAD01} + rc;ico;cur;bmp;dlg;rc2;rct;bin;rgs;gif;jpg;jpeg;jpe;resx;tiff;tif;png;wav;mfcribbon-ms + + + {a4cd0bce-0a2a-43d9-9c9f-b21a3b607e90} + + + {a85ee263-380d-4d37-b167-6629cfd5177f} + + + {010a0176-a146-4d3a-824a-fd683904774d} + + + {71c9502a-ee59-4d5e-873f-c9cc792e7c76} + + + {4fd3183a-c457-430c-b762-f767a5788bca} + + + {53cd179e-22d8-43e2-bc61-516d3861fae6} + + + {08d548b5-4d0b-4ce4-85e6-5ff3fc987758} + + + + + Header Files + + + Header Files + + + Header Files + + + Header Files + + + Header Files + + + Header Files\J2534_CAN + + + Header Files\J2534_ISO15765 + + + Header Files\depends + + + Header Files\depends + + + Header Files\boilerplate + + + Header Files\boilerplate + + + Header Files\boilerplate + + + Header Files\boilerplate + + + Header Files + + + Header Files\J2534_ISO15765 + + + Header Files + + + Header Files\J2534_ISO15765 + + + Header Files\J2534_CAN + + + Header Files + + + Header Files + + + Header Files + + + Header Files + + + + + Source Files + + + Source Files + + + Source Files + + + Source Files + + + Source Files + + + Source Files\J2534_CAN + + + Source Files\J2534_ISO15765 + + + Source Files\boilerplate + + + Source Files\boilerplate + + + Source Files\J2534_ISO15765 + + + Source Files + + + Source Files\J2534_CAN + + + Source Files + + + + + Resource Files + + + + + + \ No newline at end of file diff --git a/panda/drivers/windows/pandaJ2534DLL/resource.h b/panda/drivers/windows/pandaJ2534DLL/resource.h new file mode 100644 index 00000000000000..771e7b80bc1e81 --- /dev/null +++ b/panda/drivers/windows/pandaJ2534DLL/resource.h @@ -0,0 +1,14 @@ +//{{NO_DEPENDENCIES}} +// Microsoft Visual C++ generated include file. +// Used by pandaJ2534DLL.rc + +// Next default values for new objects +// +#ifdef APSTUDIO_INVOKED +#ifndef APSTUDIO_READONLY_SYMBOLS +#define _APS_NEXT_RESOURCE_VALUE 101 +#define _APS_NEXT_COMMAND_VALUE 40001 +#define _APS_NEXT_CONTROL_VALUE 1001 +#define _APS_NEXT_SYMED_VALUE 101 +#endif +#endif diff --git a/panda/drivers/windows/pandaJ2534DLL/stdafx.cpp b/panda/drivers/windows/pandaJ2534DLL/stdafx.cpp new file mode 100644 index 00000000000000..c27db9ee2d9eb4 --- /dev/null +++ b/panda/drivers/windows/pandaJ2534DLL/stdafx.cpp @@ -0,0 +1,8 @@ +// stdafx.cpp : source file that includes just the standard includes +// pandaJ2534DLL.pch will be the pre-compiled header +// stdafx.obj will contain the pre-compiled type information + +#include "stdafx.h" + +// TODO: reference any additional headers you need in STDAFX.H +// and not in this file diff --git a/panda/drivers/windows/pandaJ2534DLL/stdafx.h b/panda/drivers/windows/pandaJ2534DLL/stdafx.h new file mode 100644 index 00000000000000..bd4a4b6f78fef9 --- /dev/null +++ b/panda/drivers/windows/pandaJ2534DLL/stdafx.h @@ -0,0 +1,14 @@ +#pragma once + +#include "targetver.h" + +#define WIN32_LEAN_AND_MEAN // Exclude rarely-used stuff from Windows headers +// Windows Header Files: +#include + +#include +#include +#include +#include +#include +#include \ No newline at end of file diff --git a/panda/drivers/windows/pandaJ2534DLL/synchronize.h b/panda/drivers/windows/pandaJ2534DLL/synchronize.h new file mode 100644 index 00000000000000..446dfc19e3f08b --- /dev/null +++ b/panda/drivers/windows/pandaJ2534DLL/synchronize.h @@ -0,0 +1,56 @@ +#pragma once +#define WIN32_LEAN_AND_MEAN +#include + +//Inspired/directly copied from https://www.codeproject.com/Articles/12362/A-quot-synchronized-quot-statement-for-C-like-in-J +//Enables easier synchronization +class Mutex { +public: + Mutex() { + InitializeCriticalSectionAndSpinCount(&critSection, 0x00000400); + //InitializeCriticalSection(&critSection); + } + + ~Mutex() { + DeleteCriticalSection(&critSection); + } + + void lock() { + EnterCriticalSection(&critSection); + } + + void unlock() { + LeaveCriticalSection(&critSection); + } + +private: + CRITICAL_SECTION critSection; +}; + +//Synchronization Controller Object +class Lock { +public: + Lock(Mutex &m) : mutex(m), locked(TRUE) { + m.lock(); + } + + ~Lock() { + mutex.unlock(); + } + + operator bool() const { + return locked; + } + + void setUnlock() { + locked = FALSE; + } + +private: + Mutex& mutex; + bool locked; +}; + +//A useful shorthand for locking and unlocking a mutex over a scope. +//CAUTION, implemented with a for loop, so break/continue are consumed. +#define synchronized(M) for(Lock M##_lock = M; M##_lock; M##_lock.setUnlock()) diff --git a/panda/drivers/windows/pandaJ2534DLL/targetver.h b/panda/drivers/windows/pandaJ2534DLL/targetver.h new file mode 100644 index 00000000000000..1bf4ee6fee02e7 --- /dev/null +++ b/panda/drivers/windows/pandaJ2534DLL/targetver.h @@ -0,0 +1,13 @@ +#pragma once + +// Including SDKDDKVer.h defines the highest available Windows platform. + +// If you wish to build your application for a previous Windows platform, include WinSDKVer.h and +// set the _WIN32_WINNT macro to the platform you wish to support before including SDKDDKVer.h. + +#include + +#define WINVER _WIN32_WINNT_WIN7 +#define _WIN32_WINNT _WIN32_WINNT_WIN7 + +#include diff --git a/panda/drivers/windows/panda_install.nsi b/panda/drivers/windows/panda_install.nsi new file mode 100644 index 00000000000000..47a4423f91b940 --- /dev/null +++ b/panda/drivers/windows/panda_install.nsi @@ -0,0 +1,214 @@ +!define J2534_Reg_Path "Software\PassThruSupport.04.04\comma.ai - panda" +!define Install_Name "panda J2534 driver" + +;NOTE! The panda software requires a VC runtime to be installed in order to work. +;This installer must be bundled with the appropriate runtime installer, and have +;the installation registry key set so the installer can tell if the runtime is +;already installed. Copy vscruntimeinfo.nsh.sample to vscruntimeinfo.nsh and edit +;it for your version of Visual Studio. +!include "redist\vscruntimeinfo.nsh" + +;-------------------------------- +;Include Modern UI +!include "MUI2.nsh" +!include "x64.nsh" + +!define MUI_ICON "panda.ico" +;NSIS is ignoring the unicon unless it is the same as the normal icon +;!define MUI_UNICON "panda_remove.ico" + +;Properly display all languages (Installer will not work on Windows 95, 98 or ME!) +Unicode true + +# Set the installer display name +Name "${Install_Name}" + +# set the name of the installer +Outfile "${Install_Name} install.exe" + +; The default installation directory +InstallDir $PROGRAMFILES\comma.ai\panda + +; Request application privileges for UAC +RequestExecutionLevel admin + +; Registry key to check for directory (so if you install again, it will +; overwrite the old one automatically) +InstallDirRegKey HKLM "SOFTWARE\${Install_Name}" "Install_Dir" + +;-------------------------------- +; Pages +!insertmacro MUI_PAGE_WELCOME +!insertmacro MUI_PAGE_LICENSE "..\..\LICENSE" +!insertmacro MUI_PAGE_COMPONENTS +!insertmacro MUI_PAGE_DIRECTORY +!insertmacro MUI_PAGE_INSTFILES + +!insertmacro MUI_UNPAGE_CONFIRM +!insertmacro MUI_UNPAGE_INSTFILES + +!insertmacro MUI_LANGUAGE "English" ;first language is the default language + +; ------------------------------------------------------------------------------------------------- +; Additional info (will appear in the "details" tab of the properties window for the installer) + +VIAddVersionKey /LANG=${LANG_ENGLISH} "ProductName" "panda OBD-II adapter" +VIAddVersionKey /LANG=${LANG_ENGLISH} "Comments" "" +VIAddVersionKey /LANG=${LANG_ENGLISH} "CompanyName" "comma.ai" +VIAddVersionKey /LANG=${LANG_ENGLISH} "LegalTrademarks" "Application released under the MIT license" +;VIAddVersionKey /LANG=${LANG_ENGLISH} "LegalCopyright" "© ${PRODUCT_NAME} Team" +;VIAddVersionKey /LANG=${LANG_ENGLISH} "FileDescription" "Jessy Exum" +;VIAddVersionKey /LANG=${LANG_ENGLISH} "FileVersion" "${PRODUCT_VERSION}" +VIProductVersion "1.0.0.0" + +;-------------------------------- +; Install Sections +Section "prerequisites" + + SectionIn RO + + SetOutPath "$INSTDIR" + + File "panda.ico" + + ;If the visual studio version this project is compiled with changes, this section + ;must be revisited. The registry key must be changed, and the VS redistributable + ;binary must be updated to the VS version used. + ClearErrors + ReadRegStr $0 HKCR ${VCRuntimeRegKey} "Version" + ${If} ${Errors} + DetailPrint "Installing Visual Studio C Runtime..." + File "${VCRuntimeSetupPath}\${VCRuntimeSetupFile}" + ExecWait '"$INSTDIR\${VCRuntimeSetupFile}" /passive /norestart' + ${Else} + DetailPrint "Visual Studio C Runtime already installed." + ${EndIf} + + ;Remove the now unnecessary runtime installer. + Delete "$INSTDIR\${VCRuntimeSetupFile}" + + ;Do the rest of the install + ; SetOutPath "$INSTDIR\driver" + + ; The inf file works for both 32 and 64 bit. + ; File "Debug_x86\panda Driver Package\panda.inf" + ; File "Debug_x86\panda Driver Package\panda.cat" + ; ${DisableX64FSRedirection} + ; nsExec::ExecToLog '"$SYSDIR\PnPutil.exe" /a "$INSTDIR\driver\panda.inf"' + ; ${EnableX64FSRedirection} + + ; Write the installation path into the registry + WriteRegStr HKLM "SOFTWARE\${Install_Name}" "Install_Dir" "$INSTDIR" + + ; Write the uninstall keys for Windows + WriteRegStr HKLM "Software\Microsoft\Windows\CurrentVersion\Uninstall\${Install_Name}" "DisplayVersion" "" + WriteRegStr HKLM "Software\Microsoft\Windows\CurrentVersion\Uninstall\${Install_Name}" "DisplayIcon" '"$INSTDIR\panda.ico",0' + WriteRegStr HKLM "Software\Microsoft\Windows\CurrentVersion\Uninstall\${Install_Name}" "DisplayName" "${Install_Name}" + WriteRegStr HKLM "Software\Microsoft\Windows\CurrentVersion\Uninstall\${Install_Name}" "Publisher" "comma.ai" + WriteRegStr HKLM "Software\Microsoft\Windows\CurrentVersion\Uninstall\${Install_Name}" "UninstallString" '"$INSTDIR\uninstall.exe"' + WriteRegStr HKLM "Software\Microsoft\Windows\CurrentVersion\Uninstall\${Install_Name}" "URLInfoAbout" "https://github.com/commaai/panda/" + WriteRegDWORD HKLM "Software\Microsoft\Windows\CurrentVersion\Uninstall\${Install_Name}" "NoModify" 1 + WriteRegDWORD HKLM "Software\Microsoft\Windows\CurrentVersion\Uninstall\${Install_Name}" "NoRepair" 1 + + SetOutPath $INSTDIR + WriteUninstaller "uninstall.exe" + +SectionEnd + +Section "J2534 Driver" + + SetOutPath $INSTDIR + + File Release_x86\pandaJ2534_0404_32.dll + + SetRegView 32 + WriteRegDWORD HKLM "${J2534_Reg_Path}" "CAN" 00000001 + WriteRegStr HKLM "${J2534_Reg_Path}" "FunctionLibrary" "$INSTDIR\pandaJ2534_0404_32.dll" + WriteRegDWORD HKLM "${J2534_Reg_Path}" "ISO15765" 00000001 + WriteRegDWORD HKLM "${J2534_Reg_Path}" "J1850VPW" 00000000 + WriteRegDWORD HKLM "${J2534_Reg_Path}" "SCI_A_ENGINE" 00000000 + WriteRegDWORD HKLM "${J2534_Reg_Path}" "SCI_A_TRANS" 00000000 + WriteRegDWORD HKLM "${J2534_Reg_Path}" "SCI_B_ENGINE" 00000000 + WriteRegDWORD HKLM "${J2534_Reg_Path}" "SCI_B_TRANS" 00000000 + WriteRegDWORD HKLM "${J2534_Reg_Path}" "J1850PWM" 00000000 + WriteRegDWORD HKLM "${J2534_Reg_Path}" "ISO9141" 00000000 + WriteRegDWORD HKLM "${J2534_Reg_Path}" "ISO14230" 00000001 + WriteRegStr HKLM "${J2534_Reg_Path}" "Name" "panda" + WriteRegStr HKLM "${J2534_Reg_Path}" "Vendor" "comma.ai" + WriteRegStr HKLM "${J2534_Reg_Path}" "ConfigApplication" "" + DetailPrint "Registered J2534 Driver" + +SectionEnd + +Section /o "Development lib/header" + + SetOutPath $SYSDIR + + File Release_x86\panda.dll + + ${If} ${RunningX64} + ${DisableX64FSRedirection} + ;Note that the x64 VS redistributable is not installed to prevent bloat. + ;If you are the rare person who uses the 64 bit raw panda driver, please + ;install the correct x64 VS runtime manually. + File Release_x64\panda.dll + ${EnableX64FSRedirection} + ${EndIf} + + SetOutPath "$INSTDIR\devel" + File panda_shared\panda.h + + SetOutPath "$INSTDIR\devel\x86" + File Release_x86\panda.lib + + SetOutPath "$INSTDIR\devel\x64" + File Release_x64\panda.lib + +SectionEnd + +;-------------------------------- +; Uninstaller +Section "Uninstall" + + ; Removing the inf file for winusb is not easy to do. + ; The best solution I can find is parsing the output + ; of the pnputil.exe /e command to find the oem#.inf + ; file that lists comma.ai as the provider. Not sure + ; if Microsoft wants these inf files to be removed. + ; Consider https://blog.sverrirs.com/2015/12/creating-windows-installer-and.html + ; These lines just remove the inf backups. + ; Delete "$INSTDIR\driver\panda.inf" + ; Delete "$INSTDIR\driver\panda.cat" + ; RMDir "$INSTDIR\driver" + + ; Remove WinUSB driver library + Delete $SYSDIR\panda.dll + ${If} ${RunningX64} + ${DisableX64FSRedirection} + Delete $SYSDIR\panda.dll + ${EnableX64FSRedirection} + ${EndIf} + + ; Remove devel files + Delete "$INSTDIR\devel\x86\panda.lib" + RMDir "$INSTDIR\devel\x86" + Delete "$INSTDIR\devel\x64\panda.lib" + RMDir "$INSTDIR\devel\x64" + Delete "$INSTDIR\devel\panda.h" + RMDir "$INSTDIR\devel" + + ; Remove registry keys + DeleteRegKey HKLM "${J2534_Reg_Path}" + DeleteRegKey HKLM "Software\Microsoft\Windows\CurrentVersion\Uninstall\${Install_Name}" + DeleteRegKey HKLM "SOFTWARE\${Install_Name}" + + ; Remove files and uninstaller + Delete "$INSTDIR\uninstall.exe" + Delete "$INSTDIR\pandaJ2534_0404_32.dll" + Delete "$INSTDIR\panda.ico" + + ; Remove directories used + RMDir "$INSTDIR" + RMDir "$PROGRAMFILES\comma.ai" + +SectionEnd diff --git a/panda/drivers/windows/panda_playground/ReadMe.txt b/panda/drivers/windows/panda_playground/ReadMe.txt new file mode 100644 index 00000000000000..37dba5d8775a99 --- /dev/null +++ b/panda/drivers/windows/panda_playground/ReadMe.txt @@ -0,0 +1,40 @@ +======================================================================== + CONSOLE APPLICATION : panda_playground Project Overview +======================================================================== + +AppWizard has created this panda_playground application for you. + +This file contains a summary of what you will find in each of the files that +make up your panda_playground application. + + +panda_playground.vcxproj + This is the main project file for VC++ projects generated using an Application Wizard. + It contains information about the version of Visual C++ that generated the file, and + information about the platforms, configurations, and project features selected with the + Application Wizard. + +panda_playground.vcxproj.filters + This is the filters file for VC++ projects generated using an Application Wizard. + It contains information about the association between the files in your project + and the filters. This association is used in the IDE to show grouping of files with + similar extensions under a specific node (for e.g. ".cpp" files are associated with the + "Source Files" filter). + +panda_playground.cpp + This is the main application source file. + +///////////////////////////////////////////////////////////////////////////// +Other standard files: + +StdAfx.h, StdAfx.cpp + These files are used to build a precompiled header (PCH) file + named panda_playground.pch and a precompiled types file named StdAfx.obj. + +///////////////////////////////////////////////////////////////////////////// +Other notes: + +AppWizard uses "TODO:" comments to indicate parts of the source code you +should add to or customize. + +///////////////////////////////////////////////////////////////////////////// diff --git a/panda/drivers/windows/panda_playground/panda_playground.cpp b/panda/drivers/windows/panda_playground/panda_playground.cpp new file mode 100644 index 00000000000000..0f51924dbcbd2d --- /dev/null +++ b/panda/drivers/windows/panda_playground/panda_playground.cpp @@ -0,0 +1,86 @@ +// panda_playground.cpp : Defines the entry point for the console application. +// + +#include "stdafx.h" +#include "pandaJ2534DLL Test\Loader4.h" +#include "ECUsim DLL\ECUsim.h" +#include + + +int _tmain(int Argc, _TCHAR *Argv) { + UNREFERENCED_PARAMETER(Argc); + UNREFERENCED_PARAMETER(Argv); + + ECUsim sim("", 500000); + + //if (LoadJ2534Dll("C:\\WINDOWS\\SysWOW64\\op20pt32.dll") != 0) { + if (LoadJ2534Dll("pandaJ2534.dll") != 0) { + auto err = GetLastError(); + return 1; + } + unsigned long did, cid, fid; + PassThruOpen("", &did); + PassThruConnect(did, ISO15765, CAN_29BIT_ID, 500000, &cid); + + PASSTHRU_MSG mask, pattern, flow; + + memcpy(mask.Data, "\xff\xff\xff\xff", 4); + mask.DataSize = 4; + mask.ProtocolID = ISO15765; + mask.TxFlags = CAN_29BIT_ID; + mask.ExtraDataIndex = 0; + mask.RxStatus = 0; + + ////////////////////////18//DA//F1//EF + memcpy(pattern.Data, "\x18\xda\xf1\xef", 4); + pattern.DataSize = 4; + pattern.ProtocolID = ISO15765; + pattern.TxFlags = CAN_29BIT_ID; + pattern.ExtraDataIndex = 0; + pattern.RxStatus = 0; + + memcpy(flow.Data, "\x18\xda\xef\xf1", 4); + flow.DataSize = 4; + flow.ProtocolID = ISO15765; + flow.TxFlags = CAN_29BIT_ID; + flow.ExtraDataIndex = 0; + flow.RxStatus = 0; + + auto res = PassThruStartMsgFilter(cid, FLOW_CONTROL_FILTER, &mask, &pattern, &flow, &fid); + if (res != STATUS_NOERROR) + return 1; + + SCONFIG_LIST list; + SCONFIG config; + config.Parameter = LOOPBACK; + config.Value = 0; + list.ConfigPtr = &config; + list.NumOfParams = 1; + + res = PassThruIoctl(cid, SET_CONFIG, &list, NULL); + if (res != STATUS_NOERROR) + return 1; + + PASSTHRU_MSG outmsg; + memcpy(outmsg.Data, "\x18\xda\xef\xf1""\xAA\xBB\xCC\xDD\xEE\xFF\x11\x22\x33\x44", 4 + 10); + outmsg.DataSize = 4 + 10; + outmsg.ProtocolID = ISO15765; + outmsg.TxFlags = CAN_29BIT_ID; + outmsg.ExtraDataIndex = 0; + outmsg.RxStatus = 0; + + unsigned long msgoutcount = 1; + + res = PassThruWriteMsgs(cid, &outmsg, &msgoutcount, 0); + if (res != STATUS_NOERROR) + return 1; + + PASSTHRU_MSG inmsg[8]; + unsigned long msgincount = 8; + + res = PassThruReadMsgs(cid, inmsg, &msgincount, 1000); + if (res != STATUS_NOERROR) + return 1; + + return 0; +} diff --git a/panda/drivers/windows/panda_playground/panda_playground.vcxproj b/panda/drivers/windows/panda_playground/panda_playground.vcxproj new file mode 100644 index 00000000000000..2b5f3120c34721 --- /dev/null +++ b/panda/drivers/windows/panda_playground/panda_playground.vcxproj @@ -0,0 +1,191 @@ + + + + + Debug + Win32 + + + Release + Win32 + + + Debug + x64 + + + Release + x64 + + + + {691DB635-C272-4B98-897E-0505B970DCA9} + Win32Proj + panda_playground + 10.0.16299.0 + + + + Application + true + v141 + Unicode + + + Application + false + v141 + true + Unicode + + + Application + true + v141 + Unicode + + + Application + false + v141 + true + Unicode + + + + + + + + + + + + + + + + + + + + + true + $(SolutionDir)$(Configuration)_$(PlatformShortName)\ + $(ProjectName)2 + + + true + $(SolutionDir)$(Configuration)_$(PlatformShortName)\ + $(ProjectName) + + + false + $(SolutionDir)$(Configuration)_$(PlatformShortName)\ + + + false + $(SolutionDir)$(Configuration)_$(PlatformShortName)\ + + + + Use + Level3 + Disabled + WIN32;_DEBUG;_CONSOLE;%(PreprocessorDefinitions) + true + %(AdditionalIncludeDirectories);$(SolutionDir) + + + Console + true + kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);$(OutDir)panda.lib;$(OutDir)ecusim.lib + + + + + Use + Level3 + Disabled + _DEBUG;_CONSOLE;%(PreprocessorDefinitions) + true + %(AdditionalIncludeDirectories);$(SolutionDir) + + + Console + true + kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);$(OutDir)panda.lib;$(OutDir)ecusim.lib + + + + + Level3 + Use + MaxSpeed + true + true + WIN32;NDEBUG;_CONSOLE;%(PreprocessorDefinitions) + true + %(AdditionalIncludeDirectories);$(SolutionDir) + + + Console + true + true + true + kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);$(OutDir)panda.lib;$(OutDir)ecusim.lib + + + + + Level3 + Use + MaxSpeed + true + true + NDEBUG;_CONSOLE;%(PreprocessorDefinitions) + true + %(AdditionalIncludeDirectories);$(SolutionDir) + + + Console + true + true + true + kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies);$(OutDir)panda.lib;$(OutDir)ecusim.lib + + + + + + + + + + + + + + + + Create + Create + Create + Create + + + + + {96e0e646-ee76-444d-9a77-a0cd7f781deb} + + + {a2bb18a5-f26b-48d6-bbb5-b83d64473c77} + + + {5528aefb-638d-49af-b9d4-965154e7d531} + + + + + + \ No newline at end of file diff --git a/panda/drivers/windows/panda_playground/panda_playground.vcxproj.filters b/panda/drivers/windows/panda_playground/panda_playground.vcxproj.filters new file mode 100644 index 00000000000000..b84fc23184e2c9 --- /dev/null +++ b/panda/drivers/windows/panda_playground/panda_playground.vcxproj.filters @@ -0,0 +1,45 @@ + + + + + {4FC737F1-C7A5-4376-A066-2A32D752A2FF} + cpp;c;cc;cxx;def;odl;idl;hpj;bat;asm;asmx + + + {93995380-89BD-4b04-88EB-625FBE52EBFB} + h;hh;hpp;hxx;hm;inl;inc;xsd + + + {67DA6AB6-F800-4c08-8B7A-83BB121AAD01} + rc;ico;cur;bmp;dlg;rc2;rct;bin;rgs;gif;jpg;jpeg;jpe;resx;tiff;tif;png;wav;mfcribbon-ms + + + + + + + + Header Files + + + Header Files + + + Header Files + + + Header Files + + + + + Source Files + + + Source Files + + + Source Files + + + \ No newline at end of file diff --git a/panda/drivers/windows/panda_playground/stdafx.cpp b/panda/drivers/windows/panda_playground/stdafx.cpp new file mode 100644 index 00000000000000..fefa8d7ec924ca --- /dev/null +++ b/panda/drivers/windows/panda_playground/stdafx.cpp @@ -0,0 +1,8 @@ +// stdafx.cpp : source file that includes just the standard includes +// panda_playground.pch will be the pre-compiled header +// stdafx.obj will contain the pre-compiled type information + +#include "stdafx.h" + +// TODO: reference any additional headers you need in STDAFX.H +// and not in this file diff --git a/panda/drivers/windows/panda_playground/stdafx.h b/panda/drivers/windows/panda_playground/stdafx.h new file mode 100644 index 00000000000000..f22759b0866ee2 --- /dev/null +++ b/panda/drivers/windows/panda_playground/stdafx.h @@ -0,0 +1,17 @@ +// stdafx.h : include file for standard system include files, +// or project specific include files that are used frequently, but +// are changed infrequently +// + +#pragma once + +#include "targetver.h" + +#define WIN32_LEAN_AND_MEAN // Exclude rarely-used stuff from Windows headers +// Windows Header Files: +#include + +#include +#include +#include +#include diff --git a/panda/drivers/windows/panda_playground/targetver.h b/panda/drivers/windows/panda_playground/targetver.h new file mode 100644 index 00000000000000..87c0086de751ba --- /dev/null +++ b/panda/drivers/windows/panda_playground/targetver.h @@ -0,0 +1,8 @@ +#pragma once + +// Including SDKDDKVer.h defines the highest available Windows platform. + +// If you wish to build your application for a previous Windows platform, include WinSDKVer.h and +// set the _WIN32_WINNT macro to the platform you wish to support before including SDKDDKVer.h. + +#include diff --git a/panda/drivers/windows/panda_remove.ico b/panda/drivers/windows/panda_remove.ico new file mode 100644 index 00000000000000..74602e03e913d3 Binary files /dev/null and b/panda/drivers/windows/panda_remove.ico differ diff --git a/panda/drivers/windows/panda_shared/device.cpp b/panda/drivers/windows/panda_shared/device.cpp new file mode 100644 index 00000000000000..83e021b7994ad4 --- /dev/null +++ b/panda/drivers/windows/panda_shared/device.cpp @@ -0,0 +1,169 @@ +#include "stdafx.h" + +#include +#include + +#include +#include + +#include + +#include "device.h" + +using namespace panda; + +//Returns the last Win32 error, in string format. Returns an empty string if there is no error. +tstring GetLastErrorAsString(){ + //Get the error message, if any. + DWORD errorMessageID = ::GetLastError(); + if (errorMessageID == 0) + return tstring(); //No error message has been recorded + + _TCHAR *messageBuffer = nullptr; + size_t size = FormatMessage(FORMAT_MESSAGE_ALLOCATE_BUFFER | FORMAT_MESSAGE_FROM_SYSTEM | FORMAT_MESSAGE_IGNORE_INSERTS, + NULL, errorMessageID, MAKELANGID(LANG_NEUTRAL, SUBLANG_DEFAULT), (_TCHAR*)&messageBuffer, 0, NULL); + + tstring message(messageBuffer, size); + + //Free the buffer. + LocalFree(messageBuffer); + + return message; +} + +std::unordered_map panda::detect_pandas() { + HDEVINFO deviceInfo; + HRESULT hr; + SP_DEVINFO_DATA deviceInfoData; + SP_DEVICE_INTERFACE_DATA interfaceData; + unsigned int deviceIndex; + + std::unordered_map map_sn_to_devpath; + + deviceInfo = SetupDiGetClassDevs(&GUID_DEVINTERFACE_panda, + NULL, NULL, DIGCF_PRESENT | DIGCF_DEVICEINTERFACE); //DIGCF_ALLCLASSES + + if (deviceInfo == INVALID_HANDLE_VALUE) { + hr = HRESULT_FROM_WIN32(GetLastError()); + _tprintf(_T("Failed to get dev handle. HR: %d\n"), hr); + return map_sn_to_devpath; + } + + ZeroMemory(&deviceInfoData, sizeof(SP_DEVINFO_DATA)); + deviceInfoData.cbSize = sizeof(SP_DEVINFO_DATA); + deviceIndex = 0; + + while (SetupDiEnumDeviceInfo(deviceInfo, deviceIndex, &deviceInfoData)) { + deviceIndex++; + _tprintf(_T("Device info index %d\n"), deviceIndex); + + interfaceData.cbSize = sizeof(SP_DEVICE_INTERFACE_DATA); + if (SetupDiEnumDeviceInterfaces(deviceInfo, &deviceInfoData, + &GUID_DEVINTERFACE_panda, 0, &interfaceData) == FALSE) { + _tprintf(_T(" Got unexpected error while accessing interface %d\n"), GetLastError()); + continue; + } + + DWORD requiredLength; + if (SetupDiGetDeviceInterfaceDetail(deviceInfo, &interfaceData, NULL, 0, &requiredLength, NULL) == FALSE + && ERROR_INSUFFICIENT_BUFFER != GetLastError()) { + _tprintf(_T(" Got unexpected error while reading interface details %d\n"), GetLastError()); + continue; + } + + PSP_DEVICE_INTERFACE_DETAIL_DATA detailData = (PSP_DEVICE_INTERFACE_DETAIL_DATA)LocalAlloc(LMEM_FIXED, requiredLength); + if (NULL == detailData) { + _tprintf(_T(" Failed to allocate %d bytes for interface data\n"), requiredLength); + continue; + } + detailData->cbSize = sizeof(SP_DEVICE_INTERFACE_DETAIL_DATA); + + DWORD length = requiredLength; + if (SetupDiGetDeviceInterfaceDetail(deviceInfo, &interfaceData, detailData, length, &requiredLength, NULL) == FALSE) { + _tprintf(_T(" Got unexpected error while reading interface details (2nd time) %d. Msg: '%s'\n"), + GetLastError(), GetLastErrorAsString().c_str()); + LocalFree(detailData); + continue; + } + + //_tprintf(_T(" Path: '%s'\n"), detailData->DevicePath); + HANDLE deviceHandle = CreateFile(detailData->DevicePath, + GENERIC_WRITE | GENERIC_READ, FILE_SHARE_WRITE | FILE_SHARE_READ, + NULL, OPEN_EXISTING, FILE_ATTRIBUTE_NORMAL | FILE_FLAG_OVERLAPPED, NULL); + + if (INVALID_HANDLE_VALUE == deviceHandle) { + _tprintf(_T(" Error opening Device Handle %d. Msg: '%s'\n"), + GetLastError(), GetLastErrorAsString().c_str()); + LocalFree(detailData); + continue; + } + + WINUSB_INTERFACE_HANDLE winusbHandle; + if (WinUsb_Initialize(deviceHandle, &winusbHandle) == FALSE) { + _tprintf(_T(" Error initializing WinUSB %d. Msg: '%s'\n"), + GetLastError(), GetLastErrorAsString().c_str()); + CloseHandle(deviceHandle); + LocalFree(detailData); + continue; + } + + USB_DEVICE_DESCRIPTOR deviceDesc; + unsigned long lengthReceived; + if (WinUsb_GetDescriptor(winusbHandle, USB_DEVICE_DESCRIPTOR_TYPE, 0, 0, + (PBYTE)&deviceDesc, sizeof(deviceDesc), &lengthReceived) == FALSE + || lengthReceived != sizeof(deviceDesc)) { + _tprintf(_T(" Error getting device descriptor %d. Msg: '%s'\n"), + GetLastError(), GetLastErrorAsString().c_str()); + WinUsb_Free(winusbHandle); + CloseHandle(deviceHandle); + LocalFree(detailData); + continue; + } + + #define SNDESCLEN 64 + PUSB_STRING_DESCRIPTOR psnDesc = (PUSB_STRING_DESCRIPTOR)LocalAlloc(LMEM_FIXED, SNDESCLEN); + if (NULL == psnDesc) { + _tprintf(_T(" Failed to allocate %d bytes for sn data\n"), SNDESCLEN); + continue; + } + + if (WinUsb_GetDescriptor(winusbHandle, USB_STRING_DESCRIPTOR_TYPE, deviceDesc.iSerialNumber, + 0x0409 /*Eng*/, (PBYTE)psnDesc, SNDESCLEN, &lengthReceived) == FALSE || lengthReceived == 0) { + _tprintf(_T(" Error getting serial number %d. Msg: '%s'\n"), + GetLastError(), GetLastErrorAsString().c_str()); + LocalFree(psnDesc); + WinUsb_Free(winusbHandle); + CloseHandle(deviceHandle); + LocalFree(detailData); + continue; + } + //The minus 2 is for the two numbers, not the null term. + psnDesc->bString[(psnDesc->bLength - 2) / sizeof(_TCHAR)] = 0; + + char w_to_m_buff[256]; + size_t mbuff_len; + if (wcstombs_s(&mbuff_len, w_to_m_buff, sizeof(w_to_m_buff), psnDesc->bString, 24) != 0) { + _tprintf(_T(" Error generating mb SN string %d. Msg: '%s'\n"), + GetLastError(), GetLastErrorAsString().c_str()); + LocalFree(psnDesc); + WinUsb_Free(winusbHandle); + CloseHandle(deviceHandle); + LocalFree(detailData); + continue; + } + std::string serialnum(w_to_m_buff, mbuff_len-1); + printf(" Device found: seriallen: %d; serial: %s\n", lengthReceived, serialnum.c_str()); + + map_sn_to_devpath[serialnum] = tstring(detailData->DevicePath); + + LocalFree(psnDesc); + WinUsb_Free(winusbHandle); + CloseHandle(deviceHandle); + LocalFree(detailData); + } + + if(deviceInfo) + SetupDiDestroyDeviceInfoList(deviceInfo); + + return map_sn_to_devpath; +} diff --git a/panda/drivers/windows/panda_shared/device.h b/panda/drivers/windows/panda_shared/device.h new file mode 100644 index 00000000000000..f11baa1c67c887 --- /dev/null +++ b/panda/drivers/windows/panda_shared/device.h @@ -0,0 +1,32 @@ +#ifndef __PANDA_DEVICE +#define __PANDA_DEVICE + +// +// Define below GUIDs +// +#include +#include + +#if defined(UNICODE) +#define _tcout std::wcout +#define tstring std::wstring +#else +#define _tcout std::cout +#define tstring std::string +#endif + +// +// Device Interface GUID. +// Used by all WinUsb devices that this application talks to. +// Must match "DeviceInterfaceGUIDs" registry value specified in the INF file. +// cce5291c-a69f-4995-a4c2-2ae57a51ade9 +// +DEFINE_GUID(GUID_DEVINTERFACE_panda, + 0xcce5291c,0xa69f,0x4995,0xa4,0xc2,0x2a,0xe5,0x7a,0x51,0xad,0xe9); + +tstring GetLastErrorAsString(); + +namespace panda { + std::unordered_map __declspec(dllexport) detect_pandas(); +} +#endif diff --git a/panda/drivers/windows/panda_shared/panda.cpp b/panda/drivers/windows/panda_shared/panda.cpp new file mode 100644 index 00000000000000..5f711b02aa28a1 --- /dev/null +++ b/panda/drivers/windows/panda_shared/panda.cpp @@ -0,0 +1,522 @@ +// panda.cpp : Defines the exported functions for the DLL application. +// +#include "stdafx.h" + +#include "device.h" +#include "panda.h" + +#define REQUEST_IN 0xC0 +#define REQUEST_OUT 0x40 + +#define CAN_TRANSMIT 1 +#define CAN_EXTENDED 4 + +using namespace panda; + +Panda::Panda( + WINUSB_INTERFACE_HANDLE WinusbHandle, + HANDLE DeviceHandle, + tstring devPath_, + std::string sn_ +) : usbh(WinusbHandle), devh(DeviceHandle), devPath(devPath_), sn(sn_) { + printf("CREATED A PANDA %s\n", this->sn.c_str()); + this->set_can_loopback(FALSE); + this->set_raw_io(TRUE); + this->set_alt_setting(0); +} + +Panda::~Panda() { + WinUsb_Free(this->usbh); + CloseHandle(this->devh); + printf("Cleanup Panda %s\n", this->sn.c_str()); +} + +std::vector Panda::listAvailablePandas() { + std::vector ret; + auto map_sn_to_devpath = detect_pandas(); + + for (auto kv : map_sn_to_devpath) { + ret.push_back(std::string(kv.first)); + } + + return ret; +} + +std::unique_ptr Panda::openPanda(std::string sn) +{ + auto map_sn_to_devpath = detect_pandas(); + + if (map_sn_to_devpath.empty()) return nullptr; + if (map_sn_to_devpath.find(sn) == map_sn_to_devpath.end() && sn != "") return nullptr; + + tstring devpath; + if (sn.empty()) { + sn = map_sn_to_devpath.begin()->first; + devpath = map_sn_to_devpath.begin()->second; + } else { + devpath = map_sn_to_devpath[sn]; + } + + HANDLE deviceHandle = CreateFile(devpath.c_str(), + GENERIC_WRITE | GENERIC_READ, FILE_SHARE_WRITE | FILE_SHARE_READ, + NULL, OPEN_EXISTING, FILE_ATTRIBUTE_NORMAL | FILE_FLAG_OVERLAPPED, NULL); + + if (INVALID_HANDLE_VALUE == deviceHandle) { + _tprintf(_T(" Error opening Device Handle %d.\n"),// Msg: '%s'\n"), + GetLastError());// , GetLastErrorAsString().c_str()); + return nullptr; + } + + WINUSB_INTERFACE_HANDLE winusbHandle; + if (WinUsb_Initialize(deviceHandle, &winusbHandle) == FALSE) { + _tprintf(_T(" Error initializing WinUSB %d.\n"),// Msg: '%s'\n"), + GetLastError());// , GetLastErrorAsString().c_str()); + CloseHandle(deviceHandle); + return nullptr; + } + + return std::unique_ptr(new Panda(winusbHandle, deviceHandle, map_sn_to_devpath[sn], sn)); +} + +std::string Panda::get_usb_sn() { + return std::string(this->sn); +} + +int Panda::control_transfer( + uint8_t bmRequestType, + uint8_t bRequest, + uint16_t wValue, + uint16_t wIndex, + void * data, + uint16_t wLength, + unsigned int timeout +) { + UNREFERENCED_PARAMETER(timeout); + + WINUSB_SETUP_PACKET SetupPacket; + ZeroMemory(&SetupPacket, sizeof(WINUSB_SETUP_PACKET)); + ULONG cbSent = 0; + + //Create the setup packet + SetupPacket.RequestType = bmRequestType; + SetupPacket.Request = bRequest; + SetupPacket.Value = wValue; + SetupPacket.Index = wIndex; + SetupPacket.Length = wLength; + + //ULONG timeout = 10; // ms + //WinUsb_SetPipePolicy(interfaceHandle, pipeID, PIPE_TRANSFER_TIMEOUT, sizeof(ULONG), &timeout); + + if (WinUsb_ControlTransfer(this->usbh, SetupPacket, (PUCHAR)data, wLength, &cbSent, 0) == FALSE) { + return -1; + } + + return cbSent; +} + +int Panda::bulk_write(UCHAR endpoint, const void * buff, ULONG length, PULONG transferred, ULONG timeout) { + if (this->usbh == INVALID_HANDLE_VALUE || !buff || !length || !transferred) return FALSE; + + if (WinUsb_WritePipe(this->usbh, endpoint, (PUCHAR)buff, length, transferred, NULL) == FALSE) { + _tprintf(_T(" Got error during bulk xfer: %d. Msg: '%s'\n"), + GetLastError(), GetLastErrorAsString().c_str()); + return FALSE; + } + return TRUE; +} + +int Panda::bulk_read(UCHAR endpoint, void * buff, ULONG buff_size, PULONG transferred, ULONG timeout) { + if (this->usbh == INVALID_HANDLE_VALUE || !buff || !buff_size || !transferred) return FALSE; + + if (WinUsb_ReadPipe(this->usbh, endpoint, (PUCHAR)buff, buff_size, transferred, NULL) == FALSE) { + _tprintf(_T(" Got error during bulk xfer: %d. Msg: '%s'\n"), + GetLastError(), GetLastErrorAsString().c_str()); + return FALSE; + } + return TRUE; +} + +bool Panda::set_alt_setting(UCHAR alt_setting) { + if (WinUsb_AbortPipe(this->usbh, 0x81) == FALSE) { + _tprintf(_T(" Error abobrting pipe before setting altsetting. continue. %d, Msg: '%s'\n"), + GetLastError(), GetLastErrorAsString().c_str()); + } + if (WinUsb_SetCurrentAlternateSetting(this->usbh, alt_setting) == FALSE) { + _tprintf(_T(" Error setting usb altsetting %d, Msg: '%s'\n"), + GetLastError(), GetLastErrorAsString().c_str()); + return FALSE; + } + + // Either the panda or the windows usb stack can drop messages + // if an odd number of messages are sent before an interrupt IN + // message is canceled. There are some other odd behaviors, but + // the best solution so far has been to send a few messages + // before using the device to clear out the pipe. No, the windows + // functions for clearing/resetting/etc the pipe did not work. + // This took way too to figure out a workaround. + // New info. The most repeatable behavior is losing the first + // message sent after setting alt setting to 1 (even without + // receiving). Something like this happened on linux sometimes. + bool loopback_backup = this->loopback; + this->set_can_loopback(TRUE); + Sleep(20); // Give time for any sent messages to appear in the RX buffer. + this->can_clear(PANDA_CAN_RX); + // send 4 messages becaus can_recv reads 4 messages at a time + for (int i = 0; i < 4; i++) { + printf("Sending PAD %d\n", i); + if (this->can_send(0x7FF, FALSE, {}, 0, PANDA_CAN1) == FALSE) { + auto err = GetLastError(); + printf("Got err on first send: %d\n", err); + } + } + Sleep(10); + //this->can_clear(PANDA_CAN_RX); + + //Read the messages so they do not contaimnate the real message stream. + this->can_recv(); + + //this->set_can_loopback(FALSE); + this->set_can_loopback(loopback_backup); + + return TRUE; +} + +UCHAR Panda::get_current_alt_setting() { + UCHAR alt_setting; + if (WinUsb_GetCurrentAlternateSetting(this->usbh, &alt_setting) == FALSE) { + _tprintf(_T(" Error getting usb altsetting %d, Msg: '%s'\n"), + GetLastError(), GetLastErrorAsString().c_str()); + return FALSE; + } + + return alt_setting; +} + +bool Panda::set_raw_io(bool val) { + UCHAR raw_io = val; + if (!WinUsb_SetPipePolicy(this->usbh, 0x81, RAW_IO, sizeof(raw_io), &raw_io)) { + _tprintf(_T(" Error setting usb raw I/O pipe policy %d, Msg: '%s'\n"), + GetLastError(), GetLastErrorAsString().c_str()); + return FALSE; + } + + return TRUE; +} + +PANDA_HEALTH Panda::get_health() +{ + WINUSB_SETUP_PACKET SetupPacket; + ZeroMemory(&SetupPacket, sizeof(WINUSB_SETUP_PACKET)); + ULONG cbSent = 0; + + //Create the setup packet + SetupPacket.RequestType = REQUEST_IN; + SetupPacket.Request = 0xD2; + SetupPacket.Value = 0; + SetupPacket.Index = 0; + SetupPacket.Length = sizeof(UCHAR); + + //uint8_t health[13]; + PANDA_HEALTH health; + + if (WinUsb_ControlTransfer(this->usbh, SetupPacket, (PUCHAR)&health, sizeof(health), &cbSent, 0) == FALSE) { + _tprintf(_T(" Got unexpected error while reading panda health (2nd time) %d. Msg: '%s'\n"), + GetLastError(), GetLastErrorAsString().c_str()); + } + + return health; +} + +bool Panda::enter_bootloader() { + return this->control_transfer(REQUEST_OUT, 0xd1, 0, 0, NULL, 0, 0) != -1; +} + +std::string Panda::get_version() { + char buff[0x40]; + ZeroMemory(&buff, sizeof(buff)); + + int xferCount = this->control_transfer(REQUEST_IN, 0xd6, 0, 0, buff, 0x40, 0); + if (xferCount == -1) return std::string(); + return std::string(buff); +} + +//TODO: Do hash stuff for calculating the serial. +std::string Panda::get_serial() { + char buff[0x20]; + ZeroMemory(&buff, sizeof(buff)); + + int xferCount = this->control_transfer(REQUEST_IN, 0xD0, 0, 0, buff, 0x20, 0); + if (xferCount == -1) return std::string(); + return std::string(buff); + + //dat = self._handle.controlRead(REQUEST_IN, 0xd0, 0, 0, 0x20); + //hashsig, calc_hash = dat[0x1c:], hashlib.sha1(dat[0:0x1c]).digest()[0:4] + // assert(hashsig == calc_hash) + // return[dat[0:0x10], dat[0x10:0x10 + 10]] +} + +//Secret appears to by raw bytes, not a string. TODO: Change returned type. +std::string Panda::get_secret() { + char buff[0x10]; + ZeroMemory(&buff, sizeof(buff)); + + int xferCount = this->control_transfer(REQUEST_IN, 0xd0, 1, 0, buff, 0x10, 0); + if (xferCount == -1) return std::string(); + return std::string(buff); +} + +bool Panda::set_usb_power(bool on) { + return this->control_transfer(REQUEST_OUT, 0xe6, (int)on, 0, NULL, 0, 0) != -1; +} + +bool Panda::set_esp_power(bool on) { + return this->control_transfer(REQUEST_OUT, 0xd9, (int)on, 0, NULL, 0, 0) != -1; +} + +bool Panda::esp_reset(uint16_t bootmode = 0) { + return this->control_transfer(REQUEST_OUT, 0xda, bootmode, 0, NULL, 0, 0) != -1; +} + +bool Panda::set_safety_mode(PANDA_SAFETY_MODE mode = SAFETY_NOOUTPUT) { + return this->control_transfer(REQUEST_OUT, 0xdc, mode, 0, NULL, 0, 0) != -1; +} + +bool Panda::set_can_forwarding(PANDA_CAN_PORT from_bus, PANDA_CAN_PORT to_bus) { + if (from_bus == PANDA_CAN_UNK) return FALSE; + return this->control_transfer(REQUEST_OUT, 0xdd, from_bus, to_bus, NULL, 0, 0) != -1; +} + +bool Panda::set_gmlan(PANDA_GMLAN_HOST_PORT bus = PANDA_GMLAN_CAN3) { + return this->control_transfer(REQUEST_OUT, 0xdb, 1, (bus == PANDA_GMLAN_CLEAR) ? 0 : bus, NULL, 0, 0) != -1; +} + +bool Panda::set_can_loopback(bool enable) { + this->loopback = enable; + return this->control_transfer(REQUEST_OUT, 0xe5, enable, 0, NULL, 0, 0) != -1; +} + +//Can not use the full range of 16 bit speed. +//cbps means centa bits per second (tento of kbps) +bool Panda::set_can_speed_cbps(PANDA_CAN_PORT bus, uint16_t speed) { + if (bus == PANDA_CAN_UNK) return FALSE; + return this->control_transfer(REQUEST_OUT, 0xde, bus, speed, NULL, 0, 0) != -1; +} + +//Can not use the full range of 16 bit speed. +bool Panda::set_can_speed_kbps(PANDA_CAN_PORT bus, uint16_t speed) { + return set_can_speed_cbps(bus, speed * 10); +} + +//Can not use full 32 bit range of rate +bool Panda::set_uart_baud(PANDA_SERIAL_PORT uart, uint32_t rate) { + return this->control_transfer(REQUEST_OUT, 0xe4, uart, rate / 300, NULL, 0, 0) != -1; +} + +bool Panda::set_uart_parity(PANDA_SERIAL_PORT uart, PANDA_SERIAL_PORT_PARITY parity) { + return this->control_transfer(REQUEST_OUT, 0xe2, uart, parity, NULL, 0, 0) != -1; +} + +bool Panda::can_send_many(const std::vector& can_msgs) { + std::vector formatted_msgs; + formatted_msgs.reserve(can_msgs.size()); + + for (auto msg : can_msgs) { + if (msg.bus == PANDA_CAN_UNK) continue; + if (msg.len > 8) continue; + PANDA_CAN_MSG_INTERNAL tmpmsg = {}; + tmpmsg.rir = (msg.addr_29b) ? + ((msg.addr << 3) | CAN_TRANSMIT | CAN_EXTENDED) : + (((msg.addr & 0x7FF) << 21) | CAN_TRANSMIT); + tmpmsg.f2 = msg.len | (msg.bus << 4); + memcpy(tmpmsg.dat, msg.dat, msg.len); + formatted_msgs.push_back(tmpmsg); + } + + if (formatted_msgs.size() == 0) return FALSE; + + unsigned int retcount; + return this->bulk_write(3, formatted_msgs.data(), + sizeof(PANDA_CAN_MSG_INTERNAL)*formatted_msgs.size(), (PULONG)&retcount, 0); +} + +bool Panda::can_send(uint32_t addr, bool addr_29b, const uint8_t *dat, uint8_t len, PANDA_CAN_PORT bus) { + if (bus == PANDA_CAN_UNK) return FALSE; + if (len > 8) return FALSE; + PANDA_CAN_MSG msg; + msg.addr_29b = addr_29b; + msg.addr = addr; + msg.len = len; + memcpy(msg.dat, dat, msg.len); + msg.bus = bus; + return this->can_send_many(std::vector{msg}); +} + +PANDA_CAN_MSG Panda::parse_can_recv(PANDA_CAN_MSG_INTERNAL *in_msg_raw) { + PANDA_CAN_MSG in_msg; + + in_msg.addr_29b = (bool)(in_msg_raw->rir & CAN_EXTENDED); + in_msg.addr = (in_msg.addr_29b) ? (in_msg_raw->rir >> 3) : (in_msg_raw->rir >> 21); + in_msg.recv_time = this->runningTime.getTimePassedUS(); + in_msg.recv_time_point = std::chrono::steady_clock::now(); + //The timestamp from the device is (in_msg_raw->f2 >> 16), + //but this 16 bit value is a little hard to use. Using a + //timer since the initialization of this device. + in_msg.len = in_msg_raw->f2 & 0xF; + memcpy(in_msg.dat, in_msg_raw->dat, 8); + + in_msg.is_receipt = ((in_msg_raw->f2 >> 4) & 0x80) == 0x80; + switch ((in_msg_raw->f2 >> 4) & 0x7F) { + case PANDA_CAN1: + in_msg.bus = PANDA_CAN1; + break; + case PANDA_CAN2: + in_msg.bus = PANDA_CAN2; + break; + case PANDA_CAN3: + in_msg.bus = PANDA_CAN3; + break; + default: + in_msg.bus = PANDA_CAN_UNK; + } + return in_msg; +} + +bool Panda::can_rx_q_push(HANDLE kill_event, DWORD timeoutms) { + while (1) { + auto w_ptr = this->w_ptr; + auto n_ptr = w_ptr + 1; + if (n_ptr == CAN_RX_QUEUE_LEN) { + n_ptr = 0; + } + + // Pause if there is not a slot available in the queue + if (n_ptr == this->r_ptr) { + printf("RX queue full!\n"); + Sleep(1); + continue; + } + + if (this->can_rx_q[n_ptr].complete) { + // TODO: is ResetEvent() faster? + CloseHandle(this->can_rx_q[n_ptr].complete); + } + + // Overlapped structure required for async read. + this->can_rx_q[n_ptr].complete = CreateEvent(NULL, TRUE, TRUE, NULL); + memset(&this->can_rx_q[n_ptr].overlapped, sizeof(OVERLAPPED), 0); + this->can_rx_q[n_ptr].overlapped.hEvent = this->can_rx_q[n_ptr].complete; + this->can_rx_q[n_ptr].error = 0; + + if (!WinUsb_ReadPipe(this->usbh, 0x81, this->can_rx_q[n_ptr].data, sizeof(this->can_rx_q[n_ptr].data), &this->can_rx_q[n_ptr].count, &this->can_rx_q[n_ptr].overlapped)) { + // An overlapped read will return true if done, or false with an + // error of ERROR_IO_PENDING if the transfer is still in process. + this->can_rx_q[n_ptr].error = GetLastError(); + } + + // Process the pipe read call from the previous invocation of this function + if (this->can_rx_q[w_ptr].error == ERROR_IO_PENDING) { + HANDLE phSignals[2] = { this->can_rx_q[w_ptr].complete, kill_event }; + auto dwError = WaitForMultipleObjects(kill_event ? 2 : 1, phSignals, FALSE, timeoutms); + + // Check if packet, timeout (nope), or break + if (dwError == WAIT_OBJECT_0) { + // Signal came from our usb object. Read the returned data. + if (!GetOverlappedResult(this->usbh, &this->can_rx_q[w_ptr].overlapped, &this->can_rx_q[w_ptr].count, TRUE)) { + // TODO: handle other error cases better. + dwError = GetLastError(); + printf("Got overlap error %d\n", dwError); + + continue; + } + } + else { + WinUsb_AbortPipe(this->usbh, 0x81); + + // Return FALSE to show that the optional signal + // was set instead of the wait breaking from a + // message or recoverable error. + if (dwError == (WAIT_OBJECT_0 + 1)) { + return FALSE; + } + continue; + } + } + else if (this->can_rx_q[w_ptr].error != 0) { // ERROR_BAD_COMMAND happens when device is unplugged. + return FALSE; + } + + this->w_ptr = n_ptr; + } + + return TRUE; +} + +void Panda::can_rx_q_pop(PANDA_CAN_MSG msg_out[], int &count) { + count = 0; + + // No data left in queue + if (this->r_ptr == this->w_ptr) { + Sleep(1); + return; + } + + auto r_ptr = this->r_ptr; + for (int i = 0; i < this->can_rx_q[r_ptr].count; i += sizeof(PANDA_CAN_MSG_INTERNAL)) { + auto in_msg_raw = (PANDA_CAN_MSG_INTERNAL *)(this->can_rx_q[r_ptr].data + i); + msg_out[count] = parse_can_recv(in_msg_raw); + ++count; + } + + // Advance read pointer (wrap around if needed) + ++r_ptr; + this->r_ptr = (r_ptr == CAN_RX_QUEUE_LEN ? 0 : r_ptr); +} + +std::vector Panda::can_recv() { + std::vector msg_recv; + int retcount; + char buff[sizeof(PANDA_CAN_MSG_INTERNAL) * 4]; + + if (this->bulk_read(0x81, buff, sizeof(buff), (PULONG)&retcount, 0) == FALSE) + return msg_recv; + + for (int i = 0; i < retcount; i += sizeof(PANDA_CAN_MSG_INTERNAL)) { + PANDA_CAN_MSG_INTERNAL *in_msg_raw = (PANDA_CAN_MSG_INTERNAL *)(buff + i); + auto in_msg = parse_can_recv(in_msg_raw); + msg_recv.push_back(in_msg); + } + + return msg_recv; +} + +bool Panda::can_clear(PANDA_CAN_PORT_CLEAR bus) { + /*Clears all messages from the specified internal CAN ringbuffer as though it were drained. + bus(int) : can bus number to clear a tx queue, or 0xFFFF to clear the global can rx queue.*/ + return this->control_transfer(REQUEST_OUT, 0xf1, bus, 0, NULL, 0, 0) != -1; +} + +std::string Panda::serial_read(PANDA_SERIAL_PORT port_number) { + std::string result; + char buff[0x40]; + while (TRUE) { + int retlen = this->control_transfer(REQUEST_IN, 0xe0, port_number, 0, &buff, 0x40, 0); + if (retlen <= 0) + break; + result += std::string(buff, retlen); + if (retlen < 0x40) break; + } + return result; +} + +int Panda::serial_write(PANDA_SERIAL_PORT port_number, const void* buff, uint16_t len) { + std::string dat; + dat += port_number; + dat += std::string((char*)buff, len); + int retcount; + if (this->bulk_write(2, dat.c_str(), len+1, (PULONG)&retcount, 0) == FALSE) return -1; + return retcount; +} + +bool Panda::serial_clear(PANDA_SERIAL_PORT port_number) { + return this->control_transfer(REQUEST_OUT, 0xf2, port_number, 0, NULL, 0, 0) != -1; +} diff --git a/panda/drivers/windows/panda_shared/panda.h b/panda/drivers/windows/panda_shared/panda.h new file mode 100644 index 00000000000000..ade8fa36a8601e --- /dev/null +++ b/panda/drivers/windows/panda_shared/panda.h @@ -0,0 +1,237 @@ +#pragma once + +// The following ifdef block is the standard way of creating macros which make exporting +// from a DLL simpler. All files within this DLL are compiled with the PANDA_EXPORTS +// symbol defined on the command line. This symbol should not be defined on any project +// that uses this DLL. This way any other project whose source files include this file see +// PANDA_API functions as being imported from a DLL, whereas this DLL sees symbols +// defined with this macro as being exported. +#ifdef PANDA_EXPORTS +#define PANDA_API __declspec(dllexport) +#else +#define PANDA_API +#endif + +#include +#include +#include +#include +#include +#include + +#include +#include + +#if defined(UNICODE) +#define _tcout std::wcout +#define tstring std::wstring +#else +#define _tcout std::cout +#define tstring std::string +#endif + +#define LIN_MSG_MAX_LEN 10 +#define CAN_RX_QUEUE_LEN 10000 +#define CAN_RX_MSG_LEN 1000 + +//template class __declspec(dllexport) std::basic_string; + +namespace panda { + typedef enum _PANDA_SAFETY_MODE : uint16_t { + SAFETY_NOOUTPUT = 0, + SAFETY_HONDA = 1, + SAFETY_ALLOUTPUT = 0x1337, + } PANDA_SAFETY_MODE; + + typedef enum _PANDA_SERIAL_PORT : uint8_t { + SERIAL_DEBUG = 0, + SERIAL_ESP = 1, + SERIAL_LIN1 = 2, + SERIAL_LIN2 = 3, + } PANDA_SERIAL_PORT; + + typedef enum _PANDA_SERIAL_PORT_PARITY : uint8_t { + PANDA_PARITY_OFF = 0, + PANDA_PARITY_EVEN = 1, + PANDA_PARITY_ODD = 2, + } PANDA_SERIAL_PORT_PARITY; + + typedef enum _PANDA_CAN_PORT : uint8_t { + PANDA_CAN1 = 0, + PANDA_CAN2 = 1, + PANDA_CAN3 = 2, + PANDA_CAN_UNK = 0xFF, + } PANDA_CAN_PORT; + + typedef enum _PANDA_CAN_PORT_CLEAR : uint16_t { + PANDA_CAN1_TX = 0, + PANDA_CAN2_TX = 1, + PANDA_CAN3_TX = 2, + PANDA_CAN_RX = 0xFFFF, + } PANDA_CAN_PORT_CLEAR; + + typedef enum _PANDA_GMLAN_HOST_PORT : uint8_t { + PANDA_GMLAN_CLEAR = 0, + PANDA_GMLAN_CAN2 = 1, + PANDA_GMLAN_CAN3 = 2, + } PANDA_GMLAN_HOST_PORT; + + #pragma pack(1) + typedef struct _PANDA_HEALTH { + uint32_t voltage; + uint32_t current; + uint8_t started; + uint8_t controls_allowed; + uint8_t gas_interceptor_detected; + uint8_t started_signal_detected; + uint8_t started_alt; + } PANDA_HEALTH, *PPANDA_HEALTH; + + typedef struct _PANDA_CAN_MSG { + uint32_t addr; + unsigned long long recv_time; //In microseconds since device initialization + std::chrono::time_point recv_time_point; + uint8_t dat[8]; + uint8_t len; + PANDA_CAN_PORT bus; + bool is_receipt; + bool addr_29b; + } PANDA_CAN_MSG; + + //Copied from https://stackoverflow.com/a/31488113 + class Timer + { + using clock = std::chrono::steady_clock; + using time_point_type = std::chrono::time_point < clock, std::chrono::microseconds >; + public: + Timer() { + start = std::chrono::time_point_cast(clock::now()); + } + + // gets the time elapsed from construction. + unsigned long long /*microseconds*/ Timer::getTimePassedUS() { + // get the new time + auto end = std::chrono::time_point_cast(clock::now()); + + // return the difference of the times + return (end - start).count(); + } + + // gets the time elapsed from construction. + unsigned long long /*milliseconds*/ Timer::getTimePassedMS() { + // get the new time + auto end = std::chrono::time_point_cast(clock::now()); + + // return the difference of the times + auto startms = std::chrono::time_point_cast(start); + return (end - startms).count(); + } + private: + time_point_type start; + }; + + // This class is exported from the panda.dll + class PANDA_API Panda { + public: + static std::vector listAvailablePandas(); + static std::unique_ptr openPanda(std::string sn); + + ~Panda(); + + std::string get_usb_sn(); + bool set_alt_setting(UCHAR alt_setting); + UCHAR get_current_alt_setting(); + bool Panda::set_raw_io(bool val); + + PANDA_HEALTH get_health(); + bool enter_bootloader(); + std::string get_version(); + std::string get_serial(); + std::string get_secret(); + + bool set_usb_power(bool on); + bool set_esp_power(bool on); + bool esp_reset(uint16_t bootmode); + bool set_safety_mode(PANDA_SAFETY_MODE mode); + bool set_can_forwarding(PANDA_CAN_PORT from_bus, PANDA_CAN_PORT to_bus); + bool set_gmlan(PANDA_GMLAN_HOST_PORT bus); + bool set_can_loopback(bool enable); + bool set_can_speed_cbps(PANDA_CAN_PORT bus, uint16_t speed); + bool set_can_speed_kbps(PANDA_CAN_PORT bus, uint16_t speed); + bool set_uart_baud(PANDA_SERIAL_PORT uart, uint32_t rate); + bool set_uart_parity(PANDA_SERIAL_PORT uart, PANDA_SERIAL_PORT_PARITY parity); + + bool can_send_many(const std::vector& can_msgs); + bool can_send(uint32_t addr, bool addr_29b, const uint8_t *dat, uint8_t len, PANDA_CAN_PORT bus); + std::vector can_recv(); + bool can_rx_q_push(HANDLE kill_event, DWORD timeoutms = INFINITE); + void can_rx_q_pop(PANDA_CAN_MSG msg_out[], int &count); + bool can_clear(PANDA_CAN_PORT_CLEAR bus); + + std::string serial_read(PANDA_SERIAL_PORT port_number); + int serial_write(PANDA_SERIAL_PORT port_number, const void* buff, uint16_t len); + bool serial_clear(PANDA_SERIAL_PORT port_number); + private: + Panda( + WINUSB_INTERFACE_HANDLE WinusbHandle, + HANDLE DeviceHandle, + tstring devPath_, + std::string sn_ + ); + + int control_transfer( + uint8_t bmRequestType, + uint8_t bRequest, + uint16_t wValue, + uint16_t wIndex, + void * data, + uint16_t wLength, + unsigned int timeout + ); + + int bulk_write( + UCHAR endpoint, + const void * buff, + ULONG length, + PULONG transferred, + ULONG timeout + ); + + int Panda::bulk_read( + UCHAR endpoint, + void * buff, + ULONG buff_size, + PULONG transferred, + ULONG timeout + ); + + #pragma pack(1) + typedef struct _PANDA_CAN_MSG_INTERNAL { + uint32_t rir; + uint32_t f2; + uint8_t dat[8]; + } PANDA_CAN_MSG_INTERNAL; + + typedef struct _CAN_RX_PIPE_READ { + unsigned char data[sizeof(PANDA_CAN_MSG_INTERNAL) * CAN_RX_MSG_LEN]; + unsigned long count; + OVERLAPPED overlapped; + HANDLE complete; + DWORD error; + } CAN_RX_PIPE_READ; + + PANDA_CAN_MSG parse_can_recv(PANDA_CAN_MSG_INTERNAL *in_msg_raw); + + WINUSB_INTERFACE_HANDLE usbh; + HANDLE devh; + tstring devPath; + std::string sn; + bool loopback; + + Timer runningTime; + CAN_RX_PIPE_READ can_rx_q[CAN_RX_QUEUE_LEN]; + unsigned long w_ptr = 0; + unsigned long r_ptr = 0; + }; + +} diff --git a/panda/drivers/windows/panda_shared/panda_shared.vcxitems b/panda/drivers/windows/panda_shared/panda_shared.vcxitems new file mode 100644 index 00000000000000..3f3b4765c0225c --- /dev/null +++ b/panda/drivers/windows/panda_shared/panda_shared.vcxitems @@ -0,0 +1,25 @@ + + + + $(MSBuildAllProjects);$(MSBuildThisFileFullPath) + true + {0c843279-68c7-4679-ae51-9bc463d50d1c} + + + + %(AdditionalIncludeDirectories);$(MSBuildThisFileDirectory) + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/panda/drivers/windows/panda_shared/targetver.h b/panda/drivers/windows/panda_shared/targetver.h new file mode 100644 index 00000000000000..1bf4ee6fee02e7 --- /dev/null +++ b/panda/drivers/windows/panda_shared/targetver.h @@ -0,0 +1,13 @@ +#pragma once + +// Including SDKDDKVer.h defines the highest available Windows platform. + +// If you wish to build your application for a previous Windows platform, include WinSDKVer.h and +// set the _WIN32_WINNT macro to the platform you wish to support before including SDKDDKVer.h. + +#include + +#define WINVER _WIN32_WINNT_WIN7 +#define _WIN32_WINNT _WIN32_WINNT_WIN7 + +#include diff --git a/panda/drivers/windows/redist/.gitignore b/panda/drivers/windows/redist/.gitignore new file mode 100644 index 00000000000000..90d431bfbaed71 --- /dev/null +++ b/panda/drivers/windows/redist/.gitignore @@ -0,0 +1,2 @@ +*.exe +vscruntimeinfo.nsh diff --git a/panda/drivers/windows/redist/README.md b/panda/drivers/windows/redist/README.md new file mode 100644 index 00000000000000..69565f11c6cd1b --- /dev/null +++ b/panda/drivers/windows/redist/README.md @@ -0,0 +1,7 @@ +When building the installer, please put the relevant vc_redist.x86.exe file into this folder. +Make sure that the uninstall registry key is correct in the panda_install.nsi file. + +Here is a list of the VC runtime downloads: https://support.microsoft.com/en-us/help/2977003/the-latest-supported-visual-c-downloads +An list of the registry keys has been maintained here: https://stackoverflow.com/a/34209692/627525 + +Copy vscruntimeinfo.nsh.sample to vscruntimeinfo.nsh and edit it for your version of Visual Studio. \ No newline at end of file diff --git a/panda/drivers/windows/redist/vscruntimeinfo.nsh.sample b/panda/drivers/windows/redist/vscruntimeinfo.nsh.sample new file mode 100644 index 00000000000000..3e74ab1d9c5b33 --- /dev/null +++ b/panda/drivers/windows/redist/vscruntimeinfo.nsh.sample @@ -0,0 +1,13 @@ +;NOTE! The panda software requires a VC runtime to be installed in order to work. +;This installer must be bundled with the appropriate runtime installer, and have +;the installation registry key set so the installer can tell if the runtime is +;already installed. + +;Here is a list of the VC runtime downloads: https://support.microsoft.com/en-us/help/2977003/the-latest-supported-visual-c-downloads +;An list of the registry keys has been maintained here: https://stackoverflow.com/a/34209692/627525 + + +;Microsoft Visual C++ 2015 Redistributable (x86) - 14.0.24123 +!define VCRuntimeRegKey "SOFTWARE\Classes\Installer\Dependencies\{206898cc-4b41-4d98-ac28-9f9ae57f91fe}" +!define VCRuntimeSetupPath "redist\" +!define VCRuntimeSetupFile "vc_redist.x86.exe" \ No newline at end of file diff --git a/panda/drivers/windows/test certs/commaaiCertStore.pvk b/panda/drivers/windows/test certs/commaaiCertStore.pvk new file mode 100644 index 00000000000000..6db0a7885d2ff4 Binary files /dev/null and b/panda/drivers/windows/test certs/commaaiCertStore.pvk differ diff --git a/panda/drivers/windows/test certs/commaaicert.cer b/panda/drivers/windows/test certs/commaaicert.cer new file mode 100644 index 00000000000000..8d0a38a7c00f37 Binary files /dev/null and b/panda/drivers/windows/test certs/commaaicert.cer differ diff --git a/panda/examples/__init__.py b/panda/examples/__init__.py new file mode 100644 index 00000000000000..e69de29bb2d1d6 diff --git a/panda/examples/can_bit_transition.md b/panda/examples/can_bit_transition.md new file mode 100644 index 00000000000000..fa0a6c6bb354fd --- /dev/null +++ b/panda/examples/can_bit_transition.md @@ -0,0 +1,25 @@ +# How to use can_bit_transition.py to reverse engineer a single bit field + +Let's say our goal is to find a brake pedal signal (caused by your foot pressing the brake pedal vs adaptive cruise control braking). + +The following process will allow you to quickly find bits that are always 0 during a period of time (when you know you were not pressing the brake with your foot) and always 1 in a different period of time (when you know you were pressing the brake with your foot). + +Open up a drive in cabana where you can find a place you used the brake pedal and another place where you did not use the brake pedal (and you can identify when you were on the brake pedal and when you were not). You may want to go out for a drive and put something in front of the camera after you put your foot on the brake and take it away before you take your foot off the brake so you can easily identify exactly when you had your foot on the brake based on the video in cabana. This is critical because this script needs the brake signal to always be high the entire time for one of the time frames. A 10 second time frame worked well for me. + +I found a drive where I knew I was not pressing the brake between timestamp 50.0 thru 65.0 and I was pressing the brake between timestamp 69.0 thru 79.0. Determine what the timestamps are in cabana by plotting any message and putting your mouse over the plot at the location you want to discover the timestamp. The tool tip on mouse hover has the format: timestamp: value + +Now download the log from cabana (Save Log button) and run the script passing in the timestamps +(replace csv file name with cabana log you downloaded and time ranges with your own) +``` +./can_bit_transition.py ./honda_crv_ex_2017_can-1520354796875.csv 50.0-65.0 69.0-79.0 +``` + +The script will output bits that were always low in the first time range and always high in the second time range (and vice versa) +``` +id 17c 0 -> 1 at byte 4 bitmask 1 +id 17c 0 -> 1 at byte 6 bitmask 32 +id 221 1 -> 0 at byte 0 bitmask 4 +id 1be 0 -> 1 at byte 0 bitmask 16 +``` + +Now I go back to cabana and graph the above bits by searching for the message by id, double clicking on the appropriate bit, and then selecting "show plot". I already knew that message id 0x17c is both user brake and adaptive cruise control braking combined, so I plotted one of those signals along side 0x221 and 0x1be. By replaying a drive I could see that 0x221 was not a brake signal (when high at random times that did not correspond to braking). Next I looked at 0x1be and I found it was the brake pedal signal I was looking for (went high whenever I pressed the brake pedal and did not go high when adaptive cruise control was braking). \ No newline at end of file diff --git a/panda/examples/can_bit_transition.py b/panda/examples/can_bit_transition.py new file mode 100755 index 00000000000000..5c15e4bbc26eed --- /dev/null +++ b/panda/examples/can_bit_transition.py @@ -0,0 +1,87 @@ +#!/usr/bin/env python + +import binascii +import csv +import sys + +class Message(): + """Details about a specific message ID.""" + def __init__(self, message_id): + self.message_id = message_id + self.ones = [0] * 8 # bit set if 1 is always seen + self.zeros = [0] * 8 # bit set if 0 is always seen + + def printBitDiff(self, other): + """Prints bits that transition from always zero to always 1 and vice versa.""" + for i in xrange(len(self.ones)): + zero_to_one = other.zeros[i] & self.ones[i] + if zero_to_one: + print 'id %s 0 -> 1 at byte %d bitmask %d' % (self.message_id, i, zero_to_one) + one_to_zero = other.ones[i] & self.zeros[i] + if one_to_zero: + print 'id %s 1 -> 0 at byte %d bitmask %d' % (self.message_id, i, one_to_zero) + + +class Info(): + """A collection of Messages.""" + + def __init__(self): + self.messages = {} # keyed by MessageID + + def load(self, filename, start, end): + """Given a CSV file, adds information about message IDs and their values.""" + with open(filename, 'rb') as input: + reader = csv.reader(input) + next(reader, None) # skip the CSV header + for row in reader: + if not len(row): continue + time = float(row[0]) + bus = int(row[2]) + if time < start or bus > 127: + continue + elif time > end: + break + if row[1].startswith('0x'): + message_id = row[1][2:] # remove leading '0x' + else: + message_id = hex(int(row[1]))[2:] # old message IDs are in decimal + message_id = '%s:%s' % (bus, message_id) + if row[3].startswith('0x'): + data = row[3][2:] # remove leading '0x' + else: + data = row[3] + new_message = False + if message_id not in self.messages: + self.messages[message_id] = Message(message_id) + new_message = True + message = self.messages[message_id] + bytes = bytearray.fromhex(data) + for i in xrange(len(bytes)): + ones = int(bytes[i]) + message.ones[i] = ones if new_message else message.ones[i] & ones + # Inverts the data and masks it to a byte to get the zeros as ones. + zeros = (~int(bytes[i])) & 0xff + message.zeros[i] = zeros if new_message else message.zeros[i] & zeros + +def PrintUnique(log_file, low_range, high_range): + # find messages with bits that are always low + start, end = map(float, low_range.split('-')) + low = Info() + low.load(log_file, start, end) + # find messages with bits that are always high + start, end = map(float, high_range.split('-')) + high = Info() + high.load(log_file, start, end) + # print messages that go from low to high + found = False + for message_id in sorted(high.messages): + if message_id in low.messages: + high.messages[message_id].printBitDiff(low.messages[message_id]) + found = True + if not found: print 'No messages that transition from always low to always high found!' + +if __name__ == "__main__": + if len(sys.argv) < 4: + print 'Usage:\n%s log.csv - -' % sys.argv[0] + sys.exit(0) + PrintUnique(sys.argv[1], sys.argv[2], sys.argv[3]) diff --git a/panda/examples/can_logger.py b/panda/examples/can_logger.py new file mode 100755 index 00000000000000..05c28a26df1228 --- /dev/null +++ b/panda/examples/can_logger.py @@ -0,0 +1,54 @@ +#!/usr/bin/env python +from __future__ import print_function +import binascii +import csv +import sys +from panda import Panda + +def can_logger(): + + try: + print("Trying to connect to Panda over USB...") + p = Panda() + + except AssertionError: + print("USB connection failed. Trying WiFi...") + + try: + p = Panda("WIFI") + except: + print("WiFi connection timed out. Please make sure your Panda is connected and try again.") + sys.exit(0) + + try: + outputfile = open('output.csv', 'wb') + csvwriter = csv.writer(outputfile) + #Write Header + csvwriter.writerow(['Bus', 'MessageID', 'Message', 'MessageLength']) + print("Writing csv file output.csv. Press Ctrl-C to exit...\n") + + bus0_msg_cnt = 0 + bus1_msg_cnt = 0 + bus2_msg_cnt = 0 + + while True: + can_recv = p.can_recv() + + for address, _, dat, src in can_recv: + csvwriter.writerow([str(src), str(hex(address)), "0x" + binascii.hexlify(dat), len(dat)]) + + if src == 0: + bus0_msg_cnt += 1 + elif src == 1: + bus1_msg_cnt += 1 + elif src == 2: + bus2_msg_cnt += 1 + + print("Message Counts... Bus 0: " + str(bus0_msg_cnt) + " Bus 1: " + str(bus1_msg_cnt) + " Bus 2: " + str(bus2_msg_cnt), end='\r') + + except KeyboardInterrupt: + print("\nNow exiting. Final message Counts... Bus 0: " + str(bus0_msg_cnt) + " Bus 1: " + str(bus1_msg_cnt) + " Bus 2: " + str(bus2_msg_cnt)) + outputfile.close() + +if __name__ == "__main__": + can_logger() diff --git a/panda/examples/can_unique.md b/panda/examples/can_unique.md new file mode 100644 index 00000000000000..bf316940d3adb9 --- /dev/null +++ b/panda/examples/can_unique.md @@ -0,0 +1,103 @@ +# How to use can_unique.py to reverse engineer a single bit field + +Let's say our goal is to find the CAN message indicating that the driver's door is either open or closed. +The following process is great for simple single-bit messages. +However for frequently changing values, such as RPM or speed, Cabana's graphical plots are probably better to use. + + +First record a few minutes of background CAN messages with all the doors closed and save it in background.csv: +``` +./can_logger.py +mv output.csv background.csv +``` +Then run can_logger.py for a few seconds while performing the action you're interested, such as opening and then closing the +front-left door and save it as door-fl-1.csv +Repeat the process and save it as door-f1-2.csv to have an easy way to confirm any suspicions. + +Now we'll use can_unique.py to look for unique bits: +``` +$ ./can_unique.py door-fl-1.csv background* +id 820 new one at byte 2 bitmask 2 +id 520 new one at byte 3 bitmask 7 +id 520 new zero at byte 3 bitmask 8 +id 520 new one at byte 5 bitmask 6 +id 520 new zero at byte 5 bitmask 9 +id 559 new zero at byte 6 bitmask 4 +id 804 new one at byte 5 bitmask 2 +id 804 new zero at byte 5 bitmask 1 + +$ ./can_unique.py door-fl-2.csv background* +id 672 new one at byte 3 bitmask 3 +id 820 new one at byte 2 bitmask 2 +id 520 new one at byte 3 bitmask 7 +id 520 new zero at byte 3 bitmask 8 +id 520 new one at byte 5 bitmask 6 +id 520 new zero at byte 5 bitmask 9 +id 559 new zero at byte 6 bitmask 4 +``` + +One of these bits hopefully indicates that the driver's door is open. +Let's go through each message ID to figure out which one is correct. +We expect any correct bits to have changed in both runs. +We can rule out 804 because it only occurred in the first run. +We can rule out 672 because it only occurred in the second run. +That leaves us with these message IDs: 820, 520, 559. Let's take a closer look at each one. + +``` +$ fgrep ,559, door-fl-1.csv |head +0,559,00ff0000000024f0 +0,559,00ff000000004464 +0,559,00ff0000000054a9 +0,559,00ff0000000064e3 +0,559,00ff00000000742e +0,559,00ff000000008451 +0,559,00ff00000000949c +0,559,00ff00000000a4d6 +0,559,00ff00000000b41b +0,559,00ff00000000c442 +``` +Message ID 559 looks like an incrementing value, so it's not what we're looking for. + +``` +$ fgrep ,520, door-fl-2.csv +0,520,26ff00f8a1890000 +0,520,26ff00f8a2890000 +0,520,26ff00f8a2890000 +0,520,26ff00f8a1890000 +0,520,26ff00f8a2890000 +0,520,26ff00f8a1890000 +0,520,26ff00f8a2890000 +0,520,26ff00f8a1890000 +0,520,26ff00f8a2890000 +0,520,26ff00f8a1890000 +0,520,26ff00f8a2890000 +0,520,26ff00f8a1890000 +``` +Message ID 520 oscillates between two values. However I only opened and closed the door once, so this is probably not it. + +``` +$ fgrep ,820, door-fl-1.csv +0,820,44000100a500c802 +0,820,44000100a500c803 +0,820,44000300a500c803 +0,820,44000300a500c802 +0,820,44000300a500c802 +0,820,44000300a500c802 +0,820,44000100a500c802 +0,820,44000100a500c802 +0,820,44000100a500c802 +``` +Message ID 820 looks promising! It starts off at 44000100a500c802 when the door is closed. +When the door is open it goes to 44000300a500c802. +Then when the door is closed again, it goes back to 44000100a500c802. +Let's confirm by looking at the data from our other run: +``` +$ fgrep ,820, door-fl-2.csv +0,820,44000100a500c802 +0,820,44000300a500c802 +0,820,44000100a500c802 +``` +Perfect! We now know that message id 820 at byte 2 bitmask 2 is set if the driver's door is open. +If we repeat the process with the front passenger's door, +then we'll find that message id 820 at byte 2 bitmask 4 is set if the front-right door is open. +This confirms our finding because it's common for similar signals to be near each other. diff --git a/panda/examples/can_unique.py b/panda/examples/can_unique.py new file mode 100755 index 00000000000000..ad6de296ee4174 --- /dev/null +++ b/panda/examples/can_unique.py @@ -0,0 +1,93 @@ +#!/usr/bin/env python + +# Given an interesting CSV file of CAN messages and a list of background CAN +# messages, print which bits in the interesting file have never appeared +# in the background files. + +# Expects the CSV file to be in the format from can_logger.py +# Bus,MessageID,Message,MessageLength +# 0,0x292,0x040000001068,6 + +# The old can_logger.py format is also supported: +# Bus,MessageID,Message +# 0,344,c000c00000000000 + + +import binascii +import csv +import sys +from panda import Panda + +class Message(): + """Details about a specific message ID.""" + def __init__(self, message_id): + self.message_id = message_id + self.data = {} # keyed by hex string encoded message data + self.ones = [0] * 8 # bit set if 1 is seen + self.zeros = [0] * 8 # bit set if 0 has been seen + + def printBitDiff(self, other): + """Prints bits that are set or cleared compared to other background.""" + for i in xrange(len(self.ones)): + new_ones = ((~other.ones[i]) & 0xff) & self.ones[i] + if new_ones: + print 'id %s new one at byte %d bitmask %d' % ( + self.message_id, i, new_ones) + new_zeros = ((~other.zeros[i]) & 0xff) & self.zeros[i] + if new_zeros: + print 'id %s new zero at byte %d bitmask %d' % ( + self.message_id, i, new_zeros) + + +class Info(): + """A collection of Messages.""" + + def __init__(self): + self.messages = {} # keyed by MessageID + + def load(self, filename): + """Given a CSV file, adds information about message IDs and their values.""" + with open(filename, 'rb') as input: + reader = csv.reader(input) + next(reader, None) # skip the CSV header + for row in reader: + bus = row[0] + if row[1].startswith('0x'): + message_id = row[1][2:] # remove leading '0x' + else: + message_id = hex(int(row[1]))[2:] # old message IDs are in decimal + message_id = '%s:%s' % (bus, message_id) + if row[1].startswith('0x'): + data = row[2][2:] # remove leading '0x' + else: + data = row[2] + if message_id not in self.messages: + self.messages[message_id] = Message(message_id) + message = self.messages[message_id] + if data not in self.messages[message_id].data: + message.data[data] = True + bytes = bytearray.fromhex(data) + for i in xrange(len(bytes)): + message.ones[i] = message.ones[i] | int(bytes[i]) + # Inverts the data and masks it to a byte to get the zeros as ones. + message.zeros[i] = message.zeros[i] | ( (~int(bytes[i])) & 0xff) + +def PrintUnique(interesting_file, background_files): + background = Info() + for background_file in background_files: + background.load(background_file) + interesting = Info() + interesting.load(interesting_file) + for message_id in sorted(interesting.messages): + if message_id not in background.messages: + print 'New message_id: %s' % message_id + else: + interesting.messages[message_id].printBitDiff( + background.messages[message_id]) + + +if __name__ == "__main__": + if len(sys.argv) < 3: + print 'Usage:\n%s interesting.csv background*.csv' % sys.argv[0] + sys.exit(0) + PrintUnique(sys.argv[1], sys.argv[2:]) diff --git a/panda/examples/get_panda_password.py b/panda/examples/get_panda_password.py new file mode 100644 index 00000000000000..11071d035346be --- /dev/null +++ b/panda/examples/get_panda_password.py @@ -0,0 +1,20 @@ +#!/usr/bin/env python +from panda import Panda + +def get_panda_password(): + + try: + print("Trying to connect to Panda over USB...") + p = Panda() + + except AssertionError: + print("USB connection failed") + sys.exit(0) + + wifi = p.get_serial() + #print('[%s]' % ', '.join(map(str, wifi))) + print("SSID: " + wifi[0]) + print("Password: " + wifi[1]) + +if __name__ == "__main__": + get_panda_password() \ No newline at end of file diff --git a/panda/examples/query_vin_and_stats.py b/panda/examples/query_vin_and_stats.py new file mode 100755 index 00000000000000..cd2185b4a6f11f --- /dev/null +++ b/panda/examples/query_vin_and_stats.py @@ -0,0 +1,59 @@ +#!/usr/bin/env python +import time +import struct +from panda import Panda +from hexdump import hexdump +from isotp import isotp_send, isotp_recv + +# 0x7e0 = Toyota +# 0x18DB33F1 for Honda? + +def get_current_data_for_pid(pid): + # 01 xx = Show current data + isotp_send(panda, "\x01"+chr(pid), 0x7e0) + return isotp_recv(panda, 0x7e8) + +def get_supported_pids(): + ret = [] + pid = 0 + while 1: + supported = struct.unpack(">I", get_current_data_for_pid(pid)[2:])[0] + for i in range(1+pid, 0x21+pid): + if supported & 0x80000000: + ret.append(i) + supported <<= 1 + pid += 0x20 + if pid not in ret: + break + return ret + +if __name__ == "__main__": + panda = Panda() + panda.set_safety_mode(Panda.SAFETY_ELM327) + panda.can_clear(0) + + # 09 02 = Get VIN + isotp_send(panda, "\x09\x02", 0x7e0) + ret = isotp_recv(panda, 0x7e8) + hexdump(ret) + print "VIN: %s" % ret[2:] + + # 03 = get DTCS + isotp_send(panda, "\x03", 0x7e0) + dtcs = isotp_recv(panda, 0x7e8) + print "DTCs:", dtcs[2:].encode("hex") + + supported_pids = get_supported_pids() + print "Supported PIDs:",supported_pids + + while 1: + speed = struct.unpack(">B", get_current_data_for_pid(13)[2:])[0] # kph + rpm = struct.unpack(">H", get_current_data_for_pid(12)[2:])[0]/4.0 # revs + throttle = struct.unpack(">B", get_current_data_for_pid(17)[2:])[0]/255.0 * 100 # percent + temp = struct.unpack(">B", get_current_data_for_pid(5)[2:])[0] - 40 # degrees C + load = struct.unpack(">B", get_current_data_for_pid(4)[2:])[0]/255.0 * 100 # percent + print "%d KPH, %d RPM, %.1f%% Throttle, %d deg C, %.1f%% load" % (speed, rpm, throttle, temp, load) + time.sleep(0.2) + + + diff --git a/panda/examples/tesla_tester.py b/panda/examples/tesla_tester.py new file mode 100644 index 00000000000000..99d8d92854423b --- /dev/null +++ b/panda/examples/tesla_tester.py @@ -0,0 +1,61 @@ +#!/usr/bin/env python +import sys +import binascii +from panda import Panda + +def tesla_tester(): + + try: + print("Trying to connect to Panda over USB...") + p = Panda() + + except AssertionError: + print("USB connection failed. Trying WiFi...") + + try: + p = Panda("WIFI") + except: + print("WiFi connection timed out. Please make sure your Panda is connected and try again.") + sys.exit(0) + + body_bus_speed = 125 # Tesla Body busses (B, BF) are 125kbps, rest are 500kbps + body_bus_num = 1 # My TDC to OBD adapter has PT on bus0 BDY on bus1 and CH on bus2 + p.set_can_speed_kbps(body_bus_num, body_bus_speed) + + # Now set the panda from its default of SAFETY_NOOUTPUT (read only) to SAFETY_ALLOUTPUT + # Careful, as this will let us send any CAN messages we want (which could be very bad!) + print("Setting Panda to output mode...") + p.set_safety_mode(Panda.SAFETY_ALLOUTPUT) + + # BDY 0x248 is the MCU_commands message, which includes folding mirrors, opening the trunk, frunk, setting the cars lock state and more. For our test, we will edit the 3rd byte, which is MCU_lockRequest. 0x01 will lock, 0x02 will unlock: + print("Unlocking Tesla...") + p.can_send(0x248, "\x00\x00\x02\x00\x00\x00\x00\x00", body_bus_num) + + #Or, we can set the first byte, MCU_frontHoodCommand + MCU_liftgateSwitch, to 0x01 to pop the frunk, or 0x04 to open/close the trunk (0x05 should open both) + print("Opening Frunk...") + p.can_send(0x248, "\x01\x00\x00\x00\x00\x00\x00\x00", body_bus_num) + + #Back to safety... + print("Disabling output on Panda...") + p.set_safety_mode(Panda.SAFETY_NOOUTPUT) + + print("Reading VIN from 0x568. This is painfully slow and can take up to 3 minutes (1 minute per message; 3 messages needed for full VIN)...") + + vin = {} + while True: + #Read the VIN + can_recv = p.can_recv() + for address, _, dat, src in can_recv: + if src == body_bus_num: + if address == 1384: #0x568 is VIN + vin_index = int(binascii.hexlify(dat)[:2]) #first byte is the index, 00, 01, 02 + vin_string = binascii.hexlify(dat)[2:] #rest of the string is the actual VIN data + vin[vin_index] = vin_string.decode("hex") + print("Got VIN index " + str(vin_index) + " data " + vin[vin_index]) + #if we have all 3 parts of the VIN, print it and break out of our while loop + if 0 in vin and 1 in vin and 2 in vin: + print("VIN: " + vin[0] + vin[1] + vin[2][:3]) + break + +if __name__ == "__main__": + tesla_tester() diff --git a/panda/panda.png b/panda/panda.png new file mode 100644 index 00000000000000..e18137d8727c0f Binary files /dev/null and b/panda/panda.png differ diff --git a/panda/python/__init__.py b/panda/python/__init__.py new file mode 100644 index 00000000000000..c49ee83622f523 --- /dev/null +++ b/panda/python/__init__.py @@ -0,0 +1,544 @@ +# python library to interface with panda +from __future__ import print_function +import binascii +import struct +import hashlib +import socket +import usb1 +import os +import time +import traceback +from dfu import PandaDFU +from esptool import ESPROM, CesantaFlasher +from flash_release import flash_release +from update import ensure_st_up_to_date +from serial import PandaSerial +from isotp import isotp_send, isotp_recv + +__version__ = '0.0.8' + +BASEDIR = os.path.join(os.path.dirname(os.path.realpath(__file__)), "../") + +DEBUG = os.getenv("PANDADEBUG") is not None + +# *** wifi mode *** + +def build_st(target, mkfile="Makefile"): + from panda import BASEDIR + assert(os.system('cd %s && make -f %s clean && make -f %s %s >/dev/null' % (os.path.join(BASEDIR, "board"), mkfile, mkfile, target)) == 0) + +def parse_can_buffer(dat): + ret = [] + for j in range(0, len(dat), 0x10): + ddat = dat[j:j+0x10] + f1, f2 = struct.unpack("II", ddat[0:8]) + extended = 4 + if f1 & extended: + address = f1 >> 3 + else: + address = f1 >> 21 + dddat = ddat[8:8+(f2&0xF)] + if DEBUG: + print(" R %x: %s" % (address, str(dddat).encode("hex"))) + ret.append((address, f2>>16, dddat, (f2>>4)&0xFF)) + return ret + +class PandaWifiStreaming(object): + def __init__(self, ip="192.168.0.10", port=1338): + self.sock = socket.socket(socket.AF_INET, socket.SOCK_DGRAM) + self.sock.setblocking(0) + self.ip = ip + self.port = port + self.kick() + + def kick(self): + # must be called at least every 5 seconds + self.sock.sendto("hello", (self.ip, self.port)) + + def can_recv(self): + ret = [] + while True: + try: + dat, addr = self.sock.recvfrom(0x200*0x10) + if addr == (self.ip, self.port): + ret += parse_can_buffer(dat) + except socket.error as e: + if e.errno != 35 and e.errno != 11: + traceback.print_exc() + break + return ret + +# stupid tunneling of USB over wifi and SPI +class WifiHandle(object): + def __init__(self, ip="192.168.0.10", port=1337): + self.sock = socket.create_connection((ip, port)) + + def __recv(self): + ret = self.sock.recv(0x44) + length = struct.unpack("I", ret[0:4])[0] + return ret[4:4+length] + + def controlWrite(self, request_type, request, value, index, data, timeout=0): + # ignore data in reply, panda doesn't use it + return self.controlRead(request_type, request, value, index, 0, timeout) + + def controlRead(self, request_type, request, value, index, length, timeout=0): + self.sock.send(struct.pack("HHBBHHH", 0, 0, request_type, request, value, index, length)) + return self.__recv() + + def bulkWrite(self, endpoint, data, timeout=0): + if len(data) > 0x10: + raise ValueError("Data must not be longer than 0x10") + self.sock.send(struct.pack("HH", endpoint, len(data))+data) + self.__recv() # to /dev/null + + def bulkRead(self, endpoint, length, timeout=0): + self.sock.send(struct.pack("HH", endpoint, 0)) + return self.__recv() + + def close(self): + self.sock.close() + +# *** normal mode *** + +class Panda(object): + SAFETY_NOOUTPUT = 0 + SAFETY_HONDA = 1 + SAFETY_TOYOTA = 2 + SAFETY_GM = 3 + SAFETY_HONDA_BOSCH = 4 + SAFETY_FORD = 5 + SAFETY_CADILLAC = 6 + SAFETY_HYUNDAI = 7 + SAFETY_TESLA = 8 + SAFETY_CHRYSLER = 9 + SAFETY_TOYOTA_IPAS = 0x1335 + SAFETY_TOYOTA_NOLIMITS = 0x1336 + SAFETY_ALLOUTPUT = 0x1337 + SAFETY_ELM327 = 0xE327 + + SERIAL_DEBUG = 0 + SERIAL_ESP = 1 + SERIAL_LIN1 = 2 + SERIAL_LIN2 = 3 + + GMLAN_CAN2 = 1 + GMLAN_CAN3 = 2 + + REQUEST_IN = usb1.ENDPOINT_IN | usb1.TYPE_VENDOR | usb1.RECIPIENT_DEVICE + REQUEST_OUT = usb1.ENDPOINT_OUT | usb1.TYPE_VENDOR | usb1.RECIPIENT_DEVICE + + def __init__(self, serial=None, claim=True): + self._serial = serial + self._handle = None + self.connect(claim) + + def close(self): + self._handle.close() + self._handle = None + + def connect(self, claim=True, wait=False): + if self._handle != None: + self.close() + + if self._serial == "WIFI": + self._handle = WifiHandle() + print("opening WIFI device") + self.wifi = True + else: + context = usb1.USBContext() + self._handle = None + self.wifi = False + + while 1: + try: + for device in context.getDeviceList(skip_on_error=True): + #print(device) + if device.getVendorID() == 0xbbaa and device.getProductID() in [0xddcc, 0xddee]: + try: + this_serial = device.getSerialNumber() + except Exception: + continue + if self._serial is None or this_serial == self._serial: + self._serial = this_serial + print("opening device", self._serial, hex(device.getProductID())) + time.sleep(1) + self.bootstub = device.getProductID() == 0xddee + self.legacy = (device.getbcdDevice() != 0x2300) + self._handle = device.open() + if claim: + self._handle.claimInterface(0) + #self._handle.setInterfaceAltSetting(0, 0) #Issue in USB stack + break + except Exception as e: + print("exception", e) + traceback.print_exc() + if wait == False or self._handle != None: + break + assert(self._handle != None) + print("connected") + + def reset(self, enter_bootstub=False, enter_bootloader=False): + # reset + try: + if enter_bootloader: + self._handle.controlWrite(Panda.REQUEST_IN, 0xd1, 0, 0, b'') + else: + if enter_bootstub: + self._handle.controlWrite(Panda.REQUEST_IN, 0xd1, 1, 0, b'') + else: + self._handle.controlWrite(Panda.REQUEST_IN, 0xd8, 0, 0, b'') + except Exception: + pass + if not enter_bootloader: + self.reconnect() + + def reconnect(self): + self.close() + time.sleep(1.0) + success = False + # wait up to 15 seconds + for i in range(0, 15): + try: + self.connect() + success = True + break + except Exception: + print("reconnecting is taking %d seconds..." % (i+1)) + try: + dfu = PandaDFU(PandaDFU.st_serial_to_dfu_serial(self._serial)) + dfu.recover() + except Exception: + pass + time.sleep(1.0) + if not success: + raise Exception("reconnect failed") + + @staticmethod + def flash_static(handle, code): + # confirm flasher is present + fr = handle.controlRead(Panda.REQUEST_IN, 0xb0, 0, 0, 0xc) + assert fr[4:8] == "\xde\xad\xd0\x0d" + + # unlock flash + print("flash: unlocking") + handle.controlWrite(Panda.REQUEST_IN, 0xb1, 0, 0, b'') + + # erase sectors 1 and 2 + print("flash: erasing") + handle.controlWrite(Panda.REQUEST_IN, 0xb2, 1, 0, b'') + handle.controlWrite(Panda.REQUEST_IN, 0xb2, 2, 0, b'') + + # flash over EP2 + STEP = 0x10 + print("flash: flashing") + for i in range(0, len(code), STEP): + handle.bulkWrite(2, code[i:i+STEP]) + + # reset + print("flash: resetting") + try: + handle.controlWrite(Panda.REQUEST_IN, 0xd8, 0, 0, b'') + except Exception: + pass + + def flash(self, fn=None, code=None, reconnect=True): + if not self.bootstub: + self.reset(enter_bootstub=True) + assert(self.bootstub) + + if fn is None and code is None: + if self.legacy: + fn = "obj/comma.bin" + print("building legacy st code") + build_st(fn, "Makefile.legacy") + else: + fn = "obj/panda.bin" + print("building panda st code") + build_st(fn) + fn = os.path.join(BASEDIR, "board", fn) + + if code is None: + with open(fn) as f: + code = f.read() + + # get version + print("flash: version is "+self.get_version()) + + # do flash + Panda.flash_static(self._handle, code) + + # reconnect + if reconnect: + self.reconnect() + + def recover(self): + self.reset(enter_bootloader=True) + while len(PandaDFU.list()) == 0: + print("waiting for DFU...") + time.sleep(0.1) + + dfu = PandaDFU(PandaDFU.st_serial_to_dfu_serial(self._serial)) + dfu.recover() + + # reflash after recover + self.connect(True, True) + self.flash() + + @staticmethod + def flash_ota_st(): + ret = os.system("cd %s && make clean && make ota" % (os.path.join(BASEDIR, "board"))) + time.sleep(1) + return ret==0 + + @staticmethod + def flash_ota_wifi(): + ret = os.system("cd %s && make clean && make ota" % (os.path.join(BASEDIR, "boardesp"))) + time.sleep(1) + return ret==0 + + @staticmethod + def list(): + context = usb1.USBContext() + ret = [] + try: + for device in context.getDeviceList(skip_on_error=True): + if device.getVendorID() == 0xbbaa and device.getProductID() in [0xddcc, 0xddee]: + try: + ret.append(device.getSerialNumber()) + except Exception: + continue + except Exception: + pass + # TODO: detect if this is real + #ret += ["WIFI"] + return ret + + def call_control_api(self, msg): + self._handle.controlWrite(Panda.REQUEST_OUT, msg, 0, 0, b'') + + # ******************* health ******************* + + def health(self): + dat = self._handle.controlRead(Panda.REQUEST_IN, 0xd2, 0, 0, 13) + a = struct.unpack("IIBBBBB", dat) + return {"voltage": a[0], "current": a[1], + "started": a[2], "controls_allowed": a[3], + "gas_interceptor_detected": a[4], + "started_signal_detected": a[5], + "started_alt": a[6]} + + # ******************* control ******************* + + def enter_bootloader(self): + try: + self._handle.controlWrite(Panda.REQUEST_OUT, 0xd1, 0, 0, b'') + except Exception as e: + print(e) + pass + + def get_version(self): + return self._handle.controlRead(Panda.REQUEST_IN, 0xd6, 0, 0, 0x40) + + def is_grey(self): + ret = self._handle.controlRead(Panda.REQUEST_IN, 0xc1, 0, 0, 0x40) + return ret == "\x01" + + def get_serial(self): + dat = self._handle.controlRead(Panda.REQUEST_IN, 0xd0, 0, 0, 0x20) + hashsig, calc_hash = dat[0x1c:], hashlib.sha1(dat[0:0x1c]).digest()[0:4] + assert(hashsig == calc_hash) + return [dat[0:0x10], dat[0x10:0x10+10]] + + def get_secret(self): + return self._handle.controlRead(Panda.REQUEST_IN, 0xd0, 1, 0, 0x10) + + # ******************* configuration ******************* + + def set_usb_power(self, on): + self._handle.controlWrite(Panda.REQUEST_OUT, 0xe6, int(on), 0, b'') + + def set_esp_power(self, on): + self._handle.controlWrite(Panda.REQUEST_OUT, 0xd9, int(on), 0, b'') + + def esp_reset(self, bootmode=0): + self._handle.controlWrite(Panda.REQUEST_OUT, 0xda, int(bootmode), 0, b'') + time.sleep(0.2) + + def set_safety_mode(self, mode=SAFETY_NOOUTPUT): + self._handle.controlWrite(Panda.REQUEST_OUT, 0xdc, mode, 0, b'') + + def set_can_forwarding(self, from_bus, to_bus): + # TODO: This feature may not work correctly with saturated buses + self._handle.controlWrite(Panda.REQUEST_OUT, 0xdd, from_bus, to_bus, b'') + + def set_gmlan(self, bus=2): + if bus is None: + self._handle.controlWrite(Panda.REQUEST_OUT, 0xdb, 0, 0, b'') + elif bus in [Panda.GMLAN_CAN2, Panda.GMLAN_CAN3]: + self._handle.controlWrite(Panda.REQUEST_OUT, 0xdb, 1, bus, b'') + + def set_can_loopback(self, enable): + # set can loopback mode for all buses + self._handle.controlWrite(Panda.REQUEST_OUT, 0xe5, int(enable), 0, b'') + + def set_can_speed_kbps(self, bus, speed): + self._handle.controlWrite(Panda.REQUEST_OUT, 0xde, bus, int(speed*10), b'') + + def set_uart_baud(self, uart, rate): + self._handle.controlWrite(Panda.REQUEST_OUT, 0xe4, uart, rate/300, b'') + + def set_uart_parity(self, uart, parity): + # parity, 0=off, 1=even, 2=odd + self._handle.controlWrite(Panda.REQUEST_OUT, 0xe2, uart, parity, b'') + + def set_uart_callback(self, uart, install): + self._handle.controlWrite(Panda.REQUEST_OUT, 0xe3, uart, int(install), b'') + + # ******************* can ******************* + + def can_send_many(self, arr): + snds = [] + transmit = 1 + extended = 4 + for addr, _, dat, bus in arr: + assert len(dat) <= 8 + if DEBUG: + print(" W %x: %s" % (addr, dat.encode("hex"))) + if addr >= 0x800: + rir = (addr << 3) | transmit | extended + else: + rir = (addr << 21) | transmit + snd = struct.pack("II", rir, len(dat) | (bus << 4)) + dat + snd = snd.ljust(0x10, b'\x00') + snds.append(snd) + + while True: + try: + #print("DAT: %s"%b''.join(snds).__repr__()) + if self.wifi: + for s in snds: + self._handle.bulkWrite(3, s) + else: + self._handle.bulkWrite(3, b''.join(snds)) + break + except (usb1.USBErrorIO, usb1.USBErrorOverflow): + print("CAN: BAD SEND MANY, RETRYING") + + def can_send(self, addr, dat, bus): + self.can_send_many([[addr, None, dat, bus]]) + + def can_recv(self): + dat = bytearray() + while True: + try: + dat = self._handle.bulkRead(1, 0x10*256) + break + except (usb1.USBErrorIO, usb1.USBErrorOverflow): + print("CAN: BAD RECV, RETRYING") + return parse_can_buffer(dat) + + def can_clear(self, bus): + """Clears all messages from the specified internal CAN ringbuffer as + though it were drained. + + Args: + bus (int): can bus number to clear a tx queue, or 0xFFFF to clear the + global can rx queue. + + """ + self._handle.controlWrite(Panda.REQUEST_OUT, 0xf1, bus, 0, b'') + + # ******************* isotp ******************* + + def isotp_send(self, addr, dat, bus, recvaddr=None, subaddr=None): + return isotp_send(self, dat, addr, bus, recvaddr, subaddr) + + def isotp_recv(self, addr, bus=0, sendaddr=None, subaddr=None): + return isotp_recv(self, addr, bus, sendaddr, subaddr) + + # ******************* serial ******************* + + def serial_read(self, port_number): + ret = [] + while 1: + lret = bytes(self._handle.controlRead(Panda.REQUEST_IN, 0xe0, port_number, 0, 0x40)) + if len(lret) == 0: + break + ret.append(lret) + return b''.join(ret) + + def serial_write(self, port_number, ln): + ret = 0 + for i in range(0, len(ln), 0x20): + ret += self._handle.bulkWrite(2, struct.pack("B", port_number) + ln[i:i+0x20]) + return ret + + def serial_clear(self, port_number): + """Clears all messages (tx and rx) from the specified internal uart + ringbuffer as though it were drained. + + Args: + port_number (int): port number of the uart to clear. + + """ + self._handle.controlWrite(Panda.REQUEST_OUT, 0xf2, port_number, 0, b'') + + # ******************* kline ******************* + + # pulse low for wakeup + def kline_wakeup(self): + if DEBUG: + print("kline wakeup...") + self._handle.controlWrite(Panda.REQUEST_OUT, 0xf0, 0, 0, b'') + if DEBUG: + print("kline wakeup done") + + def kline_drain(self, bus=2): + # drain buffer + bret = bytearray() + while True: + ret = self._handle.controlRead(Panda.REQUEST_IN, 0xe0, bus, 0, 0x40) + if len(ret) == 0: + break + elif DEBUG: + print("kline drain: "+str(ret).encode("hex")) + bret += ret + return bytes(bret) + + def kline_ll_recv(self, cnt, bus=2): + echo = bytearray() + while len(echo) != cnt: + ret = str(self._handle.controlRead(Panda.REQUEST_OUT, 0xe0, bus, 0, cnt-len(echo))) + if DEBUG and len(ret) > 0: + print("kline recv: "+ret.encode("hex")) + echo += ret + return str(echo) + + def kline_send(self, x, bus=2, checksum=True): + def get_checksum(dat): + result = 0 + result += sum(map(ord, dat)) if isinstance(b'dat', str) else sum(dat) + result = -result + return struct.pack("B", result % 0x100) + + self.kline_drain(bus=bus) + if checksum: + x += get_checksum(x) + for i in range(0, len(x), 0xf): + ts = x[i:i+0xf] + if DEBUG: + print("kline send: "+ts.encode("hex")) + self._handle.bulkWrite(2, chr(bus).encode()+ts) + echo = self.kline_ll_recv(len(ts), bus=bus) + if echo != ts: + print("**** ECHO ERROR %d ****" % i) + print(binascii.hexlify(echo)) + print(binascii.hexlify(ts)) + assert echo == ts + + def kline_recv(self, bus=2): + msg = self.kline_ll_recv(2, bus=bus) + msg += self.kline_ll_recv(ord(msg[1])-2, bus=bus) + return msg + diff --git a/panda/python/dfu.py b/panda/python/dfu.py new file mode 100644 index 00000000000000..782b4dca429906 --- /dev/null +++ b/panda/python/dfu.py @@ -0,0 +1,122 @@ +from __future__ import print_function +import os +import usb1 +import struct +import time + +# *** DFU mode *** + +DFU_DNLOAD = 1 +DFU_UPLOAD = 2 +DFU_GETSTATUS = 3 +DFU_CLRSTATUS = 4 +DFU_ABORT = 6 + +class PandaDFU(object): + def __init__(self, dfu_serial): + context = usb1.USBContext() + for device in context.getDeviceList(skip_on_error=True): + if device.getVendorID() == 0x0483 and device.getProductID() == 0xdf11: + try: + this_dfu_serial = device._getASCIIStringDescriptor(3) + except Exception: + continue + if this_dfu_serial == dfu_serial or dfu_serial is None: + self._handle = device.open() + self.legacy = "07*128Kg" in self._handle.getASCIIStringDescriptor(4) + return + raise Exception("failed to open "+dfu_serial) + + @staticmethod + def list(): + context = usb1.USBContext() + dfu_serials = [] + try: + for device in context.getDeviceList(skip_on_error=True): + if device.getVendorID() == 0x0483 and device.getProductID() == 0xdf11: + try: + dfu_serials.append(device._getASCIIStringDescriptor(3)) + except Exception: + pass + except Exception: + pass + return dfu_serials + + @staticmethod + def st_serial_to_dfu_serial(st): + if st == None or st == "none": + return None + uid_base = struct.unpack("H"*6, st.decode("hex")) + return struct.pack("!HHH", uid_base[1] + uid_base[5], uid_base[0] + uid_base[4] + 0xA, uid_base[3]).encode("hex").upper() + + + def status(self): + while 1: + dat = str(self._handle.controlRead(0x21, DFU_GETSTATUS, 0, 0, 6)) + if dat[1] == "\x00": + break + + def clear_status(self): + # Clear status + stat = str(self._handle.controlRead(0x21, DFU_GETSTATUS, 0, 0, 6)) + if stat[4] == "\x0a": + self._handle.controlRead(0x21, DFU_CLRSTATUS, 0, 0, 0) + elif stat[4] == "\x09": + self._handle.controlWrite(0x21, DFU_ABORT, 0, 0, "") + self.status() + stat = str(self._handle.controlRead(0x21, DFU_GETSTATUS, 0, 0, 6)) + + def erase(self, address): + self._handle.controlWrite(0x21, DFU_DNLOAD, 0, 0, "\x41" + struct.pack("I", address)) + self.status() + + def program(self, address, dat, block_size=None): + if block_size == None: + block_size = len(dat) + + # Set Address Pointer + self._handle.controlWrite(0x21, DFU_DNLOAD, 0, 0, "\x21" + struct.pack("I", address)) + self.status() + + # Program + dat += "\xFF"*((block_size-len(dat)) % block_size) + for i in range(0, len(dat)/block_size): + ldat = dat[i*block_size:(i+1)*block_size] + print("programming %d with length %d" % (i, len(ldat))) + self._handle.controlWrite(0x21, DFU_DNLOAD, 2+i, 0, ldat) + self.status() + + def program_bootstub(self, code_bootstub): + self.clear_status() + self.erase(0x8004000) + self.erase(0x8000000) + self.program(0x8000000, code_bootstub, 0x800) + self.reset() + + def recover(self): + from panda import BASEDIR, build_st + if self.legacy: + fn = "obj/bootstub.comma.bin" + print("building legacy bootstub") + build_st(fn, "Makefile.legacy") + else: + fn = "obj/bootstub.panda.bin" + print("building panda bootstub") + build_st(fn) + fn = os.path.join(BASEDIR, "board", fn) + + with open(fn) as f: + code = f.read() + + self.program_bootstub(code) + + def reset(self): + # **** Reset **** + self._handle.controlWrite(0x21, DFU_DNLOAD, 0, 0, "\x21" + struct.pack("I", 0x8000000)) + self.status() + try: + self._handle.controlWrite(0x21, DFU_DNLOAD, 2, 0, "") + stat = str(self._handle.controlRead(0x21, DFU_GETSTATUS, 0, 0, 6)) + except Exception: + pass + diff --git a/panda/python/esptool.py b/panda/python/esptool.py new file mode 100755 index 00000000000000..970aa3d4d83fd5 --- /dev/null +++ b/panda/python/esptool.py @@ -0,0 +1,1314 @@ +#!/usr/bin/env python +# NB: Before sending a PR to change the above line to '#!/usr/bin/env python2', please read https://github.com/themadinventor/esptool/issues/21 +# +# ESP8266 ROM Bootloader Utility +# https://github.com/themadinventor/esptool +# +# Copyright (C) 2014-2016 Fredrik Ahlberg, Angus Gratton, other contributors as noted. +# +# 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. +# +# You should have received a copy of the GNU General Public License along with +# this program; if not, write to the Free Software Foundation, Inc., 51 Franklin +# Street, Fifth Floor, Boston, MA 02110-1301 USA. + +import argparse +import hashlib +import inspect +import json +import os +#import serial +import struct +import subprocess +import sys +import tempfile +import time +import traceback +import usb1 + +__version__ = "1.2" + +class FakePort(object): + def __init__(self, serial=None): + from panda import Panda + self.panda = Panda(serial) + + # will only work on new st, old ones will stay @ 921600 + self.baudrate = 230400 + + @property + def baudrate(self): + return self._baudrate + + @baudrate.setter + def baudrate(self, x): + print "set baud to", x + self.panda.set_uart_baud(1, x) + + def write(self, buf): + SEND_STEP = 0x20 + for i in range(0, len(buf), SEND_STEP): + self.panda.serial_write(1, buf[i:i+SEND_STEP]) + + def flushInput(self): + self.panda.serial_clear(1) + + def flushOutput(self): + self.panda.serial_clear(1) + + def read(self, llen): + ret = self.panda._handle.controlRead(usb1.TYPE_VENDOR | usb1.RECIPIENT_DEVICE, 0xe0, 1, 0, 1) + if ret == '': + time.sleep(0.1) + ret = self.panda._handle.controlRead(usb1.TYPE_VENDOR | usb1.RECIPIENT_DEVICE, 0xe0, 1, 0, 1) + return str(ret) + + def reset(self): + self.panda.esp_reset(1) + + def inWaiting(self): + return False + +class ESPROM(object): + # These are the currently known commands supported by the ROM + ESP_FLASH_BEGIN = 0x02 + ESP_FLASH_DATA = 0x03 + ESP_FLASH_END = 0x04 + ESP_MEM_BEGIN = 0x05 + ESP_MEM_END = 0x06 + ESP_MEM_DATA = 0x07 + ESP_SYNC = 0x08 + ESP_WRITE_REG = 0x09 + ESP_READ_REG = 0x0a + + # Maximum block sized for RAM and Flash writes, respectively. + ESP_RAM_BLOCK = 0x1800 + ESP_FLASH_BLOCK = 0x400 + + # Default baudrate. The ROM auto-bauds, so we can use more or less whatever we want. + ESP_ROM_BAUD = 115200 + + # First byte of the application image + ESP_IMAGE_MAGIC = 0xe9 + + # Initial state for the checksum routine + ESP_CHECKSUM_MAGIC = 0xef + + # OTP ROM addresses + ESP_OTP_MAC0 = 0x3ff00050 + ESP_OTP_MAC1 = 0x3ff00054 + ESP_OTP_MAC3 = 0x3ff0005c + + # Flash sector size, minimum unit of erase. + ESP_FLASH_SECTOR = 0x1000 + + def __init__(self, port=None, baud=ESP_ROM_BAUD): + self._port = FakePort(port) + self._slip_reader = slip_reader(self._port) + + """ Read a SLIP packet from the serial port """ + def read(self): + return self._slip_reader.next() + + """ Write bytes to the serial port while performing SLIP escaping """ + def write(self, packet): + buf = '\xc0' \ + + (packet.replace('\xdb','\xdb\xdd').replace('\xc0','\xdb\xdc')) \ + + '\xc0' + self._port.write(buf) + + """ Calculate checksum of a blob, as it is defined by the ROM """ + @staticmethod + def checksum(data, state=ESP_CHECKSUM_MAGIC): + for b in data: + state ^= ord(b) + return state + + """ Send a request and read the response """ + def command(self, op=None, data=None, chk=0): + if op is not None: + pkt = struct.pack('> 16) & 0xff, (mac3 >> 8) & 0xff, mac3 & 0xff) + elif ((mac1 >> 16) & 0xff) == 0: + oui = (0x18, 0xfe, 0x34) + elif ((mac1 >> 16) & 0xff) == 1: + oui = (0xac, 0xd0, 0x74) + else: + raise FatalError("Unknown OUI") + return oui + ((mac1 >> 8) & 0xff, mac1 & 0xff, (mac0 >> 24) & 0xff) + + """ Read Chip ID from OTP ROM - see http://esp8266-re.foogod.com/wiki/System_get_chip_id_%28IoT_RTOS_SDK_0.9.9%29 """ + def chip_id(self): + id0 = self.read_reg(self.ESP_OTP_MAC0) + id1 = self.read_reg(self.ESP_OTP_MAC1) + return (id0 >> 24) | ((id1 & 0xffffff) << 8) + + """ Read SPI flash manufacturer and device id """ + def flash_id(self): + self.flash_begin(0, 0) + self.write_reg(0x60000240, 0x0, 0xffffffff) + self.write_reg(0x60000200, 0x10000000, 0xffffffff) + flash_id = self.read_reg(0x60000240) + return flash_id + + """ Abuse the loader protocol to force flash to be left in write mode """ + def flash_unlock_dio(self): + # Enable flash write mode + self.flash_begin(0, 0) + # Reset the chip rather than call flash_finish(), which would have + # write protected the chip again (why oh why does it do that?!) + self.mem_begin(0,0,0,0x40100000) + self.mem_finish(0x40000080) + + """ Perform a chip erase of SPI flash """ + def flash_erase(self): + # Trick ROM to initialize SFlash + self.flash_begin(0, 0) + + # This is hacky: we don't have a custom stub, instead we trick + # the bootloader to jump to the SPIEraseChip() routine and then halt/crash + # when it tries to boot an unconfigured system. + self.mem_begin(0,0,0,0x40100000) + self.mem_finish(0x40004984) + + # Yup - there's no good way to detect if we succeeded. + # It it on the other hand unlikely to fail. + + def run_stub(self, stub, params, read_output=True): + stub = dict(stub) + stub['code'] = unhexify(stub['code']) + if 'data' in stub: + stub['data'] = unhexify(stub['data']) + + if stub['num_params'] != len(params): + raise FatalError('Stub requires %d params, %d provided' + % (stub['num_params'], len(params))) + + params = struct.pack('<' + ('I' * stub['num_params']), *params) + pc = params + stub['code'] + + # Upload + self.mem_begin(len(pc), 1, len(pc), stub['params_start']) + self.mem_block(pc, 0) + if 'data' in stub: + self.mem_begin(len(stub['data']), 1, len(stub['data']), stub['data_start']) + self.mem_block(stub['data'], 0) + self.mem_finish(stub['entry']) + + if read_output: + print 'Stub executed, reading response:' + while True: + p = self.read() + print hexify(p) + if p == '': + return + + +class ESPBOOTLOADER(object): + """ These are constants related to software ESP bootloader, working with 'v2' image files """ + + # First byte of the "v2" application image + IMAGE_V2_MAGIC = 0xea + + # First 'segment' value in a "v2" application image, appears to be a constant version value? + IMAGE_V2_SEGMENT = 4 + + +def LoadFirmwareImage(filename): + """ Load a firmware image, without knowing what kind of file (v1 or v2) it is. + + Returns a BaseFirmwareImage subclass, either ESPFirmwareImage (v1) or OTAFirmwareImage (v2). + """ + with open(filename, 'rb') as f: + magic = ord(f.read(1)) + f.seek(0) + if magic == ESPROM.ESP_IMAGE_MAGIC: + return ESPFirmwareImage(f) + elif magic == ESPBOOTLOADER.IMAGE_V2_MAGIC: + return OTAFirmwareImage(f) + else: + raise FatalError("Invalid image magic number: %d" % magic) + + +class BaseFirmwareImage(object): + """ Base class with common firmware image functions """ + def __init__(self): + self.segments = [] + self.entrypoint = 0 + + def add_segment(self, addr, data, pad_to=4): + """ Add a segment to the image, with specified address & data + (padded to a boundary of pad_to size) """ + # Data should be aligned on word boundary + l = len(data) + if l % pad_to: + data += b"\x00" * (pad_to - l % pad_to) + if l > 0: + self.segments.append((addr, len(data), data)) + + def load_segment(self, f, is_irom_segment=False): + """ Load the next segment from the image file """ + (offset, size) = struct.unpack(' 0x40200000 or offset < 0x3ffe0000 or size > 65536: + raise FatalError('Suspicious segment 0x%x, length %d' % (offset, size)) + segment_data = f.read(size) + if len(segment_data) < size: + raise FatalError('End of file reading segment 0x%x, length %d (actual length %d)' % (offset, size, len(segment_data))) + segment = (offset, size, segment_data) + self.segments.append(segment) + return segment + + def save_segment(self, f, segment, checksum=None): + """ Save the next segment to the image file, return next checksum value if provided """ + (offset, size, data) = segment + f.write(struct.pack(' 16: + raise FatalError('Invalid firmware image magic=%d segments=%d' % (magic, segments)) + + for i in xrange(segments): + self.load_segment(load_file) + self.checksum = self.read_checksum(load_file) + + def save(self, filename): + with open(filename, 'wb') as f: + self.write_v1_header(f, self.segments) + checksum = ESPROM.ESP_CHECKSUM_MAGIC + for segment in self.segments: + checksum = self.save_segment(f, segment, checksum) + self.append_checksum(f, checksum) + + +class OTAFirmwareImage(BaseFirmwareImage): + """ 'Version 2' firmware image, segments loaded by software bootloader stub + (ie Espressif bootloader or rboot) + """ + def __init__(self, load_file=None): + super(OTAFirmwareImage, self).__init__() + self.version = 2 + if load_file is not None: + (magic, segments, first_flash_mode, first_flash_size_freq, first_entrypoint) = struct.unpack(' 16: + raise FatalError('Invalid V2 second header magic=%d segments=%d' % (magic, segments)) + + # load all the usual segments + for _ in xrange(segments): + self.load_segment(load_file) + self.checksum = self.read_checksum(load_file) + + def save(self, filename): + with open(filename, 'wb') as f: + # Save first header for irom0 segment + f.write(struct.pack(' 0: + esp._port.baudrate = baud_rate + # Read the greeting. + p = esp.read() + if p != 'OHAI': + raise FatalError('Failed to connect to the flasher (got %s)' % hexify(p)) + + def flash_write(self, addr, data, show_progress=False): + assert addr % self._esp.ESP_FLASH_SECTOR == 0, 'Address must be sector-aligned' + assert len(data) % self._esp.ESP_FLASH_SECTOR == 0, 'Length must be sector-aligned' + sys.stdout.write('Writing %d @ 0x%x... ' % (len(data), addr)) + sys.stdout.flush() + self._esp.write(struct.pack(' length: + raise FatalError('Read more than expected') + p = self._esp.read() + if len(p) != 16: + raise FatalError('Expected digest, got: %s' % hexify(p)) + expected_digest = hexify(p).upper() + digest = hashlib.md5(data).hexdigest().upper() + print + if digest != expected_digest: + raise FatalError('Digest mismatch: expected %s, got %s' % (expected_digest, digest)) + p = self._esp.read() + if len(p) != 1: + raise FatalError('Expected status, got: %s' % hexify(p)) + status_code = struct.unpack(', ) or a single +# argument. + +def load_ram(esp, args): + image = LoadFirmwareImage(args.filename) + + print 'RAM boot...' + for (offset, size, data) in image.segments: + print 'Downloading %d bytes at %08x...' % (size, offset), + sys.stdout.flush() + esp.mem_begin(size, div_roundup(size, esp.ESP_RAM_BLOCK), esp.ESP_RAM_BLOCK, offset) + + seq = 0 + while len(data) > 0: + esp.mem_block(data[0:esp.ESP_RAM_BLOCK], seq) + data = data[esp.ESP_RAM_BLOCK:] + seq += 1 + print 'done!' + + print 'All segments done, executing at %08x' % image.entrypoint + esp.mem_finish(image.entrypoint) + + +def read_mem(esp, args): + print '0x%08x = 0x%08x' % (args.address, esp.read_reg(args.address)) + + +def write_mem(esp, args): + esp.write_reg(args.address, args.value, args.mask, 0) + print 'Wrote %08x, mask %08x to %08x' % (args.value, args.mask, args.address) + + +def dump_mem(esp, args): + f = file(args.filename, 'wb') + for i in xrange(args.size / 4): + d = esp.read_reg(args.address + (i * 4)) + f.write(struct.pack('> 16 + args.flash_size = {18: '2m', 19: '4m', 20: '8m', 21: '16m', 22: '32m'}.get(size_id) + if args.flash_size is None: + print 'Warning: Could not auto-detect Flash size (FlashID=0x%x, SizeID=0x%x), defaulting to 4m' % (flash_id, size_id) + args.flash_size = '4m' + else: + print 'Auto-detected Flash size:', args.flash_size + + +def write_flash(esp, args): + detect_flash_size(esp, args) + flash_mode = {'qio':0, 'qout':1, 'dio':2, 'dout': 3}[args.flash_mode] + flash_size_freq = {'4m':0x00, '2m':0x10, '8m':0x20, '16m':0x30, '32m':0x40, '16m-c1': 0x50, '32m-c1':0x60, '32m-c2':0x70}[args.flash_size] + flash_size_freq += {'40m':0, '26m':1, '20m':2, '80m': 0xf}[args.flash_freq] + flash_params = struct.pack('BB', flash_mode, flash_size_freq) + + flasher = CesantaFlasher(esp, args.baud) + + for address, argfile in args.addr_filename: + image = argfile.read() + argfile.seek(0) # rewind in case we need it again + if address + len(image) > int(args.flash_size.split('m')[0]) * (1 << 17): + print 'WARNING: Unlikely to work as data goes beyond end of flash. Hint: Use --flash_size' + # Fix sflash config data. + if address == 0 and image[0] == '\xe9': + print 'Flash params set to 0x%02x%02x' % (flash_mode, flash_size_freq) + image = image[0:2] + flash_params + image[4:] + # Pad to sector size, which is the minimum unit of writing (erasing really). + if len(image) % esp.ESP_FLASH_SECTOR != 0: + image += '\xff' * (esp.ESP_FLASH_SECTOR - (len(image) % esp.ESP_FLASH_SECTOR)) + t = time.time() + flasher.flash_write(address, image, not args.no_progress) + t = time.time() - t + print ('\rWrote %d bytes at 0x%x in %.1f seconds (%.1f kbit/s)...' + % (len(image), address, t, len(image) / t * 8 / 1000)) + print 'Leaving...' + if args.verify: + print 'Verifying just-written flash...' + _verify_flash(flasher, args, flash_params) + flasher.boot_fw() + + +def image_info(args): + image = LoadFirmwareImage(args.filename) + print('Image version: %d' % image.version) + print('Entry point: %08x' % image.entrypoint) if image.entrypoint != 0 else 'Entry point not set' + print '%d segments' % len(image.segments) + print + checksum = ESPROM.ESP_CHECKSUM_MAGIC + for (idx, (offset, size, data)) in enumerate(image.segments): + if image.version == 2 and idx == 0: + print 'Segment 1: %d bytes IROM0 (no load address)' % size + else: + print 'Segment %d: %5d bytes at %08x' % (idx + 1, size, offset) + checksum = ESPROM.checksum(data, checksum) + print + print 'Checksum: %02x (%s)' % (image.checksum, 'valid' if image.checksum == checksum else 'invalid!') + + +def make_image(args): + image = ESPFirmwareImage() + if len(args.segfile) == 0: + raise FatalError('No segments specified') + if len(args.segfile) != len(args.segaddr): + raise FatalError('Number of specified files does not match number of specified addresses') + for (seg, addr) in zip(args.segfile, args.segaddr): + data = file(seg, 'rb').read() + image.add_segment(addr, data) + image.entrypoint = args.entrypoint + image.save(args.output) + + +def elf2image(args): + e = ELFFile(args.input) + if args.version == '1': + image = ESPFirmwareImage() + else: + image = OTAFirmwareImage() + irom_data = e.load_section('.irom0.text') + if len(irom_data) == 0: + raise FatalError(".irom0.text section not found in ELF file - can't create V2 image.") + image.add_segment(0, irom_data, 16) + image.entrypoint = e.get_entry_point() + for section, start in ((".text", "_text_start"), (".data", "_data_start"), (".rodata", "_rodata_start")): + data = e.load_section(section) + image.add_segment(e.get_symbol_addr(start), data) + + image.flash_mode = {'qio':0, 'qout':1, 'dio':2, 'dout': 3}[args.flash_mode] + image.flash_size_freq = {'4m':0x00, '2m':0x10, '8m':0x20, '16m':0x30, '32m':0x40, '16m-c1': 0x50, '32m-c1':0x60, '32m-c2':0x70}[args.flash_size] + image.flash_size_freq += {'40m':0, '26m':1, '20m':2, '80m': 0xf}[args.flash_freq] + + irom_offs = e.get_symbol_addr("_irom0_text_start") - 0x40200000 + + if args.version == '1': + if args.output is None: + args.output = args.input + '-' + image.save(args.output + "0x00000.bin") + data = e.load_section(".irom0.text") + if irom_offs < 0: + raise FatalError('Address of symbol _irom0_text_start in ELF is located before flash mapping address. Bad linker script?') + if (irom_offs & 0xFFF) != 0: # irom0 isn't flash sector aligned + print "WARNING: irom0 section offset is 0x%08x. ELF is probably linked for 'elf2image --version=2'" % irom_offs + with open(args.output + "0x%05x.bin" % irom_offs, "wb") as f: + f.write(data) + f.close() + else: # V2 OTA image + if args.output is None: + args.output = "%s-0x%05x.bin" % (os.path.splitext(args.input)[0], irom_offs & ~(ESPROM.ESP_FLASH_SECTOR - 1)) + image.save(args.output) + + +def read_mac(esp, args): + mac = esp.read_mac() + print 'MAC: %s' % ':'.join(map(lambda x: '%02x' % x, mac)) + + +def chip_id(esp, args): + chipid = esp.chip_id() + print 'Chip ID: 0x%08x' % chipid + + +def erase_flash(esp, args): + flasher = CesantaFlasher(esp, args.baud) + print 'Erasing flash (this may take a while)...' + t = time.time() + flasher.flash_erase_chip() + t = time.time() - t + print 'Erase took %.1f seconds' % t + + +def run(esp, args): + esp.run() + + +def flash_id(esp, args): + flash_id = esp.flash_id() + esp.flash_finish(False) + print 'Manufacturer: %02x' % (flash_id & 0xff) + print 'Device: %02x%02x' % ((flash_id >> 8) & 0xff, (flash_id >> 16) & 0xff) + + +def read_flash(esp, args): + flasher = CesantaFlasher(esp, args.baud) + t = time.time() + data = flasher.flash_read(args.address, args.size, not args.no_progress) + t = time.time() - t + print ('\rRead %d bytes at 0x%x in %.1f seconds (%.1f kbit/s)...' + % (len(data), args.address, t, len(data) / t * 8 / 1000)) + file(args.filename, 'wb').write(data) + + +def _verify_flash(flasher, args, flash_params=None): + differences = False + for address, argfile in args.addr_filename: + image = argfile.read() + argfile.seek(0) # rewind in case we need it again + if address == 0 and image[0] == '\xe9' and flash_params is not None: + image = image[0:2] + flash_params + image[4:] + image_size = len(image) + print 'Verifying 0x%x (%d) bytes @ 0x%08x in flash against %s...' % (image_size, image_size, address, argfile.name) + # Try digest first, only read if there are differences. + digest, _ = flasher.flash_digest(address, image_size) + digest = hexify(digest).upper() + expected_digest = hashlib.md5(image).hexdigest().upper() + if digest == expected_digest: + print '-- verify OK (digest matched)' + continue + else: + differences = True + if getattr(args, 'diff', 'no') != 'yes': + print '-- verify FAILED (digest mismatch)' + continue + + flash = flasher.flash_read(address, image_size) + assert flash != image + diff = [i for i in xrange(image_size) if flash[i] != image[i]] + print '-- verify FAILED: %d differences, first @ 0x%08x' % (len(diff), address + diff[0]) + for d in diff: + print ' %08x %02x %02x' % (address + d, ord(flash[d]), ord(image[d])) + if differences: + raise FatalError("Verify failed.") + + +def verify_flash(esp, args, flash_params=None): + flasher = CesantaFlasher(esp) + _verify_flash(flasher, args, flash_params) + + +def version(args): + print __version__ + +# +# End of operations functions +# + + +def main(): + parser = argparse.ArgumentParser(description='esptool.py v%s - ESP8266 ROM Bootloader Utility' % __version__, prog='esptool') + + parser.add_argument( + '--port', '-p', + help='Serial port device', + default=os.environ.get('ESPTOOL_PORT', None)) + + parser.add_argument( + '--baud', '-b', + help='Serial port baud rate used when flashing/reading', + type=arg_auto_int, + default=os.environ.get('ESPTOOL_BAUD', ESPROM.ESP_ROM_BAUD)) + + subparsers = parser.add_subparsers( + dest='operation', + help='Run esptool {command} -h for additional help') + + parser_load_ram = subparsers.add_parser( + 'load_ram', + help='Download an image to RAM and execute') + parser_load_ram.add_argument('filename', help='Firmware image') + + parser_dump_mem = subparsers.add_parser( + 'dump_mem', + help='Dump arbitrary memory to disk') + parser_dump_mem.add_argument('address', help='Base address', type=arg_auto_int) + parser_dump_mem.add_argument('size', help='Size of region to dump', type=arg_auto_int) + parser_dump_mem.add_argument('filename', help='Name of binary dump') + + parser_read_mem = subparsers.add_parser( + 'read_mem', + help='Read arbitrary memory location') + parser_read_mem.add_argument('address', help='Address to read', type=arg_auto_int) + + parser_write_mem = subparsers.add_parser( + 'write_mem', + help='Read-modify-write to arbitrary memory location') + parser_write_mem.add_argument('address', help='Address to write', type=arg_auto_int) + parser_write_mem.add_argument('value', help='Value', type=arg_auto_int) + parser_write_mem.add_argument('mask', help='Mask of bits to write', type=arg_auto_int) + + def add_spi_flash_subparsers(parent, auto_detect=False): + """ Add common parser arguments for SPI flash properties """ + parent.add_argument('--flash_freq', '-ff', help='SPI Flash frequency', + choices=['40m', '26m', '20m', '80m'], + default=os.environ.get('ESPTOOL_FF', '40m')) + parent.add_argument('--flash_mode', '-fm', help='SPI Flash mode', + choices=['qio', 'qout', 'dio', 'dout'], + default=os.environ.get('ESPTOOL_FM', 'qio')) + choices = ['4m', '2m', '8m', '16m', '32m', '16m-c1', '32m-c1', '32m-c2'] + default = '4m' + if auto_detect: + default = 'detect' + choices.insert(0, 'detect') + parent.add_argument('--flash_size', '-fs', help='SPI Flash size in Mbit', type=str.lower, + choices=choices, + default=os.environ.get('ESPTOOL_FS', default)) + + parser_write_flash = subparsers.add_parser( + 'write_flash', + help='Write a binary blob to flash') + parser_write_flash.add_argument('addr_filename', metavar='
', help='Address followed by binary filename, separated by space', + action=AddrFilenamePairAction) + add_spi_flash_subparsers(parser_write_flash, auto_detect=True) + parser_write_flash.add_argument('--no-progress', '-p', help='Suppress progress output', action="store_true") + parser_write_flash.add_argument('--verify', help='Verify just-written data (only necessary if very cautious, data is already CRCed', action='store_true') + + subparsers.add_parser( + 'run', + help='Run application code in flash') + + parser_image_info = subparsers.add_parser( + 'image_info', + help='Dump headers from an application image') + parser_image_info.add_argument('filename', help='Image file to parse') + + parser_make_image = subparsers.add_parser( + 'make_image', + help='Create an application image from binary files') + parser_make_image.add_argument('output', help='Output image file') + parser_make_image.add_argument('--segfile', '-f', action='append', help='Segment input file') + parser_make_image.add_argument('--segaddr', '-a', action='append', help='Segment base address', type=arg_auto_int) + parser_make_image.add_argument('--entrypoint', '-e', help='Address of entry point', type=arg_auto_int, default=0) + + parser_elf2image = subparsers.add_parser( + 'elf2image', + help='Create an application image from ELF file') + parser_elf2image.add_argument('input', help='Input ELF file') + parser_elf2image.add_argument('--output', '-o', help='Output filename prefix (for version 1 image), or filename (for version 2 single image)', type=str) + parser_elf2image.add_argument('--version', '-e', help='Output image version', choices=['1','2'], default='1') + add_spi_flash_subparsers(parser_elf2image) + + subparsers.add_parser( + 'read_mac', + help='Read MAC address from OTP ROM') + + subparsers.add_parser( + 'chip_id', + help='Read Chip ID from OTP ROM') + + subparsers.add_parser( + 'flash_id', + help='Read SPI flash manufacturer and device ID') + + parser_read_flash = subparsers.add_parser( + 'read_flash', + help='Read SPI flash content') + parser_read_flash.add_argument('address', help='Start address', type=arg_auto_int) + parser_read_flash.add_argument('size', help='Size of region to dump', type=arg_auto_int) + parser_read_flash.add_argument('filename', help='Name of binary dump') + parser_read_flash.add_argument('--no-progress', '-p', help='Suppress progress output', action="store_true") + + parser_verify_flash = subparsers.add_parser( + 'verify_flash', + help='Verify a binary blob against flash') + parser_verify_flash.add_argument('addr_filename', help='Address and binary file to verify there, separated by space', + action=AddrFilenamePairAction) + parser_verify_flash.add_argument('--diff', '-d', help='Show differences', + choices=['no', 'yes'], default='no') + + subparsers.add_parser( + 'erase_flash', + help='Perform Chip Erase on SPI flash') + + subparsers.add_parser( + 'version', help='Print esptool version') + + # internal sanity check - every operation matches a module function of the same name + for operation in subparsers.choices.keys(): + assert operation in globals(), "%s should be a module function" % operation + + args = parser.parse_args() + + print 'esptool.py v%s' % __version__ + + # operation function can take 1 arg (args), 2 args (esp, arg) + # or be a member function of the ESPROM class. + + operation_func = globals()[args.operation] + operation_args,_,_,_ = inspect.getargspec(operation_func) + if operation_args[0] == 'esp': # operation function takes an ESPROM connection object + initial_baud = min(ESPROM.ESP_ROM_BAUD, args.baud) # don't sync faster than the default baud rate + esp = ESPROM(args.port, initial_baud) + esp.connect() + operation_func(esp, args) + else: + operation_func(args) + + +class AddrFilenamePairAction(argparse.Action): + """ Custom parser class for the address/filename pairs passed as arguments """ + def __init__(self, option_strings, dest, nargs='+', **kwargs): + super(AddrFilenamePairAction, self).__init__(option_strings, dest, nargs, **kwargs) + + def __call__(self, parser, namespace, values, option_string=None): + # validate pair arguments + pairs = [] + for i in range(0,len(values),2): + try: + address = int(values[i],0) + except ValueError as e: + raise argparse.ArgumentError(self,'Address "%s" must be a number' % values[i]) + try: + argfile = open(values[i + 1], 'rb') + except IOError as e: + raise argparse.ArgumentError(self, e) + except IndexError: + raise argparse.ArgumentError(self,'Must be pairs of an address and the binary filename to write there') + pairs.append((address, argfile)) + setattr(namespace, self.dest, pairs) + +# This is "wrapped" stub_flasher.c, to be loaded using run_stub. +_CESANTA_FLASHER_STUB = """\ +{"code_start": 1074790404, "code": "080000601C000060000000601000006031FCFF71FCFF\ +81FCFFC02000680332D218C020004807404074DCC48608005823C0200098081BA5A9239245005803\ +1B555903582337350129230B446604DFC6F3FF21EEFFC0200069020DF0000000010078480040004A\ +0040B449004012C1F0C921D911E901DD0209312020B4ED033C2C56C2073020B43C3C56420701F5FF\ +C000003C4C569206CD0EEADD860300202C4101F1FFC0000056A204C2DCF0C02DC0CC6CCAE2D1EAFF\ +0606002030F456D3FD86FBFF00002020F501E8FFC00000EC82D0CCC0C02EC0C73DEB2ADC46030020\ +2C4101E1FFC00000DC42C2DCF0C02DC056BCFEC602003C5C8601003C6C4600003C7C08312D0CD811\ +C821E80112C1100DF0000C180000140010400C0000607418000064180000801800008C1800008418\ +0000881800009018000018980040880F0040A80F0040349800404C4A0040740F0040800F0040980F\ +00400099004012C1E091F5FFC961CD0221EFFFE941F9310971D9519011C01A223902E2D1180C0222\ +6E1D21E4FF31E9FF2AF11A332D0F42630001EAFFC00000C030B43C2256A31621E1FF1A2228022030\ +B43C3256B31501ADFFC00000DD023C4256ED1431D6FF4D010C52D90E192E126E0101DDFFC0000021\ +D2FF32A101C020004802303420C0200039022C0201D7FFC00000463300000031CDFF1A333803D023\ +C03199FF27B31ADC7F31CBFF1A3328030198FFC0000056C20E2193FF2ADD060E000031C6FF1A3328\ +030191FFC0000056820DD2DD10460800000021BEFF1A2228029CE231BCFFC020F51A33290331BBFF\ +C02C411A332903C0F0F4222E1D22D204273D9332A3FFC02000280E27B3F721ABFF381E1A2242A400\ +01B5FFC00000381E2D0C42A40001B3FFC0000056120801B2FFC00000C02000280EC2DC0422D2FCC0\ +2000290E01ADFFC00000222E1D22D204226E1D281E22D204E7B204291E860000126E012198FF32A0\ +042A21C54C003198FF222E1D1A33380337B202C6D6FF2C02019FFFC000002191FF318CFF1A223A31\ +019CFFC00000218DFF1C031A22C549000C02060300003C528601003C624600003C72918BFF9A1108\ +71C861D851E841F83112C1200DF00010000068100000581000007010000074100000781000007C10\ +0000801000001C4B0040803C004091FDFF12C1E061F7FFC961E941F9310971D9519011C01A662906\ +21F3FFC2D1101A22390231F2FF0C0F1A33590331EAFFF26C1AED045C2247B3028636002D0C016DFF\ +C0000021E5FF41EAFF2A611A4469040622000021E4FF1A222802F0D2C0D7BE01DD0E31E0FF4D0D1A\ +3328033D0101E2FFC00000561209D03D2010212001DFFFC000004D0D2D0C3D01015DFFC0000041D5\ +FFDAFF1A444804D0648041D2FF1A4462640061D1FF106680622600673F1331D0FF10338028030C43\ +853A002642164613000041CAFF222C1A1A444804202FC047328006F6FF222C1A273F3861C2FF222C\ +1A1A6668066732B921BDFF3D0C1022800148FFC0000021BAFF1C031A2201BFFFC000000C02460300\ +5C3206020000005C424600005C5291B7FF9A110871C861D851E841F83112C1200DF0B0100000C010\ +0000D010000012C1E091FEFFC961D951E9410971F931CD039011C0ED02DD0431A1FF9C1422A06247\ +B302062D0021F4FF1A22490286010021F1FF1A223902219CFF2AF12D0F011FFFC00000461C0022D1\ +10011CFFC0000021E9FFFD0C1A222802C7B20621E6FF1A22F8022D0E3D014D0F0195FFC000008C52\ +22A063C6180000218BFF3D01102280F04F200111FFC00000AC7D22D1103D014D0F010DFFC0000021\ +D6FF32D110102280010EFFC0000021D3FF1C031A220185FFC00000FAEEF0CCC056ACF821CDFF317A\ +FF1A223A310105FFC0000021C9FF1C031A22017CFFC000002D0C91C8FF9A110871C861D851E841F8\ +3112C1200DF0000200600000001040020060FFFFFF0012C1E00C02290131FAFF21FAFF026107C961\ +C02000226300C02000C80320CC10564CFF21F5FFC02000380221F4FF20231029010C432D010163FF\ +C0000008712D0CC86112C1200DF00080FE3F8449004012C1D0C9A109B17CFC22C1110C13C51C0026\ +1202463000220111C24110B68202462B0031F5FF3022A02802A002002D011C03851A0066820A2801\ +32210105A6FF0607003C12C60500000010212032A01085180066A20F2221003811482105B3FF2241\ +10861A004C1206FDFF2D011C03C5160066B20E280138114821583185CFFF06F7FF005C1286F5FF00\ +10212032A01085140066A20D2221003811482105E1FF06EFFF0022A06146EDFF45F0FFC6EBFF0000\ +01D2FFC0000006E9FF000C022241100C1322C110C50F00220111060600000022C1100C13C50E0022\ +011132C2FA303074B6230206C8FF08B1C8A112C1300DF0000000000010404F484149007519031027\ +000000110040A8100040BC0F0040583F0040CC2E00401CE20040D83900408000004021F4FF12C1E0\ +C961C80221F2FF097129010C02D951C91101F4FFC0000001F3FFC00000AC2C22A3E801F2FFC00000\ +21EAFFC031412A233D0C01EFFFC000003D0222A00001EDFFC00000C1E4FF2D0C01E8FFC000002D01\ +32A004450400C5E7FFDD022D0C01E3FFC00000666D1F4B2131DCFF4600004B22C0200048023794F5\ +31D9FFC0200039023DF08601000001DCFFC000000871C861D85112C1200DF000000012C1F0026103\ +01EAFEC00000083112C1100DF000643B004012C1D0E98109B1C9A1D991F97129013911E2A0C001FA\ +FFC00000CD02E792F40C0DE2A0C0F2A0DB860D00000001F4FFC00000204220E71240F7921C226102\ +01EFFFC0000052A0DC482157120952A0DD571205460500004D0C3801DA234242001BDD3811379DC5\ +C6000000000C0DC2A0C001E3FFC00000C792F608B12D0DC8A1D891E881F87112C1300DF00000", "\ +entry": 1074792180, "num_params": 1, "params_start": 1074790400, "data": "FE0510\ +401A0610403B0610405A0610407A061040820610408C0610408C061040", "data_start": 10736\ +43520} +""" + +if __name__ == '__main__': + try: + main() + except FatalError as e: + print '\nA fatal error occurred: %s' % e + sys.exit(2) diff --git a/panda/python/flash_release.py b/panda/python/flash_release.py new file mode 100755 index 00000000000000..51f6a72e7a6c07 --- /dev/null +++ b/panda/python/flash_release.py @@ -0,0 +1,95 @@ +#!/usr/bin/env python +from __future__ import print_function +import sys +import time +import requests +import json +import StringIO + +def flash_release(path=None, st_serial=None): + from panda import Panda, PandaDFU, ESPROM, CesantaFlasher + from zipfile import ZipFile + + def status(x): + print("\033[1;32;40m"+x+"\033[00m") + + if st_serial == None: + # look for Panda + panda_list = Panda.list() + if len(panda_list) == 0: + raise Exception("panda not found, make sure it's connected and your user can access it") + elif len(panda_list) > 1: + raise Exception("Please only connect one panda") + st_serial = panda_list[0] + print("Using panda with serial %s" % st_serial) + + if path == None: + print("Fetching latest firmware from github.com/commaai/panda-artifacts") + r = requests.get("https://raw.githubusercontent.com/commaai/panda-artifacts/master/latest.json") + url = json.loads(r.text)['url'] + r = requests.get(url) + print("Fetching firmware from %s" % url) + path = StringIO.StringIO(r.content) + + zf = ZipFile(path) + zf.printdir() + + version = zf.read("version") + status("0. Preparing to flash "+version) + + code_bootstub = zf.read("bootstub.panda.bin") + code_panda = zf.read("panda.bin") + + code_boot_15 = zf.read("boot_v1.5.bin") + code_boot_15 = code_boot_15[0:2] + "\x00\x30" + code_boot_15[4:] + + code_user1 = zf.read("user1.bin") + code_user2 = zf.read("user2.bin") + + # enter DFU mode + status("1. Entering DFU mode") + panda = Panda(st_serial) + panda.enter_bootloader() + time.sleep(1) + + # program bootstub + status("2. Programming bootstub") + dfu = PandaDFU(PandaDFU.st_serial_to_dfu_serial(st_serial)) + dfu.program_bootstub(code_bootstub) + time.sleep(1) + + # flash main code + status("3. Flashing main code") + panda = Panda(st_serial) + panda.flash(code=code_panda) + panda.close() + + # flashing ESP + status("4. Flashing ESP (slow!)") + align = lambda x, sz=0x1000: x+"\xFF"*((sz-len(x)) % sz) + esp = ESPROM(st_serial) + esp.connect() + flasher = CesantaFlasher(esp, 230400) + flasher.flash_write(0x0, align(code_boot_15), True) + flasher.flash_write(0x1000, align(code_user1), True) + flasher.flash_write(0x81000, align(code_user2), True) + flasher.flash_write(0x3FE000, "\xFF"*0x1000) + flasher.boot_fw() + del flasher + del esp + time.sleep(1) + + # check for connection + status("5. Verifying version") + panda = Panda(st_serial) + my_version = panda.get_version() + print("dongle id: %s" % panda.get_serial()[0]) + print(my_version, "should be", version) + assert(str(version) == str(my_version)) + + # done! + status("6. Success!") + +if __name__ == "__main__": + flash_release(*sys.argv[1:]) + diff --git a/panda/python/isotp.py b/panda/python/isotp.py new file mode 100644 index 00000000000000..d68aa4d70e0bbe --- /dev/null +++ b/panda/python/isotp.py @@ -0,0 +1,135 @@ +DEBUG = False + +def msg(x): + if DEBUG: + print "S:",x.encode("hex") + if len(x) <= 7: + ret = chr(len(x)) + x + else: + assert False + return ret.ljust(8, "\x00") + +kmsgs = [] +def recv(panda, cnt, addr, nbus): + global kmsgs + ret = [] + + while len(ret) < cnt: + kmsgs += panda.can_recv() + nmsgs = [] + for ids, ts, dat, bus in kmsgs: + if ids == addr and bus == nbus and len(ret) < cnt: + ret.append(dat) + else: + # leave around + nmsgs.append((ids, ts, dat, bus)) + kmsgs = nmsgs[-256:] + return map(str, ret) + +def isotp_recv_subaddr(panda, addr, bus, sendaddr, subaddr): + msg = recv(panda, 1, addr, bus)[0] + + # TODO: handle other subaddr also communicating + assert ord(msg[0]) == subaddr + + if ord(msg[1])&0xf0 == 0x10: + # first + tlen = ((ord(msg[1]) & 0xf) << 8) | ord(msg[2]) + dat = msg[3:] + + # 0 block size? + CONTINUE = chr(subaddr) + "\x30" + "\x00"*6 + panda.can_send(sendaddr, CONTINUE, bus) + + idx = 1 + for mm in recv(panda, (tlen-len(dat) + 5)/6, addr, bus): + assert ord(mm[0]) == subaddr + assert ord(mm[1]) == (0x20 | (idx&0xF)) + dat += mm[2:] + idx += 1 + elif ord(msg[1])&0xf0 == 0x00: + # single + tlen = ord(msg[1]) & 0xf + dat = msg[2:] + else: + print msg.encode("hex") + assert False + + return dat[0:tlen] + +# **** import below this line **** + +def isotp_send(panda, x, addr, bus=0, recvaddr=None, subaddr=None): + if recvaddr is None: + recvaddr = addr+8 + + if len(x) <= 7 and subaddr is None: + panda.can_send(addr, msg(x), bus) + elif len(x) <= 6 and subaddr is not None: + panda.can_send(addr, chr(subaddr)+msg(x)[0:7], bus) + else: + if subaddr: + ss = chr(subaddr) + chr(0x10 + (len(x)>>8)) + chr(len(x)&0xFF) + x[0:5] + x = x[5:] + else: + ss = chr(0x10 + (len(x)>>8)) + chr(len(x)&0xFF) + x[0:6] + x = x[6:] + idx = 1 + sends = [] + while len(x) > 0: + if subaddr: + sends.append(((chr(subaddr) + chr(0x20 + (idx&0xF)) + x[0:6]).ljust(8, "\x00"))) + x = x[6:] + else: + sends.append(((chr(0x20 + (idx&0xF)) + x[0:7]).ljust(8, "\x00"))) + x = x[7:] + idx += 1 + + # actually send + panda.can_send(addr, ss, bus) + rr = recv(panda, 1, recvaddr, bus)[0] + if rr.find("\x30\x01") != -1: + for s in sends[:-1]: + panda.can_send(addr, s, 0) + rr = recv(panda, 1, recvaddr, bus)[0] + panda.can_send(addr, sends[-1], 0) + else: + panda.can_send_many([(addr, None, s, 0) for s in sends]) + +def isotp_recv(panda, addr, bus=0, sendaddr=None, subaddr=None): + if sendaddr is None: + sendaddr = addr-8 + + if subaddr is not None: + dat = isotp_recv_subaddr(panda, addr, bus, sendaddr, subaddr) + else: + msg = recv(panda, 1, addr, bus)[0] + + if ord(msg[0])&0xf0 == 0x10: + # first + tlen = ((ord(msg[0]) & 0xf) << 8) | ord(msg[1]) + dat = msg[2:] + + # 0 block size? + CONTINUE = "\x30" + "\x00"*7 + + panda.can_send(sendaddr, CONTINUE, bus) + + idx = 1 + for mm in recv(panda, (tlen-len(dat) + 6)/7, addr, bus): + assert ord(mm[0]) == (0x20 | (idx&0xF)) + dat += mm[1:] + idx += 1 + elif ord(msg[0])&0xf0 == 0x00: + # single + tlen = ord(msg[0]) & 0xf + dat = msg[1:] + else: + assert False + dat = dat[0:tlen] + + if DEBUG: + print "R:",dat.encode("hex") + + return dat + diff --git a/panda/python/serial.py b/panda/python/serial.py new file mode 100644 index 00000000000000..1bcfebb32eabd0 --- /dev/null +++ b/panda/python/serial.py @@ -0,0 +1,27 @@ +# mimic a python serial port +class PandaSerial(object): + def __init__(self, panda, port, baud): + self.panda = panda + self.port = port + self.panda.set_uart_parity(self.port, 0) + self.panda.set_uart_baud(self.port, baud) + self.buf = "" + + def read(self, l=1): + tt = self.panda.serial_read(self.port) + if len(tt) > 0: + #print "R: ", tt.encode("hex") + self.buf += tt + ret = self.buf[0:l] + self.buf = self.buf[l:] + return ret + + def write(self, dat): + #print "W: ", dat.encode("hex") + #print ' pigeon_send("' + ''.join(map(lambda x: "\\x%02X" % ord(x), dat)) + '");' + return self.panda.serial_write(self.port, dat) + + def close(self): + pass + + diff --git a/panda/python/update.py b/panda/python/update.py new file mode 100755 index 00000000000000..d393df9fb44152 --- /dev/null +++ b/panda/python/update.py @@ -0,0 +1,44 @@ +#!/usr/bin/env python +import os +import time + +def ensure_st_up_to_date(): + from panda import Panda, PandaDFU, BASEDIR + + with open(os.path.join(BASEDIR, "VERSION")) as f: + repo_version = f.read() + + panda = None + panda_dfu = None + should_flash_recover = False + + while 1: + # break on normal mode Panda + panda_list = Panda.list() + if len(panda_list) > 0: + panda = Panda(panda_list[0]) + break + + # flash on DFU mode Panda + panda_dfu = PandaDFU.list() + if len(panda_dfu) > 0: + panda_dfu = PandaDFU(panda_dfu[0]) + panda_dfu.recover() + + print "waiting for board..." + time.sleep(1) + + if panda.bootstub or not panda.get_version().startswith(repo_version): + panda.flash() + + if panda.bootstub: + panda.recover() + + assert(not panda.bootstub) + version = str(panda.get_version()) + print("%s should be %s" % (version, repo_version)) + assert(version.startswith(repo_version)) + +if __name__ == "__main__": + ensure_st_up_to_date() + diff --git a/panda/release/.gitignore b/panda/release/.gitignore new file mode 100644 index 00000000000000..c4c4ffc6aa41a8 --- /dev/null +++ b/panda/release/.gitignore @@ -0,0 +1 @@ +*.zip diff --git a/panda/release/make_release.sh b/panda/release/make_release.sh new file mode 100755 index 00000000000000..7be994c82c8813 --- /dev/null +++ b/panda/release/make_release.sh @@ -0,0 +1,40 @@ +#!/bin/bash + +if [ ! -d "../../pandaextra" ]; then + echo "No release cert found, cannot build release." + echo "You probably aren't looking to do this anyway." + exit +fi + +export RELEASE=1 + +# make ST + bootstub +pushd . +cd ../board +make clean +make obj/panda.bin +make obj/bootstub.panda.bin +popd + +# make ESP +pushd . +cd ../boardesp +make clean +make user1.bin +make user2.bin +popd + +# make release +mkdir obj +make -f ../common/version.mk +make obj/gitversion.h +RELEASE_NAME=$(python -c "import sys;sys.stdout.write(open('obj/gitversion.h').read().split('\"')[1])") +echo -en $RELEASE_NAME > /tmp/version +rm -rf obj + +# make zip file +pushd . +cd .. +zip -j release/panda-$RELEASE_NAME.zip ~/one/panda/board/obj/bootstub.panda.bin ~/one/panda/board/obj/panda.bin ~/one/panda/boardesp/user?.bin ~/one/panda/boardesp/esp-open-sdk/ESP8266_NONOS_SDK_V1.5.4_16_05_20/bin/boot_v1.5.bin /tmp/version +popd + diff --git a/panda/release/ota_release.sh b/panda/release/ota_release.sh new file mode 100755 index 00000000000000..541a196ba7e408 --- /dev/null +++ b/panda/release/ota_release.sh @@ -0,0 +1,18 @@ +#!/bin/bash +mkdir -p /tmp/panda_firmware +unzip -o $1 -d /tmp/panda_firmware + +curl http://192.168.0.10/ + +echo "flashing user1" +curl http://192.168.0.10/espupdate1 --upload-file /tmp/panda_firmware/user1.bin +echo "flashing user2" +curl http://192.168.0.10/espupdate2 --upload-file /tmp/panda_firmware/user2.bin +echo "waiting 10s for reboot" +sleep 10 +echo "flashing st" +curl http://192.168.0.10/stupdate --upload-file /tmp/panda_firmware/panda.bin +sleep 2 +curl http://192.168.0.10/ +echo "done" + diff --git a/panda/requirements.txt b/panda/requirements.txt new file mode 100644 index 00000000000000..e968bfb6bad43e --- /dev/null +++ b/panda/requirements.txt @@ -0,0 +1,4 @@ +libusb1 +hexdump +pycrypto +tqdm diff --git a/panda/run_automated_tests.sh b/panda/run_automated_tests.sh new file mode 100755 index 00000000000000..d7b7541902d9eb --- /dev/null +++ b/panda/run_automated_tests.sh @@ -0,0 +1,3 @@ +#!/bin/bash +PYTHONPATH="." nosetests -x -s tests/automated/$1*.py + diff --git a/panda/setup.cfg b/panda/setup.cfg new file mode 100644 index 00000000000000..3480374bc2f25b --- /dev/null +++ b/panda/setup.cfg @@ -0,0 +1,2 @@ +[bdist_wheel] +universal=1 \ No newline at end of file diff --git a/panda/setup.py b/panda/setup.py new file mode 100644 index 00000000000000..312fdca42a0848 --- /dev/null +++ b/panda/setup.py @@ -0,0 +1,65 @@ +#-*- coding: utf-8 -*- + +""" + Panda CAN Controller Dongle + ~~~~~ + + Setup + ````` + + $ pip install . # or python setup.py install +""" + +import codecs +import os +import re +from setuptools import setup, Extension + +here = os.path.abspath(os.path.dirname(__file__)) + +def read(*parts): + """Taken from pypa pip setup.py: + intentionally *not* adding an encoding option to open, See: + https://github.com/pypa/virtualenv/issues/201#issuecomment-3145690 + """ + return codecs.open(os.path.join(here, *parts), 'r').read() + + +def find_version(*file_paths): + version_file = read(*file_paths) + version_match = re.search(r"^__version__ = ['\"]([^'\"]*)['\"]", + version_file, re.M) + if version_match: + return version_match.group(1) + raise RuntimeError("Unable to find version string.") + +setup( + name='pandacan', + version=find_version("python", "__init__.py"), + url='https://github.com/commaai/panda', + author='comma.ai', + author_email='', + packages=[ + 'panda', + ], + package_dir = {'panda': 'python'}, + platforms='any', + license='MIT', + install_requires=[ + 'libusb1 >= 1.6.4', + 'hexdump >= 3.3', + 'pycrypto >= 2.6.1', + 'tqdm >= 4.14.0', + 'requests' + ], + ext_modules = [], + description="Code powering the comma.ai panda", + long_description='See https://github.com/commaai/panda', + classifiers=[ + 'Development Status :: 2 - Pre-Alpha', + "Natural Language :: English", + "Programming Language :: Python :: 2", + "Programming Language :: Python :: 3", + "Topic :: System :: Hardware", + ], +) diff --git a/panda/tests/__init__.py b/panda/tests/__init__.py new file mode 100644 index 00000000000000..e69de29bb2d1d6 diff --git a/panda/tests/all_wifi_test.py b/panda/tests/all_wifi_test.py new file mode 100755 index 00000000000000..4e9d3a5318a16c --- /dev/null +++ b/panda/tests/all_wifi_test.py @@ -0,0 +1,29 @@ +#!/usr/bin/python +import requests +import json +from automated.helpers import _connect_wifi +from panda import Panda +from nose.tools import assert_equal + +if __name__ == "__main__": + print("Fetching latest firmware from github.com/commaai/panda-artifacts") + r = requests.get("https://raw.githubusercontent.com/commaai/panda-artifacts/master/latest.json") + latest_version = json.loads(r.text)['version'] + + for p in Panda.list(): + dongle_id, pw = Panda(p).get_serial() + print dongle_id, pw + assert(dongle_id.isalnum()) + _connect_wifi(dongle_id, pw) + + r = requests.get("http://192.168.0.10/") + print r.text + wifi_dongle_id = r.text.split("ssid: panda-")[1].split("
")[0] + st_version = r.text.split("st version:")[1].strip().split("
")[0] + esp_version = r.text.split("esp version:")[1].strip().split("
")[0] + + assert_equal(str(dongle_id), wifi_dongle_id) + assert_equal(latest_version, st_version) + assert_equal(latest_version, esp_version) + + diff --git a/panda/tests/automated/0_builds.py b/panda/tests/automated/0_builds.py new file mode 100644 index 00000000000000..d5e434a2c22876 --- /dev/null +++ b/panda/tests/automated/0_builds.py @@ -0,0 +1,15 @@ +import os +from panda import build_st + +def test_build_legacy(): + build_st("obj/comma.bin", "Makefile.legacy") + +def test_build_bootstub_legacy(): + build_st("obj/bootstub.comma.bin", "Makefile.legacy") + +def test_build_panda(): + build_st("obj/panda.bin") + +def test_build_bootstub_panda(): + build_st("obj/bootstub.panda.bin") + diff --git a/panda/tests/automated/1_program.py b/panda/tests/automated/1_program.py new file mode 100644 index 00000000000000..7da801bcd54e7b --- /dev/null +++ b/panda/tests/automated/1_program.py @@ -0,0 +1,11 @@ +import os +from panda import Panda + +def test_recover(): + p = Panda() + p.recover() + +def test_flash(): + p = Panda() + p.flash() + diff --git a/panda/tests/automated/2_usb_to_can.py b/panda/tests/automated/2_usb_to_can.py new file mode 100644 index 00000000000000..481564240752a2 --- /dev/null +++ b/panda/tests/automated/2_usb_to_can.py @@ -0,0 +1,186 @@ +from __future__ import print_function +import os +import sys +import time +from panda import Panda +from nose.tools import timed, assert_equal, assert_less, assert_greater +from helpers import time_many_sends, connect_wo_esp + +SPEED_NORMAL = 500 +SPEED_GMLAN = 33.3 + +def test_can_loopback(): + p = connect_wo_esp() + + # enable output mode + p.set_safety_mode(Panda.SAFETY_ALLOUTPUT) + + # enable CAN loopback mode + p.set_can_loopback(True) + + if p.legacy: + busses = [0,1] + else: + busses = [0,1,2] + + for bus in busses: + # set bus 0 speed to 250 + p.set_can_speed_kbps(bus, 250) + + # send a message on bus 0 + p.can_send(0x1aa, "message", bus) + + # confirm receive both on loopback and send receipt + time.sleep(0.05) + r = p.can_recv() + sr = filter(lambda x: x[3] == 0x80 | bus, r) + lb = filter(lambda x: x[3] == bus, r) + assert len(sr) == 1 + assert len(lb) == 1 + + # confirm data is correct + assert 0x1aa == sr[0][0] == lb[0][0] + assert "message" == sr[0][2] == lb[0][2] + +def test_safety_nooutput(): + p = connect_wo_esp() + + # enable output mode + p.set_safety_mode(Panda.SAFETY_NOOUTPUT) + + # enable CAN loopback mode + p.set_can_loopback(True) + + # send a message on bus 0 + p.can_send(0x1aa, "message", 0) + + # confirm receive nothing + time.sleep(0.05) + r = p.can_recv() + assert len(r) == 0 + +def test_reliability(): + p = connect_wo_esp() + + LOOP_COUNT = 100 + MSG_COUNT = 100 + + # enable output mode + p.set_safety_mode(Panda.SAFETY_ALLOUTPUT) + p.set_can_loopback(True) + p.set_can_speed_kbps(0, 1000) + + addrs = range(100, 100+MSG_COUNT) + ts = [(j, 0, "\xaa"*8, 0) for j in addrs] + + # 100 loops + for i in range(LOOP_COUNT): + st = time.time() + + p.can_send_many(ts) + + r = [] + while len(r) < 200 and (time.time() - st) < 0.5: + r.extend(p.can_recv()) + + sent_echo = filter(lambda x: x[3] == 0x80, r) + loopback_resp = filter(lambda x: x[3] == 0, r) + + assert_equal(sorted(map(lambda x: x[0], loopback_resp)), addrs) + assert_equal(sorted(map(lambda x: x[0], sent_echo)), addrs) + assert_equal(len(r), 200) + + # take sub 20ms + et = (time.time()-st)*1000.0 + assert_less(et, 20) + + sys.stdout.write("P") + sys.stdout.flush() + +def test_throughput(): + p = connect_wo_esp() + + # enable output mode + p.set_safety_mode(Panda.SAFETY_ALLOUTPUT) + + # enable CAN loopback mode + p.set_can_loopback(True) + + for speed in [100,250,500,750,1000]: + # set bus 0 speed to speed + p.set_can_speed_kbps(0, speed) + time.sleep(0.05) + + comp_kbps = time_many_sends(p, 0) + + # bit count from https://en.wikipedia.org/wiki/CAN_bus + saturation_pct = (comp_kbps/speed) * 100.0 + assert_greater(saturation_pct, 80) + assert_less(saturation_pct, 100) + + print("loopback 100 messages at speed %d, comp speed is %.2f, percent %.2f" % (speed, comp_kbps, saturation_pct)) + +def test_gmlan(): + p = connect_wo_esp() + + if p.legacy: + return + + # enable output mode + p.set_safety_mode(Panda.SAFETY_ALLOUTPUT) + + # enable CAN loopback mode + p.set_can_loopback(True) + + p.set_can_speed_kbps(1, SPEED_NORMAL) + p.set_can_speed_kbps(2, SPEED_NORMAL) + p.set_can_speed_kbps(3, SPEED_GMLAN) + + # set gmlan on CAN2 + for bus in [Panda.GMLAN_CAN2, Panda.GMLAN_CAN3, Panda.GMLAN_CAN2, Panda.GMLAN_CAN3]: + p.set_gmlan(bus) + comp_kbps_gmlan = time_many_sends(p, 3) + assert_greater(comp_kbps_gmlan, 0.8 * SPEED_GMLAN) + assert_less(comp_kbps_gmlan, 1.0 * SPEED_GMLAN) + + p.set_gmlan(None) + comp_kbps_normal = time_many_sends(p, bus) + assert_greater(comp_kbps_normal, 0.8 * SPEED_NORMAL) + assert_less(comp_kbps_normal, 1.0 * SPEED_NORMAL) + + print("%d: %.2f kbps vs %.2f kbps" % (bus, comp_kbps_gmlan, comp_kbps_normal)) + +def test_gmlan_bad_toggle(): + p = connect_wo_esp() + + if p.legacy: + return + + # enable output mode + p.set_safety_mode(Panda.SAFETY_ALLOUTPUT) + + # enable CAN loopback mode + p.set_can_loopback(True) + + # GMLAN_CAN2 + for bus in [Panda.GMLAN_CAN2, Panda.GMLAN_CAN3]: + p.set_gmlan(bus) + comp_kbps_gmlan = time_many_sends(p, 3) + assert_greater(comp_kbps_gmlan, 0.6 * SPEED_GMLAN) + assert_less(comp_kbps_gmlan, 1.0 * SPEED_GMLAN) + + # normal + for bus in [Panda.GMLAN_CAN2, Panda.GMLAN_CAN3]: + p.set_gmlan(None) + comp_kbps_normal = time_many_sends(p, bus) + assert_greater(comp_kbps_normal, 0.6 * SPEED_NORMAL) + assert_less(comp_kbps_normal, 1.0 * SPEED_NORMAL) + + +# this will fail if you have hardware serial connected +def test_serial_debug(): + p = connect_wo_esp() + junk = p.serial_read(Panda.SERIAL_DEBUG) + p.call_control_api(0xc0) + assert(p.serial_read(Panda.SERIAL_DEBUG).startswith("can ")) + diff --git a/panda/tests/automated/3_wifi.py b/panda/tests/automated/3_wifi.py new file mode 100644 index 00000000000000..c6f4154ba8eaec --- /dev/null +++ b/panda/tests/automated/3_wifi.py @@ -0,0 +1,33 @@ +from __future__ import print_function +import os +from panda import Panda +from helpers import connect_wifi +import requests + +def test_get_serial(): + p = Panda() + print(p.get_serial()) + +def test_get_serial_in_flash_mode(): + p = Panda() + p.reset(enter_bootstub=True) + assert(p.bootstub) + print(p.get_serial()) + p.reset() + +def test_connect_wifi(): + connect_wifi() + +def test_flash_wifi(): + Panda.flash_ota_wifi() + connect_wifi() + +def test_wifi_flash_st(): + Panda.flash_ota_st() + +def test_webpage_fetch(): + r = requests.get("http://192.168.0.10/") + print(r.text) + + assert "This is your comma.ai panda" in r.text + diff --git a/panda/tests/automated/4_wifi_functionality.py b/panda/tests/automated/4_wifi_functionality.py new file mode 100644 index 00000000000000..68686008e3373f --- /dev/null +++ b/panda/tests/automated/4_wifi_functionality.py @@ -0,0 +1,52 @@ +from __future__ import print_function +import time +from panda import Panda +from helpers import time_many_sends, connect_wifi +from nose.tools import timed, assert_equal, assert_less, assert_greater + +def test_get_serial_wifi(): + connect_wifi() + + p = Panda("WIFI") + print(p.get_serial()) + +def test_throughput(): + p = Panda() + + # enable output mode + p.set_safety_mode(Panda.SAFETY_ALLOUTPUT) + + # enable CAN loopback mode + p.set_can_loopback(True) + + p = Panda("WIFI") + + for speed in [100,250,500,750,1000]: + # set bus 0 speed to speed + p.set_can_speed_kbps(0, speed) + time.sleep(0.05) + + comp_kbps = time_many_sends(p, 0) + + # bit count from https://en.wikipedia.org/wiki/CAN_bus + saturation_pct = (comp_kbps/speed) * 100.0 + #assert_greater(saturation_pct, 80) + #assert_less(saturation_pct, 100) + + print("WIFI loopback 100 messages at speed %d, comp speed is %.2f, percent %.2f" % (speed, comp_kbps, saturation_pct)) + +def test_recv_only(): + p = Panda() + p.set_safety_mode(Panda.SAFETY_ALLOUTPUT) + p.set_can_loopback(True) + pwifi = Panda("WIFI") + + # TODO: msg_count=1000 drops packets, is this fixable? + for msg_count in [10,100,200]: + speed = 500 + p.set_can_speed_kbps(0, speed) + comp_kbps = time_many_sends(p, 0, pwifi, msg_count) + saturation_pct = (comp_kbps/speed) * 100.0 + + print("HT WIFI loopback %d messages at speed %d, comp speed is %.2f, percent %.2f" % (msg_count, speed, comp_kbps, saturation_pct)) + diff --git a/panda/tests/automated/5_wifi_udp.py b/panda/tests/automated/5_wifi_udp.py new file mode 100644 index 00000000000000..7d6ccba660b645 --- /dev/null +++ b/panda/tests/automated/5_wifi_udp.py @@ -0,0 +1,39 @@ +from __future__ import print_function +import sys +import time +from helpers import time_many_sends, connect_wifi +from panda import Panda, PandaWifiStreaming +from nose.tools import timed, assert_equal, assert_less, assert_greater + +def test_udp_doesnt_drop(): + connect_wifi() + + p = Panda() + p.set_safety_mode(Panda.SAFETY_ALLOUTPUT) + p.set_can_loopback(True) + + pwifi = PandaWifiStreaming() + while 1: + if len(pwifi.can_recv()) == 0: + break + + for msg_count in [1, 100]: + for i in range({1: 0x80, 100: 0x20}[msg_count]): + pwifi.kick() + + speed = 500 + p.set_can_speed_kbps(0, speed) + comp_kbps = time_many_sends(p, 0, pwifi, msg_count=msg_count, msg_id=0x100+i) + saturation_pct = (comp_kbps/speed) * 100.0 + + if msg_count == 1: + sys.stdout.write(".") + sys.stdout.flush() + else: + print("UDP WIFI loopback %d messages at speed %d, comp speed is %.2f, percent %.2f" % (msg_count, speed, comp_kbps, saturation_pct)) + assert_greater(saturation_pct, 40) + assert_less(saturation_pct, 100) + print("") + + + diff --git a/panda/tests/automated/__init__.py b/panda/tests/automated/__init__.py new file mode 100644 index 00000000000000..e69de29bb2d1d6 diff --git a/panda/tests/automated/helpers.py b/panda/tests/automated/helpers.py new file mode 100644 index 00000000000000..1ddced117980ee --- /dev/null +++ b/panda/tests/automated/helpers.py @@ -0,0 +1,95 @@ +import os +import sys +import time +import random +import subprocess +import requests +from panda import Panda +from nose.tools import timed, assert_equal, assert_less, assert_greater + +def connect_wo_esp(): + # connect to the panda + p = Panda() + + # power down the ESP + p.set_esp_power(False) + + # clear old junk + while len(p.can_recv()) > 0: + pass + + return p + +def connect_wifi(): + p = Panda() + dongle_id, pw = p.get_serial() + assert(dongle_id.isalnum()) + _connect_wifi(dongle_id, pw) + +def _connect_wifi(dongle_id, pw, insecure_okay=False): + ssid = str("panda-" + dongle_id) + + print("WIFI: connecting to %s" % ssid) + + while 1: + if sys.platform == "darwin": + os.system("networksetup -setairportnetwork en0 %s %s" % (ssid, pw)) + else: + wlan_interface = subprocess.check_output(["sh", "-c", "iw dev | awk '/Interface/ {print $2}'"]).strip() + cnt = 0 + MAX_TRIES = 10 + while cnt < MAX_TRIES: + print "WIFI: scanning %d" % cnt + os.system("sudo iwlist %s scanning > /dev/null" % wlan_interface) + os.system("nmcli device wifi rescan") + wifi_scan = filter(lambda x: ssid in x, subprocess.check_output(["nmcli","dev", "wifi", "list"]).split("\n")) + if len(wifi_scan) != 0: + break + time.sleep(0.1) + # MAX_TRIES tries, ~10 seconds max + cnt += 1 + assert cnt < MAX_TRIES + if "-pair" in wifi_scan[0]: + os.system("nmcli d wifi connect %s-pair" % (ssid)) + if insecure_okay: + break + # fetch webpage + print "connecting to insecure network to secure" + r = requests.get("http://192.168.0.10/") + assert r.status_code==200 + + print "securing" + try: + r = requests.get("http://192.168.0.10/secure", timeout=0.01) + except requests.exceptions.Timeout: + pass + else: + os.system("nmcli d wifi connect %s password %s" % (ssid, pw)) + break + + # TODO: confirm that it's connected to the right panda + +def time_many_sends(p, bus, precv=None, msg_count=100, msg_id=None): + if precv == None: + precv = p + if msg_id == None: + msg_id = random.randint(0x100, 0x200) + + st = time.time() + p.can_send_many([(msg_id, 0, "\xaa"*8, bus)]*msg_count) + r = [] + + while len(r) < (msg_count*2) and (time.time() - st) < 3: + r.extend(precv.can_recv()) + + sent_echo = filter(lambda x: x[3] == 0x80 | bus and x[0] == msg_id, r) + loopback_resp = filter(lambda x: x[3] == bus and x[0] == msg_id, r) + + assert_equal(len(sent_echo), msg_count) + assert_equal(len(loopback_resp), msg_count) + + et = (time.time()-st)*1000.0 + comp_kbps = (1+11+1+1+1+4+8*8+15+1+1+1+7)*msg_count / et + + return comp_kbps + diff --git a/panda/tests/build/Dockerfile b/panda/tests/build/Dockerfile new file mode 100644 index 00000000000000..276a25ed0b9495 --- /dev/null +++ b/panda/tests/build/Dockerfile @@ -0,0 +1,17 @@ +FROM ubuntu:16.04 + +RUN apt-get update && apt-get install -y gcc-arm-none-eabi libnewlib-arm-none-eabi python python-pip gcc g++ git autoconf gperf bison flex automake texinfo wget help2man gawk libtool libtool-bin ncurses-dev unzip unrar-free libexpat-dev sed bzip2 + +RUN pip install pycrypto==2.6.1 + +# Build esp toolchain +RUN mkdir -p /panda/boardesp +WORKDIR /panda/boardesp +RUN git clone --recursive https://github.com/pfalcon/esp-open-sdk.git +WORKDIR /panda/boardesp/esp-open-sdk +RUN git checkout 03f5e898a059451ec5f3de30e7feff30455f7ce +RUN CT_ALLOW_BUILD_AS_ROOT_SURE=1 make STANDALONE=y + +COPY . /panda + +WORKDIR /panda diff --git a/panda/tests/can_printer.py b/panda/tests/can_printer.py new file mode 100755 index 00000000000000..e863889c16424b --- /dev/null +++ b/panda/tests/can_printer.py @@ -0,0 +1,39 @@ +#!/usr/bin/env python +from __future__ import print_function +import os +import sys +import time +from collections import defaultdict +import binascii + +sys.path.append(os.path.join(os.path.dirname(os.path.realpath(__file__)), "..")) +from panda import Panda + +# fake +def sec_since_boot(): + return time.time() + +def can_printer(): + p = Panda() + p.set_safety_mode(0x1337) + + start = sec_since_boot() + lp = sec_since_boot() + msgs = defaultdict(list) + canbus = int(os.getenv("CAN", 0)) + while True: + can_recv = p.can_recv() + for address, _, dat, src in can_recv: + if src == canbus: + msgs[address].append(dat) + + if sec_since_boot() - lp > 0.1: + dd = chr(27) + "[2J" + dd += "%5.2f\n" % (sec_since_boot() - start) + for k,v in sorted(zip(msgs.keys(), map(lambda x: binascii.hexlify(x[-1]), msgs.values()))): + dd += "%s(%6d) %s\n" % ("%04X(%4d)" % (k,k),len(msgs[k]), v) + print(dd) + lp = sec_since_boot() + +if __name__ == "__main__": + can_printer() diff --git a/panda/tests/debug_console.py b/panda/tests/debug_console.py new file mode 100755 index 00000000000000..f4db77f091e0da --- /dev/null +++ b/panda/tests/debug_console.py @@ -0,0 +1,41 @@ +#!/usr/bin/env python +from __future__ import print_function +import os +import sys +import time +import select + +sys.path.append(os.path.join(os.path.dirname(os.path.realpath(__file__)), "..")) +from panda import Panda + +setcolor = ["\033[1;32;40m", "\033[1;31;40m"] +unsetcolor = "\033[00m" + +if __name__ == "__main__": + port_number = int(os.getenv("PORT", 0)) + claim = os.getenv("CLAIM") is not None + + serials = Panda.list() + if os.getenv("SERIAL"): + serials = filter(lambda x: x==os.getenv("SERIAL"), serials) + + pandas = list(map(lambda x: Panda(x, claim=claim), serials)) + + if os.getenv("BAUD") is not None: + for panda in pandas: + panda.set_uart_baud(port_number, int(os.getenv("BAUD"))) + + while True: + for i, panda in enumerate(pandas): + while True: + ret = panda.serial_read(port_number) + if len(ret) > 0: + sys.stdout.write(setcolor[i] + str(ret) + unsetcolor) + sys.stdout.flush() + else: + break + if select.select([sys.stdin], [], [], 0) == ([sys.stdin], [], []): + ln = sys.stdin.readline() + if claim: + panda.serial_write(port_number, ln) + time.sleep(0.01) diff --git a/panda/tests/disable_esp.py b/panda/tests/disable_esp.py new file mode 100755 index 00000000000000..abebd9c17b8a5d --- /dev/null +++ b/panda/tests/disable_esp.py @@ -0,0 +1,4 @@ +#!/usr/bin/env python +from panda import Panda +Panda().set_esp_power(False) + diff --git a/panda/tests/elm_car_simulator.py b/panda/tests/elm_car_simulator.py new file mode 100755 index 00000000000000..f931e66ff40999 --- /dev/null +++ b/panda/tests/elm_car_simulator.py @@ -0,0 +1,325 @@ +#!/usr/bin/env python +"""Used to Reverse/Test ELM protocol auto detect and OBD message response without a car.""" +from __future__ import print_function +import sys +import os +import struct +import binascii +import time +import threading +from collections import deque + +sys.path.append(os.path.join(os.path.dirname(os.path.realpath(__file__)), "..")) +from panda import Panda + +def lin_checksum(dat): + return sum(dat) % 0x100 + +class ELMCarSimulator(): + def __init__(self, sn, silent=False, can_kbaud=500, + can=True, can11b=True, can29b=True, + lin=True): + self.__p = Panda(sn if sn else Panda.list()[0]) + self.__on = True + self.__stop = False + self.__silent = silent + + self.__lin_timer = None + self.__lin_active = False + self.__lin_enable = lin + self.__lin_monitor_thread = threading.Thread(target=self.__lin_monitor) + + self.__can_multipart_data = None + self.__can_kbaud = can_kbaud + self.__can_extra_noise_msgs = deque() + self.__can_enable = can + self.__can11b = can11b + self.__can29b = can29b + self.__can_monitor_thread = threading.Thread(target=self.__can_monitor) + + @property + def panda(self): + return self.__p + + def stop(self): + if self.__lin_timer: + self.__lin_timer.cancel() + self.__lin_timeout_handler() + + self.__stop = True + + def join(self): + if self.__lin_monitor_thread.is_alive(): + self.__lin_monitor_thread.join() + if self.__can_monitor_thread.is_alive(): + self.__can_monitor_thread.join() + if self.__p: + print("closing handle") + self.__p.close() + + def set_enable(self, on): + self.__on = on + + def start(self): + self.panda.set_safety_mode(Panda.SAFETY_ALLOUTPUT) + if self.__lin_enable: + self.__lin_monitor_thread.start() + if self.__can_enable: + self.__can_monitor_thread.start() + + ######################### + # LIN related functions # + ######################### + + def __lin_monitor(self): + print("STARTING LIN THREAD") + self.panda.set_uart_baud(2, 10400) + self.panda.kline_drain() # Toss whatever was already there + + lin_buff = bytearray() + + while not self.__stop: + lin_msg = self.panda.serial_read(2) + if not lin_msg: + continue + + lin_buff += lin_msg + #print(" ** Buff", lin_buff) + if lin_buff.endswith(b'\x00\xc1\x33\xf1\x81\x66'): # Leading 0 is wakeup + lin_buff = bytearray() + self.__lin_active = True + print("GOT LIN (KWP FAST) WAKEUP SIGNAL") + self._lin_send(0x10, b'\xC1\x8F\xE9') + self.__reset_lin_timeout() + continue + if self.__lin_active: + msglen = lin_buff[0] & 0x7 + if lin_buff[0] & 0xF8 not in (0x80, 0xC0): + print("Invalid bytes at start of message") + print(" BUFF", lin_buff) + continue + if len(lin_buff) < msglen + 4: continue + if lin_checksum(lin_buff[:-1]) != lin_buff[-1]: continue + self.__lin_process_msg(lin_buff[0] & 0xF8, #Priority + lin_buff[1], lin_buff[2], lin_buff[3:-1]) + lin_buff = bytearray() + + def _lin_send(self, to_addr, msg): + if not self.__silent: + print(" LIN Reply (%x)" % to_addr, binascii.hexlify(msg)) + + PHYS_ADDR = 0x80 + FUNC_ADDR = 0xC0 + RECV = 0xF1 + SEND = 0x33 # Car OBD Functional Address + headers = struct.pack("BBB", PHYS_ADDR | len(msg), RECV, to_addr) + if not self.__silent: + print(" Sending LIN", binascii.hexlify(headers+msg), + hex(sum(bytearray(headers+msg))%0x100)) + self.panda.kline_send(headers + msg) + + def __reset_lin_timeout(self): + if self.__lin_timer: + self.__lin_timer.cancel() + self.__lin_timer = threading.Timer(5, self.__lin_timeout_handler) + self.__lin_timer.start() + + def __lin_timeout_handler(self): + print("LIN TIMEOUT") + self.__lin_timer = None + self.__lin_active = False + + @property + def lin_active(self): + return self.__lin_active + + def __lin_process_msg(self, priority, toaddr, fromaddr, data): + self.__reset_lin_timeout() + + if not self.__silent and data != b'\x3E': + print("LIN MSG", "Addr:", hex(toaddr), "obdLen:", len(data), + binascii.hexlify(data)) + + outmsg = None + #if data == b'\x3E': + # print("KEEP ALIVE") + #el + if len(data) > 1: + outmsg = self._process_obd(data[0], data[1]) + + if outmsg: + obd_header = struct.pack("BB", 0x40 | data[0], data[1]) + if len(outmsg) <= 5: + self._lin_send(0x10, obd_header + outmsg) + else: + first_msg_len = min(4, len(outmsg)%4) or 4 + self._lin_send(0x10, obd_header + b'\x01' + + b'\x00'*(4-first_msg_len) + + outmsg[:first_msg_len]) + + for num, i in enumerate(range(first_msg_len, len(outmsg), 4)): + self._lin_send(0x10, obd_header + + struct.pack('B', (num+2)%0x100) + outmsg[i:i+4]) + + ######################### + # CAN related functions # + ######################### + + def __can_monitor(self): + print("STARTING CAN THREAD") + self.panda.set_can_speed_kbps(0, self.__can_kbaud) + self.panda.can_recv() # Toss whatever was already there + + while not self.__stop: + for address, ts, data, src in self.panda.can_recv(): + if self.__on and src is 0 and len(data) == 8 and data[0] >= 2: + if not self.__silent: + print("Processing CAN message", src, hex(address), binascii.hexlify(data)) + self.__can_process_msg(data[1], data[2], address, ts, data, src) + elif not self.__silent: + print("Rejecting CAN message", src, hex(address), binascii.hexlify(data)) + + def can_mode_11b(self): + self.__can11b = True + self.__can29b = False + + def can_mode_29b(self): + self.__can11b = False + self.__can29b = True + + def can_mode_11b_29b(self): + self.__can11b = True + self.__can29b = True + + def change_can_baud(self, kbaud): + self.__can_kbaud = kbaud + self.panda.set_can_speed_kbps(0, self.__can_kbaud) + + def can_add_extra_noise(self, noise_msg, addr=None): + self.__can_extra_noise_msgs.append((addr, noise_msg)) + + def _can_send(self, addr, msg): + if not self.__silent: + print(" CAN Reply (%x)" % addr, binascii.hexlify(msg)) + self.panda.can_send(addr, msg + b'\x00'*(8-len(msg)), 0) + if self.__can_extra_noise_msgs: + noise = self.__can_extra_noise_msgs.popleft() + self.panda.can_send(noise[0] if noise[0] is not None else addr, + noise[1] + b'\x00'*(8-len(noise[1])), 0) + + def _can_addr_matches(self, addr): + if self.__can11b and (addr == 0x7DF or (addr & 0x7F8) == 0x7E0): + return True + if self.__can29b and (addr == 0x18db33f1 or (addr & 0x1FFF00FF) == 0x18da00f1): + return True + return False + + def __can_process_msg(self, mode, pid, address, ts, data, src): + if not self.__silent: + print("CAN MSG", binascii.hexlify(data[1:1+data[0]]), + "Addr:", hex(address), "Mode:", hex(mode)[2:].zfill(2), + "PID:", hex(pid)[2:].zfill(2), "canLen:", len(data), + binascii.hexlify(data)) + + if self._can_addr_matches(address) and len(data) == 8: + outmsg = None + if data[:3] == b'\x30\x00\x00' and len(self.__can_multipart_data): + if not self.__silent: + print("Request for more data"); + outaddr = 0x7E8 if address == 0x7DF or address == 0x7E0 else 0x18DAF110 + msgnum = 1 + while(self.__can_multipart_data): + datalen = min(7, len(self.__can_multipart_data)) + msgpiece = struct.pack("B", 0x20 | msgnum) + self.__can_multipart_data[:datalen] + self._can_send(outaddr, msgpiece) + self.__can_multipart_data = self.__can_multipart_data[7:] + msgnum = (msgnum+1)%0x10 + time.sleep(0.01) + + else: + outmsg = self._process_obd(mode, pid) + + if outmsg: + outaddr = 0x7E8 if address == 0x7DF or address == 0x7E0 else 0x18DAF110 + + if len(outmsg) <= 5: + self._can_send(outaddr, + struct.pack("BBB", len(outmsg)+2, 0x40|data[1], pid) + outmsg) + else: + first_msg_len = min(3, len(outmsg)%7) + payload_len = len(outmsg)+3 + msgpiece = struct.pack("BBBBB", 0x10 | ((payload_len>>8)&0xF), + payload_len&0xFF, + 0x40|data[1], pid, 1) + outmsg[:first_msg_len] + self._can_send(outaddr, msgpiece) + self.__can_multipart_data = outmsg[first_msg_len:] + + ######################### + # General OBD functions # + ######################### + + def _process_obd(self, mode, pid): + if mode == 0x01: # Mode: Show current data + if pid == 0x00: #List supported things + return b"\xff\xff\xff\xfe"#b"\xBE\x1F\xB8\x10" #Bitfield, random features + elif pid == 0x01: # Monitor Status since DTC cleared + return b"\x00\x00\x00\x00" #Bitfield, random features + elif pid == 0x04: # Calculated engine load + return b"\x2f" + elif pid == 0x05: # Engine coolant temperature + return b"\x3c" + elif pid == 0x0B: # Intake manifold absolute pressure + return b"\x90" + elif pid == 0x0C: # Engine RPM + return b"\x1A\xF8" + elif pid == 0x0D: # Vehicle Speed + return b"\x53" + elif pid == 0x10: # MAF air flow rate + return b"\x01\xA0" + elif pid == 0x11: # Throttle Position + return b"\x90" + elif pid == 0x33: # Absolute Barometric Pressure + return b"\x90" + elif mode == 0x09: # Mode: Request vehicle information + if pid == 0x02: # Show VIN + return b"1D4GP00R55B123456" + if pid == 0xFC: # test long multi message. Ligned up for LIN responses + return b''.join((struct.pack(">BBH", 0xAA, 0xAA, num+1) for num in range(80))) + if pid == 0xFD: # test long multi message + parts = (b'\xAA\xAA\xAA' + struct.pack(">I", num) for num in range(80)) + return b'\xAA\xAA\xAA' + b''.join(parts) + if pid == 0xFE: # test very long multi message + parts = (b'\xAA\xAA\xAA' + struct.pack(">I", num) for num in range(584)) + return b'\xAA\xAA\xAA' + b''.join(parts) + b'\xAA' + if pid == 0xFF: + return b'\xAA\x00\x00' +\ + b"".join(((b'\xAA'*5)+struct.pack(">H", num+1) for num in range(584))) + #return b"\xAA"*100#(0xFFF-3) + + +if __name__ == "__main__": + serial = os.getenv("SERIAL") if os.getenv("SERIAL") else None + kbaud = int(os.getenv("CANKBAUD")) if os.getenv("CANKBAUD") else 500 + bitwidth = int(os.getenv("CANBITWIDTH")) if os.getenv("CANBITWIDTH") else 0 + canenable = bool(int(os.getenv("CANENABLE"))) if os.getenv("CANENABLE") else True + linenable = bool(int(os.getenv("LINENABLE"))) if os.getenv("LINENABLE") else True + sim = ELMCarSimulator(serial, can_kbaud=kbaud, can=canenable, lin=linenable) + if(bitwidth == 0): + sim.can_mode_11b_29b() + if(bitwidth == 11): + sim.can_mode_11b() + if(bitwidth == 29): + sim.can_mode_29b() + + import signal + def signal_handler(signal, frame): + print('\nShutting down simulator') + sim.stop() + sim.join() + sys.exit(0) + + signal.signal(signal.SIGINT, signal_handler) + + sim.start() + + signal.pause() diff --git a/panda/tests/elm_throughput.py b/panda/tests/elm_throughput.py new file mode 100755 index 00000000000000..39625728899a74 --- /dev/null +++ b/panda/tests/elm_throughput.py @@ -0,0 +1,46 @@ +#!/usr/bin/env python +from __future__ import print_function +import socket +import threading +import select + +class Reader(threading.Thread): + def __init__(self, s, *args, **kwargs): + super(Reader, self).__init__(*args, **kwargs) + self._s = s + self.__stop = False + + def stop(self): + self.__stop = True + + def run(self): + while not self.__stop: + s.recv(1000) + +def read_or_fail(s): + ready = select.select([s], [], [], 4) + assert ready[0], "Socket did not receive data within the timeout duration." + return s.recv(1000) + +def send_msg(s, msg): + s.send(msg) + res = b'' + while not res.endswith(">"): + res += read_or_fail(s) + return res + +if __name__ == "__main__": + s = socket.create_connection(("192.168.0.10", 35000)) + #t1 = Reader(s) + #t1.start() + send_msg(s, b"ATZ\r") + send_msg(s, b"ATL1\r") + print(send_msg(s, b"ATE0\r")) + print(send_msg(s, b"ATS0\r")) + print(send_msg(s, b"ATSP6\r")) + + print("\nLOOP\n") + + while True: + print(send_msg(s, b"0100\r")) + print(send_msg(s, b"010d\r")) diff --git a/panda/tests/elm_wifi.py b/panda/tests/elm_wifi.py new file mode 100644 index 00000000000000..f5a8849833df60 --- /dev/null +++ b/panda/tests/elm_wifi.py @@ -0,0 +1,669 @@ +from __future__ import print_function +import os +import sys +import time +import socket +import select +import pytest +import struct + +sys.path.append(os.path.join(os.path.dirname(os.path.realpath(__file__)), "..")) +import elm_car_simulator +sys.path.append(os.path.join(os.path.dirname(os.path.realpath(__file__)), "..", "..")) +from panda import Panda + +def elm_connect(): + s = socket.create_connection(("192.168.0.10", 35000)) + s.setblocking(0) + return s + +def read_or_fail(s): + ready = select.select([s], [], [], 4) + assert ready[0], "Socket did not receive data within the timeout duration." + return s.recv(1000) + +def sendrecv(s, dat): + s.send(dat) + return read_or_fail(s) + +def send_compare(s, dat, ret, timeout=4): + s.send(dat) + res = b'' + while ret.startswith(res) and ret != res: + print("Waiting") + ready = select.select([s], [], [], timeout) + if not ready[0]: + print("current recv data:", repr(res)) + break; + res += s.recv(1000) + #print("final recv data: '%s'" % repr(res)) + assert ret == res#, "Data does not agree (%s) (%s)"%(repr(ret), repr(res)) + +def sync_reset(s): + s.send("ATZ\r") + res = b'' + while not res.endswith("ELM327 v1.5\r\r>"): + res += read_or_fail(s) + print("Reset response is '%s'" % repr(res)) + +def test_reset(): + s = socket.create_connection(("192.168.0.10", 35000)) + s.setblocking(0) + + try: + sync_reset(s) + finally: + s.close() + +def test_elm_cli(): + s = elm_connect() + + try: + sync_reset(s) + + send_compare(s, b'ATI\r', b'ATI\rELM327 v1.5\r\r>') + + #Test Echo Off + #Expected to be misimplimentation, but this is how the reference device behaved. + send_compare(s, b'ATE0\r', b'ATE0\rOK\r\r>') #Here is the odd part + send_compare(s, b'ATE0\r', b'OK\r\r>') #Should prob show this immediately + send_compare(s, b'ATI\r', b'ELM327 v1.5\r\r>') + + #Test Newline On + send_compare(s, b'ATL1\r', b'OK\r\n\r\n>') + send_compare(s, b'ATI\r', b'ELM327 v1.5\r\n\r\n>') + send_compare(s, b'ATL0\r', b'OK\r\r>') + send_compare(s, b'ATI\r', b'ELM327 v1.5\r\r>') + + send_compare(s, b'ATI\r', b'ELM327 v1.5\r\r>') #Test repeat command no echo + send_compare(s, b'\r', b'ELM327 v1.5\r\r>') + + send_compare(s, b'aTi\r', b'ELM327 v1.5\r\r>') #Test different case + + send_compare(s, b' a T i\r', b'ELM327 v1.5\r\r>') #Test with white space + + send_compare(s, b'ATCATHAT\r', b'?\r\r>') #Test Invalid AT command + + send_compare(s, b'01 00 00 00 00 00 00 00\r', b'?\r\r>') #Test Invalid (too long) OBD command + send_compare(s, b'01 GZ\r', b'?\r\r>') #Test Invalid (Non hex chars) OBD command + finally: + s.close() + +def test_elm_setget_protocol(): + s = elm_connect() + + try: + sync_reset(s) + send_compare(s, b'ATE0\r', b'ATE0\rOK\r\r>') # Echo OFF + + send_compare(s, b'ATSP0\r', b"OK\r\r>") # Set auto + send_compare(s, b'ATDP\r', b"AUTO\r\r>") + send_compare(s, b'ATDPN\r', b"A0\r\r>") + + send_compare(s, b'ATSP6\r', b"OK\r\r>") # Set protocol + send_compare(s, b'ATDP\r', b"ISO 15765-4 (CAN 11/500)\r\r>") + send_compare(s, b'ATDPN\r', b"6\r\r>") + + send_compare(s, b'ATSPA6\r', b"OK\r\r>") # Set auto with protocol default + send_compare(s, b'ATDP\r', b"AUTO, ISO 15765-4 (CAN 11/500)\r\r>") + send_compare(s, b'ATDPN\r', b"A6\r\r>") + + send_compare(s, b'ATSP7\r', b"OK\r\r>") + send_compare(s, b'ATDP\r', b"ISO 15765-4 (CAN 29/500)\r\r>") + send_compare(s, b'ATDPN\r', b"7\r\r>") #Test Does not accept invalid protocols + send_compare(s, b'ATSPD\r', b"?\r\r>") + send_compare(s, b'ATDP\r', b"ISO 15765-4 (CAN 29/500)\r\r>") + send_compare(s, b'ATDPN\r', b"7\r\r>") + finally: + s.close() + +def test_elm_protocol_failure(): + s = elm_connect() + + try: + sync_reset(s) + send_compare(s, b'ATE0\r', b'ATE0\rOK\r\r>') # Echo OFF + + send_compare(s, b'ATSP0\r', b"OK\r\r>") + send_compare(s, b'0100\r', b"SEARCHING...\rUNABLE TO CONNECT\r\r>", timeout=10) + + send_compare(s, b'ATSP1\r', b"OK\r\r>") + send_compare(s, b'0100\r', b"NO DATA\r\r>") + + send_compare(s, b'ATSP2\r', b"OK\r\r>") + send_compare(s, b'0100\r', b"NO DATA\r\r>") + + send_compare(s, b'ATSP3\r', b"OK\r\r>") + send_compare(s, b'0100\r', b"BUS INIT: ...ERROR\r\r>") + + send_compare(s, b'ATSP4\r', b"OK\r\r>") + send_compare(s, b'0100\r', b"BUS INIT: ...ERROR\r\r>") + + send_compare(s, b'ATSP5\r', b"OK\r\r>") + send_compare(s, b'0100\r', b"BUS INIT: ERROR\r\r>") + + #send_compare(s, b'ATSP6\r', b"OK\r\r>") + #send_compare(s, b'0100\r', b"NO DATA\r\r>") + # + #send_compare(s, b'ATSP7\r', b"OK\r\r>") + #send_compare(s, b'0100\r', b"NO DATA\r\r>") + # + #send_compare(s, b'ATSP8\r', b"OK\r\r>") + #send_compare(s, b'0100\r', b"NO DATA\r\r>") + # + #send_compare(s, b'ATSP9\r', b"OK\r\r>") + #send_compare(s, b'0100\r', b"NO DATA\r\r>") + # + #send_compare(s, b'ATSPA\r', b"OK\r\r>") + #send_compare(s, b'0100\r', b"NO DATA\r\r>") + # + #send_compare(s, b'ATSPB\r', b"OK\r\r>") + #send_compare(s, b'0100\r', b"NO DATA\r\r>") + # + #send_compare(s, b'ATSPC\r', b"OK\r\r>") + #send_compare(s, b'0100\r', b"NO DATA\r\r>") + finally: + s.close() + +def test_elm_protocol_autodetect_ISO14230_KWP_FAST(): + s = elm_connect() + serial = os.getenv("CANSIMSERIAL") if os.getenv("CANSIMSERIAL") else None + sim = elm_car_simulator.ELMCarSimulator(serial, can=False)#, silent=True) + sim.start() + + try: + sync_reset(s) + send_compare(s, b'ATE0\r', b'ATE0\rOK\r\r>') # Echo OFF + send_compare(s, b'ATH0\r', b'OK\r\r>') # Headers ON + send_compare(s, b'ATS0\r', b"OK\r\r>") + + send_compare(s, b'ATSP0\r', b"OK\r\r>") + send_compare(s, b'010D\r', b"SEARCHING...\r410D53\r\r>", timeout=10) + send_compare(s, b'ATDPN\r', b"A5\r\r>") + finally: + sim.stop() + sim.join() + s.close() + +def test_elm_basic_send_lin(): + s = elm_connect() + serial = os.getenv("CANSIMSERIAL") if os.getenv("CANSIMSERIAL") else None + sim = elm_car_simulator.ELMCarSimulator(serial, can=False)#, silent=True) + sim.start() + + try: + sync_reset(s) + send_compare(s, b'ATSP5\r', b"ATSP5\rOK\r\r>") # Set Proto + + send_compare(s, b'ATE0\r', b'ATE0\rOK\r\r>') # Echo OFF + send_compare(s, b'0100\r', b"BUS INIT: OK\r41 00 FF FF FF FE \r\r>") + send_compare(s, b'010D\r', b"41 0D 53 \r\r>") + + send_compare(s, b'ATS0\r', b'OK\r\r>') # Spaces Off + send_compare(s, b'0100\r', b"4100FFFFFFFE\r\r>") + send_compare(s, b'010D\r', b"410D53\r\r>") + + send_compare(s, b'ATH1\r', b'OK\r\r>') # Spaces Off Headers On + send_compare(s, b'0100\r', b"86F1104100FFFFFFFEC3\r\r>") + send_compare(s, b'010D\r', b"83F110410D5325\r\r>") + + send_compare(s, b'ATS1\r', b'OK\r\r>') # Spaces On Headers On + send_compare(s, b'0100\r', b"86 F1 10 41 00 FF FF FF FE C3 \r\r>") + send_compare(s, b'010D\r', b"83 F1 10 41 0D 53 25 \r\r>") + + send_compare(s, b'1F00\r', b"NO DATA\r\r>") # Unhandled msg, no response. + + # Repeat last check to see if it still works after NO DATA was received + send_compare(s, b'0100\r', b"86 F1 10 41 00 FF FF FF FE C3 \r\r>") + send_compare(s, b'010D\r', b"83 F1 10 41 0D 53 25 \r\r>") + finally: + sim.stop() + sim.join() + s.close() + +def test_elm_send_lin_multiline_msg(): + s = elm_connect() + serial = os.getenv("CANSIMSERIAL") if os.getenv("CANSIMSERIAL") else None + sim = elm_car_simulator.ELMCarSimulator(serial, can=False) + sim.start() + + try: + sync_reset(s) + send_compare(s, b'ATE0\r', b'ATE0\rOK\r\r>') # Echo OFF + send_compare(s, b'ATSP5\r', b"OK\r\r>") # Set Proto + + send_compare(s, b'0902\r', # headers OFF, Spaces ON + b"BUS INIT: OK\r" + "49 02 01 00 00 00 31 \r" + "49 02 02 44 34 47 50 \r" + "49 02 03 30 30 52 35 \r" + "49 02 04 35 42 31 32 \r" + "49 02 05 33 34 35 36 \r\r>") + + send_compare(s, b'ATS0\r', b'OK\r\r>') # Spaces OFF + send_compare(s, b'0902\r', # Headers OFF, Spaces OFF + b"49020100000031\r" + "49020244344750\r" + "49020330305235\r" + "49020435423132\r" + "49020533343536\r\r>") + + send_compare(s, b'ATH1\r', b'OK\r\r>') # Headers ON + send_compare(s, b'0902\r', # Headers ON, Spaces OFF + b"87F1104902010000003105\r" + "87F11049020244344750E4\r" + "87F11049020330305235BD\r" + "87F11049020435423132B1\r" + "87F11049020533343536AA\r\r>") + + send_compare(s, b'ATS1\r', b'OK\r\r>') # Spaces ON + send_compare(s, b'0902\r', # Headers ON, Spaces ON + b"87 F1 10 49 02 01 00 00 00 31 05 \r" + "87 F1 10 49 02 02 44 34 47 50 E4 \r" + "87 F1 10 49 02 03 30 30 52 35 BD \r" + "87 F1 10 49 02 04 35 42 31 32 B1 \r" + "87 F1 10 49 02 05 33 34 35 36 AA \r\r>") + finally: + sim.stop() + sim.join() + s.close() + +def test_elm_send_lin_multiline_msg_throughput(): + s = elm_connect() + serial = os.getenv("CANSIMSERIAL") if os.getenv("CANSIMSERIAL") else None + sim = elm_car_simulator.ELMCarSimulator(serial, can=False, silent=True) + sim.start() + + try: + sync_reset(s) + send_compare(s, b'ATSP5\r', b"ATSP5\rOK\r\r>") # Set Proto + send_compare(s, b'ATE0\r', b'ATE0\rOK\r\r>') # Echo OFF + send_compare(s, b'ATS0\r', b'OK\r\r>') # Spaces OFF + send_compare(s, b'ATH0\r', b'OK\r\r>') # Headers OFF + + send_compare(s, b'09fc\r', # headers OFF, Spaces OFF + b"BUS INIT: OK\r" + + b''.join((b'49FC' + hex(num+1)[2:].upper().zfill(2) + + b'AAAA' + hex(num+1)[2:].upper().zfill(4) + b'\r' + for num in range(80))) + + b"\r>", + timeout=10 + ) + finally: + sim.stop() + sim.join() + s.close() + +def test_elm_panda_safety_mode_KWPFast(): + serial = os.getenv("CANSIMSERIAL") if os.getenv("CANSIMSERIAL") else None + p_car = Panda(serial) # Configure this so the messages will send + p_car.set_safety_mode(Panda.SAFETY_ALLOUTPUT) + p_car.kline_drain() + + p_elm = Panda("WIFI") + p_elm.set_safety_mode(0xE327); + + def get_checksum(dat): + result = 0 + result += sum(map(ord, dat)) if isinstance(b'dat', str) else sum(dat) + return struct.pack("B", result % 0x100) + + def timed_recv_check(p, bus, goodmsg): + t = time.time() + msg = bytearray() + + while time.time()-t < 0.5 and len(msg) != len(goodmsg): + msg += p._handle.controlRead(Panda.REQUEST_OUT, 0xe0, bus, 0, len(goodmsg)-len(msg)) + #print("Received", repr(msg)) + if msg == goodmsg: + return True + time.sleep(0.01) + return False + + def kline_send(p, x, bus=2): + p.kline_drain(bus=bus) + p._handle.bulkWrite(2, chr(bus).encode()+x) + return timed_recv_check(p, bus, x) + + def did_send(priority, toaddr, fromaddr, dat, bus=2, checkbyte=None): + msgout = struct.pack("BBB", priority | len(dat), toaddr, fromaddr) + dat + msgout += get_checksum(msgout) if checkbyte is None else checkbyte + print("Sending", hex(priority), hex(toaddr), hex(fromaddr), repr(msgout)) + + if not kline_send(p_elm, msgout, bus=bus): + return False + return timed_recv_check(p_car, bus, msgout) + + assert not did_send(0xC0, 0x33, 0xF1, b'\x01\x0F', bus=3) #wrong bus + assert not did_send(0xC0, 0x33, 0xF1, b'') #wrong length + assert not did_send(0xB0, 0x33, 0xF1, b'\x01\x0E') #bad priority + assert not did_send(0xC0, 0x00, 0xF1, b'\x01\x0D') #bad addr + assert not did_send(0xC0, 0x33, 0x00, b'\x01\x0C') #bad addr + + assert did_send(0xC0, 0x33, 0xF1, b'\x01\x0B') #good! (obd func req) + +def test_elm_lin_keepalive(): + s = elm_connect() + serial = os.getenv("CANSIMSERIAL") if os.getenv("CANSIMSERIAL") else None + sim = elm_car_simulator.ELMCarSimulator(serial, can=False, silent=True) + sim.start() + + try: + sync_reset(s) + send_compare(s, b'ATSP5\r', b"ATSP5\rOK\r\r>") # Set Proto + send_compare(s, b'ATE0\r', b'ATE0\rOK\r\r>') # Echo OFF + send_compare(s, b'ATS0\r', b'OK\r\r>') # Spaces OFF + send_compare(s, b'ATH0\r', b'OK\r\r>') # Headers OFF + + send_compare(s, b'0100\r', b"BUS INIT: OK\r4100FFFFFFFE\r\r>") + assert sim.lin_active + time.sleep(6) + assert sim.lin_active + + send_compare(s, b'ATPC\r', b"OK\r\r>") #STOP KEEPALIVE + assert sim.lin_active + time.sleep(6) + assert not sim.lin_active + + finally: + sim.stop() + sim.join() + s.close() + +#//////////// +def test_elm_protocol_autodetect_ISO15765(): + s = elm_connect() + serial = os.getenv("CANSIMSERIAL") if os.getenv("CANSIMSERIAL") else None + sim = elm_car_simulator.ELMCarSimulator(serial, lin=False, silent=True) + sim.start() + + try: + sync_reset(s) + send_compare(s, b'ATE0\r', b'ATE0\rOK\r\r>') # Echo OFF + send_compare(s, b'ATH1\r', b'OK\r\r>') # Headers ON + send_compare(s, b'ATS0\r', b"OK\r\r>") + + sim.can_mode_11b() + send_compare(s, b'ATSP0\r', b"OK\r\r>") + send_compare(s, b'010D\r', b"SEARCHING...\r7E803410D53\r\r>", timeout=10) + send_compare(s, b'ATDPN\r', b"A6\r\r>") + + sim.can_mode_29b() + send_compare(s, b'ATSP0\r', b"OK\r\r>") + send_compare(s, b'010D\r', b"SEARCHING...\r18DAF11003410D53\r\r>", timeout=10) + send_compare(s, b'ATDPN\r', b"A7\r\r>") + + sim.change_can_baud(250) + + sim.can_mode_11b() + send_compare(s, b'ATSP0\r', b"OK\r\r>") + send_compare(s, b'010D\r', b"SEARCHING...\r7E803410D53\r\r>", timeout=10) + send_compare(s, b'ATDPN\r', b"A8\r\r>") + + sim.can_mode_29b() + send_compare(s, b'ATSP0\r', b"OK\r\r>") + send_compare(s, b'010D\r', b"SEARCHING...\r18DAF11003410D53\r\r>", timeout=10) + send_compare(s, b'ATDPN\r', b"A9\r\r>") + finally: + sim.stop() + sim.join() + s.close() + +def test_elm_basic_send_can(): + s = elm_connect() + serial = os.getenv("CANSIMSERIAL") if os.getenv("CANSIMSERIAL") else None + sim = elm_car_simulator.ELMCarSimulator(serial, lin=False, silent=True) + sim.start() + + try: + sync_reset(s) + send_compare(s, b'ATSP6\r', b"ATSP6\rOK\r\r>") # Set Proto + + send_compare(s, b'ATE0\r', b'ATE0\rOK\r\r>') # Echo OFF + send_compare(s, b'0100\r', b"41 00 FF FF FF FE \r\r>") + send_compare(s, b'010D\r', b"41 0D 53 \r\r>") + + send_compare(s, b'ATS0\r', b'OK\r\r>') # Spaces Off + send_compare(s, b'0100\r', b"4100FFFFFFFE\r\r>") + send_compare(s, b'010D\r', b"410D53\r\r>") + + send_compare(s, b'ATH1\r', b'OK\r\r>') # Spaces Off Headers On + send_compare(s, b'0100\r', b"7E8064100FFFFFFFE\r\r>") + send_compare(s, b'010D\r', b"7E803410D53\r\r>") + + send_compare(s, b'ATS1\r', b'OK\r\r>') # Spaces On Headers On + send_compare(s, b'0100\r', b"7E8 06 41 00 FF FF FF FE \r\r>") + send_compare(s, b'010D\r', b"7E8 03 41 0D 53 \r\r>") + + send_compare(s, b'1F00\r', b"NO DATA\r\r>") # Unhandled msg, no response. + + # Repeat last check to see if it still works after NO DATA was received + send_compare(s, b'0100\r', b"7E8 06 41 00 FF FF FF FE \r\r>") + send_compare(s, b'010D\r', b"7E8 03 41 0D 53 \r\r>") + finally: + sim.stop() + sim.join() + s.close() + +def test_elm_send_can_multimsg(): + s = elm_connect() + serial = os.getenv("CANSIMSERIAL") if os.getenv("CANSIMSERIAL") else None + sim = elm_car_simulator.ELMCarSimulator(serial, lin=False) + sim.start() + + try: + sync_reset(s) + send_compare(s, b'ATE0\r', b'ATE0\rOK\r\r>') # Echo OFF + send_compare(s, b'ATS1\r', b'OK\r\r>') # Spaces OFF + send_compare(s, b'ATH1\r', b'OK\r\r>') # Headers ON + + send_compare(s, b'ATSP6\r', b"OK\r\r>") # Set Proto ISO 15765-4 (CAN 11/500) + sim.can_add_extra_noise(b'\x03\x41\x0D\xFA', addr=0x7E9)# Inject message into the stream + send_compare(s, b'010D\r', + b"7E8 03 41 0D 53 \r" + "7E9 03 41 0D FA \r\r>") # Check it was ignored. + finally: + sim.stop() + sim.join() + s.close() + +"""The ability to correctly filter out messages with the wrong PID is not +implemented correctly in the reference device.""" +def test_elm_can_check_mode_pid(): + s = elm_connect() + serial = os.getenv("CANSIMSERIAL") if os.getenv("CANSIMSERIAL") else None + sim = elm_car_simulator.ELMCarSimulator(serial, lin=False) + sim.start() + + try: + sync_reset(s) + send_compare(s, b'ATE0\r', b'ATE0\rOK\r\r>') # Echo OFF + send_compare(s, b'ATS0\r', b'OK\r\r>') # Spaces OFF + send_compare(s, b'ATH0\r', b'OK\r\r>') # Headers OFF + + send_compare(s, b'ATSP6\r', b"OK\r\r>") # Set Proto ISO 15765-4 (CAN 11/500) + sim.can_add_extra_noise(b'\x03\x41\x0E\xFA')# Inject message into the stream + send_compare(s, b'010D\r', b"410D53\r\r>") # Check it was ignored. + send_compare(s, b'0100\r', b"4100FFFFFFFE\r\r>") # Check it was ignored again. + finally: + sim.stop() + sim.join() + s.close() + +def test_elm_send_can_multiline_msg(): + s = elm_connect() + serial = os.getenv("CANSIMSERIAL") if os.getenv("CANSIMSERIAL") else None + sim = elm_car_simulator.ELMCarSimulator(serial, lin=False) + sim.start() + + try: + sync_reset(s) + send_compare(s, b'ATSP6\r', b"ATSP6\rOK\r\r>") # Set Proto + send_compare(s, b'ATE0\r', b'ATE0\rOK\r\r>') # Echo OFF + + send_compare(s, b'0902\r', # headers OFF, Spaces ON + b"014 \r" + "0: 49 02 01 31 44 34 \r" + "1: 47 50 30 30 52 35 35 \r" + "2: 42 31 32 33 34 35 36 \r\r>") + + send_compare(s, b'ATS0\r', b'OK\r\r>') # Spaces OFF + send_compare(s, b'0902\r', # Headers OFF, Spaces OFF + b"014\r" + "0:490201314434\r" + "1:47503030523535\r" + "2:42313233343536\r\r>") + + send_compare(s, b'ATH1\r', b'OK\r\r>') # Headers ON + send_compare(s, b'0902\r', # Headers ON, Spaces OFF + b"7E81014490201314434\r" + "7E82147503030523535\r" + "7E82242313233343536\r\r>") + + send_compare(s, b'ATS1\r', b'OK\r\r>') # Spaces ON + send_compare(s, b'0902\r', # Headers ON, Spaces ON + b"7E8 10 14 49 02 01 31 44 34 \r" + "7E8 21 47 50 30 30 52 35 35 \r" + "7E8 22 42 31 32 33 34 35 36 \r\r>") + finally: + sim.stop() + sim.join() + s.close() + +def test_elm_send_can_multiline_msg_throughput(): + s = elm_connect() + serial = os.getenv("CANSIMSERIAL") if os.getenv("CANSIMSERIAL") else None + sim = elm_car_simulator.ELMCarSimulator(serial, lin=False, silent=True) + sim.start() + + try: + sync_reset(s) + send_compare(s, b'ATSP6\r', b"ATSP6\rOK\r\r>") # Set Proto + send_compare(s, b'ATE0\r', b'ATE0\rOK\r\r>') # Echo OFF + send_compare(s, b'ATS0\r', b'OK\r\r>') # Spaces OFF + send_compare(s, b'ATH1\r', b'OK\r\r>') # Headers ON + + rows = 584 + send_compare(s, b'09ff\r', # headers ON, Spaces OFF + ("7E8" + "1" + hex((rows*7)+6)[2:].upper().zfill(3) + "49FF01"+"AA0000\r" + + "".join( + ("7E82"+hex((num+1)%0x10)[2:].upper()+("AA"*5) + + hex(num+1)[2:].upper().zfill(4) + "\r" for num in range(rows)) + ) + "\r>").encode(), + timeout=10 + ) + finally: + sim.stop() + sim.join() + s.close() + +def test_elm_interrupted_obd_cmd_resets_state(): + s = elm_connect() + serial = os.getenv("CANSIMSERIAL") if os.getenv("CANSIMSERIAL") else None + sim = elm_car_simulator.ELMCarSimulator(serial, lin=False, silent=True) + sim.start() + + try: + sync_reset(s) + send_compare(s, b'ATE0\r', b'ATE0\rOK\r\r>') # Echo OFF + send_compare(s, b'ATS0\r', b'OK\r\r>') # Spaces OFF + s.send(b"09fd\r") + ready = select.select([s], [], [], 4) + assert ready[0], "Socket did not receive data within the timeout duration." + s.send(b"ATI\r") + + assert b"236\r0:49FD01AAAAAA\r" in s.recv(10000) + + #Will likely have to be improved to scan for STOPPED if the FW gets more responsive. + ready = select.select([s], [], [], 4) + assert ready[0], "Socket did not receive data within the timeout duration." + + assert b"STOPPED" in s.recv(10000) + + sim.set_enable(False) + send_compare(s, b'09fd\r', b"NO DATA\r\r>") + finally: + sim.stop() + sim.join() + s.close() + +def test_elm_can_baud(): + s = elm_connect() + serial = os.getenv("CANSIMSERIAL") if os.getenv("CANSIMSERIAL") else None + sim = elm_car_simulator.ELMCarSimulator(serial, lin=False) + sim.start() + + try: + sync_reset(s) + send_compare(s, b'ATE0\r', b'ATE0\rOK\r\r>') # Echo OFF + send_compare(s, b'ATS0\r', b'OK\r\r>') # Spaces OFF + send_compare(s, b'ATH1\r', b'OK\r\r>') # Headers ON + + send_compare(s, b'ATSP6\r', b"OK\r\r>") # Set Proto ISO 15765-4 (CAN 11/500) + send_compare(s, b'0100\r', b"7E8064100FFFFFFFE\r\r>") + + send_compare(s, b'ATSP8\r', b"OK\r\r>") # Set Proto ISO 15765-4 (CAN 11/250) + send_compare(s, b'0100\r', b"CAN ERROR\r\r>") + + sim.change_can_baud(250) + + send_compare(s, b'ATSP6\r', b"OK\r\r>") # Set Proto ISO 15765-4 (CAN 11/500) + send_compare(s, b'0100\r', b"CAN ERROR\r\r>") + + send_compare(s, b'ATSP8\r', b"OK\r\r>") # Set Proto ISO 15765-4 (CAN 11/250) + send_compare(s, b'0100\r', b"7E8064100FFFFFFFE\r\r>") + finally: + sim.stop() + sim.join() + s.close() + +def test_elm_panda_safety_mode_ISO15765(): + s = elm_connect() + serial = os.getenv("CANSIMSERIAL") if os.getenv("CANSIMSERIAL") else None + p_car = Panda(serial) # Configure this so the messages will send + p_car.set_can_speed_kbps(0, 500) + p_car.set_safety_mode(Panda.SAFETY_ALLOUTPUT) + + p_elm = Panda("WIFI") + p_elm.set_safety_mode(0xE327); + + #sim = elm_car_simulator.ELMCarSimulator(serial, lin=False) + #sim.start() + + def did_send(p, addr, dat, bus): + p.can_send(addr, dat, bus) + t = time.time() + while time.time()-t < 0.5: + msg = p.can_recv() + for addrin, _, datin, busin in msg: + if (0x80 | bus) == busin and addr == addrin and datin == dat: + return True + time.sleep(0.01) + return False + + try: + sync_reset(s) # Reset elm (which requests the ELM327 safety mode) + + #29 bit + assert not did_send(p_elm, 0x18DB33F1, b'\x02\x01\x00\x00\x00\x00\x00\x00', 1) #wrong canid + assert not did_send(p_elm, 0x18DB33F1, b'\x02\x01\x00', 0) #wrong length + assert not did_send(p_elm, 0x10000000, b'\x02\x01\x00\x00\x00\x00\x00\x00', 0) #bad addr + assert not did_send(p_elm, 0x18DAF133, b'\x02\x01\x00\x00\x00\x00\x00\x00', 0) #bad addr (phy addr) + assert not did_send(p_elm, 0x18DAF000, b'\x02\x01\x00\x00\x00\x00\x00\x00', 0) #bad addr + assert not did_send(p_elm, 0x18DAF1F3, b'\x02\x01\x00\x00\x00\x00\x00\x00', 0) #bad addr! (phys rsp to elm) + + assert did_send(p_elm, 0x18DB33F1, b'\x02\x01\x00\x00\x00\x00\x00\x00', 0) #good! (obd func req) + assert did_send(p_elm, 0x18DA10F1, b'\x02\x01\x00\x00\x00\x00\x00\x00', 0) #good! (phys response) + + #11 bit + assert not did_send(p_elm, 0X7DF, b'\x02\x01\x00\x00\x00\x00\x00\x00', 1) #wrong canid + assert not did_send(p_elm, 0X7DF, b'\x02\x01\x00', 0) #wrong length + assert not did_send(p_elm, 0xAA, b'\x02\x01\x00\x00\x00\x00\x00\x00', 0) #bad addr + assert not did_send(p_elm, 0x7DA, b'\x02\x01\x00\x00\x00\x00\x00\x00', 0) #bad addr (phy addr) + assert not did_send(p_elm, 0x7E8, b'\x02\x01\x00\x00\x00\x00\x00\x00', 0) #bad addr (sending 'response') + + assert did_send(p_elm, 0x7DF, b'\x02\x01\x00\x00\x00\x00\x00\x00', 0) #good! (obd func req) + assert did_send(p_elm, 0x7E1, b'\x02\x01\x00\x00\x00\x00\x00\x00', 0) #good! (phys response) + + finally: + s.close() diff --git a/panda/tests/flashing_loop.sh b/panda/tests/flashing_loop.sh new file mode 100755 index 00000000000000..2eaf850c835c92 --- /dev/null +++ b/panda/tests/flashing_loop.sh @@ -0,0 +1,9 @@ +#!/bin/bash +cd ../board +make clean + +while true; do + make ota + sleep 10 +done + diff --git a/panda/tests/get_version.py b/panda/tests/get_version.py new file mode 100755 index 00000000000000..0cd7795fdcc71d --- /dev/null +++ b/panda/tests/get_version.py @@ -0,0 +1,9 @@ +#!/usr/bin/env python +from panda import Panda + +if __name__ == "__main__": + for p in Panda.list(): + pp = Panda(p) + print("%s: %s" % (pp.get_serial()[0], pp.get_version())) + + diff --git a/panda/tests/gmbitbang/recv.py b/panda/tests/gmbitbang/recv.py new file mode 100755 index 00000000000000..6eb70aa4ad3abb --- /dev/null +++ b/panda/tests/gmbitbang/recv.py @@ -0,0 +1,17 @@ +#!/usr/bin/env python +import time +from panda import Panda + +p = Panda() +p.set_safety_mode(Panda.SAFETY_ALLOUTPUT) +p.set_gmlan(bus=2) +#p.can_send(0xaaa, "\x00\x00", bus=3) +last_add = None +while 1: + ret = p.can_recv() + if len(ret) > 0: + add = ret[0][0] + if last_add is not None and add != last_add+1: + print "MISS %d %d" % (last_add, add) + last_add = add + print ret diff --git a/panda/tests/gmbitbang/rigol.py b/panda/tests/gmbitbang/rigol.py new file mode 100755 index 00000000000000..3d690fdd84c725 --- /dev/null +++ b/panda/tests/gmbitbang/rigol.py @@ -0,0 +1,35 @@ +#!/usr/bin/env python +import numpy as np +import visa +import matplotlib.pyplot as plt + +resources = visa.ResourceManager() +print resources.list_resources() + +scope = resources.open_resource('USB0::0x1AB1::0x04CE::DS1ZA184652242::INSTR', timeout=2000, chunk_size=1024000) +print(scope.query('*IDN?').strip()) + +#voltscale = scope.ask_for_values(':CHAN1:SCAL?')[0] +#voltoffset = scope.ask_for_values(":CHAN1:OFFS?")[0] + +#scope.write(":STOP") +scope.write(":WAV:POIN:MODE RAW") +scope.write(":WAV:DATA? CHAN1")[10:] +rawdata = scope.read_raw() +data = np.frombuffer(rawdata, 'B') +print data.shape + +s1 = data[0:650] +s2 = data[650:] +s1i = np.argmax(s1 > 100) +s2i = np.argmax(s2 > 100) +s1 = s1[s1i:] +s2 = s2[s2i:] + +plt.plot(s1) +plt.plot(s2) +plt.show() +#data = (data - 130.0 - voltoffset/voltscale*25) / 25 * voltscale + +print data + diff --git a/panda/tests/gmbitbang/test.py b/panda/tests/gmbitbang/test.py new file mode 100755 index 00000000000000..652ac1ddd8ad24 --- /dev/null +++ b/panda/tests/gmbitbang/test.py @@ -0,0 +1,33 @@ +#!/usr/bin/env python +import time +from panda import Panda + +p1 = Panda('380016000551363338383037') +p2 = Panda('430026000951363338383037') + +# this is a test, no safety +p1.set_safety_mode(Panda.SAFETY_ALLOUTPUT) +p2.set_safety_mode(Panda.SAFETY_ALLOUTPUT) + +# get versions +print(p1.get_version()) +print(p2.get_version()) + +# this sets bus 2 to actually be GMLAN +p2.set_gmlan(bus=2) + +# send w bitbang then without +#iden = 123 +iden = 18000 +#dat = "\x01\x02" +dat = "\x01\x02\x03\x04\x05\x06\x07\x08" +while 1: + iden += 1 + p1.set_gmlan(bus=None) + p1.can_send(iden, dat, bus=3) + #p1.set_gmlan(bus=2) + #p1.can_send(iden, dat, bus=3) + time.sleep(0.01) + print p2.can_recv() + #exit(0) + diff --git a/panda/tests/gmbitbang/test_one.py b/panda/tests/gmbitbang/test_one.py new file mode 100755 index 00000000000000..a398e2780385b1 --- /dev/null +++ b/panda/tests/gmbitbang/test_one.py @@ -0,0 +1,23 @@ +#!/usr/bin/env python +import time +from panda import Panda + +p = Panda() +p.set_safety_mode(Panda.SAFETY_ALLOUTPUT) + +# ack any crap on bus +p.set_gmlan(bus=2) +time.sleep(0.1) +while len(p.can_recv()) > 0: + print "clearing" + time.sleep(0.1) +print "cleared" +p.set_gmlan(bus=None) + +iden = 18000 +dat = "\x01\x02\x03\x04\x05\x06\x07\x08" +while 1: + iden += 1 + p.can_send(iden, dat, bus=3) + time.sleep(0.01) + diff --git a/panda/tests/gmbitbang/test_packer.c b/panda/tests/gmbitbang/test_packer.c new file mode 100644 index 00000000000000..f056dd48125d34 --- /dev/null +++ b/panda/tests/gmbitbang/test_packer.c @@ -0,0 +1,32 @@ +#include +#include + +typedef struct { + uint32_t RIR; /*!< CAN receive FIFO mailbox identifier register */ + uint32_t RDTR; /*!< CAN receive FIFO mailbox data length control and time stamp register */ + uint32_t RDLR; /*!< CAN receive FIFO mailbox data low register */ + uint32_t RDHR; /*!< CAN receive FIFO mailbox data high register */ +} CAN_FIFOMailBox_TypeDef; + +#include "../../board/drivers/canbitbang.h" + +int main() { + char out[300]; + CAN_FIFOMailBox_TypeDef to_bang = {0}; + to_bang.RIR = 20 << 21; + to_bang.RDTR = 1; + to_bang.RDLR = 1; + + int len = get_bit_message(out, &to_bang); + printf("T:"); + for (int i = 0; i < len; i++) { + printf("%d", out[i]); + } + printf("\n"); + printf("R:0000010010100000100010000010011110111010100111111111111111"); + printf("\n"); + return 0; +} + + + diff --git a/panda/tests/location_listener.py b/panda/tests/location_listener.py new file mode 100755 index 00000000000000..cbbb00d794f5e3 --- /dev/null +++ b/panda/tests/location_listener.py @@ -0,0 +1,47 @@ +#!/usr/bin/env python +import os +import time +import sys + +sys.path.append(os.path.join(os.path.dirname(os.path.realpath(__file__)), "..")) +from panda import Panda, PandaSerial + +def add_nmea_checksum(msg): + d = msg[1:] + cs = 0 + for i in d: + cs ^= ord(i) + return msg + "*%02X" % cs + +if __name__ == "__main__": + panda = Panda() + ser = PandaSerial(panda, 1, 9600) + + # power cycle by toggling reset + print "resetting" + panda.set_esp_power(0) + time.sleep(0.5) + panda.set_esp_power(1) + time.sleep(0.5) + print "done" + print ser.read(1024) + + # upping baud rate + baudrate = 460800 + + print "upping baud rate" + msg = add_nmea_checksum("$PUBX,41,1,0007,0003,%d,0" % baudrate)+"\r\n" + print msg + ser.write(msg) + time.sleep(0.1) # needs a wait for it to actually send + + # new panda serial + ser = PandaSerial(panda, 1, baudrate) + + while True: + ret = ser.read(1024) + if len(ret) > 0: + sys.stdout.write(ret) + sys.stdout.flush() + #print str(ret).encode("hex") + diff --git a/panda/tests/loopback_test.py b/panda/tests/loopback_test.py new file mode 100755 index 00000000000000..a871295ad6fd83 --- /dev/null +++ b/panda/tests/loopback_test.py @@ -0,0 +1,127 @@ +#!/usr/bin/env python +from __future__ import print_function +import os +import sys +import time +import random +import argparse + +from hexdump import hexdump +from itertools import permutations + +sys.path.append(os.path.join(os.path.dirname(os.path.realpath(__file__)), "..")) +from panda import Panda + +def get_test_string(): + return b"test"+os.urandom(10) + +def run_test(sleep_duration): + pandas = Panda.list() + print(pandas) + + if len(pandas) == 0: + print("NO PANDAS") + assert False + + if len(pandas) == 1: + # if we only have one on USB, assume the other is on wifi + pandas.append("WIFI") + run_test_w_pandas(pandas, sleep_duration) + +def run_test_w_pandas(pandas, sleep_duration): + h = list(map(lambda x: Panda(x), pandas)) + print("H", h) + + for hh in h: + hh.set_safety_mode(Panda.SAFETY_ALLOUTPUT) + + # test both directions + for ho in permutations(range(len(h)), r=2): + print("***************** TESTING", ho) + + panda0, panda1 = h[ho[0]], h[ho[1]] + + if(panda0._serial == "WIFI"): + print(" *** Can not send can data over wifi panda. Skipping! ***") + continue + + # **** test health packet **** + print("health", ho[0], h[ho[0]].health()) + + # **** test K/L line loopback **** + for bus in [2,3]: + # flush the output + h[ho[1]].kline_drain(bus=bus) + + # send the characters + st = get_test_string() + st = b"\xaa"+chr(len(st)+3).encode()+st + h[ho[0]].kline_send(st, bus=bus, checksum=False) + + # check for receive + ret = h[ho[1]].kline_drain(bus=bus) + + print("ST Data:") + hexdump(st) + print("RET Data:") + hexdump(ret) + assert st == ret + print("K/L pass", bus, ho, "\n") + time.sleep(sleep_duration) + + # **** test can line loopback **** + for bus, gmlan in [(0, False), (1, False), (2, False), (1, True), (2, True)]: + print("\ntest can", bus) + # flush + cans_echo = panda0.can_recv() + cans_loop = panda1.can_recv() + + panda0.set_gmlan(None) + panda1.set_gmlan(None) + + if gmlan is True: + panda0.set_gmlan(bus) + panda1.set_gmlan(bus) + bus = 3 + + # send the characters + at = random.randint(1, 2000) + st = get_test_string()[0:8] + panda0.can_send(at, st, bus) + time.sleep(0.1) + + # check for receive + cans_echo = panda0.can_recv() + cans_loop = panda1.can_recv() + + print("Bus", bus, "echo", cans_echo, "loop", cans_loop) + + assert len(cans_echo) == 1 + assert len(cans_loop) == 1 + + assert cans_echo[0][0] == at + assert cans_loop[0][0] == at + + assert cans_echo[0][2] == st + assert cans_loop[0][2] == st + + assert cans_echo[0][3] == 0x80 | bus + if cans_loop[0][3] != bus: + print("EXPECTED %d GOT %d" % (bus, cans_loop[0][3])) + assert cans_loop[0][3] == bus + + print("CAN pass", bus, ho) + time.sleep(sleep_duration) + +if __name__ == "__main__": + parser = argparse.ArgumentParser() + parser.add_argument("-n", type=int, help="Number of test iterations to run") + parser.add_argument("-sleep", type=int, help="Sleep time between tests", default=0) + args = parser.parse_args() + + if args.n is None: + while True: + run_test(sleep_duration=args.sleep) + else: + for i in range(args.n): + run_test(sleep_duration=args.sleep) diff --git a/panda/tests/pedal/enter_canloader.py b/panda/tests/pedal/enter_canloader.py new file mode 100755 index 00000000000000..c6f06ca35499a0 --- /dev/null +++ b/panda/tests/pedal/enter_canloader.py @@ -0,0 +1,76 @@ +#!/usr/bin/env python +import sys +import time +import struct +import argparse +import signal +from panda import Panda + +class CanHandle(object): + def __init__(self, p): + self.p = p + + def transact(self, dat): + #print "W:",dat.encode("hex") + self.p.isotp_send(1, dat, 0, recvaddr=2) + + def _handle_timeout(signum, frame): + # will happen on reset + raise Exception("timeout") + + signal.signal(signal.SIGALRM, _handle_timeout) + signal.alarm(1) + try: + ret = self.p.isotp_recv(2, 0, sendaddr=1) + finally: + signal.alarm(0) + + #print "R:",ret.encode("hex") + return ret + + def controlWrite(self, request_type, request, value, index, data, timeout=0): + # ignore data in reply, panda doesn't use it + return self.controlRead(request_type, request, value, index, 0, timeout) + + def controlRead(self, request_type, request, value, index, length, timeout=0): + dat = struct.pack("HHBBHHH", 0, 0, request_type, request, value, index, length) + return self.transact(dat) + + def bulkWrite(self, endpoint, data, timeout=0): + if len(data) > 0x10: + raise ValueError("Data must not be longer than 0x10") + dat = struct.pack("HH", endpoint, len(data))+data + return self.transact(dat) + + def bulkRead(self, endpoint, length, timeout=0): + dat = struct.pack("HH", endpoint, 0) + return self.transact(dat) + +if __name__ == "__main__": + parser = argparse.ArgumentParser(description='Flash pedal over can') + parser.add_argument('--recover', action='store_true') + parser.add_argument("fn", type=str, nargs='?', help="flash file") + args = parser.parse_args() + + p = Panda() + p.set_safety_mode(0x1337) + + while 1: + if len(p.can_recv()) == 0: + break + + if args.recover: + p.can_send(0x200, "\xce\xfa\xad\xde\x1e\x0b\xb0\x02", 0) + exit(0) + else: + p.can_send(0x200, "\xce\xfa\xad\xde\x1e\x0b\xb0\x0a", 0) + + if args.fn: + time.sleep(0.1) + print "flashing", args.fn + code = open(args.fn).read() + Panda.flash_static(CanHandle(p), code) + + print "can flash done" + + diff --git a/panda/tests/read_st_flash.sh b/panda/tests/read_st_flash.sh new file mode 100755 index 00000000000000..ffcfd7bbfe725b --- /dev/null +++ b/panda/tests/read_st_flash.sh @@ -0,0 +1,6 @@ +#!/bin/bash +rm -f /tmp/dump_bootstub +rm -f /tmp/dump_main +dfu-util -a 0 -s 0x08000000 -U /tmp/dump_bootstub +dfu-util -a 0 -s 0x08004000 -U /tmp/dump_main + diff --git a/panda/tests/read_winusb_descriptors.py b/panda/tests/read_winusb_descriptors.py new file mode 100644 index 00000000000000..e38df8d1caa9c3 --- /dev/null +++ b/panda/tests/read_winusb_descriptors.py @@ -0,0 +1,29 @@ +#!/usr/bin/env python +from panda import Panda +from hexdump import hexdump + +DEBUG = False + +if __name__ == "__main__": + p = Panda() + + len = p._handle.controlRead(Panda.REQUEST_IN, 0x06, 3 << 8 | 238, 0, 1) + print 'Microsoft OS String Descriptor' + dat = p._handle.controlRead(Panda.REQUEST_IN, 0x06, 3 << 8 | 238, 0, len[0]) + if DEBUG: print 'LEN: {}'.format(hex(len[0])) + hexdump("".join(map(chr, dat))) + + ms_vendor_code = dat[16] + if DEBUG: print 'MS_VENDOR_CODE: {}'.format(hex(len[0])) + + print '\nMicrosoft Compatible ID Feature Descriptor' + len = p._handle.controlRead(Panda.REQUEST_IN, ms_vendor_code, 0, 4, 1) + if DEBUG: print 'LEN: {}'.format(hex(len[0])) + dat = p._handle.controlRead(Panda.REQUEST_IN, ms_vendor_code, 0, 4, len[0]) + hexdump("".join(map(chr, dat))) + + print '\nMicrosoft Extended Properties Feature Descriptor' + len = p._handle.controlRead(Panda.REQUEST_IN, ms_vendor_code, 0, 5, 1) + if DEBUG: print 'LEN: {}'.format(hex(len[0])) + dat = p._handle.controlRead(Panda.REQUEST_IN, ms_vendor_code, 0, 5, len[0]) + hexdump("".join(map(chr, dat))) diff --git a/panda/tests/safety/Dockerfile b/panda/tests/safety/Dockerfile new file mode 100644 index 00000000000000..9381fdc4085759 --- /dev/null +++ b/panda/tests/safety/Dockerfile @@ -0,0 +1,6 @@ +FROM ubuntu:16.04 + +RUN apt-get update && apt-get install -y clang make python python-pip +COPY tests/safety/requirements.txt /panda/tests/safety/requirements.txt +RUN pip install -r /panda/tests/safety/requirements.txt +COPY . /panda diff --git a/panda/tests/safety/Makefile b/panda/tests/safety/Makefile new file mode 100644 index 00000000000000..334a29427d7d29 --- /dev/null +++ b/panda/tests/safety/Makefile @@ -0,0 +1,18 @@ +CC = clang +CCFLAGS = -O3 -fPIC -DPANDA -I. + +.PHONY: all +all: libpandasafety.so + +libpandasafety.so: test.o + $(CC) -shared -o '$@' $^ -lm + +test.o: test.c + @echo "[ CC ] $@" + $(CC) $(CCFLAGS) -MMD -c -I../../board -o '$@' '$<' + +.PHONY: clean +clean: + rm -f libpandasafety.so test.o test.d + +-include test.d diff --git a/panda/tests/safety/libpandasafety_py.py b/panda/tests/safety/libpandasafety_py.py new file mode 100644 index 00000000000000..53936761d52d3b --- /dev/null +++ b/panda/tests/safety/libpandasafety_py.py @@ -0,0 +1,96 @@ +import os +import subprocess + +from cffi import FFI + +can_dir = os.path.dirname(os.path.abspath(__file__)) +libpandasafety_fn = os.path.join(can_dir, "libpandasafety.so") +subprocess.check_call(["make"], cwd=can_dir) + +ffi = FFI() +ffi.cdef(""" +typedef struct +{ + uint32_t TIR; /*!< CAN TX mailbox identifier register */ + uint32_t TDTR; /*!< CAN mailbox data length control and time stamp register */ + uint32_t TDLR; /*!< CAN mailbox data low register */ + uint32_t TDHR; /*!< CAN mailbox data high register */ +} CAN_TxMailBox_TypeDef; + +typedef struct +{ + uint32_t RIR; /*!< CAN receive FIFO mailbox identifier register */ + uint32_t RDTR; /*!< CAN receive FIFO mailbox data length control and time stamp register */ + uint32_t RDLR; /*!< CAN receive FIFO mailbox data low register */ + uint32_t RDHR; /*!< CAN receive FIFO mailbox data high register */ +} CAN_FIFOMailBox_TypeDef; + +typedef struct +{ + uint32_t CNT; +} TIM_TypeDef; + +void toyota_rx_hook(CAN_FIFOMailBox_TypeDef *to_push); +int toyota_tx_hook(CAN_FIFOMailBox_TypeDef *to_send); +void toyota_init(int16_t param); +void set_controls_allowed(int c); +void reset_angle_control(void); +int get_controls_allowed(void); +void init_tests_toyota(void); +void set_timer(int t); +void set_toyota_torque_meas(int min, int max); +void set_cadillac_torque_driver(int min, int max); +void set_gm_torque_driver(int min, int max); +void set_hyundai_torque_driver(int min, int max); +void set_chrysler_torque_meas(int min, int max); +void set_toyota_rt_torque_last(int t); +void set_toyota_desired_torque_last(int t); +int get_toyota_torque_meas_min(void); +int get_toyota_torque_meas_max(void); +int get_chrysler_torque_meas_min(void); +int get_chrysler_torque_meas_max(void); + +void init_tests_honda(void); +int get_ego_speed(void); +void honda_init(int16_t param); +void honda_rx_hook(CAN_FIFOMailBox_TypeDef *to_push); +int honda_tx_hook(CAN_FIFOMailBox_TypeDef *to_send); +int get_brake_prev(void); +int get_gas_prev(void); +void set_honda_alt_brake_msg(bool); +void set_bosch_hardware(bool); + +void init_tests_cadillac(void); +void cadillac_init(int16_t param); +void cadillac_rx_hook(CAN_FIFOMailBox_TypeDef *to_push); +int cadillac_tx_hook(CAN_FIFOMailBox_TypeDef *to_send); +void set_cadillac_desired_torque_last(int t); +void set_cadillac_rt_torque_last(int t); + +void init_tests_gm(void); +void gm_init(int16_t param); +void gm_rx_hook(CAN_FIFOMailBox_TypeDef *to_push); +int gm_tx_hook(CAN_FIFOMailBox_TypeDef *to_send); +void set_gm_desired_torque_last(int t); +void set_gm_rt_torque_last(int t); + +void init_tests_hyundai(void); +void nooutput_init(int16_t param); +void hyundai_rx_hook(CAN_FIFOMailBox_TypeDef *to_push); +int hyundai_tx_hook(CAN_FIFOMailBox_TypeDef *to_send); +void set_hyundai_desired_torque_last(int t); +void set_hyundai_rt_torque_last(int t); + +void toyota_ipas_rx_hook(CAN_FIFOMailBox_TypeDef *to_push); +int toyota_ipas_tx_hook(CAN_FIFOMailBox_TypeDef *to_send); + +void init_tests_chrysler(void); +void chrysler_rx_hook(CAN_FIFOMailBox_TypeDef *to_push); +int chrysler_tx_hook(CAN_FIFOMailBox_TypeDef *to_send); +void set_chrysler_desired_torque_last(int t); +void set_chrysler_rt_torque_last(int t); + + +""") + +libpandasafety = ffi.dlopen(libpandasafety_fn) diff --git a/panda/tests/safety/requirements.txt b/panda/tests/safety/requirements.txt new file mode 100644 index 00000000000000..8bbfb1d7df38a2 --- /dev/null +++ b/panda/tests/safety/requirements.txt @@ -0,0 +1,2 @@ +cffi==1.11.4 +numpy==1.14.1 diff --git a/panda/tests/safety/test.c b/panda/tests/safety/test.c new file mode 100644 index 00000000000000..b1390c41c25528 --- /dev/null +++ b/panda/tests/safety/test.c @@ -0,0 +1,225 @@ +#include +#include + +typedef struct +{ + uint32_t TIR; /*!< CAN TX mailbox identifier register */ + uint32_t TDTR; /*!< CAN mailbox data length control and time stamp register */ + uint32_t TDLR; /*!< CAN mailbox data low register */ + uint32_t TDHR; /*!< CAN mailbox data high register */ +} CAN_TxMailBox_TypeDef; + +typedef struct +{ + uint32_t RIR; /*!< CAN receive FIFO mailbox identifier register */ + uint32_t RDTR; /*!< CAN receive FIFO mailbox data length control and time stamp register */ + uint32_t RDLR; /*!< CAN receive FIFO mailbox data low register */ + uint32_t RDHR; /*!< CAN receive FIFO mailbox data high register */ +} CAN_FIFOMailBox_TypeDef; + +typedef struct +{ + uint32_t CNT; +} TIM_TypeDef; + +struct sample_t toyota_torque_meas; +struct sample_t cadillac_torque_driver; +struct sample_t gm_torque_driver; +struct sample_t hyundai_torque_driver; +struct sample_t chrysler_torque_driver; + +TIM_TypeDef timer; +TIM_TypeDef *TIM2 = &timer; + +#define min(a,b) \ + ({ __typeof__ (a) _a = (a); \ + __typeof__ (b) _b = (b); \ + _a < _b ? _a : _b; }) + +#define max(a,b) \ + ({ __typeof__ (a) _a = (a); \ + __typeof__ (b) _b = (b); \ + _a > _b ? _a : _b; }) + + +#define PANDA +#define static +#include "safety.h" + +void set_controls_allowed(int c){ + controls_allowed = c; +} + +void reset_angle_control(void){ + angle_control = 0; +} + +int get_controls_allowed(void){ + return controls_allowed; +} + +void set_timer(int t){ + timer.CNT = t; +} + +void set_toyota_torque_meas(int min, int max){ + toyota_torque_meas.min = min; + toyota_torque_meas.max = max; +} + +void set_cadillac_torque_driver(int min, int max){ + cadillac_torque_driver.min = min; + cadillac_torque_driver.max = max; +} + +void set_gm_torque_driver(int min, int max){ + gm_torque_driver.min = min; + gm_torque_driver.max = max; +} + +void set_hyundai_torque_driver(int min, int max){ + hyundai_torque_driver.min = min; + hyundai_torque_driver.max = max; +} + +void set_chrysler_torque_meas(int min, int max){ + chrysler_torque_meas.min = min; + chrysler_torque_meas.max = max; +} + +int get_chrysler_torque_meas_min(void){ + return chrysler_torque_meas.min; +} + +int get_chrysler_torque_meas_max(void){ + return chrysler_torque_meas.max; +} + +int get_toyota_torque_meas_min(void){ + return toyota_torque_meas.min; +} + +int get_toyota_torque_meas_max(void){ + return toyota_torque_meas.max; +} + +void set_toyota_rt_torque_last(int t){ + toyota_rt_torque_last = t; +} + +void set_cadillac_rt_torque_last(int t){ + cadillac_rt_torque_last = t; +} + +void set_gm_rt_torque_last(int t){ + gm_rt_torque_last = t; +} + +void set_hyundai_rt_torque_last(int t){ + hyundai_rt_torque_last = t; +} + +void set_chrysler_rt_torque_last(int t){ + chrysler_rt_torque_last = t; +} + +void set_toyota_desired_torque_last(int t){ + toyota_desired_torque_last = t; +} + +void set_cadillac_desired_torque_last(int t){ + for (int i = 0; i < 4; i++) cadillac_desired_torque_last[i] = t; +} + +void set_gm_desired_torque_last(int t){ + gm_desired_torque_last = t; +} + +void set_hyundai_desired_torque_last(int t){ + hyundai_desired_torque_last = t; +} + +void set_chrysler_desired_torque_last(int t){ + chrysler_desired_torque_last = t; +} + +int get_ego_speed(void){ + return ego_speed; +} + +int get_brake_prev(void){ + return brake_prev; +} + +int get_gas_prev(void){ + return gas_prev; +} + +void set_honda_alt_brake_msg(bool c){ + honda_alt_brake_msg = c; +} + +void set_bosch_hardware(bool c){ + bosch_hardware = c; +} + +void init_tests_toyota(void){ + toyota_torque_meas.min = 0; + toyota_torque_meas.max = 0; + toyota_desired_torque_last = 0; + toyota_rt_torque_last = 0; + toyota_ts_last = 0; + set_timer(0); +} + +void init_tests_cadillac(void){ + cadillac_torque_driver.min = 0; + cadillac_torque_driver.max = 0; + for (int i = 0; i < 4; i++) cadillac_desired_torque_last[i] = 0; + cadillac_rt_torque_last = 0; + cadillac_ts_last = 0; + set_timer(0); +} + +void init_tests_gm(void){ + gm_torque_driver.min = 0; + gm_torque_driver.max = 0; + gm_desired_torque_last = 0; + gm_rt_torque_last = 0; + gm_ts_last = 0; + set_timer(0); +} + +void init_tests_hyundai(void){ + hyundai_torque_driver.min = 0; + hyundai_torque_driver.max = 0; + hyundai_desired_torque_last = 0; + hyundai_rt_torque_last = 0; + hyundai_ts_last = 0; + set_timer(0); +} + +void init_tests_chrysler(void){ + chrysler_torque_driver.min = 0; + chrysler_torque_driver.max = 0; + chrysler_desired_torque_last = 0; + chrysler_rt_torque_last = 0; + chrysler_ts_last = 0; + set_timer(0); +} + +void init_tests_honda(void){ + ego_speed = 0; + gas_interceptor_detected = 0; + brake_prev = 0; + gas_prev = 0; +} + +void set_gmlan_digital_output(int to_set){ +} + +void reset_gmlan_switch_timeout(void){ +} + +void gmlan_switch_init(int timeout_enable){ +} diff --git a/panda/tests/safety/test.sh b/panda/tests/safety/test.sh new file mode 100755 index 00000000000000..83d8f5b31fa420 --- /dev/null +++ b/panda/tests/safety/test.sh @@ -0,0 +1,2 @@ +#!/usr/bin/env sh +python -m unittest discover . diff --git a/panda/tests/safety/test_cadillac.py b/panda/tests/safety/test_cadillac.py new file mode 100644 index 00000000000000..53c943e966d6fc --- /dev/null +++ b/panda/tests/safety/test_cadillac.py @@ -0,0 +1,182 @@ +#!/usr/bin/env python2 +import unittest +import numpy as np +import libpandasafety_py + +MAX_RATE_UP = 2 +MAX_RATE_DOWN = 5 +MAX_TORQUE = 150 + +MAX_RT_DELTA = 75 +RT_INTERVAL = 250000 + +DRIVER_TORQUE_ALLOWANCE = 50; +DRIVER_TORQUE_FACTOR = 4; + +IPAS_OVERRIDE_THRESHOLD = 200 + +def twos_comp(val, bits): + if val >= 0: + return val + else: + return (2**bits) + val + +def sign(a): + if a > 0: + return 1 + else: + return -1 + +class TestCadillacSafety(unittest.TestCase): + @classmethod + def setUp(cls): + cls.safety = libpandasafety_py.libpandasafety + cls.safety.cadillac_init(0) + cls.safety.init_tests_cadillac() + + def _set_prev_torque(self, t): + self.safety.set_cadillac_desired_torque_last(t) + self.safety.set_cadillac_rt_torque_last(t) + + def _torque_driver_msg(self, torque): + to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_send[0].RIR = 0x164 << 21 + + t = twos_comp(torque, 11) + to_send[0].RDLR = ((t >> 8) & 0x7) | ((t & 0xFF) << 8) + return to_send + + def _torque_driver_msg_array(self, torque): + for i in range(3): + self.safety.cadillac_ipas_rx_hook(self._torque_driver_msg(torque)) + + def _torque_msg(self, torque): + to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_send[0].RIR = 0x151 << 21 + + t = twos_comp(torque, 14) + to_send[0].RDLR = ((t >> 8) & 0x3F) | ((t & 0xFF) << 8) + return to_send + + def test_default_controls_not_allowed(self): + self.assertFalse(self.safety.get_controls_allowed()) + + def test_manually_enable_controls_allowed(self): + self.safety.set_controls_allowed(1) + self.assertTrue(self.safety.get_controls_allowed()) + self.safety.set_controls_allowed(0) + + def test_enable_control_allowed_from_cruise(self): + to_push = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_push[0].RIR = 0x370 << 21 + to_push[0].RDLR = 0x800000 + to_push[0].RDTR = 0 + + self.safety.cadillac_rx_hook(to_push) + self.assertTrue(self.safety.get_controls_allowed()) + + def test_disable_control_allowed_from_cruise(self): + to_push = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_push[0].RIR = 0x370 << 21 + to_push[0].RDLR = 0 + to_push[0].RDTR = 0 + + self.safety.set_controls_allowed(1) + self.safety.cadillac_rx_hook(to_push) + self.assertFalse(self.safety.get_controls_allowed()) + + def test_torque_absolute_limits(self): + for controls_allowed in [True, False]: + for torque in np.arange(-MAX_TORQUE - 1000, MAX_TORQUE + 1000, MAX_RATE_UP): + self.safety.set_controls_allowed(controls_allowed) + self.safety.set_cadillac_rt_torque_last(torque) + self.safety.set_cadillac_torque_driver(0, 0) + self.safety.set_cadillac_desired_torque_last(torque - MAX_RATE_UP) + + if controls_allowed: + send = (-MAX_TORQUE <= torque <= MAX_TORQUE) + else: + send = torque == 0 + + self.assertEqual(send, self.safety.cadillac_tx_hook(self._torque_msg(torque))) + + def test_non_realtime_limit_up(self): + self.safety.set_cadillac_torque_driver(0, 0) + self.safety.set_controls_allowed(True) + + self._set_prev_torque(0) + self.assertTrue(self.safety.cadillac_tx_hook(self._torque_msg(MAX_RATE_UP))) + self._set_prev_torque(0) + self.assertTrue(self.safety.cadillac_tx_hook(self._torque_msg(-MAX_RATE_UP))) + + self._set_prev_torque(0) + self.assertFalse(self.safety.cadillac_tx_hook(self._torque_msg(MAX_RATE_UP + 1))) + self.safety.set_controls_allowed(True) + self._set_prev_torque(0) + self.assertFalse(self.safety.cadillac_tx_hook(self._torque_msg(-MAX_RATE_UP - 1))) + + def test_non_realtime_limit_down(self): + self.safety.set_cadillac_torque_driver(0, 0) + self.safety.set_controls_allowed(True) + + def test_exceed_torque_sensor(self): + self.safety.set_controls_allowed(True) + + for sign in [-1, 1]: + for t in np.arange(0, DRIVER_TORQUE_ALLOWANCE + 1, 1): + t *= -sign + self.safety.set_cadillac_torque_driver(t, t) + self._set_prev_torque(MAX_TORQUE * sign) + self.assertTrue(self.safety.cadillac_tx_hook(self._torque_msg(MAX_TORQUE * sign))) + + self.safety.set_cadillac_torque_driver(DRIVER_TORQUE_ALLOWANCE + 1, DRIVER_TORQUE_ALLOWANCE + 1) + self.assertFalse(self.safety.cadillac_tx_hook(self._torque_msg(-MAX_TORQUE))) + + # spot check some individual cases + for sign in [-1, 1]: + driver_torque = (DRIVER_TORQUE_ALLOWANCE + 10) * sign + torque_desired = (MAX_TORQUE - 10 * DRIVER_TORQUE_FACTOR) * sign + delta = 1 * sign + self._set_prev_torque(torque_desired) + self.safety.set_cadillac_torque_driver(-driver_torque, -driver_torque) + self.assertTrue(self.safety.cadillac_tx_hook(self._torque_msg(torque_desired))) + self._set_prev_torque(torque_desired + delta) + self.safety.set_cadillac_torque_driver(-driver_torque, -driver_torque) + self.assertFalse(self.safety.cadillac_tx_hook(self._torque_msg(torque_desired + delta))) + + self._set_prev_torque(MAX_TORQUE * sign) + self.safety.set_cadillac_torque_driver(-MAX_TORQUE * sign, -MAX_TORQUE * sign) + self.assertTrue(self.safety.cadillac_tx_hook(self._torque_msg((MAX_TORQUE - MAX_RATE_DOWN) * sign))) + self._set_prev_torque(MAX_TORQUE * sign) + self.safety.set_cadillac_torque_driver(-MAX_TORQUE * sign, -MAX_TORQUE * sign) + self.assertTrue(self.safety.cadillac_tx_hook(self._torque_msg(0))) + self._set_prev_torque(MAX_TORQUE * sign) + self.safety.set_cadillac_torque_driver(-MAX_TORQUE * sign, -MAX_TORQUE * sign) + self.assertFalse(self.safety.cadillac_tx_hook(self._torque_msg((MAX_TORQUE - MAX_RATE_DOWN + 1) * sign))) + + + def test_realtime_limits(self): + self.safety.set_controls_allowed(True) + + for sign in [-1, 1]: + self.safety.init_tests_cadillac() + self._set_prev_torque(0) + self.safety.set_cadillac_torque_driver(0, 0) + for t in np.arange(0, MAX_RT_DELTA, 1): + t *= sign + self.assertTrue(self.safety.cadillac_tx_hook(self._torque_msg(t))) + self.assertFalse(self.safety.cadillac_tx_hook(self._torque_msg(sign * (MAX_RT_DELTA + 1)))) + + self._set_prev_torque(0) + for t in np.arange(0, MAX_RT_DELTA, 1): + t *= sign + self.assertTrue(self.safety.cadillac_tx_hook(self._torque_msg(t))) + + # Increase timer to update rt_torque_last + self.safety.set_timer(RT_INTERVAL + 1) + self.assertTrue(self.safety.cadillac_tx_hook(self._torque_msg(sign * (MAX_RT_DELTA - 1)))) + self.assertTrue(self.safety.cadillac_tx_hook(self._torque_msg(sign * (MAX_RT_DELTA + 1)))) + + +if __name__ == "__main__": + unittest.main() diff --git a/panda/tests/safety/test_chrysler.py b/panda/tests/safety/test_chrysler.py new file mode 100755 index 00000000000000..568c92aaaadbf7 --- /dev/null +++ b/panda/tests/safety/test_chrysler.py @@ -0,0 +1,171 @@ +#!/usr/bin/env python2 +import unittest +import numpy as np +import libpandasafety_py + +MAX_RATE_UP = 3 +MAX_RATE_DOWN = 3 +MAX_STEER = 261 + +MAX_RT_DELTA = 112 +RT_INTERVAL = 250000 + +MAX_TORQUE_ERROR = 80 + +def twos_comp(val, bits): + if val >= 0: + return val + else: + return (2**bits) + val + +def sign(a): + if a > 0: + return 1 + else: + return -1 + +class TestChryslerSafety(unittest.TestCase): + @classmethod + def setUp(cls): + cls.safety = libpandasafety_py.libpandasafety + cls.safety.nooutput_init(0) + cls.safety.init_tests_chrysler() + + def _button_msg(self, buttons): + to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_send[0].RIR = 1265 << 21 + to_send[0].RDLR = buttons + return to_send + + def _set_prev_torque(self, t): + self.safety.set_chrysler_desired_torque_last(t) + self.safety.set_chrysler_rt_torque_last(t) + self.safety.set_chrysler_torque_meas(t, t) + + def _torque_meas_msg(self, torque): + to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_send[0].RIR = 544 << 21 + to_send[0].RDHR = ((torque + 1024) >> 8) + (((torque + 1024) & 0xff) << 8) + return to_send + + def _torque_msg(self, torque): + to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_send[0].RIR = 0x292 << 21 + to_send[0].RDLR = ((torque + 1024) >> 8) + (((torque + 1024) & 0xff) << 8) + return to_send + + def test_default_controls_not_allowed(self): + self.assertFalse(self.safety.get_controls_allowed()) + + def test_steer_safety_check(self): + for enabled in [0, 1]: + for t in range(-MAX_STEER*2, MAX_STEER*2): + self.safety.set_controls_allowed(enabled) + self._set_prev_torque(t) + if abs(t) > MAX_STEER or (not enabled and abs(t) > 0): + self.assertFalse(self.safety.chrysler_tx_hook(self._torque_msg(t))) + else: + self.assertTrue(self.safety.chrysler_tx_hook(self._torque_msg(t))) + + def test_manually_enable_controls_allowed(self): + self.safety.set_controls_allowed(1) + self.assertTrue(self.safety.get_controls_allowed()) + self.safety.set_controls_allowed(0) + self.assertFalse(self.safety.get_controls_allowed()) + + def test_enable_control_allowed_from_cruise(self): + to_push = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_push[0].RIR = 0x1f4 << 21 + to_push[0].RDLR = 0x380000 + + self.safety.chrysler_rx_hook(to_push) + self.assertTrue(self.safety.get_controls_allowed()) + + def test_disable_control_allowed_from_cruise(self): + to_push = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_push[0].RIR = 0x1f4 << 21 + to_push[0].RDLR = 0 + + self.safety.set_controls_allowed(1) + self.safety.chrysler_rx_hook(to_push) + self.assertFalse(self.safety.get_controls_allowed()) + + def test_non_realtime_limit_up(self): + self.safety.set_controls_allowed(True) + + self._set_prev_torque(0) + self.assertTrue(self.safety.chrysler_tx_hook(self._torque_msg(MAX_RATE_UP))) + + self._set_prev_torque(0) + self.assertFalse(self.safety.chrysler_tx_hook(self._torque_msg(MAX_RATE_UP + 1))) + + def test_non_realtime_limit_down(self): + self.safety.set_controls_allowed(True) + + self.safety.set_chrysler_rt_torque_last(MAX_STEER) + torque_meas = MAX_STEER - MAX_TORQUE_ERROR - 20 + self.safety.set_chrysler_torque_meas(torque_meas, torque_meas) + self.safety.set_chrysler_desired_torque_last(MAX_STEER) + self.assertTrue(self.safety.chrysler_tx_hook(self._torque_msg(MAX_STEER - MAX_RATE_DOWN))) + + self.safety.set_chrysler_rt_torque_last(MAX_STEER) + self.safety.set_chrysler_torque_meas(torque_meas, torque_meas) + self.safety.set_chrysler_desired_torque_last(MAX_STEER) + self.assertFalse(self.safety.chrysler_tx_hook(self._torque_msg(MAX_STEER - MAX_RATE_DOWN + 1))) + + def test_exceed_torque_sensor(self): + self.safety.set_controls_allowed(True) + + for sign in [-1, 1]: + self._set_prev_torque(0) + for t in np.arange(0, MAX_TORQUE_ERROR + 2, 2): # step needs to be smaller than MAX_TORQUE_ERROR + t *= sign + self.assertTrue(self.safety.chrysler_tx_hook(self._torque_msg(t))) + + self.assertFalse(self.safety.chrysler_tx_hook(self._torque_msg(sign * (MAX_TORQUE_ERROR + 2)))) + + def test_realtime_limit_up(self): + self.safety.set_controls_allowed(True) + + for sign in [-1, 1]: + self.safety.init_tests_chrysler() + self._set_prev_torque(0) + for t in np.arange(0, MAX_RT_DELTA+1, 1): + t *= sign + self.safety.set_chrysler_torque_meas(t, t) + self.assertTrue(self.safety.chrysler_tx_hook(self._torque_msg(t))) + self.assertFalse(self.safety.chrysler_tx_hook(self._torque_msg(sign * (MAX_RT_DELTA + 1)))) + + self._set_prev_torque(0) + for t in np.arange(0, MAX_RT_DELTA+1, 1): + t *= sign + self.safety.set_chrysler_torque_meas(t, t) + self.assertTrue(self.safety.chrysler_tx_hook(self._torque_msg(t))) + + # Increase timer to update rt_torque_last + self.safety.set_timer(RT_INTERVAL + 1) + self.assertTrue(self.safety.chrysler_tx_hook(self._torque_msg(sign * MAX_RT_DELTA))) + self.assertTrue(self.safety.chrysler_tx_hook(self._torque_msg(sign * (MAX_RT_DELTA + 1)))) + + def test_torque_measurements(self): + self.safety.chrysler_rx_hook(self._torque_meas_msg(50)) + self.safety.chrysler_rx_hook(self._torque_meas_msg(-50)) + self.safety.chrysler_rx_hook(self._torque_meas_msg(0)) + self.safety.chrysler_rx_hook(self._torque_meas_msg(0)) + self.safety.chrysler_rx_hook(self._torque_meas_msg(0)) + self.safety.chrysler_rx_hook(self._torque_meas_msg(0)) + + self.assertEqual(-50, self.safety.get_chrysler_torque_meas_min()) + self.assertEqual(50, self.safety.get_chrysler_torque_meas_max()) + + self.safety.chrysler_rx_hook(self._torque_meas_msg(0)) + self.assertEqual(0, self.safety.get_chrysler_torque_meas_max()) + self.assertEqual(-50, self.safety.get_chrysler_torque_meas_min()) + + self.safety.chrysler_rx_hook(self._torque_meas_msg(0)) + self.assertEqual(0, self.safety.get_chrysler_torque_meas_max()) + self.assertEqual(0, self.safety.get_chrysler_torque_meas_min()) + + +if __name__ == "__main__": + unittest.main() diff --git a/panda/tests/safety/test_gm.py b/panda/tests/safety/test_gm.py new file mode 100644 index 00000000000000..299de5a7e9ff51 --- /dev/null +++ b/panda/tests/safety/test_gm.py @@ -0,0 +1,266 @@ +#!/usr/bin/env python2 +import unittest +import numpy as np +import libpandasafety_py + +MAX_RATE_UP = 7 +MAX_RATE_DOWN = 17 +MAX_STEER = 300 +MAX_BRAKE = 350 +MAX_GAS = 3072 +MAX_REGEN = 1404 + +MAX_RT_DELTA = 128 +RT_INTERVAL = 250000 + +DRIVER_TORQUE_ALLOWANCE = 50; +DRIVER_TORQUE_FACTOR = 4; + +def twos_comp(val, bits): + if val >= 0: + return val + else: + return (2**bits) + val + +def sign(a): + if a > 0: + return 1 + else: + return -1 + +class TestGmSafety(unittest.TestCase): + @classmethod + def setUp(cls): + cls.safety = libpandasafety_py.libpandasafety + cls.safety.gm_init(0) + cls.safety.init_tests_gm() + + def _speed_msg(self, speed): + to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_send[0].RIR = 842 << 21 + to_send[0].RDLR = speed + return to_send + + def _button_msg(self, buttons): + to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_send[0].RIR = 481 << 21 + to_send[0].RDHR = buttons << 12 + return to_send + + def _brake_msg(self, brake): + to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_send[0].RIR = 241 << 21 + to_send[0].RDLR = 0xa00 if brake else 0x900 + return to_send + + def _gas_msg(self, gas): + to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_send[0].RIR = 417 << 21 + to_send[0].RDHR = (1 << 16) if gas else 0 + return to_send + + def _send_brake_msg(self, brake): + to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_send[0].RIR = 789 << 21 + brake = (-brake) & 0xfff + to_send[0].RDLR = (brake >> 8) | ((brake &0xff) << 8) + return to_send + + def _send_gas_msg(self, gas): + to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_send[0].RIR = 715 << 21 + to_send[0].RDLR = ((gas & 0x1f) << 27) | ((gas & 0xfe0) << 11) + return to_send + + def _set_prev_torque(self, t): + self.safety.set_gm_desired_torque_last(t) + self.safety.set_gm_rt_torque_last(t) + + def _torque_driver_msg(self, torque): + to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_send[0].RIR = 388 << 21 + + t = twos_comp(torque, 11) + to_send[0].RDHR = (((t >> 8) & 0x7) << 16) | ((t & 0xFF) << 24) + return to_send + + def _torque_msg(self, torque): + to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_send[0].RIR = 384 << 21 + + t = twos_comp(torque, 11) + to_send[0].RDLR = ((t >> 8) & 0x7) | ((t & 0xFF) << 8) + return to_send + + def test_default_controls_not_allowed(self): + self.assertFalse(self.safety.get_controls_allowed()) + + def test_resume_button(self): + RESUME_BTN = 2 + self.safety.set_controls_allowed(0) + self.safety.gm_rx_hook(self._button_msg(RESUME_BTN)) + self.assertTrue(self.safety.get_controls_allowed()) + + def test_set_button(self): + SET_BTN = 3 + self.safety.set_controls_allowed(0) + self.safety.gm_rx_hook(self._button_msg(SET_BTN)) + self.assertTrue(self.safety.get_controls_allowed()) + + def test_cancel_button(self): + CANCEL_BTN = 6 + self.safety.set_controls_allowed(1) + self.safety.gm_rx_hook(self._button_msg(CANCEL_BTN)) + self.assertFalse(self.safety.get_controls_allowed()) + + def test_disengage_on_brake(self): + self.safety.set_controls_allowed(1) + self.safety.gm_rx_hook(self._brake_msg(True)) + self.assertFalse(self.safety.get_controls_allowed()) + + def test_allow_brake_at_zero_speed(self): + # Brake was already pressed + self.safety.gm_rx_hook(self._brake_msg(True)) + self.safety.set_controls_allowed(1) + + self.safety.gm_rx_hook(self._brake_msg(True)) + self.assertTrue(self.safety.get_controls_allowed()) + self.safety.gm_rx_hook(self._brake_msg(False)) + + def test_not_allow_brake_when_moving(self): + # Brake was already pressed + self.safety.gm_rx_hook(self._brake_msg(True)) + self.safety.gm_rx_hook(self._speed_msg(100)) + self.safety.set_controls_allowed(1) + + self.safety.gm_rx_hook(self._brake_msg(True)) + self.assertFalse(self.safety.get_controls_allowed()) + self.safety.gm_rx_hook(self._brake_msg(False)) + + def test_disengage_on_gas(self): + self.safety.set_controls_allowed(1) + self.safety.gm_rx_hook(self._gas_msg(True)) + self.assertFalse(self.safety.get_controls_allowed()) + self.safety.gm_rx_hook(self._gas_msg(False)) + + def test_allow_engage_with_gas_pressed(self): + self.safety.gm_rx_hook(self._gas_msg(True)) + self.safety.set_controls_allowed(1) + self.safety.gm_rx_hook(self._gas_msg(True)) + self.assertTrue(self.safety.get_controls_allowed()) + self.safety.gm_rx_hook(self._gas_msg(False)) + + def test_brake_safety_check(self): + for enabled in [0, 1]: + for b in range(0, 500): + self.safety.set_controls_allowed(enabled) + if abs(b) > MAX_BRAKE or (not enabled and b != 0): + self.assertFalse(self.safety.gm_tx_hook(self._send_brake_msg(b))) + else: + self.assertTrue(self.safety.gm_tx_hook(self._send_brake_msg(b))) + + def test_gas_safety_check(self): + for enabled in [0, 1]: + for g in range(0, 2**12-1): + self.safety.set_controls_allowed(enabled) + if abs(g) > MAX_GAS or (not enabled and g != MAX_REGEN): + self.assertFalse(self.safety.gm_tx_hook(self._send_gas_msg(g))) + else: + self.assertTrue(self.safety.gm_tx_hook(self._send_gas_msg(g))) + + def test_steer_safety_check(self): + for enabled in [0, 1]: + for t in range(-0x200, 0x200): + self.safety.set_controls_allowed(enabled) + self._set_prev_torque(t) + if abs(t) > MAX_STEER or (not enabled and abs(t) > 0): + self.assertFalse(self.safety.gm_tx_hook(self._torque_msg(t))) + else: + self.assertTrue(self.safety.gm_tx_hook(self._torque_msg(t))) + + def test_manually_enable_controls_allowed(self): + self.safety.set_controls_allowed(1) + self.assertTrue(self.safety.get_controls_allowed()) + self.safety.set_controls_allowed(0) + self.assertFalse(self.safety.get_controls_allowed()) + + def test_non_realtime_limit_up(self): + self.safety.set_gm_torque_driver(0, 0) + self.safety.set_controls_allowed(True) + + self._set_prev_torque(0) + self.assertTrue(self.safety.gm_tx_hook(self._torque_msg(MAX_RATE_UP))) + self._set_prev_torque(0) + self.assertTrue(self.safety.gm_tx_hook(self._torque_msg(-MAX_RATE_UP))) + + self._set_prev_torque(0) + self.assertFalse(self.safety.gm_tx_hook(self._torque_msg(MAX_RATE_UP + 1))) + self.safety.set_controls_allowed(True) + self._set_prev_torque(0) + self.assertFalse(self.safety.gm_tx_hook(self._torque_msg(-MAX_RATE_UP - 1))) + + def test_non_realtime_limit_down(self): + self.safety.set_gm_torque_driver(0, 0) + self.safety.set_controls_allowed(True) + + def test_against_torque_driver(self): + self.safety.set_controls_allowed(True) + + for sign in [-1, 1]: + for t in np.arange(0, DRIVER_TORQUE_ALLOWANCE + 1, 1): + t *= -sign + self.safety.set_gm_torque_driver(t, t) + self._set_prev_torque(MAX_STEER * sign) + self.assertTrue(self.safety.gm_tx_hook(self._torque_msg(MAX_STEER * sign))) + + self.safety.set_gm_torque_driver(DRIVER_TORQUE_ALLOWANCE + 1, DRIVER_TORQUE_ALLOWANCE + 1) + self.assertFalse(self.safety.gm_tx_hook(self._torque_msg(-MAX_STEER))) + + # spot check some individual cases + for sign in [-1, 1]: + driver_torque = (DRIVER_TORQUE_ALLOWANCE + 10) * sign + torque_desired = (MAX_STEER - 10 * DRIVER_TORQUE_FACTOR) * sign + delta = 1 * sign + self._set_prev_torque(torque_desired) + self.safety.set_gm_torque_driver(-driver_torque, -driver_torque) + self.assertTrue(self.safety.gm_tx_hook(self._torque_msg(torque_desired))) + self._set_prev_torque(torque_desired + delta) + self.safety.set_gm_torque_driver(-driver_torque, -driver_torque) + self.assertFalse(self.safety.gm_tx_hook(self._torque_msg(torque_desired + delta))) + + self._set_prev_torque(MAX_STEER * sign) + self.safety.set_gm_torque_driver(-MAX_STEER * sign, -MAX_STEER * sign) + self.assertTrue(self.safety.gm_tx_hook(self._torque_msg((MAX_STEER - MAX_RATE_DOWN) * sign))) + self._set_prev_torque(MAX_STEER * sign) + self.safety.set_gm_torque_driver(-MAX_STEER * sign, -MAX_STEER * sign) + self.assertTrue(self.safety.gm_tx_hook(self._torque_msg(0))) + self._set_prev_torque(MAX_STEER * sign) + self.safety.set_gm_torque_driver(-MAX_STEER * sign, -MAX_STEER * sign) + self.assertFalse(self.safety.gm_tx_hook(self._torque_msg((MAX_STEER - MAX_RATE_DOWN + 1) * sign))) + + + def test_realtime_limits(self): + self.safety.set_controls_allowed(True) + + for sign in [-1, 1]: + self.safety.init_tests_gm() + self._set_prev_torque(0) + self.safety.set_gm_torque_driver(0, 0) + for t in np.arange(0, MAX_RT_DELTA, 1): + t *= sign + self.assertTrue(self.safety.gm_tx_hook(self._torque_msg(t))) + self.assertFalse(self.safety.gm_tx_hook(self._torque_msg(sign * (MAX_RT_DELTA + 1)))) + + self._set_prev_torque(0) + for t in np.arange(0, MAX_RT_DELTA, 1): + t *= sign + self.assertTrue(self.safety.gm_tx_hook(self._torque_msg(t))) + + # Increase timer to update rt_torque_last + self.safety.set_timer(RT_INTERVAL + 1) + self.assertTrue(self.safety.gm_tx_hook(self._torque_msg(sign * (MAX_RT_DELTA - 1)))) + self.assertTrue(self.safety.gm_tx_hook(self._torque_msg(sign * (MAX_RT_DELTA + 1)))) + + +if __name__ == "__main__": + unittest.main() diff --git a/panda/tests/safety/test_honda.py b/panda/tests/safety/test_honda.py new file mode 100755 index 00000000000000..48b678eaaec43e --- /dev/null +++ b/panda/tests/safety/test_honda.py @@ -0,0 +1,185 @@ +#!/usr/bin/env python2 +import unittest +import numpy as np +import libpandasafety_py + + +class TestHondaSafety(unittest.TestCase): + @classmethod + def setUp(cls): + cls.safety = libpandasafety_py.libpandasafety + cls.safety.honda_init(0) + cls.safety.init_tests_honda() + + def _speed_msg(self, speed): + to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_send[0].RIR = 0x158 << 21 + to_send[0].RDLR = speed + + return to_send + + def _button_msg(self, buttons, msg): + to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_send[0].RIR = msg << 21 + to_send[0].RDLR = buttons << 5 + + return to_send + + def _brake_msg(self, brake): + to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_send[0].RIR = 0x17C << 21 + to_send[0].RDHR = 0x200000 if brake else 0 + + return to_send + + def _alt_brake_msg(self, brake): + to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_send[0].RIR = 0x1BE << 21 + to_send[0].RDLR = 0x10 if brake else 0 + + return to_send + + def _gas_msg(self, gas): + to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_send[0].RIR = 0x17C << 21 + to_send[0].RDLR = 1 if gas else 0 + + return to_send + + def _send_brake_msg(self, brake): + to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_send[0].RIR = 0x1FA << 21 + to_send[0].RDLR = brake + + return to_send + + def _send_gas_msg(self, gas): + to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_send[0].RIR = 0x200 << 21 + to_send[0].RDLR = gas + + return to_send + + def _send_steer_msg(self, steer): + to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_send[0].RIR = 0xE4 << 21 + to_send[0].RDLR = steer + + return to_send + + def test_default_controls_not_allowed(self): + self.assertFalse(self.safety.get_controls_allowed()) + + def test_resume_button(self): + RESUME_BTN = 4 + self.safety.set_controls_allowed(0) + self.safety.honda_rx_hook(self._button_msg(RESUME_BTN, 0x1A6)) + self.assertTrue(self.safety.get_controls_allowed()) + + def test_set_button(self): + SET_BTN = 3 + self.safety.set_controls_allowed(0) + self.safety.honda_rx_hook(self._button_msg(SET_BTN, 0x1A6)) + self.assertTrue(self.safety.get_controls_allowed()) + + def test_cancel_button(self): + CANCEL_BTN = 2 + self.safety.set_controls_allowed(1) + self.safety.honda_rx_hook(self._button_msg(CANCEL_BTN, 0x1A6)) + self.assertFalse(self.safety.get_controls_allowed()) + + def test_sample_speed(self): + self.assertEqual(0, self.safety.get_ego_speed()) + self.safety.honda_rx_hook(self._speed_msg(100)) + self.assertEqual(100, self.safety.get_ego_speed()) + + def test_prev_brake(self): + self.assertFalse(self.safety.get_brake_prev()) + self.safety.honda_rx_hook(self._brake_msg(True)) + self.assertTrue(self.safety.get_brake_prev()) + + def test_disengage_on_brake(self): + self.safety.set_controls_allowed(1) + self.safety.honda_rx_hook(self._brake_msg(1)) + self.assertFalse(self.safety.get_controls_allowed()) + + def test_alt_disengage_on_brake(self): + self.safety.set_honda_alt_brake_msg(1) + self.safety.set_controls_allowed(1) + self.safety.honda_rx_hook(self._alt_brake_msg(1)) + self.assertFalse(self.safety.get_controls_allowed()) + + self.safety.set_honda_alt_brake_msg(0) + self.safety.set_controls_allowed(1) + self.safety.honda_rx_hook(self._alt_brake_msg(1)) + self.assertTrue(self.safety.get_controls_allowed()) + + def test_allow_brake_at_zero_speed(self): + # Brake was already pressed + self.safety.honda_rx_hook(self._brake_msg(True)) + self.safety.set_controls_allowed(1) + + self.safety.honda_rx_hook(self._brake_msg(True)) + self.assertTrue(self.safety.get_controls_allowed()) + self.safety.honda_rx_hook(self._brake_msg(False)) # reset no brakes + + def test_not_allow_brake_when_moving(self): + # Brake was already pressed + self.safety.honda_rx_hook(self._brake_msg(True)) + self.safety.honda_rx_hook(self._speed_msg(100)) + self.safety.set_controls_allowed(1) + + self.safety.honda_rx_hook(self._brake_msg(True)) + self.assertFalse(self.safety.get_controls_allowed()) + + def test_prev_gas(self): + self.assertFalse(self.safety.get_gas_prev()) + self.safety.honda_rx_hook(self._gas_msg(True)) + self.assertTrue(self.safety.get_gas_prev()) + + def test_disengage_on_gas(self): + self.safety.set_controls_allowed(1) + self.safety.honda_rx_hook(self._gas_msg(1)) + self.assertFalse(self.safety.get_controls_allowed()) + + def test_allow_engage_with_gas_pressed(self): + self.safety.honda_rx_hook(self._gas_msg(1)) + self.safety.set_controls_allowed(1) + self.safety.honda_rx_hook(self._gas_msg(1)) + self.assertTrue(self.safety.get_controls_allowed()) + + def test_brake_safety_check(self): + self.assertTrue(self.safety.honda_tx_hook(self._send_brake_msg(0x0000))) + self.assertFalse(self.safety.honda_tx_hook(self._send_brake_msg(0x1000))) + + self.safety.set_controls_allowed(1) + self.assertTrue(self.safety.honda_tx_hook(self._send_brake_msg(0x1000))) + self.assertFalse(self.safety.honda_tx_hook(self._send_brake_msg(0x00F0))) + + def test_gas_safety_check(self): + self.safety.set_controls_allowed(0) + self.assertTrue(self.safety.honda_tx_hook(self._send_gas_msg(0x0000))) + self.assertFalse(self.safety.honda_tx_hook(self._send_gas_msg(0x1000))) + + def test_steer_safety_check(self): + self.safety.set_controls_allowed(0) + self.assertTrue(self.safety.honda_tx_hook(self._send_steer_msg(0x0000))) + self.assertFalse(self.safety.honda_tx_hook(self._send_steer_msg(0x1000))) + + def test_spam_cancel_safety_check(self): + RESUME_BTN = 4 + SET_BTN = 3 + CANCEL_BTN = 2 + BUTTON_MSG = 0x296 + self.safety.set_bosch_hardware(1) + self.safety.set_controls_allowed(0) + self.assertTrue(self.safety.honda_tx_hook(self._button_msg(CANCEL_BTN, BUTTON_MSG))) + self.assertFalse(self.safety.honda_tx_hook(self._button_msg(RESUME_BTN, BUTTON_MSG))) + self.assertFalse(self.safety.honda_tx_hook(self._button_msg(SET_BTN, BUTTON_MSG))) + # do not block resume if we are engaged already + self.safety.set_controls_allowed(1) + self.assertTrue(self.safety.honda_tx_hook(self._button_msg(RESUME_BTN, BUTTON_MSG))) + + +if __name__ == "__main__": + unittest.main() diff --git a/panda/tests/safety/test_hyundai.py b/panda/tests/safety/test_hyundai.py new file mode 100644 index 00000000000000..0a6ce0f91f3d03 --- /dev/null +++ b/panda/tests/safety/test_hyundai.py @@ -0,0 +1,186 @@ +#!/usr/bin/env python2 +import unittest +import numpy as np +import libpandasafety_py + +MAX_RATE_UP = 3 +MAX_RATE_DOWN = 7 +MAX_STEER = 250 + +MAX_RT_DELTA = 112 +RT_INTERVAL = 250000 + +DRIVER_TORQUE_ALLOWANCE = 50; +DRIVER_TORQUE_FACTOR = 2; + +def twos_comp(val, bits): + if val >= 0: + return val + else: + return (2**bits) + val + +def sign(a): + if a > 0: + return 1 + else: + return -1 + +class TestHyundaiSafety(unittest.TestCase): + @classmethod + def setUp(cls): + cls.safety = libpandasafety_py.libpandasafety + cls.safety.nooutput_init(0) + cls.safety.init_tests_hyundai() + + def _button_msg(self, buttons): + to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_send[0].RIR = 1265 << 21 + to_send[0].RDLR = buttons + return to_send + + def _set_prev_torque(self, t): + self.safety.set_hyundai_desired_torque_last(t) + self.safety.set_hyundai_rt_torque_last(t) + + def _torque_driver_msg(self, torque): + to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_send[0].RIR = 897 << 21 + to_send[0].RDLR = (torque + 2048) << 11 + return to_send + + def _torque_msg(self, torque): + to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_send[0].RIR = 832 << 21 + to_send[0].RDLR = (torque + 1024) << 16 + return to_send + + def test_default_controls_not_allowed(self): + self.assertFalse(self.safety.get_controls_allowed()) + + def test_steer_safety_check(self): + for enabled in [0, 1]: + for t in range(-0x200, 0x200): + self.safety.set_controls_allowed(enabled) + self._set_prev_torque(t) + if abs(t) > MAX_STEER or (not enabled and abs(t) > 0): + self.assertFalse(self.safety.hyundai_tx_hook(self._torque_msg(t))) + else: + self.assertTrue(self.safety.hyundai_tx_hook(self._torque_msg(t))) + + def test_manually_enable_controls_allowed(self): + self.safety.set_controls_allowed(1) + self.assertTrue(self.safety.get_controls_allowed()) + self.safety.set_controls_allowed(0) + self.assertFalse(self.safety.get_controls_allowed()) + + def test_enable_control_allowed_from_cruise(self): + to_push = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_push[0].RIR = 1057 << 21 + to_push[0].RDLR = 1 << 13 + + self.safety.hyundai_rx_hook(to_push) + self.assertTrue(self.safety.get_controls_allowed()) + + def test_disable_control_allowed_from_cruise(self): + to_push = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_push[0].RIR = 1057 << 21 + to_push[0].RDLR = 0 + + self.safety.set_controls_allowed(1) + self.safety.hyundai_rx_hook(to_push) + self.assertFalse(self.safety.get_controls_allowed()) + + def test_non_realtime_limit_up(self): + self.safety.set_hyundai_torque_driver(0, 0) + self.safety.set_controls_allowed(True) + + self._set_prev_torque(0) + self.assertTrue(self.safety.hyundai_tx_hook(self._torque_msg(MAX_RATE_UP))) + self._set_prev_torque(0) + self.assertTrue(self.safety.hyundai_tx_hook(self._torque_msg(-MAX_RATE_UP))) + + self._set_prev_torque(0) + self.assertFalse(self.safety.hyundai_tx_hook(self._torque_msg(MAX_RATE_UP + 1))) + self.safety.set_controls_allowed(True) + self._set_prev_torque(0) + self.assertFalse(self.safety.hyundai_tx_hook(self._torque_msg(-MAX_RATE_UP - 1))) + + def test_non_realtime_limit_down(self): + self.safety.set_hyundai_torque_driver(0, 0) + self.safety.set_controls_allowed(True) + + def test_against_torque_driver(self): + self.safety.set_controls_allowed(True) + + for sign in [-1, 1]: + for t in np.arange(0, DRIVER_TORQUE_ALLOWANCE + 1, 1): + t *= -sign + self.safety.set_hyundai_torque_driver(t, t) + self._set_prev_torque(MAX_STEER * sign) + self.assertTrue(self.safety.hyundai_tx_hook(self._torque_msg(MAX_STEER * sign))) + + self.safety.set_hyundai_torque_driver(DRIVER_TORQUE_ALLOWANCE + 1, DRIVER_TORQUE_ALLOWANCE + 1) + self.assertFalse(self.safety.hyundai_tx_hook(self._torque_msg(-MAX_STEER))) + + # spot check some individual cases + for sign in [-1, 1]: + driver_torque = (DRIVER_TORQUE_ALLOWANCE + 10) * sign + torque_desired = (MAX_STEER - 10 * DRIVER_TORQUE_FACTOR) * sign + delta = 1 * sign + self._set_prev_torque(torque_desired) + self.safety.set_hyundai_torque_driver(-driver_torque, -driver_torque) + self.assertTrue(self.safety.hyundai_tx_hook(self._torque_msg(torque_desired))) + self._set_prev_torque(torque_desired + delta) + self.safety.set_hyundai_torque_driver(-driver_torque, -driver_torque) + self.assertFalse(self.safety.hyundai_tx_hook(self._torque_msg(torque_desired + delta))) + + self._set_prev_torque(MAX_STEER * sign) + self.safety.set_hyundai_torque_driver(-MAX_STEER * sign, -MAX_STEER * sign) + self.assertTrue(self.safety.hyundai_tx_hook(self._torque_msg((MAX_STEER - MAX_RATE_DOWN) * sign))) + self._set_prev_torque(MAX_STEER * sign) + self.safety.set_hyundai_torque_driver(-MAX_STEER * sign, -MAX_STEER * sign) + self.assertTrue(self.safety.hyundai_tx_hook(self._torque_msg(0))) + self._set_prev_torque(MAX_STEER * sign) + self.safety.set_hyundai_torque_driver(-MAX_STEER * sign, -MAX_STEER * sign) + self.assertFalse(self.safety.hyundai_tx_hook(self._torque_msg((MAX_STEER - MAX_RATE_DOWN + 1) * sign))) + + + def test_realtime_limits(self): + self.safety.set_controls_allowed(True) + + for sign in [-1, 1]: + self.safety.init_tests_hyundai() + self._set_prev_torque(0) + self.safety.set_hyundai_torque_driver(0, 0) + for t in np.arange(0, MAX_RT_DELTA, 1): + t *= sign + self.assertTrue(self.safety.hyundai_tx_hook(self._torque_msg(t))) + self.assertFalse(self.safety.hyundai_tx_hook(self._torque_msg(sign * (MAX_RT_DELTA + 1)))) + + self._set_prev_torque(0) + for t in np.arange(0, MAX_RT_DELTA, 1): + t *= sign + self.assertTrue(self.safety.hyundai_tx_hook(self._torque_msg(t))) + + # Increase timer to update rt_torque_last + self.safety.set_timer(RT_INTERVAL + 1) + self.assertTrue(self.safety.hyundai_tx_hook(self._torque_msg(sign * (MAX_RT_DELTA - 1)))) + self.assertTrue(self.safety.hyundai_tx_hook(self._torque_msg(sign * (MAX_RT_DELTA + 1)))) + + + #def test_spam_cancel_safety_check(self): + # RESUME_BTN = 1 + # SET_BTN = 2 + # CANCEL_BTN = 4 + # BUTTON_MSG = 1265 + # self.safety.set_controls_allowed(0) + # self.assertTrue(self.safety.hyundai_tx_hook(self._button_msg(CANCEL_BTN))) + # self.assertFalse(self.safety.hyundai_tx_hook(self._button_msg(RESUME_BTN))) + # self.assertFalse(self.safety.hyundai_tx_hook(self._button_msg(SET_BTN))) + # # do not block resume if we are engaged already + # self.safety.set_controls_allowed(1) + # self.assertTrue(self.safety.hyundai_tx_hook(self._button_msg(RESUME_BTN))) + + +if __name__ == "__main__": + unittest.main() diff --git a/panda/tests/safety/test_toyota.py b/panda/tests/safety/test_toyota.py new file mode 100644 index 00000000000000..40bc4bcf5d8f97 --- /dev/null +++ b/panda/tests/safety/test_toyota.py @@ -0,0 +1,414 @@ +#!/usr/bin/env python2 +import unittest +import numpy as np +import libpandasafety_py + +MAX_RATE_UP = 10 +MAX_RATE_DOWN = 25 +MAX_TORQUE = 1500 + +MAX_ACCEL = 1500 +MIN_ACCEL = -3000 + +MAX_RT_DELTA = 375 +RT_INTERVAL = 250000 + +MAX_TORQUE_ERROR = 350 + +IPAS_OVERRIDE_THRESHOLD = 200 + +ANGLE_DELTA_BP = [0., 5., 15.] +ANGLE_DELTA_V = [5., .8, .15] # windup limit +ANGLE_DELTA_VU = [5., 3.5, 0.4] # unwind limit + +def twos_comp(val, bits): + if val >= 0: + return val + else: + return (2**bits) + val + +def sign(a): + if a > 0: + return 1 + else: + return -1 + +class TestToyotaSafety(unittest.TestCase): + @classmethod + def setUp(cls): + cls.safety = libpandasafety_py.libpandasafety + cls.safety.toyota_init(100) + cls.safety.init_tests_toyota() + + def _set_prev_torque(self, t): + self.safety.set_toyota_desired_torque_last(t) + self.safety.set_toyota_rt_torque_last(t) + self.safety.set_toyota_torque_meas(t, t) + + def _torque_meas_msg(self, torque): + to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_send[0].RIR = 0x260 << 21 + + t = twos_comp(torque, 16) + to_send[0].RDHR = t | ((t & 0xFF) << 16) + return to_send + + def _torque_driver_msg(self, torque): + to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_send[0].RIR = 0x260 << 21 + + t = twos_comp(torque, 16) + to_send[0].RDLR = t | ((t & 0xFF) << 16) + return to_send + + def _torque_driver_msg_array(self, torque): + for i in range(6): + self.safety.toyota_ipas_rx_hook(self._torque_driver_msg(torque)) + + def _angle_meas_msg(self, angle): + to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_send[0].RIR = 0x25 << 21 + + t = twos_comp(angle, 12) + to_send[0].RDLR = ((t & 0xF00) >> 8) | ((t & 0xFF) << 8) + return to_send + + def _angle_meas_msg_array(self, angle): + for i in range(6): + self.safety.toyota_ipas_rx_hook(self._angle_meas_msg(angle)) + + def _torque_msg(self, torque): + to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_send[0].RIR = 0x2E4 << 21 + + t = twos_comp(torque, 16) + to_send[0].RDLR = t | ((t & 0xFF) << 16) + return to_send + + def _ipas_state_msg(self, state): + to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_send[0].RIR = 0x262 << 21 + + to_send[0].RDLR = state & 0xF + return to_send + + def _ipas_control_msg(self, angle, state): + # note: we command 2/3 of the angle due to CAN conversion + to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_send[0].RIR = 0x266 << 21 + + t = twos_comp(angle, 12) + to_send[0].RDLR = ((t & 0xF00) >> 8) | ((t & 0xFF) << 8) + to_send[0].RDLR |= ((state & 0xf) << 4) + + return to_send + + def _speed_msg(self, speed): + to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_send[0].RIR = 0xb4 << 21 + speed = int(speed * 100 * 3.6) + + to_send[0].RDHR = ((speed & 0xFF) << 16) | (speed & 0xFF00) + return to_send + + def _accel_msg(self, accel): + to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_send[0].RIR = 0x343 << 21 + + a = twos_comp(accel, 16) + to_send[0].RDLR = (a & 0xFF) << 8 | (a >> 8) + return to_send + + def test_default_controls_not_allowed(self): + self.assertFalse(self.safety.get_controls_allowed()) + + def test_manually_enable_controls_allowed(self): + self.safety.set_controls_allowed(1) + self.assertTrue(self.safety.get_controls_allowed()) + + def test_enable_control_allowed_from_cruise(self): + to_push = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_push[0].RIR = 0x1D2 << 21 + to_push[0].RDLR = 0x20 + + self.safety.toyota_rx_hook(to_push) + self.assertTrue(self.safety.get_controls_allowed()) + + def test_disable_control_allowed_from_cruise(self): + to_push = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *') + to_push[0].RIR = 0x1D2 << 21 + to_push[0].RDLR = 0 + + self.safety.set_controls_allowed(1) + self.safety.toyota_rx_hook(to_push) + self.assertFalse(self.safety.get_controls_allowed()) + + def test_accel_actuation_limits(self): + for accel in np.arange(MIN_ACCEL - 1000, MAX_ACCEL + 1000, 100): + for controls_allowed in [True, False]: + self.safety.set_controls_allowed(controls_allowed) + + if controls_allowed: + send = MIN_ACCEL <= accel <= MAX_ACCEL + else: + send = accel == 0 + self.assertEqual(send, self.safety.toyota_tx_hook(self._accel_msg(accel))) + + def test_torque_absolute_limits(self): + for controls_allowed in [True, False]: + for torque in np.arange(-MAX_TORQUE - 1000, MAX_TORQUE + 1000, MAX_RATE_UP): + self.safety.set_controls_allowed(controls_allowed) + self.safety.set_toyota_rt_torque_last(torque) + self.safety.set_toyota_torque_meas(torque, torque) + self.safety.set_toyota_desired_torque_last(torque - MAX_RATE_UP) + + if controls_allowed: + send = (-MAX_TORQUE <= torque <= MAX_TORQUE) + else: + send = torque == 0 + + self.assertEqual(send, self.safety.toyota_tx_hook(self._torque_msg(torque))) + + def test_non_realtime_limit_up(self): + self.safety.set_controls_allowed(True) + + self._set_prev_torque(0) + self.assertTrue(self.safety.toyota_tx_hook(self._torque_msg(MAX_RATE_UP))) + + self._set_prev_torque(0) + self.assertFalse(self.safety.toyota_tx_hook(self._torque_msg(MAX_RATE_UP + 1))) + + def test_non_realtime_limit_down(self): + self.safety.set_controls_allowed(True) + + self.safety.set_toyota_rt_torque_last(1000) + self.safety.set_toyota_torque_meas(500, 500) + self.safety.set_toyota_desired_torque_last(1000) + self.assertTrue(self.safety.toyota_tx_hook(self._torque_msg(1000 - MAX_RATE_DOWN))) + + self.safety.set_toyota_rt_torque_last(1000) + self.safety.set_toyota_torque_meas(500, 500) + self.safety.set_toyota_desired_torque_last(1000) + self.assertFalse(self.safety.toyota_tx_hook(self._torque_msg(1000 - MAX_RATE_DOWN + 1))) + + def test_exceed_torque_sensor(self): + self.safety.set_controls_allowed(True) + + for sign in [-1, 1]: + self._set_prev_torque(0) + for t in np.arange(0, MAX_TORQUE_ERROR + 10, 10): + t *= sign + self.assertTrue(self.safety.toyota_tx_hook(self._torque_msg(t))) + + self.assertFalse(self.safety.toyota_tx_hook(self._torque_msg(sign * (MAX_TORQUE_ERROR + 10)))) + + def test_realtime_limit_up(self): + self.safety.set_controls_allowed(True) + + for sign in [-1, 1]: + self.safety.init_tests_toyota() + self._set_prev_torque(0) + for t in np.arange(0, 380, 10): + t *= sign + self.safety.set_toyota_torque_meas(t, t) + self.assertTrue(self.safety.toyota_tx_hook(self._torque_msg(t))) + self.assertFalse(self.safety.toyota_tx_hook(self._torque_msg(sign * 380))) + + self._set_prev_torque(0) + for t in np.arange(0, 370, 10): + t *= sign + self.safety.set_toyota_torque_meas(t, t) + self.assertTrue(self.safety.toyota_tx_hook(self._torque_msg(t))) + + # Increase timer to update rt_torque_last + self.safety.set_timer(RT_INTERVAL + 1) + self.assertTrue(self.safety.toyota_tx_hook(self._torque_msg(sign * 370))) + self.assertTrue(self.safety.toyota_tx_hook(self._torque_msg(sign * 380))) + + def test_torque_measurements(self): + self.safety.toyota_rx_hook(self._torque_meas_msg(50)) + self.safety.toyota_rx_hook(self._torque_meas_msg(-50)) + self.safety.toyota_rx_hook(self._torque_meas_msg(0)) + self.safety.toyota_rx_hook(self._torque_meas_msg(0)) + self.safety.toyota_rx_hook(self._torque_meas_msg(0)) + self.safety.toyota_rx_hook(self._torque_meas_msg(0)) + + self.assertEqual(-51, self.safety.get_toyota_torque_meas_min()) + self.assertEqual(51, self.safety.get_toyota_torque_meas_max()) + + self.safety.toyota_rx_hook(self._torque_meas_msg(0)) + self.assertEqual(-1, self.safety.get_toyota_torque_meas_max()) + self.assertEqual(-51, self.safety.get_toyota_torque_meas_min()) + + self.safety.toyota_rx_hook(self._torque_meas_msg(0)) + self.assertEqual(-1, self.safety.get_toyota_torque_meas_max()) + self.assertEqual(-1, self.safety.get_toyota_torque_meas_min()) + + def test_ipas_override(self): + + ## angle control is not active + self.safety.set_controls_allowed(1) + + # 3 consecutive msgs where driver exceeds threshold but angle_control isn't active + self.safety.set_controls_allowed(1) + self._torque_driver_msg_array(IPAS_OVERRIDE_THRESHOLD + 1) + self.assertTrue(self.safety.get_controls_allowed()) + + self._torque_driver_msg_array(-IPAS_OVERRIDE_THRESHOLD - 1) + self.assertTrue(self.safety.get_controls_allowed()) + + # ipas state is override + self.safety.toyota_ipas_rx_hook(self._ipas_state_msg(5)) + self.assertTrue(self.safety.get_controls_allowed()) + + ## now angle control is active + self.safety.toyota_ipas_tx_hook(self._ipas_control_msg(0, 0)) + self.safety.toyota_ipas_rx_hook(self._ipas_state_msg(0)) + + # 3 consecutive msgs where driver does exceed threshold + self.safety.set_controls_allowed(1) + self._torque_driver_msg_array(IPAS_OVERRIDE_THRESHOLD + 1) + self.assertFalse(self.safety.get_controls_allowed()) + + self.safety.set_controls_allowed(1) + self._torque_driver_msg_array(-IPAS_OVERRIDE_THRESHOLD - 1) + self.assertFalse(self.safety.get_controls_allowed()) + + # ipas state is override and torque isn't overriding any more + self.safety.set_controls_allowed(1) + self._torque_driver_msg_array(0) + self.safety.toyota_ipas_rx_hook(self._ipas_state_msg(5)) + self.assertFalse(self.safety.get_controls_allowed()) + + # 3 consecutive msgs where driver does not exceed threshold and + # ipas state is not override + self.safety.set_controls_allowed(1) + self.safety.toyota_ipas_rx_hook(self._ipas_state_msg(0)) + self.assertTrue(self.safety.get_controls_allowed()) + + self._torque_driver_msg_array(IPAS_OVERRIDE_THRESHOLD) + self.assertTrue(self.safety.get_controls_allowed()) + + self._torque_driver_msg_array(-IPAS_OVERRIDE_THRESHOLD) + self.assertTrue(self.safety.get_controls_allowed()) + + # reset no angle control at the end of the test + self.safety.reset_angle_control() + + def test_angle_cmd_when_disabled(self): + + self.safety.set_controls_allowed(0) + + # test angle cmd too far from actual + angle_refs = [-10, 10] + deltas = range(-2, 3) + expected_results = [False, True, True, True, False] + + for a in angle_refs: + self._angle_meas_msg_array(a) + for i, d in enumerate(deltas): + self.assertEqual(expected_results[i], self.safety.toyota_ipas_tx_hook(self._ipas_control_msg(a + d, 1))) + + # test ipas state cmd enabled + self._angle_meas_msg_array(0) + self.assertEqual(0, self.safety.toyota_ipas_tx_hook(self._ipas_control_msg(0, 3))) + + # reset no angle control at the end of the test + self.safety.reset_angle_control() + + def test_angle_cmd_when_enabled(self): + + # ipas angle cmd should pass through when controls are enabled + + self.safety.set_controls_allowed(1) + self._angle_meas_msg_array(0) + self.safety.toyota_ipas_rx_hook(self._speed_msg(0.1)) + + self.assertEqual(1, self.safety.toyota_ipas_tx_hook(self._ipas_control_msg(0, 1))) + self.assertEqual(1, self.safety.toyota_ipas_tx_hook(self._ipas_control_msg(4, 1))) + self.assertEqual(1, self.safety.toyota_ipas_tx_hook(self._ipas_control_msg(0, 3))) + self.assertEqual(1, self.safety.toyota_ipas_tx_hook(self._ipas_control_msg(-4, 3))) + self.assertEqual(1, self.safety.toyota_ipas_tx_hook(self._ipas_control_msg(-8, 3))) + + # reset no angle control at the end of the test + self.safety.reset_angle_control() + + + def test_angle_cmd_rate_when_disabled(self): + + # as long as the command is close to the measured, no rate limit is enforced when + # controls are disabled + self.safety.set_controls_allowed(0) + self.safety.toyota_ipas_rx_hook(self._angle_meas_msg(0)) + self.assertEqual(1, self.safety.toyota_ipas_tx_hook(self._ipas_control_msg(0, 1))) + self.safety.toyota_ipas_rx_hook(self._angle_meas_msg(100)) + self.assertEqual(1, self.safety.toyota_ipas_tx_hook(self._ipas_control_msg(100, 1))) + self.safety.toyota_ipas_rx_hook(self._angle_meas_msg(-100)) + self.assertEqual(1, self.safety.toyota_ipas_tx_hook(self._ipas_control_msg(-100, 1))) + + # reset no angle control at the end of the test + self.safety.reset_angle_control() + + def test_angle_cmd_rate_when_enabled(self): + + # when controls are allowed, angle cmd rate limit is enforced + # test 1: no limitations if we stay within limits + speeds = [0., 1., 5., 10., 15., 100.] + angles = [-300, -100, -10, 0, 10, 100, 300] + for a in angles: + for s in speeds: + + # first test against false positives + self._angle_meas_msg_array(a) + self.safety.toyota_ipas_tx_hook(self._ipas_control_msg(a, 1)) + self.safety.set_controls_allowed(1) + self.safety.toyota_ipas_rx_hook(self._speed_msg(s)) + max_delta_up = int(np.interp(s, ANGLE_DELTA_BP, ANGLE_DELTA_V) * 2 / 3. + 1.) + max_delta_down = int(np.interp(s, ANGLE_DELTA_BP, ANGLE_DELTA_VU) * 2 / 3. + 1.) + self.assertEqual(True, self.safety.toyota_ipas_tx_hook(self._ipas_control_msg(a + sign(a) * max_delta_up, 1))) + self.assertTrue(self.safety.get_controls_allowed()) + self.assertEqual(True, self.safety.toyota_ipas_tx_hook(self._ipas_control_msg(a, 1))) + self.assertTrue(self.safety.get_controls_allowed()) + self.assertEqual(True, self.safety.toyota_ipas_tx_hook(self._ipas_control_msg(a - sign(a) * max_delta_down, 1))) + self.assertTrue(self.safety.get_controls_allowed()) + + # now inject too high rates + self.assertEqual(False, self.safety.toyota_ipas_tx_hook(self._ipas_control_msg(a + sign(a) * + (max_delta_up + 1), 1))) + self.assertFalse(self.safety.get_controls_allowed()) + self.safety.set_controls_allowed(1) + self.assertEqual(True, self.safety.toyota_ipas_tx_hook(self._ipas_control_msg(a + sign(a) * max_delta_up, 1))) + self.assertTrue(self.safety.get_controls_allowed()) + self.assertEqual(True, self.safety.toyota_ipas_tx_hook(self._ipas_control_msg(a, 1))) + self.assertTrue(self.safety.get_controls_allowed()) + self.assertEqual(False, self.safety.toyota_ipas_tx_hook(self._ipas_control_msg(a - sign(a) * + (max_delta_down + 1), 1))) + self.assertFalse(self.safety.get_controls_allowed()) + + # reset no angle control at the end of the test + self.safety.reset_angle_control() + + def test_angle_measured_rate(self): + + speeds = [0., 1., 5., 10., 15., 100.] + angles = [-300, -100, -10, 0, 10, 100, 300] + angles = [10] + for a in angles: + for s in speeds: + self._angle_meas_msg_array(a) + self.safety.toyota_ipas_tx_hook(self._ipas_control_msg(a, 1)) + self.safety.set_controls_allowed(1) + self.safety.toyota_ipas_rx_hook(self._speed_msg(s)) + max_delta_up = int(np.interp(s, ANGLE_DELTA_BP, ANGLE_DELTA_V) * 2 / 3. + 1.) + max_delta_down = int(np.interp(s, ANGLE_DELTA_BP, ANGLE_DELTA_VU) * 2 / 3. + 1.) + self.safety.toyota_ipas_rx_hook(self._angle_meas_msg(a)) + self.assertTrue(self.safety.get_controls_allowed()) + self.safety.toyota_ipas_rx_hook(self._angle_meas_msg(a + 150)) + self.assertFalse(self.safety.get_controls_allowed()) + + # reset no angle control at the end of the test + self.safety.reset_angle_control() + + +if __name__ == "__main__": + unittest.main() diff --git a/panda/tests/standalone_test.py b/panda/tests/standalone_test.py new file mode 100755 index 00000000000000..ca6ea49f1056de --- /dev/null +++ b/panda/tests/standalone_test.py @@ -0,0 +1,38 @@ +#!/usr/bin/env python +import os +import sys +import struct +import time + +sys.path.append(os.path.join(os.path.dirname(os.path.realpath(__file__)), "..")) +from panda import Panda + +if __name__ == "__main__": + if os.getenv("WIFI") is not None: + p = Panda("WIFI") + else: + p = Panda() + print(p.get_serial()) + print(p.health()) + + t1 = time.time() + for i in range(100): + p.get_serial() + t2 = time.time() + print("100 requests took %.2f ms" % ((t2-t1)*1000)) + + p.set_safety_mode(Panda.SAFETY_ALLOUTPUT) + + a = 0 + while True: + # flood + msg = b"\xaa"*4 + struct.pack("I", a) + p.can_send(0xaa, msg, 0) + p.can_send(0xaa, msg, 1) + p.can_send(0xaa, msg, 4) + time.sleep(0.01) + + dat = p.can_recv() + if len(dat) > 0: + print(dat) + a += 1 diff --git a/panda/tests/throughput_test.py b/panda/tests/throughput_test.py new file mode 100755 index 00000000000000..5812ce42c2aa1c --- /dev/null +++ b/panda/tests/throughput_test.py @@ -0,0 +1,64 @@ +#!/usr/bin/env python +from __future__ import print_function +import os +import sys +import struct +import time +from tqdm import tqdm + +sys.path.append(os.path.join(os.path.dirname(os.path.realpath(__file__)), "..")) +from panda import Panda, PandaWifiStreaming + +# test throughput between USB and wifi + +if __name__ == "__main__": + print(Panda.list()) + p_out = Panda("108018800f51363038363036") + print(p_out.get_serial()) + #p_in = Panda("02001b000f51363038363036") + p_in = Panda("WIFI") + print(p_in.get_serial()) + + p_in = PandaWifiStreaming() + + #while True: + # p_in.can_recv() + #sys.exit(0) + + p_out.set_controls_allowed(True) + + set_out, set_in = set(), set() + + # drain + p_out.can_recv() + p_in.can_recv() + + BATCH_SIZE = 16 + for a in tqdm(range(0, 10000, BATCH_SIZE)): + for b in range(0, BATCH_SIZE): + msg = b"\xaa"*4 + struct.pack("I", a+b) + if a%1 == 0: + p_out.can_send(0xaa, msg, 0) + + dat_out, dat_in = p_out.can_recv(), p_in.can_recv() + if len(dat_in) != 0: + print(len(dat_in)) + + num_out = [struct.unpack("I", i[4:])[0] for _, _, i, _ in dat_out] + num_in = [struct.unpack("I", i[4:])[0] for _, _, i, _ in dat_in] + + set_in.update(num_in) + set_out.update(num_out) + + # swag + print("waiting for packets") + time.sleep(2.0) + dat_in = p_in.can_recv() + print(len(dat_in)) + num_in = [struct.unpack("I", i[4:])[0] for _, _, i, _ in dat_in] + set_in.update(num_in) + + if len(set_out - set_in): + print("MISSING %d" % len(set_out - set_in)) + if len(set_out - set_in) < 256: + print(map(hex, sorted(list(set_out - set_in)))) diff --git a/panda/tests/tucan_loopback.py b/panda/tests/tucan_loopback.py new file mode 100755 index 00000000000000..a3f3e6e2d7cbad --- /dev/null +++ b/panda/tests/tucan_loopback.py @@ -0,0 +1,125 @@ +#!/usr/bin/env python +from __future__ import print_function +import os +import sys +import time +import random +import argparse + +from hexdump import hexdump +from itertools import permutations + +sys.path.append(os.path.join(os.path.dirname(os.path.realpath(__file__)), "..")) +from panda import Panda + +def get_test_string(): + return b"test"+os.urandom(10) + +def run_test(sleep_duration): + pandas = Panda.list() + print(pandas) + + if len(pandas) == 0: + print("NO PANDAS") + assert False + + if len(pandas) == 1: + # if we only have one on USB, assume the other is on wifi + pandas.append("WIFI") + run_test_w_pandas(pandas, sleep_duration) + +def run_test_w_pandas(pandas, sleep_duration): + h = list(map(lambda x: Panda(x), pandas)) + print("H", h) + + for hh in h: + hh.set_controls_allowed(True) + + # test both directions + for ho in permutations(range(len(h)), r=2): + print("***************** TESTING", ho) + + panda0, panda1 = h[ho[0]], h[ho[1]] + + if(panda0._serial == "WIFI"): + print(" *** Can not send can data over wifi panda. Skipping! ***") + continue + + # **** test health packet **** + print("health", ho[0], h[ho[0]].health()) + + # **** test K/L line loopback **** + for bus in [2,3]: + # flush the output + h[ho[1]].kline_drain(bus=bus) + + # send the characters + st = get_test_string() + st = b"\xaa"+chr(len(st)+3).encode()+st + h[ho[0]].kline_send(st, bus=bus, checksum=False) + + # check for receive + ret = h[ho[1]].kline_drain(bus=bus) + + print("ST Data:") + hexdump(st) + print("RET Data:") + hexdump(ret) + assert st == ret + print("K/L pass", bus, ho, "\n") + time.sleep(sleep_duration) + + # **** test can line loopback **** +# for bus, gmlan in [(0, None), (1, False), (2, False), (1, True), (2, True)]: +for bus, gmlan in [(0, None), (1, None)]: + print("\ntest can", bus) + # flush + cans_echo = panda0.can_recv() + cans_loop = panda1.can_recv() + + if gmlan is not None: + panda0.set_gmlan(gmlan, bus) + panda1.set_gmlan(gmlan, bus) + + # send the characters + # pick addresses high enough to not conflict with honda code + at = random.randint(1024, 2000) + st = get_test_string()[0:8] + panda0.can_send(at, st, bus) + time.sleep(0.1) + + # check for receive + cans_echo = panda0.can_recv() + cans_loop = panda1.can_recv() + + print("Bus", bus, "echo", cans_echo, "loop", cans_loop) + + assert len(cans_echo) == 1 + assert len(cans_loop) == 1 + + assert cans_echo[0][0] == at + assert cans_loop[0][0] == at + + assert cans_echo[0][2] == st + assert cans_loop[0][2] == st + + assert cans_echo[0][3] == 0x80 | bus + if cans_loop[0][3] != bus: + print("EXPECTED %d GOT %d" % (bus, cans_loop[0][3])) + assert cans_loop[0][3] == bus + + print("CAN pass", bus, ho) + time.sleep(sleep_duration) + +if __name__ == "__main__": + parser = argparse.ArgumentParser() + parser.add_argument("-n", type=int, help="Number of test iterations to run") + parser.add_argument("-sleep", type=int, help="Sleep time between tests", default=0) + args = parser.parse_args() + + if args.n is None: + while True: + run_test(sleep_duration=args.sleep) + else: + for i in range(args.n): + run_test(sleep_duration=args.sleep) diff --git a/phonelibs/boringssl/build.txt b/phonelibs/boringssl/build.txt new file mode 100644 index 00000000000000..0c9cd0d31d244e --- /dev/null +++ b/phonelibs/boringssl/build.txt @@ -0,0 +1,7 @@ +# with neos tree +cd ~/android/system +mka libcrypt_static libssl_static + +cp ~/android/system/out/target/product/oneplus3/obj/STATIC_LIBRARIES/libcrypto_static_intermediates/libcrypto_static.a lib/ +cp ~/android/system/out/target/product/oneplus3/obj/STATIC_LIBRARIES/libssl_static_intermediates/libssl_static.a lib/ + diff --git a/phonelibs/boringssl/include/openssl/aead.h b/phonelibs/boringssl/include/openssl/aead.h new file mode 100644 index 00000000000000..dc453e342d204c --- /dev/null +++ b/phonelibs/boringssl/include/openssl/aead.h @@ -0,0 +1,315 @@ +/* Copyright (c) 2014, Google Inc. + * + * Permission to use, copy, modify, and/or distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY + * SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN ACTION + * OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF OR IN + * CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. */ + +#ifndef OPENSSL_HEADER_AEAD_H +#define OPENSSL_HEADER_AEAD_H + +#include + +#if defined(__cplusplus) +extern "C" { +#endif + + +/* Authenticated Encryption with Additional Data. + * + * AEAD couples confidentiality and integrity in a single primtive. AEAD + * algorithms take a key and then can seal and open individual messages. Each + * message has a unique, per-message nonce and, optionally, additional data + * which is authenticated but not included in the ciphertext. + * + * The |EVP_AEAD_CTX_init| function initialises an |EVP_AEAD_CTX| structure and + * performs any precomputation needed to use |aead| with |key|. The length of + * the key, |key_len|, is given in bytes. + * + * The |tag_len| argument contains the length of the tags, in bytes, and allows + * for the processing of truncated authenticators. A zero value indicates that + * the default tag length should be used and this is defined as + * |EVP_AEAD_DEFAULT_TAG_LENGTH| in order to make the code clear. Using + * truncated tags increases an attacker's chance of creating a valid forgery. + * Be aware that the attacker's chance may increase more than exponentially as + * would naively be expected. + * + * When no longer needed, the initialised |EVP_AEAD_CTX| structure must be + * passed to |EVP_AEAD_CTX_cleanup|, which will deallocate any memory used. + * + * With an |EVP_AEAD_CTX| in hand, one can seal and open messages. These + * operations are intended to meet the standard notions of privacy and + * authenticity for authenticated encryption. For formal definitions see + * Bellare and Namprempre, "Authenticated encryption: relations among notions + * and analysis of the generic composition paradigm," Lecture Notes in Computer + * Science B<1976> (2000), 531–545, + * http://www-cse.ucsd.edu/~mihir/papers/oem.html. + * + * When sealing messages, a nonce must be given. The length of the nonce is + * fixed by the AEAD in use and is returned by |EVP_AEAD_nonce_length|. *The + * nonce must be unique for all messages with the same key*. This is critically + * important - nonce reuse may completely undermine the security of the AEAD. + * Nonces may be predictable and public, so long as they are unique. Uniqueness + * may be achieved with a simple counter or, if large enough, may be generated + * randomly. The nonce must be passed into the "open" operation by the receiver + * so must either be implicit (e.g. a counter), or must be transmitted along + * with the sealed message. + * + * The "seal" and "open" operations are atomic - an entire message must be + * encrypted or decrypted in a single call. Large messages may have to be split + * up in order to accomodate this. When doing so, be mindful of the need not to + * repeat nonces and the possibility that an attacker could duplicate, reorder + * or drop message chunks. For example, using a single key for a given (large) + * message and sealing chunks with nonces counting from zero would be secure as + * long as the number of chunks was securely transmitted. (Otherwise an + * attacker could truncate the message by dropping chunks from the end.) + * + * The number of chunks could be transmitted by prefixing it to the plaintext, + * for example. This also assumes that no other message would ever use the same + * key otherwise the rule that nonces must be unique for a given key would be + * violated. + * + * The "seal" and "open" operations also permit additional data to be + * authenticated via the |ad| parameter. This data is not included in the + * ciphertext and must be identical for both the "seal" and "open" call. This + * permits implicit context to be authenticated but may be empty if not needed. + * + * The "seal" and "open" operations may work in-place if the |out| and |in| + * arguments are equal. They may also be used to shift the data left inside the + * same buffer if |out| is less than |in|. However, |out| may not point inside + * the input data otherwise the input may be overwritten before it has been + * read. This situation will cause an error. + * + * The "seal" and "open" operations return one on success and zero on error. */ + + +/* AEAD algorithms. */ + +/* EVP_aead_aes_128_gcm is AES-128 in Galois Counter Mode. */ +OPENSSL_EXPORT const EVP_AEAD *EVP_aead_aes_128_gcm(void); + +/* EVP_aead_aes_256_gcm is AES-256 in Galois Counter Mode. */ +OPENSSL_EXPORT const EVP_AEAD *EVP_aead_aes_256_gcm(void); + +/* EVP_aead_chacha20_poly1305 is an AEAD built from ChaCha20 and Poly1305. */ +OPENSSL_EXPORT const EVP_AEAD *EVP_aead_chacha20_poly1305(void); + +/* EVP_aead_aes_128_key_wrap is AES-128 Key Wrap mode. This should never be + * used except to interoperate with existing systems that use this mode. + * + * If the nonce is empty then the default nonce will be used, otherwise it must + * be eight bytes long. The input must be a multiple of eight bytes long. No + * additional data can be given to this mode. */ +OPENSSL_EXPORT const EVP_AEAD *EVP_aead_aes_128_key_wrap(void); + +/* EVP_aead_aes_256_key_wrap is AES-256 in Key Wrap mode. This should never be + * used except to interoperate with existing systems that use this mode. + * + * See |EVP_aead_aes_128_key_wrap| for details. */ +OPENSSL_EXPORT const EVP_AEAD *EVP_aead_aes_256_key_wrap(void); + +/* EVP_aead_aes_128_ctr_hmac_sha256 is AES-128 in CTR mode with HMAC-SHA256 for + * authentication. The nonce is 12 bytes; the bottom 32-bits are used as the + * block counter, thus the maximum plaintext size is 64GB. */ +OPENSSL_EXPORT const EVP_AEAD *EVP_aead_aes_128_ctr_hmac_sha256(void); + +/* EVP_aead_aes_128_ctr_hmac_sha256 is AES-256 in CTR mode with HMAC-SHA256 for + * authentication. See |EVP_aead_aes_128_ctr_hmac_sha256| for details. */ +OPENSSL_EXPORT const EVP_AEAD *EVP_aead_aes_256_ctr_hmac_sha256(void); + +/* EVP_has_aes_hardware returns one if we enable hardware support for fast and + * constant-time AES-GCM. */ +OPENSSL_EXPORT int EVP_has_aes_hardware(void); + + +/* TLS-specific AEAD algorithms. + * + * These AEAD primitives do not meet the definition of generic AEADs. They are + * all specific to TLS and should not be used outside of that context. They must + * be initialized with |EVP_AEAD_CTX_init_with_direction|, are stateful, and may + * not be used concurrently. Any nonces are used as IVs, so they must be + * unpredictable. They only accept an |ad| parameter of length 11 (the standard + * TLS one with length omitted). */ + +OPENSSL_EXPORT const EVP_AEAD *EVP_aead_rc4_md5_tls(void); +OPENSSL_EXPORT const EVP_AEAD *EVP_aead_rc4_sha1_tls(void); + +OPENSSL_EXPORT const EVP_AEAD *EVP_aead_aes_128_cbc_sha1_tls(void); +OPENSSL_EXPORT const EVP_AEAD *EVP_aead_aes_128_cbc_sha1_tls_implicit_iv(void); +OPENSSL_EXPORT const EVP_AEAD *EVP_aead_aes_128_cbc_sha256_tls(void); + +OPENSSL_EXPORT const EVP_AEAD *EVP_aead_aes_256_cbc_sha1_tls(void); +OPENSSL_EXPORT const EVP_AEAD *EVP_aead_aes_256_cbc_sha1_tls_implicit_iv(void); +OPENSSL_EXPORT const EVP_AEAD *EVP_aead_aes_256_cbc_sha256_tls(void); +OPENSSL_EXPORT const EVP_AEAD *EVP_aead_aes_256_cbc_sha384_tls(void); + +OPENSSL_EXPORT const EVP_AEAD *EVP_aead_des_ede3_cbc_sha1_tls(void); +OPENSSL_EXPORT const EVP_AEAD *EVP_aead_des_ede3_cbc_sha1_tls_implicit_iv(void); + + +/* SSLv3-specific AEAD algorithms. + * + * These AEAD primitives do not meet the definition of generic AEADs. They are + * all specific to SSLv3 and should not be used outside of that context. They + * must be initialized with |EVP_AEAD_CTX_init_with_direction|, are stateful, + * and may not be used concurrently. They only accept an |ad| parameter of + * length 9 (the standard TLS one with length and version omitted). */ + +OPENSSL_EXPORT const EVP_AEAD *EVP_aead_rc4_md5_ssl3(void); +OPENSSL_EXPORT const EVP_AEAD *EVP_aead_rc4_sha1_ssl3(void); +OPENSSL_EXPORT const EVP_AEAD *EVP_aead_aes_128_cbc_sha1_ssl3(void); +OPENSSL_EXPORT const EVP_AEAD *EVP_aead_aes_256_cbc_sha1_ssl3(void); +OPENSSL_EXPORT const EVP_AEAD *EVP_aead_des_ede3_cbc_sha1_ssl3(void); + + +/* Utility functions. */ + +/* EVP_AEAD_key_length returns the length, in bytes, of the keys used by + * |aead|. */ +OPENSSL_EXPORT size_t EVP_AEAD_key_length(const EVP_AEAD *aead); + +/* EVP_AEAD_nonce_length returns the length, in bytes, of the per-message nonce + * for |aead|. */ +OPENSSL_EXPORT size_t EVP_AEAD_nonce_length(const EVP_AEAD *aead); + +/* EVP_AEAD_max_overhead returns the maximum number of additional bytes added + * by the act of sealing data with |aead|. */ +OPENSSL_EXPORT size_t EVP_AEAD_max_overhead(const EVP_AEAD *aead); + +/* EVP_AEAD_max_tag_len returns the maximum tag length when using |aead|. This + * is the largest value that can be passed as |tag_len| to + * |EVP_AEAD_CTX_init|. */ +OPENSSL_EXPORT size_t EVP_AEAD_max_tag_len(const EVP_AEAD *aead); + + +/* AEAD operations. */ + +/* An EVP_AEAD_CTX represents an AEAD algorithm configured with a specific key + * and message-independent IV. */ +typedef struct evp_aead_ctx_st { + const EVP_AEAD *aead; + /* aead_state is an opaque pointer to whatever state the AEAD needs to + * maintain. */ + void *aead_state; +} EVP_AEAD_CTX; + +/* EVP_AEAD_MAX_KEY_LENGTH contains the maximum key length used by + * any AEAD defined in this header. */ +#define EVP_AEAD_MAX_KEY_LENGTH 80 + +/* EVP_AEAD_MAX_NONCE_LENGTH contains the maximum nonce length used by + * any AEAD defined in this header. */ +#define EVP_AEAD_MAX_NONCE_LENGTH 16 + +/* EVP_AEAD_MAX_OVERHEAD contains the maximum overhead used by any AEAD + * defined in this header. */ +#define EVP_AEAD_MAX_OVERHEAD 64 + +/* EVP_AEAD_DEFAULT_TAG_LENGTH is a magic value that can be passed to + * EVP_AEAD_CTX_init to indicate that the default tag length for an AEAD should + * be used. */ +#define EVP_AEAD_DEFAULT_TAG_LENGTH 0 + +/* evp_aead_direction_t denotes the direction of an AEAD operation. */ +enum evp_aead_direction_t { + evp_aead_open, + evp_aead_seal, +}; + +/* EVP_AEAD_CTX_init initializes |ctx| for the given AEAD algorithm from |impl|. + * The |impl| argument may be NULL to choose the default implementation. + * Authentication tags may be truncated by passing a size as |tag_len|. A + * |tag_len| of zero indicates the default tag length and this is defined as + * EVP_AEAD_DEFAULT_TAG_LENGTH for readability. + * + * Returns 1 on success. Otherwise returns 0 and pushes to the error stack. In + * the error case, you do not need to call |EVP_AEAD_CTX_cleanup|, but it's + * harmless to do so. */ +OPENSSL_EXPORT int EVP_AEAD_CTX_init(EVP_AEAD_CTX *ctx, const EVP_AEAD *aead, + const uint8_t *key, size_t key_len, + size_t tag_len, ENGINE *impl); + +/* EVP_AEAD_CTX_init_with_direction calls |EVP_AEAD_CTX_init| for normal + * AEADs. For TLS-specific and SSL3-specific AEADs, it initializes |ctx| for a + * given direction. */ +OPENSSL_EXPORT int EVP_AEAD_CTX_init_with_direction( + EVP_AEAD_CTX *ctx, const EVP_AEAD *aead, const uint8_t *key, size_t key_len, + size_t tag_len, enum evp_aead_direction_t dir); + +/* EVP_AEAD_CTX_cleanup frees any data allocated by |ctx|. It is a no-op to + * call |EVP_AEAD_CTX_cleanup| on a |EVP_AEAD_CTX| that has been |memset| to + * all zeros. */ +OPENSSL_EXPORT void EVP_AEAD_CTX_cleanup(EVP_AEAD_CTX *ctx); + +/* EVP_AEAD_CTX_seal encrypts and authenticates |in_len| bytes from |in| and + * authenticates |ad_len| bytes from |ad| and writes the result to |out|. It + * returns one on success and zero otherwise. + * + * This function may be called (with the same |EVP_AEAD_CTX|) concurrently with + * itself or |EVP_AEAD_CTX_open|. + * + * At most |max_out_len| bytes are written to |out| and, in order to ensure + * success, |max_out_len| should be |in_len| plus the result of + * |EVP_AEAD_max_overhead|. On successful return, |*out_len| is set to the + * actual number of bytes written. + * + * The length of |nonce|, |nonce_len|, must be equal to the result of + * |EVP_AEAD_nonce_length| for this AEAD. + * + * |EVP_AEAD_CTX_seal| never results in a partial output. If |max_out_len| is + * insufficient, zero will be returned. (In this case, |*out_len| is set to + * zero.) + * + * If |in| and |out| alias then |out| must be <= |in|. */ +OPENSSL_EXPORT int EVP_AEAD_CTX_seal(const EVP_AEAD_CTX *ctx, uint8_t *out, + size_t *out_len, size_t max_out_len, + const uint8_t *nonce, size_t nonce_len, + const uint8_t *in, size_t in_len, + const uint8_t *ad, size_t ad_len); + +/* EVP_AEAD_CTX_open authenticates |in_len| bytes from |in| and |ad_len| bytes + * from |ad| and decrypts at most |in_len| bytes into |out|. It returns one on + * success and zero otherwise. + * + * This function may be called (with the same |EVP_AEAD_CTX|) concurrently with + * itself or |EVP_AEAD_CTX_seal|. + * + * At most |in_len| bytes are written to |out|. In order to ensure success, + * |max_out_len| should be at least |in_len|. On successful return, |*out_len| + * is set to the the actual number of bytes written. + * + * The length of |nonce|, |nonce_len|, must be equal to the result of + * |EVP_AEAD_nonce_length| for this AEAD. + * + * |EVP_AEAD_CTX_open| never results in a partial output. If |max_out_len| is + * insufficient, zero will be returned. (In this case, |*out_len| is set to + * zero.) + * + * If |in| and |out| alias then |out| must be <= |in|. */ +OPENSSL_EXPORT int EVP_AEAD_CTX_open(const EVP_AEAD_CTX *ctx, uint8_t *out, + size_t *out_len, size_t max_out_len, + const uint8_t *nonce, size_t nonce_len, + const uint8_t *in, size_t in_len, + const uint8_t *ad, size_t ad_len); + + +/* Obscure functions. */ + +/* EVP_AEAD_CTX_get_rc4_state sets |*out_key| to point to an RC4 key structure. + * It returns one on success or zero if |ctx| doesn't have an RC4 key. */ +OPENSSL_EXPORT int EVP_AEAD_CTX_get_rc4_state(const EVP_AEAD_CTX *ctx, + const RC4_KEY **out_key); + + +#if defined(__cplusplus) +} /* extern C */ +#endif + +#endif /* OPENSSL_HEADER_AEAD_H */ diff --git a/phonelibs/boringssl/include/openssl/aes.h b/phonelibs/boringssl/include/openssl/aes.h new file mode 100644 index 00000000000000..84cde416e64432 --- /dev/null +++ b/phonelibs/boringssl/include/openssl/aes.h @@ -0,0 +1,158 @@ +/* ==================================================================== + * Copyright (c) 2002-2006 The OpenSSL Project. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * + * 3. All advertising materials mentioning features or use of this + * software must display the following acknowledgment: + * "This product includes software developed by the OpenSSL Project + * for use in the OpenSSL Toolkit. (http://www.openssl.org/)" + * + * 4. The names "OpenSSL Toolkit" and "OpenSSL Project" must not be used to + * endorse or promote products derived from this software without + * prior written permission. For written permission, please contact + * openssl-core@openssl.org. + * + * 5. Products derived from this software may not be called "OpenSSL" + * nor may "OpenSSL" appear in their names without prior written + * permission of the OpenSSL Project. + * + * 6. Redistributions of any form whatsoever must retain the following + * acknowledgment: + * "This product includes software developed by the OpenSSL Project + * for use in the OpenSSL Toolkit (http://www.openssl.org/)" + * + * THIS SOFTWARE IS PROVIDED BY THE OpenSSL PROJECT ``AS IS'' AND ANY + * EXPRESSED OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR + * PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE OpenSSL PROJECT OR + * ITS CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, + * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT + * NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + * STRICT LIABILITY, OR TORT (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 OPENSSL_HEADER_AES_H +#define OPENSSL_HEADER_AES_H + +#include + +#if defined(__cplusplus) +extern "C" { +#endif + + +/* Raw AES functions. */ + + +#define AES_ENCRYPT 1 +#define AES_DECRYPT 0 + +/* AES_MAXNR is the maximum number of AES rounds. */ +#define AES_MAXNR 14 + +#define AES_BLOCK_SIZE 16 + +/* aes_key_st should be an opaque type, but EVP requires that the size be + * known. */ +struct aes_key_st { + uint32_t rd_key[4 * (AES_MAXNR + 1)]; + unsigned rounds; +}; +typedef struct aes_key_st AES_KEY; + +/* AES_set_encrypt_key configures |aeskey| to encrypt with the |bits|-bit key, + * |key|. + * + * WARNING: unlike other OpenSSL functions, this returns zero on success and a + * negative number on error. */ +OPENSSL_EXPORT int AES_set_encrypt_key(const uint8_t *key, unsigned bits, + AES_KEY *aeskey); + +/* AES_set_decrypt_key configures |aeskey| to decrypt with the |bits|-bit key, + * |key|. + * + * WARNING: unlike other OpenSSL functions, this returns zero on success and a + * negative number on error. */ +OPENSSL_EXPORT int AES_set_decrypt_key(const uint8_t *key, unsigned bits, + AES_KEY *aeskey); + +/* AES_encrypt encrypts a single block from |in| to |out| with |key|. The |in| + * and |out| pointers may overlap. */ +OPENSSL_EXPORT void AES_encrypt(const uint8_t *in, uint8_t *out, + const AES_KEY *key); + +/* AES_decrypt decrypts a single block from |in| to |out| with |key|. The |in| + * and |out| pointers may overlap. */ +OPENSSL_EXPORT void AES_decrypt(const uint8_t *in, uint8_t *out, + const AES_KEY *key); + + +/* Block cipher modes. */ + +/* AES_ctr128_encrypt encrypts (or decrypts, it's the same in CTR mode) |len| + * bytes from |in| to |out|. The |num| parameter must be set to zero on the + * first call and |ivec| will be incremented. */ +OPENSSL_EXPORT void AES_ctr128_encrypt(const uint8_t *in, uint8_t *out, + size_t len, const AES_KEY *key, + uint8_t ivec[AES_BLOCK_SIZE], + uint8_t ecount_buf[AES_BLOCK_SIZE], + unsigned int *num); + +/* AES_ecb_encrypt encrypts (or decrypts, if |enc| == |AES_DECRYPT|) a single, + * 16 byte block from |in| to |out|. */ +OPENSSL_EXPORT void AES_ecb_encrypt(const uint8_t *in, uint8_t *out, + const AES_KEY *key, const int enc); + +/* AES_cbc_encrypt encrypts (or decrypts, if |enc| == |AES_DECRYPT|) |len| + * bytes from |in| to |out|. The length must be a multiple of the block size. */ +OPENSSL_EXPORT void AES_cbc_encrypt(const uint8_t *in, uint8_t *out, size_t len, + const AES_KEY *key, uint8_t *ivec, + const int enc); + +/* AES_ofb128_encrypt encrypts (or decrypts, it's the same in CTR mode) |len| + * bytes from |in| to |out|. The |num| parameter must be set to zero on the + * first call. */ +OPENSSL_EXPORT void AES_ofb128_encrypt(const uint8_t *in, uint8_t *out, + size_t len, const AES_KEY *key, + uint8_t *ivec, int *num); + +/* AES_cfb128_encrypt encrypts (or decrypts, if |enc| == |AES_DECRYPT|) |len| + * bytes from |in| to |out|. The |num| parameter must be set to zero on the + * first call. */ +OPENSSL_EXPORT void AES_cfb128_encrypt(const uint8_t *in, uint8_t *out, + size_t len, const AES_KEY *key, + uint8_t *ivec, int *num, int enc); + + +/* Android compatibility section. + * + * These functions are declared, temporarily, for Android because + * wpa_supplicant will take a little time to sync with upstream. Outside of + * Android they'll have no definition. */ + +OPENSSL_EXPORT int AES_wrap_key(AES_KEY *key, const uint8_t *iv, uint8_t *out, + const uint8_t *in, unsigned in_len); +OPENSSL_EXPORT int AES_unwrap_key(AES_KEY *key, const uint8_t *iv, uint8_t *out, + const uint8_t *in, unsigned in_len); + + +#if defined(__cplusplus) +} /* extern C */ +#endif + +#endif /* OPENSSL_HEADER_AES_H */ diff --git a/phonelibs/boringssl/include/openssl/asn1.h b/phonelibs/boringssl/include/openssl/asn1.h new file mode 100644 index 00000000000000..4baf81c6bdc442 --- /dev/null +++ b/phonelibs/boringssl/include/openssl/asn1.h @@ -0,0 +1,1234 @@ +/* crypto/asn1/asn1.h */ +/* Copyright (C) 1995-1998 Eric Young (eay@cryptsoft.com) + * All rights reserved. + * + * This package is an SSL implementation written + * by Eric Young (eay@cryptsoft.com). + * The implementation was written so as to conform with Netscapes SSL. + * + * This library is free for commercial and non-commercial use as long as + * the following conditions are aheared to. The following conditions + * apply to all code found in this distribution, be it the RC4, RSA, + * lhash, DES, etc., code; not just the SSL code. The SSL documentation + * included with this distribution is covered by the same copyright terms + * except that the holder is Tim Hudson (tjh@cryptsoft.com). + * + * Copyright remains Eric Young's, and as such any Copyright notices in + * the code are not to be removed. + * If this package is used in a product, Eric Young should be given attribution + * as the author of the parts of the library used. + * This can be in the form of a textual message at program startup or + * in documentation (online or textual) provided with the package. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must 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. All advertising materials mentioning features or use of this software + * must display the following acknowledgement: + * "This product includes cryptographic software written by + * Eric Young (eay@cryptsoft.com)" + * The word 'cryptographic' can be left out if the rouines from the library + * being used are not cryptographic related :-). + * 4. If you include any Windows specific code (or a derivative thereof) from + * the apps directory (application code) you must include an acknowledgement: + * "This product includes software written by Tim Hudson (tjh@cryptsoft.com)" + * + * THIS SOFTWARE IS PROVIDED BY ERIC YOUNG ``AS IS'' AND + * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHOR OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (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 licence and distribution terms for any publically available version or + * derivative of this code cannot be changed. i.e. this code cannot simply be + * copied and put under another distribution licence + * [including the GNU Public Licence.] + */ + +#ifndef HEADER_ASN1_H +#define HEADER_ASN1_H + +#include + +#include + +#include +#include + +#include + +#ifdef __cplusplus +extern "C" { +#endif + +#define V_ASN1_UNIVERSAL 0x00 +#define V_ASN1_APPLICATION 0x40 +#define V_ASN1_CONTEXT_SPECIFIC 0x80 +#define V_ASN1_PRIVATE 0xc0 + +#define V_ASN1_CONSTRUCTED 0x20 +#define V_ASN1_PRIMITIVE_TAG 0x1f +#define V_ASN1_PRIMATIVE_TAG 0x1f + +#define V_ASN1_APP_CHOOSE -2 /* let the recipient choose */ +#define V_ASN1_OTHER -3 /* used in ASN1_TYPE */ +#define V_ASN1_ANY -4 /* used in ASN1 template code */ + +#define V_ASN1_NEG 0x100 /* negative flag */ + +#define V_ASN1_UNDEF -1 +#define V_ASN1_EOC 0 +#define V_ASN1_BOOLEAN 1 /**/ +#define V_ASN1_INTEGER 2 +#define V_ASN1_NEG_INTEGER (2 | V_ASN1_NEG) +#define V_ASN1_BIT_STRING 3 +#define V_ASN1_OCTET_STRING 4 +#define V_ASN1_NULL 5 +#define V_ASN1_OBJECT 6 +#define V_ASN1_OBJECT_DESCRIPTOR 7 +#define V_ASN1_EXTERNAL 8 +#define V_ASN1_REAL 9 +#define V_ASN1_ENUMERATED 10 +#define V_ASN1_NEG_ENUMERATED (10 | V_ASN1_NEG) +#define V_ASN1_UTF8STRING 12 +#define V_ASN1_SEQUENCE 16 +#define V_ASN1_SET 17 +#define V_ASN1_NUMERICSTRING 18 /**/ +#define V_ASN1_PRINTABLESTRING 19 +#define V_ASN1_T61STRING 20 +#define V_ASN1_TELETEXSTRING 20 /* alias */ +#define V_ASN1_VIDEOTEXSTRING 21 /**/ +#define V_ASN1_IA5STRING 22 +#define V_ASN1_UTCTIME 23 +#define V_ASN1_GENERALIZEDTIME 24 /**/ +#define V_ASN1_GRAPHICSTRING 25 /**/ +#define V_ASN1_ISO64STRING 26 /**/ +#define V_ASN1_VISIBLESTRING 26 /* alias */ +#define V_ASN1_GENERALSTRING 27 /**/ +#define V_ASN1_UNIVERSALSTRING 28 /**/ +#define V_ASN1_BMPSTRING 30 + +/* For use with d2i_ASN1_type_bytes() */ +#define B_ASN1_NUMERICSTRING 0x0001 +#define B_ASN1_PRINTABLESTRING 0x0002 +#define B_ASN1_T61STRING 0x0004 +#define B_ASN1_TELETEXSTRING 0x0004 +#define B_ASN1_VIDEOTEXSTRING 0x0008 +#define B_ASN1_IA5STRING 0x0010 +#define B_ASN1_GRAPHICSTRING 0x0020 +#define B_ASN1_ISO64STRING 0x0040 +#define B_ASN1_VISIBLESTRING 0x0040 +#define B_ASN1_GENERALSTRING 0x0080 +#define B_ASN1_UNIVERSALSTRING 0x0100 +#define B_ASN1_OCTET_STRING 0x0200 +#define B_ASN1_BIT_STRING 0x0400 +#define B_ASN1_BMPSTRING 0x0800 +#define B_ASN1_UNKNOWN 0x1000 +#define B_ASN1_UTF8STRING 0x2000 +#define B_ASN1_UTCTIME 0x4000 +#define B_ASN1_GENERALIZEDTIME 0x8000 +#define B_ASN1_SEQUENCE 0x10000 + +/* For use with ASN1_mbstring_copy() */ +#define MBSTRING_FLAG 0x1000 +#define MBSTRING_UTF8 (MBSTRING_FLAG) +#define MBSTRING_ASC (MBSTRING_FLAG|1) +#define MBSTRING_BMP (MBSTRING_FLAG|2) +#define MBSTRING_UNIV (MBSTRING_FLAG|4) + +#define SMIME_OLDMIME 0x400 +#define SMIME_CRLFEOL 0x800 +#define SMIME_STREAM 0x1000 + +#define DECLARE_ASN1_SET_OF(type) /* filled in by mkstack.pl */ +#define IMPLEMENT_ASN1_SET_OF(type) /* nothing, no longer needed */ + +/* We MUST make sure that, except for constness, asn1_ctx_st and + asn1_const_ctx are exactly the same. Fortunately, as soon as + the old ASN1 parsing macros are gone, we can throw this away + as well... */ +typedef struct asn1_ctx_st + { + unsigned char *p;/* work char pointer */ + int eos; /* end of sequence read for indefinite encoding */ + int error; /* error code to use when returning an error */ + int inf; /* constructed if 0x20, indefinite is 0x21 */ + int tag; /* tag from last 'get object' */ + int xclass; /* class from last 'get object' */ + long slen; /* length of last 'get object' */ + unsigned char *max; /* largest value of p allowed */ + unsigned char *q;/* temporary variable */ + unsigned char **pp;/* variable */ + int line; /* used in error processing */ + } ASN1_CTX; + +typedef struct asn1_const_ctx_st + { + const unsigned char *p;/* work char pointer */ + int eos; /* end of sequence read for indefinite encoding */ + int error; /* error code to use when returning an error */ + int inf; /* constructed if 0x20, indefinite is 0x21 */ + int tag; /* tag from last 'get object' */ + int xclass; /* class from last 'get object' */ + long slen; /* length of last 'get object' */ + const unsigned char *max; /* largest value of p allowed */ + const unsigned char *q;/* temporary variable */ + const unsigned char **pp;/* variable */ + int line; /* used in error processing */ + } ASN1_const_CTX; + +/* These are used internally in the ASN1_OBJECT to keep track of + * whether the names and data need to be free()ed */ +#define ASN1_OBJECT_FLAG_DYNAMIC 0x01 /* internal use */ +#define ASN1_OBJECT_FLAG_CRITICAL 0x02 /* critical x509v3 object id */ +#define ASN1_OBJECT_FLAG_DYNAMIC_STRINGS 0x04 /* internal use */ +#define ASN1_OBJECT_FLAG_DYNAMIC_DATA 0x08 /* internal use */ +struct asn1_object_st + { + const char *sn,*ln; + int nid; + int length; + const unsigned char *data; /* data remains const after init */ + int flags; /* Should we free this one */ + }; + +#define ASN1_STRING_FLAG_BITS_LEFT 0x08 /* Set if 0x07 has bits left value */ +/* This indicates that the ASN1_STRING is not a real value but just a place + * holder for the location where indefinite length constructed data should + * be inserted in the memory buffer + */ +#define ASN1_STRING_FLAG_NDEF 0x010 + +/* This flag is used by the CMS code to indicate that a string is not + * complete and is a place holder for content when it had all been + * accessed. The flag will be reset when content has been written to it. + */ + +#define ASN1_STRING_FLAG_CONT 0x020 +/* This flag is used by ASN1 code to indicate an ASN1_STRING is an MSTRING + * type. + */ +#define ASN1_STRING_FLAG_MSTRING 0x040 +/* This is the base type that holds just about everything :-) */ +struct asn1_string_st + { + int length; + int type; + unsigned char *data; + /* The value of the following field depends on the type being + * held. It is mostly being used for BIT_STRING so if the + * input data has a non-zero 'unused bits' value, it will be + * handled correctly */ + long flags; + }; + +/* ASN1_ENCODING structure: this is used to save the received + * encoding of an ASN1 type. This is useful to get round + * problems with invalid encodings which can break signatures. + */ + +typedef struct ASN1_ENCODING_st + { + unsigned char *enc; /* DER encoding */ + long len; /* Length of encoding */ + int modified; /* set to 1 if 'enc' is invalid */ + } ASN1_ENCODING; + +/* Used with ASN1 LONG type: if a long is set to this it is omitted */ +#define ASN1_LONG_UNDEF 0x7fffffffL + +#define STABLE_FLAGS_MALLOC 0x01 +#define STABLE_NO_MASK 0x02 +#define DIRSTRING_TYPE \ + (B_ASN1_PRINTABLESTRING|B_ASN1_T61STRING|B_ASN1_BMPSTRING|B_ASN1_UTF8STRING) +#define PKCS9STRING_TYPE (DIRSTRING_TYPE|B_ASN1_IA5STRING) + +typedef struct asn1_string_table_st { + int nid; + long minsize; + long maxsize; + unsigned long mask; + unsigned long flags; +} ASN1_STRING_TABLE; + +/* size limits: this stuff is taken straight from RFC2459 */ + +#define ub_name 32768 +#define ub_common_name 64 +#define ub_locality_name 128 +#define ub_state_name 128 +#define ub_organization_name 64 +#define ub_organization_unit_name 64 +#define ub_title 64 +#define ub_email_address 128 + +/* Declarations for template structures: for full definitions + * see asn1t.h + */ +typedef struct ASN1_TEMPLATE_st ASN1_TEMPLATE; +typedef struct ASN1_TLC_st ASN1_TLC; +/* This is just an opaque pointer */ +typedef struct ASN1_VALUE_st ASN1_VALUE; + +/* Declare ASN1 functions: the implement macro in in asn1t.h */ + +#define DECLARE_ASN1_FUNCTIONS(type) DECLARE_ASN1_FUNCTIONS_name(type, type) + +#define DECLARE_ASN1_ALLOC_FUNCTIONS(type) \ + DECLARE_ASN1_ALLOC_FUNCTIONS_name(type, type) + +#define DECLARE_ASN1_FUNCTIONS_name(type, name) \ + DECLARE_ASN1_ALLOC_FUNCTIONS_name(type, name) \ + DECLARE_ASN1_ENCODE_FUNCTIONS(type, name, name) + +#define DECLARE_ASN1_FUNCTIONS_fname(type, itname, name) \ + DECLARE_ASN1_ALLOC_FUNCTIONS_name(type, name) \ + DECLARE_ASN1_ENCODE_FUNCTIONS(type, itname, name) + +#define DECLARE_ASN1_ENCODE_FUNCTIONS(type, itname, name) \ + OPENSSL_EXPORT type *d2i_##name(type **a, const unsigned char **in, long len); \ + OPENSSL_EXPORT int i2d_##name(type *a, unsigned char **out); \ + DECLARE_ASN1_ITEM(itname) + +#define DECLARE_ASN1_ENCODE_FUNCTIONS_const(type, name) \ + OPENSSL_EXPORT type *d2i_##name(type **a, const unsigned char **in, long len); \ + OPENSSL_EXPORT int i2d_##name(const type *a, unsigned char **out); \ + DECLARE_ASN1_ITEM(name) + +#define DECLARE_ASN1_NDEF_FUNCTION(name) \ + OPENSSL_EXPORT int i2d_##name##_NDEF(name *a, unsigned char **out); + +#define DECLARE_ASN1_FUNCTIONS_const(name) \ + DECLARE_ASN1_ALLOC_FUNCTIONS(name) \ + DECLARE_ASN1_ENCODE_FUNCTIONS_const(name, name) + +#define DECLARE_ASN1_ALLOC_FUNCTIONS_name(type, name) \ + OPENSSL_EXPORT type *name##_new(void); \ + OPENSSL_EXPORT void name##_free(type *a); + +#define DECLARE_ASN1_PRINT_FUNCTION(stname) \ + DECLARE_ASN1_PRINT_FUNCTION_fname(stname, stname) + +#define DECLARE_ASN1_PRINT_FUNCTION_fname(stname, fname) \ + OPENSSL_EXPORT int fname##_print_ctx(BIO *out, stname *x, int indent, \ + const ASN1_PCTX *pctx); + +#define D2I_OF(type) type *(*)(type **,const unsigned char **,long) +#define I2D_OF(type) int (*)(type *,unsigned char **) +#define I2D_OF_const(type) int (*)(const type *,unsigned char **) + +#define CHECKED_D2I_OF(type, d2i) \ + ((d2i_of_void*) (1 ? d2i : ((D2I_OF(type))0))) +#define CHECKED_I2D_OF(type, i2d) \ + ((i2d_of_void*) (1 ? i2d : ((I2D_OF(type))0))) +#define CHECKED_NEW_OF(type, xnew) \ + ((void *(*)(void)) (1 ? xnew : ((type *(*)(void))0))) +#define CHECKED_PPTR_OF(type, p) \ + ((void**) (1 ? p : (type**)0)) + +#define TYPEDEF_D2I_OF(type) typedef type *d2i_of_##type(type **,const unsigned char **,long) +#define TYPEDEF_I2D_OF(type) typedef int i2d_of_##type(const type *,unsigned char **) +#define TYPEDEF_D2I2D_OF(type) TYPEDEF_D2I_OF(type); TYPEDEF_I2D_OF(type) + +TYPEDEF_D2I2D_OF(void); + +/* The following macros and typedefs allow an ASN1_ITEM + * to be embedded in a structure and referenced. Since + * the ASN1_ITEM pointers need to be globally accessible + * (possibly from shared libraries) they may exist in + * different forms. On platforms that support it the + * ASN1_ITEM structure itself will be globally exported. + * Other platforms will export a function that returns + * an ASN1_ITEM pointer. + * + * To handle both cases transparently the macros below + * should be used instead of hard coding an ASN1_ITEM + * pointer in a structure. + * + * The structure will look like this: + * + * typedef struct SOMETHING_st { + * ... + * ASN1_ITEM_EXP *iptr; + * ... + * } SOMETHING; + * + * It would be initialised as e.g.: + * + * SOMETHING somevar = {...,ASN1_ITEM_ref(X509),...}; + * + * and the actual pointer extracted with: + * + * const ASN1_ITEM *it = ASN1_ITEM_ptr(somevar.iptr); + * + * Finally an ASN1_ITEM pointer can be extracted from an + * appropriate reference with: ASN1_ITEM_rptr(X509). This + * would be used when a function takes an ASN1_ITEM * argument. + * + */ + +/* ASN1_ITEM pointer exported type */ +typedef const ASN1_ITEM ASN1_ITEM_EXP; + +/* Macro to obtain ASN1_ITEM pointer from exported type */ +#define ASN1_ITEM_ptr(iptr) (iptr) + +/* Macro to include ASN1_ITEM pointer from base type */ +#define ASN1_ITEM_ref(iptr) (&(iptr##_it)) + +#define ASN1_ITEM_rptr(ref) (&(ref##_it)) + +#define DECLARE_ASN1_ITEM(name) \ + extern OPENSSL_EXPORT const ASN1_ITEM name##_it; + +/* Parameters used by ASN1_STRING_print_ex() */ + +/* These determine which characters to escape: + * RFC2253 special characters, control characters and + * MSB set characters + */ + +#define ASN1_STRFLGS_ESC_2253 1 +#define ASN1_STRFLGS_ESC_CTRL 2 +#define ASN1_STRFLGS_ESC_MSB 4 + + +/* This flag determines how we do escaping: normally + * RC2253 backslash only, set this to use backslash and + * quote. + */ + +#define ASN1_STRFLGS_ESC_QUOTE 8 + + +/* These three flags are internal use only. */ + +/* Character is a valid PrintableString character */ +#define CHARTYPE_PRINTABLESTRING 0x10 +/* Character needs escaping if it is the first character */ +#define CHARTYPE_FIRST_ESC_2253 0x20 +/* Character needs escaping if it is the last character */ +#define CHARTYPE_LAST_ESC_2253 0x40 + +/* NB the internal flags are safely reused below by flags + * handled at the top level. + */ + +/* If this is set we convert all character strings + * to UTF8 first + */ + +#define ASN1_STRFLGS_UTF8_CONVERT 0x10 + +/* If this is set we don't attempt to interpret content: + * just assume all strings are 1 byte per character. This + * will produce some pretty odd looking output! + */ + +#define ASN1_STRFLGS_IGNORE_TYPE 0x20 + +/* If this is set we include the string type in the output */ +#define ASN1_STRFLGS_SHOW_TYPE 0x40 + +/* This determines which strings to display and which to + * 'dump' (hex dump of content octets or DER encoding). We can + * only dump non character strings or everything. If we + * don't dump 'unknown' they are interpreted as character + * strings with 1 octet per character and are subject to + * the usual escaping options. + */ + +#define ASN1_STRFLGS_DUMP_ALL 0x80 +#define ASN1_STRFLGS_DUMP_UNKNOWN 0x100 + +/* These determine what 'dumping' does, we can dump the + * content octets or the DER encoding: both use the + * RFC2253 #XXXXX notation. + */ + +#define ASN1_STRFLGS_DUMP_DER 0x200 + +/* All the string flags consistent with RFC2253, + * escaping control characters isn't essential in + * RFC2253 but it is advisable anyway. + */ + +#define ASN1_STRFLGS_RFC2253 (ASN1_STRFLGS_ESC_2253 | \ + ASN1_STRFLGS_ESC_CTRL | \ + ASN1_STRFLGS_ESC_MSB | \ + ASN1_STRFLGS_UTF8_CONVERT | \ + ASN1_STRFLGS_DUMP_UNKNOWN | \ + ASN1_STRFLGS_DUMP_DER) + +DECLARE_ASN1_SET_OF(ASN1_INTEGER) + +typedef struct asn1_type_st + { + int type; + union { + char *ptr; + ASN1_BOOLEAN boolean; + ASN1_STRING * asn1_string; + ASN1_OBJECT * object; + ASN1_INTEGER * integer; + ASN1_ENUMERATED * enumerated; + ASN1_BIT_STRING * bit_string; + ASN1_OCTET_STRING * octet_string; + ASN1_PRINTABLESTRING * printablestring; + ASN1_T61STRING * t61string; + ASN1_IA5STRING * ia5string; + ASN1_GENERALSTRING * generalstring; + ASN1_BMPSTRING * bmpstring; + ASN1_UNIVERSALSTRING * universalstring; + ASN1_UTCTIME * utctime; + ASN1_GENERALIZEDTIME * generalizedtime; + ASN1_VISIBLESTRING * visiblestring; + ASN1_UTF8STRING * utf8string; + /* set and sequence are left complete and still + * contain the set or sequence bytes */ + ASN1_STRING * set; + ASN1_STRING * sequence; + ASN1_VALUE * asn1_value; + } value; + } ASN1_TYPE; + +DECLARE_ASN1_SET_OF(ASN1_TYPE) + +typedef STACK_OF(ASN1_TYPE) ASN1_SEQUENCE_ANY; + +DECLARE_ASN1_ENCODE_FUNCTIONS_const(ASN1_SEQUENCE_ANY, ASN1_SEQUENCE_ANY) +DECLARE_ASN1_ENCODE_FUNCTIONS_const(ASN1_SEQUENCE_ANY, ASN1_SET_ANY) + +struct X509_algor_st + { + ASN1_OBJECT *algorithm; + ASN1_TYPE *parameter; + } /* X509_ALGOR */; +DEFINE_STACK_OF(X509_ALGOR); + +DECLARE_ASN1_FUNCTIONS(X509_ALGOR) + +typedef struct NETSCAPE_X509_st + { + ASN1_OCTET_STRING *header; + X509 *cert; + } NETSCAPE_X509; + +/* This is used to contain a list of bit names */ +typedef struct BIT_STRING_BITNAME_st { + int bitnum; + const char *lname; + const char *sname; +} BIT_STRING_BITNAME; + + +#define M_ASN1_STRING_length(x) ((x)->length) +#define M_ASN1_STRING_length_set(x, n) ((x)->length = (n)) +#define M_ASN1_STRING_type(x) ((x)->type) +#define M_ASN1_STRING_data(x) ((x)->data) + +/* Macros for string operations */ +#define M_ASN1_BIT_STRING_new() (ASN1_BIT_STRING *)\ + ASN1_STRING_type_new(V_ASN1_BIT_STRING) +#define M_ASN1_BIT_STRING_free(a) ASN1_STRING_free((ASN1_STRING *)a) +#define M_ASN1_BIT_STRING_dup(a) (ASN1_BIT_STRING *)\ + ASN1_STRING_dup((const ASN1_STRING *)a) +#define M_ASN1_BIT_STRING_cmp(a,b) ASN1_STRING_cmp(\ + (const ASN1_STRING *)a,(const ASN1_STRING *)b) +#define M_ASN1_BIT_STRING_set(a,b,c) ASN1_STRING_set((ASN1_STRING *)a,b,c) + +#define M_ASN1_INTEGER_new() (ASN1_INTEGER *)\ + ASN1_STRING_type_new(V_ASN1_INTEGER) +#define M_ASN1_INTEGER_free(a) ASN1_STRING_free((ASN1_STRING *)a) +#define M_ASN1_INTEGER_dup(a) (ASN1_INTEGER *)\ + ASN1_STRING_dup((const ASN1_STRING *)a) +#define M_ASN1_INTEGER_cmp(a,b) ASN1_STRING_cmp(\ + (const ASN1_STRING *)a,(const ASN1_STRING *)b) + +#define M_ASN1_ENUMERATED_new() (ASN1_ENUMERATED *)\ + ASN1_STRING_type_new(V_ASN1_ENUMERATED) +#define M_ASN1_ENUMERATED_free(a) ASN1_STRING_free((ASN1_STRING *)a) +#define M_ASN1_ENUMERATED_dup(a) (ASN1_ENUMERATED *)\ + ASN1_STRING_dup((const ASN1_STRING *)a) +#define M_ASN1_ENUMERATED_cmp(a,b) ASN1_STRING_cmp(\ + (const ASN1_STRING *)a,(const ASN1_STRING *)b) + +#define M_ASN1_OCTET_STRING_new() (ASN1_OCTET_STRING *)\ + ASN1_STRING_type_new(V_ASN1_OCTET_STRING) +#define M_ASN1_OCTET_STRING_free(a) ASN1_STRING_free((ASN1_STRING *)a) +#define M_ASN1_OCTET_STRING_dup(a) (ASN1_OCTET_STRING *)\ + ASN1_STRING_dup((const ASN1_STRING *)a) +#define M_ASN1_OCTET_STRING_cmp(a,b) ASN1_STRING_cmp(\ + (const ASN1_STRING *)a,(const ASN1_STRING *)b) +#define M_ASN1_OCTET_STRING_set(a,b,c) ASN1_STRING_set((ASN1_STRING *)a,b,c) +#define M_ASN1_OCTET_STRING_print(a,b) ASN1_STRING_print(a,(ASN1_STRING *)b) +#define M_i2d_ASN1_OCTET_STRING(a,pp) \ + i2d_ASN1_bytes((ASN1_STRING *)a,pp,V_ASN1_OCTET_STRING,\ + V_ASN1_UNIVERSAL) + +#define B_ASN1_TIME \ + B_ASN1_UTCTIME | \ + B_ASN1_GENERALIZEDTIME + +#define B_ASN1_PRINTABLE \ + B_ASN1_NUMERICSTRING| \ + B_ASN1_PRINTABLESTRING| \ + B_ASN1_T61STRING| \ + B_ASN1_IA5STRING| \ + B_ASN1_BIT_STRING| \ + B_ASN1_UNIVERSALSTRING|\ + B_ASN1_BMPSTRING|\ + B_ASN1_UTF8STRING|\ + B_ASN1_SEQUENCE|\ + B_ASN1_UNKNOWN + +#define B_ASN1_DIRECTORYSTRING \ + B_ASN1_PRINTABLESTRING| \ + B_ASN1_TELETEXSTRING|\ + B_ASN1_BMPSTRING|\ + B_ASN1_UNIVERSALSTRING|\ + B_ASN1_UTF8STRING + +#define B_ASN1_DISPLAYTEXT \ + B_ASN1_IA5STRING| \ + B_ASN1_VISIBLESTRING| \ + B_ASN1_BMPSTRING|\ + B_ASN1_UTF8STRING + +#define M_ASN1_PRINTABLE_new() ASN1_STRING_type_new(V_ASN1_T61STRING) +#define M_ASN1_PRINTABLE_free(a) ASN1_STRING_free((ASN1_STRING *)a) +#define M_i2d_ASN1_PRINTABLE(a,pp) i2d_ASN1_bytes((ASN1_STRING *)a,\ + pp,a->type,V_ASN1_UNIVERSAL) +#define M_d2i_ASN1_PRINTABLE(a,pp,l) \ + d2i_ASN1_type_bytes((ASN1_STRING **)a,pp,l, \ + B_ASN1_PRINTABLE) + +#define M_DIRECTORYSTRING_new() ASN1_STRING_type_new(V_ASN1_PRINTABLESTRING) +#define M_DIRECTORYSTRING_free(a) ASN1_STRING_free((ASN1_STRING *)a) +#define M_i2d_DIRECTORYSTRING(a,pp) i2d_ASN1_bytes((ASN1_STRING *)a,\ + pp,a->type,V_ASN1_UNIVERSAL) +#define M_d2i_DIRECTORYSTRING(a,pp,l) \ + d2i_ASN1_type_bytes((ASN1_STRING **)a,pp,l, \ + B_ASN1_DIRECTORYSTRING) + +#define M_DISPLAYTEXT_new() ASN1_STRING_type_new(V_ASN1_VISIBLESTRING) +#define M_DISPLAYTEXT_free(a) ASN1_STRING_free((ASN1_STRING *)a) +#define M_i2d_DISPLAYTEXT(a,pp) i2d_ASN1_bytes((ASN1_STRING *)a,\ + pp,a->type,V_ASN1_UNIVERSAL) +#define M_d2i_DISPLAYTEXT(a,pp,l) \ + d2i_ASN1_type_bytes((ASN1_STRING **)a,pp,l, \ + B_ASN1_DISPLAYTEXT) + +#define M_ASN1_PRINTABLESTRING_new() (ASN1_PRINTABLESTRING *)\ + ASN1_STRING_type_new(V_ASN1_PRINTABLESTRING) +#define M_ASN1_PRINTABLESTRING_free(a) ASN1_STRING_free((ASN1_STRING *)a) +#define M_i2d_ASN1_PRINTABLESTRING(a,pp) \ + i2d_ASN1_bytes((ASN1_STRING *)a,pp,V_ASN1_PRINTABLESTRING,\ + V_ASN1_UNIVERSAL) +#define M_d2i_ASN1_PRINTABLESTRING(a,pp,l) \ + (ASN1_PRINTABLESTRING *)d2i_ASN1_type_bytes\ + ((ASN1_STRING **)a,pp,l,B_ASN1_PRINTABLESTRING) + +#define M_ASN1_T61STRING_new() (ASN1_T61STRING *)\ + ASN1_STRING_type_new(V_ASN1_T61STRING) +#define M_ASN1_T61STRING_free(a) ASN1_STRING_free((ASN1_STRING *)a) +#define M_i2d_ASN1_T61STRING(a,pp) \ + i2d_ASN1_bytes((ASN1_STRING *)a,pp,V_ASN1_T61STRING,\ + V_ASN1_UNIVERSAL) +#define M_d2i_ASN1_T61STRING(a,pp,l) \ + (ASN1_T61STRING *)d2i_ASN1_type_bytes\ + ((ASN1_STRING **)a,pp,l,B_ASN1_T61STRING) + +#define M_ASN1_IA5STRING_new() (ASN1_IA5STRING *)\ + ASN1_STRING_type_new(V_ASN1_IA5STRING) +#define M_ASN1_IA5STRING_free(a) ASN1_STRING_free((ASN1_STRING *)a) +#define M_ASN1_IA5STRING_dup(a) \ + (ASN1_IA5STRING *)ASN1_STRING_dup((const ASN1_STRING *)a) +#define M_i2d_ASN1_IA5STRING(a,pp) \ + i2d_ASN1_bytes((ASN1_STRING *)a,pp,V_ASN1_IA5STRING,\ + V_ASN1_UNIVERSAL) +#define M_d2i_ASN1_IA5STRING(a,pp,l) \ + (ASN1_IA5STRING *)d2i_ASN1_type_bytes((ASN1_STRING **)a,pp,l,\ + B_ASN1_IA5STRING) + +#define M_ASN1_UTCTIME_new() (ASN1_UTCTIME *)\ + ASN1_STRING_type_new(V_ASN1_UTCTIME) +#define M_ASN1_UTCTIME_free(a) ASN1_STRING_free((ASN1_STRING *)a) +#define M_ASN1_UTCTIME_dup(a) (ASN1_UTCTIME *)\ + ASN1_STRING_dup((const ASN1_STRING *)a) + +#define M_ASN1_GENERALIZEDTIME_new() (ASN1_GENERALIZEDTIME *)\ + ASN1_STRING_type_new(V_ASN1_GENERALIZEDTIME) +#define M_ASN1_GENERALIZEDTIME_free(a) ASN1_STRING_free((ASN1_STRING *)a) +#define M_ASN1_GENERALIZEDTIME_dup(a) (ASN1_GENERALIZEDTIME *)ASN1_STRING_dup(\ + (const ASN1_STRING *)a) + +#define M_ASN1_TIME_new() (ASN1_TIME *)\ + ASN1_STRING_type_new(V_ASN1_UTCTIME) +#define M_ASN1_TIME_free(a) ASN1_STRING_free((ASN1_STRING *)a) +#define M_ASN1_TIME_dup(a) (ASN1_TIME *)\ + ASN1_STRING_dup((const ASN1_STRING *)a) + +#define M_ASN1_GENERALSTRING_new() (ASN1_GENERALSTRING *)\ + ASN1_STRING_type_new(V_ASN1_GENERALSTRING) +#define M_ASN1_GENERALSTRING_free(a) ASN1_STRING_free((ASN1_STRING *)a) +#define M_i2d_ASN1_GENERALSTRING(a,pp) \ + i2d_ASN1_bytes((ASN1_STRING *)a,pp,V_ASN1_GENERALSTRING,\ + V_ASN1_UNIVERSAL) +#define M_d2i_ASN1_GENERALSTRING(a,pp,l) \ + (ASN1_GENERALSTRING *)d2i_ASN1_type_bytes\ + ((ASN1_STRING **)a,pp,l,B_ASN1_GENERALSTRING) + +#define M_ASN1_UNIVERSALSTRING_new() (ASN1_UNIVERSALSTRING *)\ + ASN1_STRING_type_new(V_ASN1_UNIVERSALSTRING) +#define M_ASN1_UNIVERSALSTRING_free(a) ASN1_STRING_free((ASN1_STRING *)a) +#define M_i2d_ASN1_UNIVERSALSTRING(a,pp) \ + i2d_ASN1_bytes((ASN1_STRING *)a,pp,V_ASN1_UNIVERSALSTRING,\ + V_ASN1_UNIVERSAL) +#define M_d2i_ASN1_UNIVERSALSTRING(a,pp,l) \ + (ASN1_UNIVERSALSTRING *)d2i_ASN1_type_bytes\ + ((ASN1_STRING **)a,pp,l,B_ASN1_UNIVERSALSTRING) + +#define M_ASN1_BMPSTRING_new() (ASN1_BMPSTRING *)\ + ASN1_STRING_type_new(V_ASN1_BMPSTRING) +#define M_ASN1_BMPSTRING_free(a) ASN1_STRING_free((ASN1_STRING *)a) +#define M_i2d_ASN1_BMPSTRING(a,pp) \ + i2d_ASN1_bytes((ASN1_STRING *)a,pp,V_ASN1_BMPSTRING,\ + V_ASN1_UNIVERSAL) +#define M_d2i_ASN1_BMPSTRING(a,pp,l) \ + (ASN1_BMPSTRING *)d2i_ASN1_type_bytes\ + ((ASN1_STRING **)a,pp,l,B_ASN1_BMPSTRING) + +#define M_ASN1_VISIBLESTRING_new() (ASN1_VISIBLESTRING *)\ + ASN1_STRING_type_new(V_ASN1_VISIBLESTRING) +#define M_ASN1_VISIBLESTRING_free(a) ASN1_STRING_free((ASN1_STRING *)a) +#define M_i2d_ASN1_VISIBLESTRING(a,pp) \ + i2d_ASN1_bytes((ASN1_STRING *)a,pp,V_ASN1_VISIBLESTRING,\ + V_ASN1_UNIVERSAL) +#define M_d2i_ASN1_VISIBLESTRING(a,pp,l) \ + (ASN1_VISIBLESTRING *)d2i_ASN1_type_bytes\ + ((ASN1_STRING **)a,pp,l,B_ASN1_VISIBLESTRING) + +#define M_ASN1_UTF8STRING_new() (ASN1_UTF8STRING *)\ + ASN1_STRING_type_new(V_ASN1_UTF8STRING) +#define M_ASN1_UTF8STRING_free(a) ASN1_STRING_free((ASN1_STRING *)a) +#define M_i2d_ASN1_UTF8STRING(a,pp) \ + i2d_ASN1_bytes((ASN1_STRING *)a,pp,V_ASN1_UTF8STRING,\ + V_ASN1_UNIVERSAL) +#define M_d2i_ASN1_UTF8STRING(a,pp,l) \ + (ASN1_UTF8STRING *)d2i_ASN1_type_bytes\ + ((ASN1_STRING **)a,pp,l,B_ASN1_UTF8STRING) + + /* for the is_set parameter to i2d_ASN1_SET */ +#define IS_SEQUENCE 0 +#define IS_SET 1 + +DECLARE_ASN1_FUNCTIONS_fname(ASN1_TYPE, ASN1_ANY, ASN1_TYPE) + +OPENSSL_EXPORT int ASN1_TYPE_get(ASN1_TYPE *a); +OPENSSL_EXPORT void ASN1_TYPE_set(ASN1_TYPE *a, int type, void *value); +OPENSSL_EXPORT int ASN1_TYPE_set1(ASN1_TYPE *a, int type, const void *value); +OPENSSL_EXPORT int ASN1_TYPE_cmp(const ASN1_TYPE *a, const ASN1_TYPE *b); + +OPENSSL_EXPORT ASN1_OBJECT * ASN1_OBJECT_new(void ); +OPENSSL_EXPORT void ASN1_OBJECT_free(ASN1_OBJECT *a); +OPENSSL_EXPORT int i2d_ASN1_OBJECT(ASN1_OBJECT *a,unsigned char **pp); +OPENSSL_EXPORT ASN1_OBJECT * c2i_ASN1_OBJECT(ASN1_OBJECT **a,const unsigned char **pp, + long length); +OPENSSL_EXPORT ASN1_OBJECT * d2i_ASN1_OBJECT(ASN1_OBJECT **a,const unsigned char **pp, + long length); + +DECLARE_ASN1_ITEM(ASN1_OBJECT) + +DECLARE_ASN1_SET_OF(ASN1_OBJECT) + +OPENSSL_EXPORT ASN1_STRING * ASN1_STRING_new(void); +OPENSSL_EXPORT void ASN1_STRING_free(ASN1_STRING *a); +OPENSSL_EXPORT int ASN1_STRING_copy(ASN1_STRING *dst, const ASN1_STRING *str); +OPENSSL_EXPORT ASN1_STRING * ASN1_STRING_dup(const ASN1_STRING *a); +OPENSSL_EXPORT ASN1_STRING * ASN1_STRING_type_new(int type ); +OPENSSL_EXPORT int ASN1_STRING_cmp(const ASN1_STRING *a, const ASN1_STRING *b); + /* Since this is used to store all sorts of things, via macros, for now, make + its data void * */ +OPENSSL_EXPORT int ASN1_STRING_set(ASN1_STRING *str, const void *data, int len); +OPENSSL_EXPORT void ASN1_STRING_set0(ASN1_STRING *str, void *data, int len); +OPENSSL_EXPORT int ASN1_STRING_length(const ASN1_STRING *x); +OPENSSL_EXPORT void ASN1_STRING_length_set(ASN1_STRING *x, int n); +OPENSSL_EXPORT int ASN1_STRING_type(ASN1_STRING *x); +OPENSSL_EXPORT unsigned char * ASN1_STRING_data(ASN1_STRING *x); + +DECLARE_ASN1_FUNCTIONS(ASN1_BIT_STRING) +OPENSSL_EXPORT int i2c_ASN1_BIT_STRING(ASN1_BIT_STRING *a,unsigned char **pp); +OPENSSL_EXPORT ASN1_BIT_STRING *c2i_ASN1_BIT_STRING(ASN1_BIT_STRING **a,const unsigned char **pp, long length); +OPENSSL_EXPORT int ASN1_BIT_STRING_set(ASN1_BIT_STRING *a, unsigned char *d, int length ); +OPENSSL_EXPORT int ASN1_BIT_STRING_set_bit(ASN1_BIT_STRING *a, int n, int value); +OPENSSL_EXPORT int ASN1_BIT_STRING_get_bit(ASN1_BIT_STRING *a, int n); +OPENSSL_EXPORT int ASN1_BIT_STRING_check(ASN1_BIT_STRING *a, unsigned char *flags, int flags_len); + +OPENSSL_EXPORT int ASN1_BIT_STRING_name_print(BIO *out, ASN1_BIT_STRING *bs, BIT_STRING_BITNAME *tbl, int indent); +OPENSSL_EXPORT int ASN1_BIT_STRING_num_asc(char *name, BIT_STRING_BITNAME *tbl); +OPENSSL_EXPORT int ASN1_BIT_STRING_set_asc(ASN1_BIT_STRING *bs, char *name, int value, BIT_STRING_BITNAME *tbl); + +OPENSSL_EXPORT int i2d_ASN1_BOOLEAN(int a,unsigned char **pp); +OPENSSL_EXPORT int d2i_ASN1_BOOLEAN(int *a,const unsigned char **pp,long length); + +DECLARE_ASN1_FUNCTIONS(ASN1_INTEGER) +OPENSSL_EXPORT int i2c_ASN1_INTEGER(ASN1_INTEGER *a,unsigned char **pp); +OPENSSL_EXPORT ASN1_INTEGER *c2i_ASN1_INTEGER(ASN1_INTEGER **a,const unsigned char **pp, long length); +OPENSSL_EXPORT ASN1_INTEGER *d2i_ASN1_UINTEGER(ASN1_INTEGER **a,const unsigned char **pp, long length); +OPENSSL_EXPORT ASN1_INTEGER * ASN1_INTEGER_dup(const ASN1_INTEGER *x); +OPENSSL_EXPORT int ASN1_INTEGER_cmp(const ASN1_INTEGER *x, const ASN1_INTEGER *y); + +DECLARE_ASN1_FUNCTIONS(ASN1_ENUMERATED) + +OPENSSL_EXPORT int ASN1_UTCTIME_check(const ASN1_UTCTIME *a); +OPENSSL_EXPORT ASN1_UTCTIME *ASN1_UTCTIME_set(ASN1_UTCTIME *s,time_t t); +OPENSSL_EXPORT ASN1_UTCTIME *ASN1_UTCTIME_adj(ASN1_UTCTIME *s, time_t t, int offset_day, long offset_sec); +OPENSSL_EXPORT int ASN1_UTCTIME_set_string(ASN1_UTCTIME *s, const char *str); +OPENSSL_EXPORT int ASN1_UTCTIME_cmp_time_t(const ASN1_UTCTIME *s, time_t t); +#if 0 +time_t ASN1_UTCTIME_get(const ASN1_UTCTIME *s); +#endif + +OPENSSL_EXPORT int ASN1_GENERALIZEDTIME_check(const ASN1_GENERALIZEDTIME *a); +OPENSSL_EXPORT ASN1_GENERALIZEDTIME *ASN1_GENERALIZEDTIME_set(ASN1_GENERALIZEDTIME *s,time_t t); +OPENSSL_EXPORT ASN1_GENERALIZEDTIME *ASN1_GENERALIZEDTIME_adj(ASN1_GENERALIZEDTIME *s, time_t t, int offset_day, long offset_sec); +OPENSSL_EXPORT int ASN1_GENERALIZEDTIME_set_string(ASN1_GENERALIZEDTIME *s, const char *str); +OPENSSL_EXPORT int ASN1_TIME_diff(int *pday, int *psec, const ASN1_TIME *from, const ASN1_TIME *to); + +DECLARE_ASN1_FUNCTIONS(ASN1_OCTET_STRING) +OPENSSL_EXPORT ASN1_OCTET_STRING * ASN1_OCTET_STRING_dup(const ASN1_OCTET_STRING *a); +OPENSSL_EXPORT int ASN1_OCTET_STRING_cmp(const ASN1_OCTET_STRING *a, const ASN1_OCTET_STRING *b); +OPENSSL_EXPORT int ASN1_OCTET_STRING_set(ASN1_OCTET_STRING *str, const unsigned char *data, int len); + +DECLARE_ASN1_FUNCTIONS(ASN1_VISIBLESTRING) +DECLARE_ASN1_FUNCTIONS(ASN1_UNIVERSALSTRING) +DECLARE_ASN1_FUNCTIONS(ASN1_UTF8STRING) +DECLARE_ASN1_FUNCTIONS(ASN1_NULL) +DECLARE_ASN1_FUNCTIONS(ASN1_BMPSTRING) + +OPENSSL_EXPORT int UTF8_getc(const unsigned char *str, int len, unsigned long *val); +OPENSSL_EXPORT int UTF8_putc(unsigned char *str, int len, unsigned long value); + +DECLARE_ASN1_FUNCTIONS_name(ASN1_STRING, ASN1_PRINTABLE) + +DECLARE_ASN1_FUNCTIONS_name(ASN1_STRING, DIRECTORYSTRING) +DECLARE_ASN1_FUNCTIONS_name(ASN1_STRING, DISPLAYTEXT) +DECLARE_ASN1_FUNCTIONS(ASN1_PRINTABLESTRING) +DECLARE_ASN1_FUNCTIONS(ASN1_T61STRING) +DECLARE_ASN1_FUNCTIONS(ASN1_IA5STRING) +DECLARE_ASN1_FUNCTIONS(ASN1_GENERALSTRING) +DECLARE_ASN1_FUNCTIONS(ASN1_UTCTIME) +DECLARE_ASN1_FUNCTIONS(ASN1_GENERALIZEDTIME) +DECLARE_ASN1_FUNCTIONS(ASN1_TIME) + +DECLARE_ASN1_ITEM(ASN1_OCTET_STRING_NDEF) + +OPENSSL_EXPORT ASN1_TIME *ASN1_TIME_set(ASN1_TIME *s,time_t t); +OPENSSL_EXPORT ASN1_TIME *ASN1_TIME_adj(ASN1_TIME *s,time_t t, int offset_day, long offset_sec); +OPENSSL_EXPORT int ASN1_TIME_check(ASN1_TIME *t); +OPENSSL_EXPORT ASN1_GENERALIZEDTIME *ASN1_TIME_to_generalizedtime(ASN1_TIME *t, ASN1_GENERALIZEDTIME **out); +OPENSSL_EXPORT int ASN1_TIME_set_string(ASN1_TIME *s, const char *str); + +OPENSSL_EXPORT int i2d_ASN1_SET(STACK_OF(OPENSSL_BLOCK) *a, unsigned char **pp, i2d_of_void *i2d, int ex_tag, int ex_class, int is_set); +OPENSSL_EXPORT STACK_OF(OPENSSL_BLOCK) *d2i_ASN1_SET(STACK_OF(OPENSSL_BLOCK) **a, + const unsigned char **pp, + long length, d2i_of_void *d2i, + void (*free_func)(OPENSSL_BLOCK), int ex_tag, + int ex_class); + +OPENSSL_EXPORT int i2a_ASN1_INTEGER(BIO *bp, ASN1_INTEGER *a); +OPENSSL_EXPORT int a2i_ASN1_INTEGER(BIO *bp,ASN1_INTEGER *bs,char *buf,int size); +OPENSSL_EXPORT int i2a_ASN1_ENUMERATED(BIO *bp, ASN1_ENUMERATED *a); +OPENSSL_EXPORT int a2i_ASN1_ENUMERATED(BIO *bp,ASN1_ENUMERATED *bs,char *buf,int size); +OPENSSL_EXPORT int i2a_ASN1_OBJECT(BIO *bp,ASN1_OBJECT *a); +OPENSSL_EXPORT int a2i_ASN1_STRING(BIO *bp,ASN1_STRING *bs,char *buf,int size); +OPENSSL_EXPORT int i2a_ASN1_STRING(BIO *bp, ASN1_STRING *a, int type); +OPENSSL_EXPORT int i2t_ASN1_OBJECT(char *buf,int buf_len,ASN1_OBJECT *a); + +OPENSSL_EXPORT int a2d_ASN1_OBJECT(unsigned char *out,int olen, const char *buf, int num); +OPENSSL_EXPORT ASN1_OBJECT *ASN1_OBJECT_create(int nid, unsigned char *data,int len, const char *sn, const char *ln); + +OPENSSL_EXPORT int ASN1_INTEGER_set(ASN1_INTEGER *a, long v); +OPENSSL_EXPORT long ASN1_INTEGER_get(const ASN1_INTEGER *a); +OPENSSL_EXPORT ASN1_INTEGER *BN_to_ASN1_INTEGER(const BIGNUM *bn, ASN1_INTEGER *ai); +OPENSSL_EXPORT BIGNUM *ASN1_INTEGER_to_BN(const ASN1_INTEGER *ai,BIGNUM *bn); + +OPENSSL_EXPORT int ASN1_ENUMERATED_set(ASN1_ENUMERATED *a, long v); +OPENSSL_EXPORT long ASN1_ENUMERATED_get(ASN1_ENUMERATED *a); +OPENSSL_EXPORT ASN1_ENUMERATED *BN_to_ASN1_ENUMERATED(BIGNUM *bn, ASN1_ENUMERATED *ai); +OPENSSL_EXPORT BIGNUM *ASN1_ENUMERATED_to_BN(ASN1_ENUMERATED *ai,BIGNUM *bn); + +/* General */ +/* given a string, return the correct type, max is the maximum length */ +OPENSSL_EXPORT int ASN1_PRINTABLE_type(const unsigned char *s, int max); + +OPENSSL_EXPORT int i2d_ASN1_bytes(ASN1_STRING *a, unsigned char **pp, int tag, int xclass); +OPENSSL_EXPORT ASN1_STRING *d2i_ASN1_bytes(ASN1_STRING **a, const unsigned char **pp, long length, int Ptag, int Pclass); +OPENSSL_EXPORT unsigned long ASN1_tag2bit(int tag); +/* type is one or more of the B_ASN1_ values. */ +OPENSSL_EXPORT ASN1_STRING *d2i_ASN1_type_bytes(ASN1_STRING **a,const unsigned char **pp, long length,int type); + +/* PARSING */ +OPENSSL_EXPORT int asn1_Finish(ASN1_CTX *c); +OPENSSL_EXPORT int asn1_const_Finish(ASN1_const_CTX *c); + +/* SPECIALS */ +OPENSSL_EXPORT int ASN1_get_object(const unsigned char **pp, long *plength, int *ptag, int *pclass, long omax); +OPENSSL_EXPORT int ASN1_check_infinite_end(unsigned char **p,long len); +OPENSSL_EXPORT int ASN1_const_check_infinite_end(const unsigned char **p,long len); +OPENSSL_EXPORT void ASN1_put_object(unsigned char **pp, int constructed, int length, int tag, int xclass); +OPENSSL_EXPORT int ASN1_put_eoc(unsigned char **pp); +OPENSSL_EXPORT int ASN1_object_size(int constructed, int length, int tag); + +/* Used to implement other functions */ +OPENSSL_EXPORT void *ASN1_dup(i2d_of_void *i2d, d2i_of_void *d2i, void *x); + +#define ASN1_dup_of(type,i2d,d2i,x) \ + ((type*)ASN1_dup(CHECKED_I2D_OF(type, i2d), \ + CHECKED_D2I_OF(type, d2i), \ + CHECKED_PTR_OF(type, x))) + +#define ASN1_dup_of_const(type,i2d,d2i,x) \ + ((type*)ASN1_dup(CHECKED_I2D_OF(const type, i2d), \ + CHECKED_D2I_OF(type, d2i), \ + CHECKED_PTR_OF(const type, x))) + +OPENSSL_EXPORT void *ASN1_item_dup(const ASN1_ITEM *it, void *x); + +/* ASN1 alloc/free macros for when a type is only used internally */ + +#define M_ASN1_new_of(type) (type *)ASN1_item_new(ASN1_ITEM_rptr(type)) +#define M_ASN1_free_of(x, type) \ + ASN1_item_free(CHECKED_PTR_OF(type, x), ASN1_ITEM_rptr(type)) + +#ifndef OPENSSL_NO_FP_API +OPENSSL_EXPORT void *ASN1_d2i_fp(void *(*xnew)(void), d2i_of_void *d2i, FILE *in, void **x); + +#define ASN1_d2i_fp_of(type,xnew,d2i,in,x) \ + ((type*)ASN1_d2i_fp(CHECKED_NEW_OF(type, xnew), \ + CHECKED_D2I_OF(type, d2i), \ + in, \ + CHECKED_PPTR_OF(type, x))) + +OPENSSL_EXPORT void *ASN1_item_d2i_fp(const ASN1_ITEM *it, FILE *in, void *x); +OPENSSL_EXPORT int ASN1_i2d_fp(i2d_of_void *i2d,FILE *out,void *x); + +#define ASN1_i2d_fp_of(type,i2d,out,x) \ + (ASN1_i2d_fp(CHECKED_I2D_OF(type, i2d), \ + out, \ + CHECKED_PTR_OF(type, x))) + +#define ASN1_i2d_fp_of_const(type,i2d,out,x) \ + (ASN1_i2d_fp(CHECKED_I2D_OF(const type, i2d), \ + out, \ + CHECKED_PTR_OF(const type, x))) + +OPENSSL_EXPORT int ASN1_item_i2d_fp(const ASN1_ITEM *it, FILE *out, void *x); +OPENSSL_EXPORT int ASN1_STRING_print_ex_fp(FILE *fp, ASN1_STRING *str, unsigned long flags); +#endif + +OPENSSL_EXPORT int ASN1_STRING_to_UTF8(unsigned char **out, ASN1_STRING *in); + +OPENSSL_EXPORT void *ASN1_d2i_bio(void *(*xnew)(void), d2i_of_void *d2i, BIO *in, void **x); + +#define ASN1_d2i_bio_of(type,xnew,d2i,in,x) \ + ((type*)ASN1_d2i_bio( CHECKED_NEW_OF(type, xnew), \ + CHECKED_D2I_OF(type, d2i), \ + in, \ + CHECKED_PPTR_OF(type, x))) + +OPENSSL_EXPORT void *ASN1_item_d2i_bio(const ASN1_ITEM *it, BIO *in, void *x); +OPENSSL_EXPORT int ASN1_i2d_bio(i2d_of_void *i2d,BIO *out, unsigned char *x); + +#define ASN1_i2d_bio_of(type,i2d,out,x) \ + (ASN1_i2d_bio(CHECKED_I2D_OF(type, i2d), \ + out, \ + CHECKED_PTR_OF(type, x))) + +#define ASN1_i2d_bio_of_const(type,i2d,out,x) \ + (ASN1_i2d_bio(CHECKED_I2D_OF(const type, i2d), \ + out, \ + CHECKED_PTR_OF(const type, x))) + +OPENSSL_EXPORT int ASN1_item_i2d_bio(const ASN1_ITEM *it, BIO *out, void *x); +OPENSSL_EXPORT int ASN1_UTCTIME_print(BIO *fp, const ASN1_UTCTIME *a); +OPENSSL_EXPORT int ASN1_GENERALIZEDTIME_print(BIO *fp, const ASN1_GENERALIZEDTIME *a); +OPENSSL_EXPORT int ASN1_TIME_print(BIO *fp, const ASN1_TIME *a); +OPENSSL_EXPORT int ASN1_STRING_print(BIO *bp, const ASN1_STRING *v); +OPENSSL_EXPORT int ASN1_STRING_print_ex(BIO *out, ASN1_STRING *str, unsigned long flags); +OPENSSL_EXPORT int ASN1_bn_print(BIO *bp, const char *number, const BIGNUM *num, unsigned char *buf, int off); +OPENSSL_EXPORT int ASN1_parse(BIO *bp,const unsigned char *pp,long len,int indent); +OPENSSL_EXPORT int ASN1_parse_dump(BIO *bp,const unsigned char *pp,long len,int indent,int dump); +OPENSSL_EXPORT const char *ASN1_tag2str(int tag); + +/* Used to load and write netscape format cert */ + +DECLARE_ASN1_FUNCTIONS(NETSCAPE_X509) + +int ASN1_UNIVERSALSTRING_to_string(ASN1_UNIVERSALSTRING *s); + +OPENSSL_EXPORT STACK_OF(OPENSSL_BLOCK) *ASN1_seq_unpack(const unsigned char *buf, int len, d2i_of_void *d2i, void (*free_func)(OPENSSL_BLOCK)); +OPENSSL_EXPORT unsigned char *ASN1_seq_pack(STACK_OF(OPENSSL_BLOCK) *safes, i2d_of_void *i2d, unsigned char **buf, int *len ); +OPENSSL_EXPORT void *ASN1_unpack_string(ASN1_STRING *oct, d2i_of_void *d2i); +OPENSSL_EXPORT void *ASN1_item_unpack(ASN1_STRING *oct, const ASN1_ITEM *it); +OPENSSL_EXPORT ASN1_STRING *ASN1_pack_string(void *obj, i2d_of_void *i2d, ASN1_OCTET_STRING **oct); + +#define ASN1_pack_string_of(type,obj,i2d,oct) \ + (ASN1_pack_string(CHECKED_PTR_OF(type, obj), \ + CHECKED_I2D_OF(type, i2d), \ + oct)) + +OPENSSL_EXPORT ASN1_STRING *ASN1_item_pack(void *obj, const ASN1_ITEM *it, ASN1_OCTET_STRING **oct); + +OPENSSL_EXPORT void ASN1_STRING_set_default_mask(unsigned long mask); +OPENSSL_EXPORT int ASN1_STRING_set_default_mask_asc(const char *p); +OPENSSL_EXPORT unsigned long ASN1_STRING_get_default_mask(void); +OPENSSL_EXPORT int ASN1_mbstring_copy(ASN1_STRING **out, const unsigned char *in, int len, int inform, unsigned long mask); +OPENSSL_EXPORT int ASN1_mbstring_ncopy(ASN1_STRING **out, const unsigned char *in, int len, int inform, unsigned long mask, long minsize, long maxsize); + +OPENSSL_EXPORT ASN1_STRING *ASN1_STRING_set_by_NID(ASN1_STRING **out, const unsigned char *in, int inlen, int inform, int nid); +OPENSSL_EXPORT ASN1_STRING_TABLE *ASN1_STRING_TABLE_get(int nid); +OPENSSL_EXPORT int ASN1_STRING_TABLE_add(int, long, long, unsigned long, unsigned long); +OPENSSL_EXPORT void ASN1_STRING_TABLE_cleanup(void); + +/* ASN1 template functions */ + +/* Old API compatible functions */ +OPENSSL_EXPORT ASN1_VALUE *ASN1_item_new(const ASN1_ITEM *it); +OPENSSL_EXPORT void ASN1_item_free(ASN1_VALUE *val, const ASN1_ITEM *it); +OPENSSL_EXPORT ASN1_VALUE * ASN1_item_d2i(ASN1_VALUE **val, const unsigned char **in, long len, const ASN1_ITEM *it); +OPENSSL_EXPORT int ASN1_item_i2d(ASN1_VALUE *val, unsigned char **out, const ASN1_ITEM *it); +OPENSSL_EXPORT int ASN1_item_ndef_i2d(ASN1_VALUE *val, unsigned char **out, const ASN1_ITEM *it); + +OPENSSL_EXPORT void ASN1_add_oid_module(void); + +OPENSSL_EXPORT ASN1_TYPE *ASN1_generate_nconf(char *str, CONF *nconf); +OPENSSL_EXPORT ASN1_TYPE *ASN1_generate_v3(char *str, X509V3_CTX *cnf); + +/* ASN1 Print flags */ + +/* Indicate missing OPTIONAL fields */ +#define ASN1_PCTX_FLAGS_SHOW_ABSENT 0x001 +/* Mark start and end of SEQUENCE */ +#define ASN1_PCTX_FLAGS_SHOW_SEQUENCE 0x002 +/* Mark start and end of SEQUENCE/SET OF */ +#define ASN1_PCTX_FLAGS_SHOW_SSOF 0x004 +/* Show the ASN1 type of primitives */ +#define ASN1_PCTX_FLAGS_SHOW_TYPE 0x008 +/* Don't show ASN1 type of ANY */ +#define ASN1_PCTX_FLAGS_NO_ANY_TYPE 0x010 +/* Don't show ASN1 type of MSTRINGs */ +#define ASN1_PCTX_FLAGS_NO_MSTRING_TYPE 0x020 +/* Don't show field names in SEQUENCE */ +#define ASN1_PCTX_FLAGS_NO_FIELD_NAME 0x040 +/* Show structure names of each SEQUENCE field */ +#define ASN1_PCTX_FLAGS_SHOW_FIELD_STRUCT_NAME 0x080 +/* Don't show structure name even at top level */ +#define ASN1_PCTX_FLAGS_NO_STRUCT_NAME 0x100 + +OPENSSL_EXPORT int ASN1_item_print(BIO *out, ASN1_VALUE *ifld, int indent, const ASN1_ITEM *it, const ASN1_PCTX *pctx); +OPENSSL_EXPORT ASN1_PCTX *ASN1_PCTX_new(void); +OPENSSL_EXPORT void ASN1_PCTX_free(ASN1_PCTX *p); +OPENSSL_EXPORT unsigned long ASN1_PCTX_get_flags(ASN1_PCTX *p); +OPENSSL_EXPORT void ASN1_PCTX_set_flags(ASN1_PCTX *p, unsigned long flags); +OPENSSL_EXPORT unsigned long ASN1_PCTX_get_nm_flags(ASN1_PCTX *p); +OPENSSL_EXPORT void ASN1_PCTX_set_nm_flags(ASN1_PCTX *p, unsigned long flags); +OPENSSL_EXPORT unsigned long ASN1_PCTX_get_cert_flags(ASN1_PCTX *p); +OPENSSL_EXPORT void ASN1_PCTX_set_cert_flags(ASN1_PCTX *p, unsigned long flags); +OPENSSL_EXPORT unsigned long ASN1_PCTX_get_oid_flags(ASN1_PCTX *p); +OPENSSL_EXPORT void ASN1_PCTX_set_oid_flags(ASN1_PCTX *p, unsigned long flags); +OPENSSL_EXPORT unsigned long ASN1_PCTX_get_str_flags(ASN1_PCTX *p); +OPENSSL_EXPORT void ASN1_PCTX_set_str_flags(ASN1_PCTX *p, unsigned long flags); + +OPENSSL_EXPORT const BIO_METHOD *BIO_f_asn1(void); + +OPENSSL_EXPORT BIO *BIO_new_NDEF(BIO *out, ASN1_VALUE *val, const ASN1_ITEM *it); + +OPENSSL_EXPORT int i2d_ASN1_bio_stream(BIO *out, ASN1_VALUE *val, BIO *in, int flags, const ASN1_ITEM *it); +OPENSSL_EXPORT int PEM_write_bio_ASN1_stream(BIO *out, ASN1_VALUE *val, BIO *in, int flags, const char *hdr, const ASN1_ITEM *it); +OPENSSL_EXPORT ASN1_VALUE *SMIME_read_ASN1(BIO *bio, BIO **bcont, const ASN1_ITEM *it); +OPENSSL_EXPORT int SMIME_crlf_copy(BIO *in, BIO *out, int flags); +OPENSSL_EXPORT int SMIME_text(BIO *in, BIO *out); + +/* BEGIN ERROR CODES */ +/* The following lines are auto generated by the script mkerr.pl. Any changes + * made after this point may be overwritten when the script is next run. + */ +void ERR_load_ASN1_strings(void); + +typedef int asn1_ps_func(BIO *b, unsigned char **pbuf, int *plen, void *parg); +OPENSSL_EXPORT int BIO_asn1_set_prefix(BIO *b, asn1_ps_func *prefix, asn1_ps_func *prefix_free); +OPENSSL_EXPORT int BIO_asn1_get_prefix(BIO *b, asn1_ps_func **pprefix, asn1_ps_func **pprefix_free); +OPENSSL_EXPORT int BIO_asn1_set_suffix(BIO *b, asn1_ps_func *suffix, asn1_ps_func *suffix_free); +OPENSSL_EXPORT int BIO_asn1_get_suffix(BIO *b, asn1_ps_func **psuffix, asn1_ps_func **psuffix_free); + +#ifdef __cplusplus +} +#endif + +#define ASN1_F_ASN1_BIT_STRING_set_bit 100 +#define ASN1_F_ASN1_ENUMERATED_set 101 +#define ASN1_F_ASN1_ENUMERATED_to_BN 102 +#define ASN1_F_ASN1_GENERALIZEDTIME_adj 103 +#define ASN1_F_ASN1_INTEGER_set 104 +#define ASN1_F_ASN1_INTEGER_to_BN 105 +#define ASN1_F_ASN1_OBJECT_new 106 +#define ASN1_F_ASN1_PCTX_new 107 +#define ASN1_F_ASN1_STRING_TABLE_add 108 +#define ASN1_F_ASN1_STRING_set 109 +#define ASN1_F_ASN1_STRING_type_new 110 +#define ASN1_F_ASN1_TIME_adj 111 +#define ASN1_F_ASN1_UTCTIME_adj 112 +#define ASN1_F_ASN1_d2i_fp 113 +#define ASN1_F_ASN1_dup 114 +#define ASN1_F_ASN1_generate_v3 115 +#define ASN1_F_ASN1_get_object 116 +#define ASN1_F_ASN1_i2d_bio 117 +#define ASN1_F_ASN1_i2d_fp 118 +#define ASN1_F_ASN1_item_d2i_fp 119 +#define ASN1_F_ASN1_item_dup 120 +#define ASN1_F_ASN1_item_ex_d2i 121 +#define ASN1_F_ASN1_item_i2d_bio 122 +#define ASN1_F_ASN1_item_i2d_fp 123 +#define ASN1_F_ASN1_item_pack 124 +#define ASN1_F_ASN1_item_unpack 125 +#define ASN1_F_ASN1_mbstring_ncopy 126 +#define ASN1_F_ASN1_template_new 127 +#define ASN1_F_BIO_new_NDEF 128 +#define ASN1_F_BN_to_ASN1_ENUMERATED 129 +#define ASN1_F_BN_to_ASN1_INTEGER 130 +#define ASN1_F_a2d_ASN1_OBJECT 131 +#define ASN1_F_a2i_ASN1_ENUMERATED 132 +#define ASN1_F_a2i_ASN1_INTEGER 133 +#define ASN1_F_a2i_ASN1_STRING 134 +#define ASN1_F_append_exp 135 +#define ASN1_F_asn1_cb 136 +#define ASN1_F_asn1_check_tlen 137 +#define ASN1_F_asn1_collate_primitive 138 +#define ASN1_F_asn1_collect 139 +#define ASN1_F_asn1_d2i_ex_primitive 140 +#define ASN1_F_asn1_d2i_read_bio 141 +#define ASN1_F_asn1_do_adb 142 +#define ASN1_F_asn1_ex_c2i 143 +#define ASN1_F_asn1_find_end 144 +#define ASN1_F_asn1_item_ex_combine_new 145 +#define ASN1_F_asn1_str2type 146 +#define ASN1_F_asn1_template_ex_d2i 147 +#define ASN1_F_asn1_template_noexp_d2i 148 +#define ASN1_F_bitstr_cb 149 +#define ASN1_F_c2i_ASN1_BIT_STRING 150 +#define ASN1_F_c2i_ASN1_INTEGER 151 +#define ASN1_F_c2i_ASN1_OBJECT 152 +#define ASN1_F_collect_data 153 +#define ASN1_F_d2i_ASN1_BOOLEAN 154 +#define ASN1_F_d2i_ASN1_OBJECT 155 +#define ASN1_F_d2i_ASN1_UINTEGER 156 +#define ASN1_F_d2i_ASN1_UTCTIME 157 +#define ASN1_F_d2i_ASN1_bytes 158 +#define ASN1_F_d2i_ASN1_type_bytes 159 +#define ASN1_F_i2d_ASN1_TIME 160 +#define ASN1_F_i2d_PrivateKey 161 +#define ASN1_F_long_c2i 162 +#define ASN1_F_parse_tagging 163 +#define ASN1_R_ASN1_LENGTH_MISMATCH 100 +#define ASN1_R_AUX_ERROR 101 +#define ASN1_R_BAD_GET_ASN1_OBJECT_CALL 102 +#define ASN1_R_BAD_OBJECT_HEADER 103 +#define ASN1_R_BMPSTRING_IS_WRONG_LENGTH 104 +#define ASN1_R_BN_LIB 105 +#define ASN1_R_BOOLEAN_IS_WRONG_LENGTH 106 +#define ASN1_R_BUFFER_TOO_SMALL 107 +#define ASN1_R_DECODE_ERROR 108 +#define ASN1_R_DEPTH_EXCEEDED 109 +#define ASN1_R_ENCODE_ERROR 110 +#define ASN1_R_ERROR_GETTING_TIME 111 +#define ASN1_R_EXPECTING_AN_ASN1_SEQUENCE 112 +#define ASN1_R_EXPECTING_AN_INTEGER 113 +#define ASN1_R_EXPECTING_AN_OBJECT 114 +#define ASN1_R_EXPECTING_A_BOOLEAN 115 +#define ASN1_R_EXPECTING_A_TIME 116 +#define ASN1_R_EXPLICIT_LENGTH_MISMATCH 117 +#define ASN1_R_EXPLICIT_TAG_NOT_CONSTRUCTED 118 +#define ASN1_R_FIELD_MISSING 119 +#define ASN1_R_FIRST_NUM_TOO_LARGE 120 +#define ASN1_R_HEADER_TOO_LONG 121 +#define ASN1_R_ILLEGAL_BITSTRING_FORMAT 122 +#define ASN1_R_ILLEGAL_BOOLEAN 123 +#define ASN1_R_ILLEGAL_CHARACTERS 124 +#define ASN1_R_ILLEGAL_FORMAT 125 +#define ASN1_R_ILLEGAL_HEX 126 +#define ASN1_R_ILLEGAL_IMPLICIT_TAG 127 +#define ASN1_R_ILLEGAL_INTEGER 128 +#define ASN1_R_ILLEGAL_NESTED_TAGGING 129 +#define ASN1_R_ILLEGAL_NULL 130 +#define ASN1_R_ILLEGAL_NULL_VALUE 131 +#define ASN1_R_ILLEGAL_OBJECT 132 +#define ASN1_R_ILLEGAL_OPTIONAL_ANY 133 +#define ASN1_R_ILLEGAL_OPTIONS_ON_ITEM_TEMPLATE 134 +#define ASN1_R_ILLEGAL_TAGGED_ANY 135 +#define ASN1_R_ILLEGAL_TIME_VALUE 136 +#define ASN1_R_INTEGER_NOT_ASCII_FORMAT 137 +#define ASN1_R_INTEGER_TOO_LARGE_FOR_LONG 138 +#define ASN1_R_INVALID_BIT_STRING_BITS_LEFT 139 +#define ASN1_R_INVALID_BMPSTRING_LENGTH 140 +#define ASN1_R_INVALID_DIGIT 141 +#define ASN1_R_INVALID_MODIFIER 142 +#define ASN1_R_INVALID_NUMBER 143 +#define ASN1_R_INVALID_OBJECT_ENCODING 144 +#define ASN1_R_INVALID_SEPARATOR 145 +#define ASN1_R_INVALID_TIME_FORMAT 146 +#define ASN1_R_INVALID_UNIVERSALSTRING_LENGTH 147 +#define ASN1_R_INVALID_UTF8STRING 148 +#define ASN1_R_LIST_ERROR 149 +#define ASN1_R_MALLOC_FAILURE 150 +#define ASN1_R_MISSING_ASN1_EOS 151 +#define ASN1_R_MISSING_EOC 152 +#define ASN1_R_MISSING_SECOND_NUMBER 153 +#define ASN1_R_MISSING_VALUE 154 +#define ASN1_R_MSTRING_NOT_UNIVERSAL 155 +#define ASN1_R_MSTRING_WRONG_TAG 156 +#define ASN1_R_NESTED_ASN1_ERROR 157 +#define ASN1_R_NESTED_ASN1_STRING 158 +#define ASN1_R_NON_HEX_CHARACTERS 159 +#define ASN1_R_NOT_ASCII_FORMAT 160 +#define ASN1_R_NOT_ENOUGH_DATA 161 +#define ASN1_R_NO_MATCHING_CHOICE_TYPE 162 +#define ASN1_R_NULL_IS_WRONG_LENGTH 163 +#define ASN1_R_OBJECT_NOT_ASCII_FORMAT 164 +#define ASN1_R_ODD_NUMBER_OF_CHARS 165 +#define ASN1_R_SECOND_NUMBER_TOO_LARGE 166 +#define ASN1_R_SEQUENCE_LENGTH_MISMATCH 167 +#define ASN1_R_SEQUENCE_NOT_CONSTRUCTED 168 +#define ASN1_R_SEQUENCE_OR_SET_NEEDS_CONFIG 169 +#define ASN1_R_SHORT_LINE 170 +#define ASN1_R_STREAMING_NOT_SUPPORTED 171 +#define ASN1_R_STRING_TOO_LONG 172 +#define ASN1_R_STRING_TOO_SHORT 173 +#define ASN1_R_TAG_VALUE_TOO_HIGH 174 +#define ASN1_R_TIME_NOT_ASCII_FORMAT 175 +#define ASN1_R_TOO_LONG 176 +#define ASN1_R_TYPE_NOT_CONSTRUCTED 177 +#define ASN1_R_TYPE_NOT_PRIMITIVE 178 +#define ASN1_R_UNEXPECTED_EOC 179 +#define ASN1_R_UNIVERSALSTRING_IS_WRONG_LENGTH 180 +#define ASN1_R_UNKNOWN_FORMAT 181 +#define ASN1_R_UNKNOWN_TAG 182 +#define ASN1_R_UNSUPPORTED_ANY_DEFINED_BY_TYPE 183 +#define ASN1_R_UNSUPPORTED_PUBLIC_KEY_TYPE 184 +#define ASN1_R_UNSUPPORTED_TYPE 185 +#define ASN1_R_WRONG_TAG 186 +#define ASN1_R_WRONG_TYPE 187 + +#endif diff --git a/phonelibs/boringssl/include/openssl/asn1_mac.h b/phonelibs/boringssl/include/openssl/asn1_mac.h new file mode 100644 index 00000000000000..49b2a286b77020 --- /dev/null +++ b/phonelibs/boringssl/include/openssl/asn1_mac.h @@ -0,0 +1,76 @@ +/* crypto/asn1/asn1_mac.h */ +/* Copyright (C) 1995-1998 Eric Young (eay@cryptsoft.com) + * All rights reserved. + * + * This package is an SSL implementation written + * by Eric Young (eay@cryptsoft.com). + * The implementation was written so as to conform with Netscapes SSL. + * + * This library is free for commercial and non-commercial use as long as + * the following conditions are aheared to. The following conditions + * apply to all code found in this distribution, be it the RC4, RSA, + * lhash, DES, etc., code; not just the SSL code. The SSL documentation + * included with this distribution is covered by the same copyright terms + * except that the holder is Tim Hudson (tjh@cryptsoft.com). + * + * Copyright remains Eric Young's, and as such any Copyright notices in + * the code are not to be removed. + * If this package is used in a product, Eric Young should be given attribution + * as the author of the parts of the library used. + * This can be in the form of a textual message at program startup or + * in documentation (online or textual) provided with the package. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must 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. All advertising materials mentioning features or use of this software + * must display the following acknowledgement: + * "This product includes cryptographic software written by + * Eric Young (eay@cryptsoft.com)" + * The word 'cryptographic' can be left out if the rouines from the library + * being used are not cryptographic related :-). + * 4. If you include any Windows specific code (or a derivative thereof) from + * the apps directory (application code) you must include an acknowledgement: + * "This product includes software written by Tim Hudson (tjh@cryptsoft.com)" + * + * THIS SOFTWARE IS PROVIDED BY ERIC YOUNG ``AS IS'' AND + * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHOR OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (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 licence and distribution terms for any publically available version or + * derivative of this code cannot be changed. i.e. this code cannot simply be + * copied and put under another distribution licence + * [including the GNU Public Licence.] + */ + +#ifndef HEADER_ASN1_MAC_H +#define HEADER_ASN1_MAC_H + +#include + +#ifdef __cplusplus +extern "C" { +#endif + + +OPENSSL_EXPORT int asn1_GetSequence(ASN1_const_CTX *c, long *length); + + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/boringssl/include/openssl/asn1t.h b/phonelibs/boringssl/include/openssl/asn1t.h new file mode 100644 index 00000000000000..0f2560b7156396 --- /dev/null +++ b/phonelibs/boringssl/include/openssl/asn1t.h @@ -0,0 +1,907 @@ +/* asn1t.h */ +/* Written by Dr Stephen N Henson (steve@openssl.org) for the OpenSSL + * project 2000. + */ +/* ==================================================================== + * Copyright (c) 2000-2005 The OpenSSL Project. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * + * 3. All advertising materials mentioning features or use of this + * software must display the following acknowledgment: + * "This product includes software developed by the OpenSSL Project + * for use in the OpenSSL Toolkit. (http://www.OpenSSL.org/)" + * + * 4. The names "OpenSSL Toolkit" and "OpenSSL Project" must not be used to + * endorse or promote products derived from this software without + * prior written permission. For written permission, please contact + * licensing@OpenSSL.org. + * + * 5. Products derived from this software may not be called "OpenSSL" + * nor may "OpenSSL" appear in their names without prior written + * permission of the OpenSSL Project. + * + * 6. Redistributions of any form whatsoever must retain the following + * acknowledgment: + * "This product includes software developed by the OpenSSL Project + * for use in the OpenSSL Toolkit (http://www.OpenSSL.org/)" + * + * THIS SOFTWARE IS PROVIDED BY THE OpenSSL PROJECT ``AS IS'' AND ANY + * EXPRESSED OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR + * PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE OpenSSL PROJECT OR + * ITS CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, + * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT + * NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + * STRICT LIABILITY, OR TORT (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 product includes cryptographic software written by Eric Young + * (eay@cryptsoft.com). This product includes software written by Tim + * Hudson (tjh@cryptsoft.com). + * + */ +#ifndef HEADER_ASN1T_H +#define HEADER_ASN1T_H + +#include +#include + +#ifdef OPENSSL_BUILD_SHLIBCRYPTO +# undef OPENSSL_EXTERN +# define OPENSSL_EXTERN OPENSSL_EXPORT +#endif + +/* ASN1 template defines, structures and functions */ + +#ifdef __cplusplus +extern "C" { +#endif + + +/* Macro to obtain ASN1_ADB pointer from a type (only used internally) */ +#define ASN1_ADB_ptr(iptr) ((const ASN1_ADB *)(iptr)) + + +/* Macros for start and end of ASN1_ITEM definition */ + +#define ASN1_ITEM_start(itname) \ + const ASN1_ITEM itname##_it = { + +#define ASN1_ITEM_end(itname) \ + }; + +/* Macros to aid ASN1 template writing */ + +#define ASN1_ITEM_TEMPLATE(tname) \ + static const ASN1_TEMPLATE tname##_item_tt + +#define ASN1_ITEM_TEMPLATE_END(tname) \ + ;\ + ASN1_ITEM_start(tname) \ + ASN1_ITYPE_PRIMITIVE,\ + -1,\ + &tname##_item_tt,\ + 0,\ + NULL,\ + 0,\ + #tname \ + ASN1_ITEM_end(tname) + + +/* This is a ASN1 type which just embeds a template */ + +/* This pair helps declare a SEQUENCE. We can do: + * + * ASN1_SEQUENCE(stname) = { + * ... SEQUENCE components ... + * } ASN1_SEQUENCE_END(stname) + * + * This will produce an ASN1_ITEM called stname_it + * for a structure called stname. + * + * If you want the same structure but a different + * name then use: + * + * ASN1_SEQUENCE(itname) = { + * ... SEQUENCE components ... + * } ASN1_SEQUENCE_END_name(stname, itname) + * + * This will create an item called itname_it using + * a structure called stname. + */ + +#define ASN1_SEQUENCE(tname) \ + static const ASN1_TEMPLATE tname##_seq_tt[] + +#define ASN1_SEQUENCE_END(stname) ASN1_SEQUENCE_END_name(stname, stname) + +#define ASN1_SEQUENCE_END_name(stname, tname) \ + ;\ + ASN1_ITEM_start(tname) \ + ASN1_ITYPE_SEQUENCE,\ + V_ASN1_SEQUENCE,\ + tname##_seq_tt,\ + sizeof(tname##_seq_tt) / sizeof(ASN1_TEMPLATE),\ + NULL,\ + sizeof(stname),\ + #stname \ + ASN1_ITEM_end(tname) + +#define ASN1_NDEF_SEQUENCE(tname) \ + ASN1_SEQUENCE(tname) + +#define ASN1_NDEF_SEQUENCE_cb(tname, cb) \ + ASN1_SEQUENCE_cb(tname, cb) + +#define ASN1_SEQUENCE_cb(tname, cb) \ + static const ASN1_AUX tname##_aux = {NULL, 0, 0, cb, 0}; \ + ASN1_SEQUENCE(tname) + +#define ASN1_BROKEN_SEQUENCE(tname) \ + static const ASN1_AUX tname##_aux = {NULL, ASN1_AFLG_BROKEN, 0, 0, 0}; \ + ASN1_SEQUENCE(tname) + +#define ASN1_SEQUENCE_ref(tname, cb) \ + static const ASN1_AUX tname##_aux = {NULL, ASN1_AFLG_REFCOUNT, offsetof(tname, references), cb, 0}; \ + ASN1_SEQUENCE(tname) + +#define ASN1_SEQUENCE_enc(tname, enc, cb) \ + static const ASN1_AUX tname##_aux = {NULL, ASN1_AFLG_ENCODING, 0, cb, offsetof(tname, enc)}; \ + ASN1_SEQUENCE(tname) + +#define ASN1_NDEF_SEQUENCE_END(tname) \ + ;\ + ASN1_ITEM_start(tname) \ + ASN1_ITYPE_NDEF_SEQUENCE,\ + V_ASN1_SEQUENCE,\ + tname##_seq_tt,\ + sizeof(tname##_seq_tt) / sizeof(ASN1_TEMPLATE),\ + NULL,\ + sizeof(tname),\ + #tname \ + ASN1_ITEM_end(tname) + +#define ASN1_BROKEN_SEQUENCE_END(stname) ASN1_SEQUENCE_END_ref(stname, stname) + +#define ASN1_SEQUENCE_END_enc(stname, tname) ASN1_SEQUENCE_END_ref(stname, tname) + +#define ASN1_SEQUENCE_END_cb(stname, tname) ASN1_SEQUENCE_END_ref(stname, tname) + +#define ASN1_SEQUENCE_END_ref(stname, tname) \ + ;\ + ASN1_ITEM_start(tname) \ + ASN1_ITYPE_SEQUENCE,\ + V_ASN1_SEQUENCE,\ + tname##_seq_tt,\ + sizeof(tname##_seq_tt) / sizeof(ASN1_TEMPLATE),\ + &tname##_aux,\ + sizeof(stname),\ + #stname \ + ASN1_ITEM_end(tname) + +#define ASN1_NDEF_SEQUENCE_END_cb(stname, tname) \ + ;\ + ASN1_ITEM_start(tname) \ + ASN1_ITYPE_NDEF_SEQUENCE,\ + V_ASN1_SEQUENCE,\ + tname##_seq_tt,\ + sizeof(tname##_seq_tt) / sizeof(ASN1_TEMPLATE),\ + &tname##_aux,\ + sizeof(stname),\ + #stname \ + ASN1_ITEM_end(tname) + + +/* This pair helps declare a CHOICE type. We can do: + * + * ASN1_CHOICE(chname) = { + * ... CHOICE options ... + * ASN1_CHOICE_END(chname) + * + * This will produce an ASN1_ITEM called chname_it + * for a structure called chname. The structure + * definition must look like this: + * typedef struct { + * int type; + * union { + * ASN1_SOMETHING *opt1; + * ASN1_SOMEOTHER *opt2; + * } value; + * } chname; + * + * the name of the selector must be 'type'. + * to use an alternative selector name use the + * ASN1_CHOICE_END_selector() version. + */ + +#define ASN1_CHOICE(tname) \ + static const ASN1_TEMPLATE tname##_ch_tt[] + +#define ASN1_CHOICE_cb(tname, cb) \ + static const ASN1_AUX tname##_aux = {NULL, 0, 0, cb, 0}; \ + ASN1_CHOICE(tname) + +#define ASN1_CHOICE_END(stname) ASN1_CHOICE_END_name(stname, stname) + +#define ASN1_CHOICE_END_name(stname, tname) ASN1_CHOICE_END_selector(stname, tname, type) + +#define ASN1_CHOICE_END_selector(stname, tname, selname) \ + ;\ + ASN1_ITEM_start(tname) \ + ASN1_ITYPE_CHOICE,\ + offsetof(stname,selname) ,\ + tname##_ch_tt,\ + sizeof(tname##_ch_tt) / sizeof(ASN1_TEMPLATE),\ + NULL,\ + sizeof(stname),\ + #stname \ + ASN1_ITEM_end(tname) + +#define ASN1_CHOICE_END_cb(stname, tname, selname) \ + ;\ + ASN1_ITEM_start(tname) \ + ASN1_ITYPE_CHOICE,\ + offsetof(stname,selname) ,\ + tname##_ch_tt,\ + sizeof(tname##_ch_tt) / sizeof(ASN1_TEMPLATE),\ + &tname##_aux,\ + sizeof(stname),\ + #stname \ + ASN1_ITEM_end(tname) + +/* This helps with the template wrapper form of ASN1_ITEM */ + +#define ASN1_EX_TEMPLATE_TYPE(flags, tag, name, type) { \ + (flags), (tag), 0,\ + #name, ASN1_ITEM_ref(type) } + +/* These help with SEQUENCE or CHOICE components */ + +/* used to declare other types */ + +#define ASN1_EX_TYPE(flags, tag, stname, field, type) { \ + (flags), (tag), offsetof(stname, field),\ + #field, ASN1_ITEM_ref(type) } + +/* used when the structure is combined with the parent */ + +#define ASN1_EX_COMBINE(flags, tag, type) { \ + (flags)|ASN1_TFLG_COMBINE, (tag), 0, NULL, ASN1_ITEM_ref(type) } + +/* implicit and explicit helper macros */ + +#define ASN1_IMP_EX(stname, field, type, tag, ex) \ + ASN1_EX_TYPE(ASN1_TFLG_IMPLICIT | ex, tag, stname, field, type) + +#define ASN1_EXP_EX(stname, field, type, tag, ex) \ + ASN1_EX_TYPE(ASN1_TFLG_EXPLICIT | ex, tag, stname, field, type) + +/* Any defined by macros: the field used is in the table itself */ + +#define ASN1_ADB_OBJECT(tblname) { ASN1_TFLG_ADB_OID, -1, 0, #tblname, (const ASN1_ITEM *)&(tblname##_adb) } +#define ASN1_ADB_INTEGER(tblname) { ASN1_TFLG_ADB_INT, -1, 0, #tblname, (const ASN1_ITEM *)&(tblname##_adb) } +/* Plain simple type */ +#define ASN1_SIMPLE(stname, field, type) ASN1_EX_TYPE(0,0, stname, field, type) + +/* OPTIONAL simple type */ +#define ASN1_OPT(stname, field, type) ASN1_EX_TYPE(ASN1_TFLG_OPTIONAL, 0, stname, field, type) + +/* IMPLICIT tagged simple type */ +#define ASN1_IMP(stname, field, type, tag) ASN1_IMP_EX(stname, field, type, tag, 0) + +/* IMPLICIT tagged OPTIONAL simple type */ +#define ASN1_IMP_OPT(stname, field, type, tag) ASN1_IMP_EX(stname, field, type, tag, ASN1_TFLG_OPTIONAL) + +/* Same as above but EXPLICIT */ + +#define ASN1_EXP(stname, field, type, tag) ASN1_EXP_EX(stname, field, type, tag, 0) +#define ASN1_EXP_OPT(stname, field, type, tag) ASN1_EXP_EX(stname, field, type, tag, ASN1_TFLG_OPTIONAL) + +/* SEQUENCE OF type */ +#define ASN1_SEQUENCE_OF(stname, field, type) \ + ASN1_EX_TYPE(ASN1_TFLG_SEQUENCE_OF, 0, stname, field, type) + +/* OPTIONAL SEQUENCE OF */ +#define ASN1_SEQUENCE_OF_OPT(stname, field, type) \ + ASN1_EX_TYPE(ASN1_TFLG_SEQUENCE_OF|ASN1_TFLG_OPTIONAL, 0, stname, field, type) + +/* Same as above but for SET OF */ + +#define ASN1_SET_OF(stname, field, type) \ + ASN1_EX_TYPE(ASN1_TFLG_SET_OF, 0, stname, field, type) + +#define ASN1_SET_OF_OPT(stname, field, type) \ + ASN1_EX_TYPE(ASN1_TFLG_SET_OF|ASN1_TFLG_OPTIONAL, 0, stname, field, type) + +/* Finally compound types of SEQUENCE, SET, IMPLICIT, EXPLICIT and OPTIONAL */ + +#define ASN1_IMP_SET_OF(stname, field, type, tag) \ + ASN1_IMP_EX(stname, field, type, tag, ASN1_TFLG_SET_OF) + +#define ASN1_EXP_SET_OF(stname, field, type, tag) \ + ASN1_EXP_EX(stname, field, type, tag, ASN1_TFLG_SET_OF) + +#define ASN1_IMP_SET_OF_OPT(stname, field, type, tag) \ + ASN1_IMP_EX(stname, field, type, tag, ASN1_TFLG_SET_OF|ASN1_TFLG_OPTIONAL) + +#define ASN1_EXP_SET_OF_OPT(stname, field, type, tag) \ + ASN1_EXP_EX(stname, field, type, tag, ASN1_TFLG_SET_OF|ASN1_TFLG_OPTIONAL) + +#define ASN1_IMP_SEQUENCE_OF(stname, field, type, tag) \ + ASN1_IMP_EX(stname, field, type, tag, ASN1_TFLG_SEQUENCE_OF) + +#define ASN1_IMP_SEQUENCE_OF_OPT(stname, field, type, tag) \ + ASN1_IMP_EX(stname, field, type, tag, ASN1_TFLG_SEQUENCE_OF|ASN1_TFLG_OPTIONAL) + +#define ASN1_EXP_SEQUENCE_OF(stname, field, type, tag) \ + ASN1_EXP_EX(stname, field, type, tag, ASN1_TFLG_SEQUENCE_OF) + +#define ASN1_EXP_SEQUENCE_OF_OPT(stname, field, type, tag) \ + ASN1_EXP_EX(stname, field, type, tag, ASN1_TFLG_SEQUENCE_OF|ASN1_TFLG_OPTIONAL) + +/* EXPLICIT using indefinite length constructed form */ +#define ASN1_NDEF_EXP(stname, field, type, tag) \ + ASN1_EXP_EX(stname, field, type, tag, ASN1_TFLG_NDEF) + +/* EXPLICIT OPTIONAL using indefinite length constructed form */ +#define ASN1_NDEF_EXP_OPT(stname, field, type, tag) \ + ASN1_EXP_EX(stname, field, type, tag, ASN1_TFLG_OPTIONAL|ASN1_TFLG_NDEF) + +/* Macros for the ASN1_ADB structure */ + +#define ASN1_ADB(name) \ + static const ASN1_ADB_TABLE name##_adbtbl[] + +#define ASN1_ADB_END(name, flags, field, app_table, def, none) \ + ;\ + static const ASN1_ADB name##_adb = {\ + flags,\ + offsetof(name, field),\ + app_table,\ + name##_adbtbl,\ + sizeof(name##_adbtbl) / sizeof(ASN1_ADB_TABLE),\ + def,\ + none\ + } + +#define ADB_ENTRY(val, template) {val, template} + +#define ASN1_ADB_TEMPLATE(name) \ + static const ASN1_TEMPLATE name##_tt + +/* This is the ASN1 template structure that defines + * a wrapper round the actual type. It determines the + * actual position of the field in the value structure, + * various flags such as OPTIONAL and the field name. + */ + +struct ASN1_TEMPLATE_st { +unsigned long flags; /* Various flags */ +long tag; /* tag, not used if no tagging */ +unsigned long offset; /* Offset of this field in structure */ +#ifndef NO_ASN1_FIELD_NAMES +const char *field_name; /* Field name */ +#endif +ASN1_ITEM_EXP *item; /* Relevant ASN1_ITEM or ASN1_ADB */ +}; + +/* Macro to extract ASN1_ITEM and ASN1_ADB pointer from ASN1_TEMPLATE */ + +#define ASN1_TEMPLATE_item(t) (t->item_ptr) +#define ASN1_TEMPLATE_adb(t) (t->item_ptr) + +typedef struct ASN1_ADB_TABLE_st ASN1_ADB_TABLE; +typedef struct ASN1_ADB_st ASN1_ADB; + +struct ASN1_ADB_st { + unsigned long flags; /* Various flags */ + unsigned long offset; /* Offset of selector field */ + STACK_OF(ASN1_ADB_TABLE) **app_items; /* Application defined items */ + const ASN1_ADB_TABLE *tbl; /* Table of possible types */ + long tblcount; /* Number of entries in tbl */ + const ASN1_TEMPLATE *default_tt; /* Type to use if no match */ + const ASN1_TEMPLATE *null_tt; /* Type to use if selector is NULL */ +}; + +struct ASN1_ADB_TABLE_st { + long value; /* NID for an object or value for an int */ + const ASN1_TEMPLATE tt; /* item for this value */ +}; + +/* template flags */ + +/* Field is optional */ +#define ASN1_TFLG_OPTIONAL (0x1) + +/* Field is a SET OF */ +#define ASN1_TFLG_SET_OF (0x1 << 1) + +/* Field is a SEQUENCE OF */ +#define ASN1_TFLG_SEQUENCE_OF (0x2 << 1) + +/* Special case: this refers to a SET OF that + * will be sorted into DER order when encoded *and* + * the corresponding STACK will be modified to match + * the new order. + */ +#define ASN1_TFLG_SET_ORDER (0x3 << 1) + +/* Mask for SET OF or SEQUENCE OF */ +#define ASN1_TFLG_SK_MASK (0x3 << 1) + +/* These flags mean the tag should be taken from the + * tag field. If EXPLICIT then the underlying type + * is used for the inner tag. + */ + +/* IMPLICIT tagging */ +#define ASN1_TFLG_IMPTAG (0x1 << 3) + + +/* EXPLICIT tagging, inner tag from underlying type */ +#define ASN1_TFLG_EXPTAG (0x2 << 3) + +#define ASN1_TFLG_TAG_MASK (0x3 << 3) + +/* context specific IMPLICIT */ +#define ASN1_TFLG_IMPLICIT ASN1_TFLG_IMPTAG|ASN1_TFLG_CONTEXT + +/* context specific EXPLICIT */ +#define ASN1_TFLG_EXPLICIT ASN1_TFLG_EXPTAG|ASN1_TFLG_CONTEXT + +/* If tagging is in force these determine the + * type of tag to use. Otherwise the tag is + * determined by the underlying type. These + * values reflect the actual octet format. + */ + +/* Universal tag */ +#define ASN1_TFLG_UNIVERSAL (0x0<<6) +/* Application tag */ +#define ASN1_TFLG_APPLICATION (0x1<<6) +/* Context specific tag */ +#define ASN1_TFLG_CONTEXT (0x2<<6) +/* Private tag */ +#define ASN1_TFLG_PRIVATE (0x3<<6) + +#define ASN1_TFLG_TAG_CLASS (0x3<<6) + +/* These are for ANY DEFINED BY type. In this case + * the 'item' field points to an ASN1_ADB structure + * which contains a table of values to decode the + * relevant type + */ + +#define ASN1_TFLG_ADB_MASK (0x3<<8) + +#define ASN1_TFLG_ADB_OID (0x1<<8) + +#define ASN1_TFLG_ADB_INT (0x1<<9) + +/* This flag means a parent structure is passed + * instead of the field: this is useful is a + * SEQUENCE is being combined with a CHOICE for + * example. Since this means the structure and + * item name will differ we need to use the + * ASN1_CHOICE_END_name() macro for example. + */ + +#define ASN1_TFLG_COMBINE (0x1<<10) + +/* This flag when present in a SEQUENCE OF, SET OF + * or EXPLICIT causes indefinite length constructed + * encoding to be used if required. + */ + +#define ASN1_TFLG_NDEF (0x1<<11) + +/* This is the actual ASN1 item itself */ + +struct ASN1_ITEM_st { +char itype; /* The item type, primitive, SEQUENCE, CHOICE or extern */ +long utype; /* underlying type */ +const ASN1_TEMPLATE *templates; /* If SEQUENCE or CHOICE this contains the contents */ +long tcount; /* Number of templates if SEQUENCE or CHOICE */ +const void *funcs; /* functions that handle this type */ +long size; /* Structure size (usually)*/ +#ifndef NO_ASN1_FIELD_NAMES +const char *sname; /* Structure name */ +#endif +}; + +/* These are values for the itype field and + * determine how the type is interpreted. + * + * For PRIMITIVE types the underlying type + * determines the behaviour if items is NULL. + * + * Otherwise templates must contain a single + * template and the type is treated in the + * same way as the type specified in the template. + * + * For SEQUENCE types the templates field points + * to the members, the size field is the + * structure size. + * + * For CHOICE types the templates field points + * to each possible member (typically a union) + * and the 'size' field is the offset of the + * selector. + * + * The 'funcs' field is used for application + * specific functions. + * + * For COMPAT types the funcs field gives a + * set of functions that handle this type, this + * supports the old d2i, i2d convention. + * + * The EXTERN type uses a new style d2i/i2d. + * The new style should be used where possible + * because it avoids things like the d2i IMPLICIT + * hack. + * + * MSTRING is a multiple string type, it is used + * for a CHOICE of character strings where the + * actual strings all occupy an ASN1_STRING + * structure. In this case the 'utype' field + * has a special meaning, it is used as a mask + * of acceptable types using the B_ASN1 constants. + * + * NDEF_SEQUENCE is the same as SEQUENCE except + * that it will use indefinite length constructed + * encoding if requested. + * + */ + +#define ASN1_ITYPE_PRIMITIVE 0x0 + +#define ASN1_ITYPE_SEQUENCE 0x1 + +#define ASN1_ITYPE_CHOICE 0x2 + +#define ASN1_ITYPE_COMPAT 0x3 + +#define ASN1_ITYPE_EXTERN 0x4 + +#define ASN1_ITYPE_MSTRING 0x5 + +#define ASN1_ITYPE_NDEF_SEQUENCE 0x6 + +/* Cache for ASN1 tag and length, so we + * don't keep re-reading it for things + * like CHOICE + */ + +struct ASN1_TLC_st{ + char valid; /* Values below are valid */ + int ret; /* return value */ + long plen; /* length */ + int ptag; /* class value */ + int pclass; /* class value */ + int hdrlen; /* header length */ +}; + +/* Typedefs for ASN1 function pointers */ + +typedef ASN1_VALUE * ASN1_new_func(void); +typedef void ASN1_free_func(ASN1_VALUE *a); +typedef ASN1_VALUE * ASN1_d2i_func(ASN1_VALUE **a, const unsigned char ** in, long length); +typedef int ASN1_i2d_func(ASN1_VALUE * a, unsigned char **in); + +typedef int ASN1_ex_d2i(ASN1_VALUE **pval, const unsigned char **in, long len, const ASN1_ITEM *it, + int tag, int aclass, char opt, ASN1_TLC *ctx); + +typedef int ASN1_ex_i2d(ASN1_VALUE **pval, unsigned char **out, const ASN1_ITEM *it, int tag, int aclass); +typedef int ASN1_ex_new_func(ASN1_VALUE **pval, const ASN1_ITEM *it); +typedef void ASN1_ex_free_func(ASN1_VALUE **pval, const ASN1_ITEM *it); + +typedef int ASN1_ex_print_func(BIO *out, ASN1_VALUE **pval, + int indent, const char *fname, + const ASN1_PCTX *pctx); + +typedef int ASN1_primitive_i2c(ASN1_VALUE **pval, unsigned char *cont, int *putype, const ASN1_ITEM *it); +typedef int ASN1_primitive_c2i(ASN1_VALUE **pval, const unsigned char *cont, int len, int utype, char *free_cont, const ASN1_ITEM *it); +typedef int ASN1_primitive_print(BIO *out, ASN1_VALUE **pval, const ASN1_ITEM *it, int indent, const ASN1_PCTX *pctx); + +typedef struct ASN1_COMPAT_FUNCS_st { + ASN1_new_func *asn1_new; + ASN1_free_func *asn1_free; + ASN1_d2i_func *asn1_d2i; + ASN1_i2d_func *asn1_i2d; +} ASN1_COMPAT_FUNCS; + +typedef struct ASN1_EXTERN_FUNCS_st { + void *app_data; + ASN1_ex_new_func *asn1_ex_new; + ASN1_ex_free_func *asn1_ex_free; + ASN1_ex_free_func *asn1_ex_clear; + ASN1_ex_d2i *asn1_ex_d2i; + ASN1_ex_i2d *asn1_ex_i2d; + ASN1_ex_print_func *asn1_ex_print; +} ASN1_EXTERN_FUNCS; + +typedef struct ASN1_PRIMITIVE_FUNCS_st { + void *app_data; + unsigned long flags; + ASN1_ex_new_func *prim_new; + ASN1_ex_free_func *prim_free; + ASN1_ex_free_func *prim_clear; + ASN1_primitive_c2i *prim_c2i; + ASN1_primitive_i2c *prim_i2c; + ASN1_primitive_print *prim_print; +} ASN1_PRIMITIVE_FUNCS; + +/* This is the ASN1_AUX structure: it handles various + * miscellaneous requirements. For example the use of + * reference counts and an informational callback. + * + * The "informational callback" is called at various + * points during the ASN1 encoding and decoding. It can + * be used to provide minor customisation of the structures + * used. This is most useful where the supplied routines + * *almost* do the right thing but need some extra help + * at a few points. If the callback returns zero then + * it is assumed a fatal error has occurred and the + * main operation should be abandoned. + * + * If major changes in the default behaviour are required + * then an external type is more appropriate. + */ + +typedef int ASN1_aux_cb(int operation, ASN1_VALUE **in, const ASN1_ITEM *it, + void *exarg); + +typedef struct ASN1_AUX_st { + void *app_data; + int flags; + int ref_offset; /* Offset of reference value */ + ASN1_aux_cb *asn1_cb; + int enc_offset; /* Offset of ASN1_ENCODING structure */ +} ASN1_AUX; + +/* For print related callbacks exarg points to this structure */ +typedef struct ASN1_PRINT_ARG_st { + BIO *out; + int indent; + const ASN1_PCTX *pctx; +} ASN1_PRINT_ARG; + +/* For streaming related callbacks exarg points to this structure */ +typedef struct ASN1_STREAM_ARG_st { + /* BIO to stream through */ + BIO *out; + /* BIO with filters appended */ + BIO *ndef_bio; + /* Streaming I/O boundary */ + unsigned char **boundary; +} ASN1_STREAM_ARG; + +/* Flags in ASN1_AUX */ + +/* Use a reference count */ +#define ASN1_AFLG_REFCOUNT 1 +/* Save the encoding of structure (useful for signatures) */ +#define ASN1_AFLG_ENCODING 2 +/* The Sequence length is invalid */ +#define ASN1_AFLG_BROKEN 4 + +/* operation values for asn1_cb */ + +#define ASN1_OP_NEW_PRE 0 +#define ASN1_OP_NEW_POST 1 +#define ASN1_OP_FREE_PRE 2 +#define ASN1_OP_FREE_POST 3 +#define ASN1_OP_D2I_PRE 4 +#define ASN1_OP_D2I_POST 5 +#define ASN1_OP_I2D_PRE 6 +#define ASN1_OP_I2D_POST 7 +#define ASN1_OP_PRINT_PRE 8 +#define ASN1_OP_PRINT_POST 9 +#define ASN1_OP_STREAM_PRE 10 +#define ASN1_OP_STREAM_POST 11 +#define ASN1_OP_DETACHED_PRE 12 +#define ASN1_OP_DETACHED_POST 13 + +/* Macro to implement a primitive type */ +#define IMPLEMENT_ASN1_TYPE(stname) IMPLEMENT_ASN1_TYPE_ex(stname, stname, 0) +#define IMPLEMENT_ASN1_TYPE_ex(itname, vname, ex) \ + ASN1_ITEM_start(itname) \ + ASN1_ITYPE_PRIMITIVE, V_##vname, NULL, 0, NULL, ex, #itname \ + ASN1_ITEM_end(itname) + +/* Macro to implement a multi string type */ +#define IMPLEMENT_ASN1_MSTRING(itname, mask) \ + ASN1_ITEM_start(itname) \ + ASN1_ITYPE_MSTRING, mask, NULL, 0, NULL, sizeof(ASN1_STRING), #itname \ + ASN1_ITEM_end(itname) + +/* Macro to implement an ASN1_ITEM in terms of old style funcs */ + +#define IMPLEMENT_COMPAT_ASN1(sname) IMPLEMENT_COMPAT_ASN1_type(sname, V_ASN1_SEQUENCE) + +#define IMPLEMENT_COMPAT_ASN1_type(sname, tag) \ + static const ASN1_COMPAT_FUNCS sname##_ff = { \ + (ASN1_new_func *)sname##_new, \ + (ASN1_free_func *)sname##_free, \ + (ASN1_d2i_func *)d2i_##sname, \ + (ASN1_i2d_func *)i2d_##sname, \ + }; \ + ASN1_ITEM_start(sname) \ + ASN1_ITYPE_COMPAT, \ + tag, \ + NULL, \ + 0, \ + &sname##_ff, \ + 0, \ + #sname \ + ASN1_ITEM_end(sname) + +#define IMPLEMENT_EXTERN_ASN1(sname, tag, fptrs) \ + ASN1_ITEM_start(sname) \ + ASN1_ITYPE_EXTERN, \ + tag, \ + NULL, \ + 0, \ + &fptrs, \ + 0, \ + #sname \ + ASN1_ITEM_end(sname) + +/* Macro to implement standard functions in terms of ASN1_ITEM structures */ + +#define IMPLEMENT_ASN1_FUNCTIONS(stname) IMPLEMENT_ASN1_FUNCTIONS_fname(stname, stname, stname) + +#define IMPLEMENT_ASN1_FUNCTIONS_name(stname, itname) IMPLEMENT_ASN1_FUNCTIONS_fname(stname, itname, itname) + +#define IMPLEMENT_ASN1_FUNCTIONS_ENCODE_name(stname, itname) \ + IMPLEMENT_ASN1_FUNCTIONS_ENCODE_fname(stname, itname, itname) + +#define IMPLEMENT_STATIC_ASN1_ALLOC_FUNCTIONS(stname) \ + IMPLEMENT_ASN1_ALLOC_FUNCTIONS_pfname(static, stname, stname, stname) + +#define IMPLEMENT_ASN1_ALLOC_FUNCTIONS(stname) \ + IMPLEMENT_ASN1_ALLOC_FUNCTIONS_fname(stname, stname, stname) + +#define IMPLEMENT_ASN1_ALLOC_FUNCTIONS_pfname(pre, stname, itname, fname) \ + pre stname *fname##_new(void) \ + { \ + return (stname *)ASN1_item_new(ASN1_ITEM_rptr(itname)); \ + } \ + pre void fname##_free(stname *a) \ + { \ + ASN1_item_free((ASN1_VALUE *)a, ASN1_ITEM_rptr(itname)); \ + } + +#define IMPLEMENT_ASN1_ALLOC_FUNCTIONS_fname(stname, itname, fname) \ + stname *fname##_new(void) \ + { \ + return (stname *)ASN1_item_new(ASN1_ITEM_rptr(itname)); \ + } \ + void fname##_free(stname *a) \ + { \ + ASN1_item_free((ASN1_VALUE *)a, ASN1_ITEM_rptr(itname)); \ + } + +#define IMPLEMENT_ASN1_FUNCTIONS_fname(stname, itname, fname) \ + IMPLEMENT_ASN1_ENCODE_FUNCTIONS_fname(stname, itname, fname) \ + IMPLEMENT_ASN1_ALLOC_FUNCTIONS_fname(stname, itname, fname) + +#define IMPLEMENT_ASN1_ENCODE_FUNCTIONS_fname(stname, itname, fname) \ + stname *d2i_##fname(stname **a, const unsigned char **in, long len) \ + { \ + return (stname *)ASN1_item_d2i((ASN1_VALUE **)a, in, len, ASN1_ITEM_rptr(itname));\ + } \ + int i2d_##fname(stname *a, unsigned char **out) \ + { \ + return ASN1_item_i2d((ASN1_VALUE *)a, out, ASN1_ITEM_rptr(itname));\ + } + +#define IMPLEMENT_ASN1_NDEF_FUNCTION(stname) \ + int i2d_##stname##_NDEF(stname *a, unsigned char **out) \ + { \ + return ASN1_item_ndef_i2d((ASN1_VALUE *)a, out, ASN1_ITEM_rptr(stname));\ + } + +/* This includes evil casts to remove const: they will go away when full + * ASN1 constification is done. + */ +#define IMPLEMENT_ASN1_ENCODE_FUNCTIONS_const_fname(stname, itname, fname) \ + stname *d2i_##fname(stname **a, const unsigned char **in, long len) \ + { \ + return (stname *)ASN1_item_d2i((ASN1_VALUE **)a, in, len, ASN1_ITEM_rptr(itname));\ + } \ + int i2d_##fname(const stname *a, unsigned char **out) \ + { \ + return ASN1_item_i2d((ASN1_VALUE *)a, out, ASN1_ITEM_rptr(itname));\ + } + +#define IMPLEMENT_ASN1_DUP_FUNCTION(stname) \ + stname * stname##_dup(stname *x) \ + { \ + return ASN1_item_dup(ASN1_ITEM_rptr(stname), x); \ + } + +#define IMPLEMENT_ASN1_PRINT_FUNCTION(stname) \ + IMPLEMENT_ASN1_PRINT_FUNCTION_fname(stname, stname, stname) + +#define IMPLEMENT_ASN1_PRINT_FUNCTION_fname(stname, itname, fname) \ + int fname##_print_ctx(BIO *out, stname *x, int indent, \ + const ASN1_PCTX *pctx) \ + { \ + return ASN1_item_print(out, (ASN1_VALUE *)x, indent, \ + ASN1_ITEM_rptr(itname), pctx); \ + } + +#define IMPLEMENT_ASN1_FUNCTIONS_const(name) \ + IMPLEMENT_ASN1_FUNCTIONS_const_fname(name, name, name) + +#define IMPLEMENT_ASN1_FUNCTIONS_const_fname(stname, itname, fname) \ + IMPLEMENT_ASN1_ENCODE_FUNCTIONS_const_fname(stname, itname, fname) \ + IMPLEMENT_ASN1_ALLOC_FUNCTIONS_fname(stname, itname, fname) + +/* external definitions for primitive types */ + +DECLARE_ASN1_ITEM(ASN1_BOOLEAN) +DECLARE_ASN1_ITEM(ASN1_TBOOLEAN) +DECLARE_ASN1_ITEM(ASN1_FBOOLEAN) +DECLARE_ASN1_ITEM(ASN1_SEQUENCE) +DECLARE_ASN1_ITEM(CBIGNUM) +DECLARE_ASN1_ITEM(BIGNUM) +DECLARE_ASN1_ITEM(LONG) +DECLARE_ASN1_ITEM(ZLONG) + +DECLARE_STACK_OF(ASN1_VALUE) + +/* Functions used internally by the ASN1 code */ + +int ASN1_item_ex_new(ASN1_VALUE **pval, const ASN1_ITEM *it); +void ASN1_item_ex_free(ASN1_VALUE **pval, const ASN1_ITEM *it); +int ASN1_template_new(ASN1_VALUE **pval, const ASN1_TEMPLATE *tt); +int ASN1_primitive_new(ASN1_VALUE **pval, const ASN1_ITEM *it); + +void ASN1_template_free(ASN1_VALUE **pval, const ASN1_TEMPLATE *tt); +int ASN1_template_d2i(ASN1_VALUE **pval, const unsigned char **in, long len, const ASN1_TEMPLATE *tt); +int ASN1_item_ex_d2i(ASN1_VALUE **pval, const unsigned char **in, long len, const ASN1_ITEM *it, + int tag, int aclass, char opt, ASN1_TLC *ctx); + +int ASN1_item_ex_i2d(ASN1_VALUE **pval, unsigned char **out, const ASN1_ITEM *it, int tag, int aclass); +int ASN1_template_i2d(ASN1_VALUE **pval, unsigned char **out, const ASN1_TEMPLATE *tt); +void ASN1_primitive_free(ASN1_VALUE **pval, const ASN1_ITEM *it); + +int asn1_ex_i2c(ASN1_VALUE **pval, unsigned char *cont, int *putype, const ASN1_ITEM *it); +int asn1_ex_c2i(ASN1_VALUE **pval, const unsigned char *cont, int len, int utype, char *free_cont, const ASN1_ITEM *it); + +int asn1_get_choice_selector(ASN1_VALUE **pval, const ASN1_ITEM *it); +int asn1_set_choice_selector(ASN1_VALUE **pval, int value, const ASN1_ITEM *it); + +ASN1_VALUE ** asn1_get_field_ptr(ASN1_VALUE **pval, const ASN1_TEMPLATE *tt); + +const ASN1_TEMPLATE *asn1_do_adb(ASN1_VALUE **pval, const ASN1_TEMPLATE *tt, int nullerr); + +void asn1_refcount_set_one(ASN1_VALUE **pval, const ASN1_ITEM *it); +int asn1_refcount_dec_and_test_zero(ASN1_VALUE **pval, const ASN1_ITEM *it); + +void asn1_enc_init(ASN1_VALUE **pval, const ASN1_ITEM *it); +void asn1_enc_free(ASN1_VALUE **pval, const ASN1_ITEM *it); +int asn1_enc_restore(int *len, unsigned char **out, ASN1_VALUE **pval, const ASN1_ITEM *it); +int asn1_enc_save(ASN1_VALUE **pval, const unsigned char *in, int inlen, const ASN1_ITEM *it); + +#ifdef __cplusplus +} +#endif +#endif diff --git a/phonelibs/boringssl/include/openssl/base.h b/phonelibs/boringssl/include/openssl/base.h new file mode 100644 index 00000000000000..b769ad5348c08a --- /dev/null +++ b/phonelibs/boringssl/include/openssl/base.h @@ -0,0 +1,233 @@ +/* ==================================================================== + * Copyright (c) 1998-2001 The OpenSSL Project. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * + * 3. All advertising materials mentioning features or use of this + * software must display the following acknowledgment: + * "This product includes software developed by the OpenSSL Project + * for use in the OpenSSL Toolkit. (http://www.openssl.org/)" + * + * 4. The names "OpenSSL Toolkit" and "OpenSSL Project" must not be used to + * endorse or promote products derived from this software without + * prior written permission. For written permission, please contact + * openssl-core@openssl.org. + * + * 5. Products derived from this software may not be called "OpenSSL" + * nor may "OpenSSL" appear in their names without prior written + * permission of the OpenSSL Project. + * + * 6. Redistributions of any form whatsoever must retain the following + * acknowledgment: + * "This product includes software developed by the OpenSSL Project + * for use in the OpenSSL Toolkit (http://www.openssl.org/)" + * + * THIS SOFTWARE IS PROVIDED BY THE OpenSSL PROJECT ``AS IS'' AND ANY + * EXPRESSED OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR + * PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE OpenSSL PROJECT OR + * ITS CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, + * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT + * NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + * STRICT LIABILITY, OR TORT (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 product includes cryptographic software written by Eric Young + * (eay@cryptsoft.com). This product includes software written by Tim + * Hudson (tjh@cryptsoft.com). */ + +#ifndef OPENSSL_HEADER_BASE_H +#define OPENSSL_HEADER_BASE_H + + +/* This file should be the first included by all BoringSSL headers. */ + +#include +#include +#include + +#include + +#if defined(__cplusplus) +extern "C" { +#endif + + +#if defined(__x86_64) || defined(_M_AMD64) || defined(_M_X64) +#define OPENSSL_64_BIT +#define OPENSSL_X86_64 +#elif defined(__x86) || defined(__i386) || defined(__i386__) || defined(_M_IX86) +#define OPENSSL_32_BIT +#define OPENSSL_X86 +#elif defined(__aarch64__) +#define OPENSSL_64_BIT +#define OPENSSL_AARCH64 +#elif defined(__arm) || defined(__arm__) || defined(_M_ARM) +#define OPENSSL_32_BIT +#define OPENSSL_ARM +#elif defined(__aarch64__) +#define OPENSSL_64_BIT +#define OPENSSL_AARCH64 +#elif defined(__mips__) && !defined(__LP64__) +#define OPENSSL_32_BIT +#define OPENSSL_MIPS +#elif defined(__mips__) && defined(__LP64__) +#define OPENSSL_64_BIT +#define OPENSSL_MIPS64 +#elif defined(__pnacl__) +#define OPENSSL_32_BIT +#define OPENSSL_PNACL +#else +#error "Unknown target CPU" +#endif + +#if defined(__APPLE__) +#define OPENSSL_APPLE +#endif + +#if defined(WIN32) || defined(_WIN32) +#define OPENSSL_WINDOWS +#endif + +#if defined(TRUSTY) +#define OPENSSL_TRUSTY +#define OPENSSL_NO_THREADS +#endif + +#define OPENSSL_IS_BORINGSSL +#define OPENSSL_VERSION_NUMBER 0x10002000 + +#if defined(BORINGSSL_SHARED_LIBRARY) + +#if defined(OPENSSL_WINDOWS) + +#if defined(BORINGSSL_IMPLEMENTATION) +#define OPENSSL_EXPORT __declspec(dllexport) +#else +#define OPENSSL_EXPORT __declspec(dllimport) +#endif + +#else /* defined(OPENSSL_WINDOWS) */ + +#if defined(BORINGSSL_IMPLEMENTATION) +#define OPENSSL_EXPORT __attribute__((visibility("default"))) +#else +#define OPENSSL_EXPORT +#endif + +#endif /* defined(OPENSSL_WINDOWS) */ + +#else /* defined(BORINGSSL_SHARED_LIBRARY) */ + +#define OPENSSL_EXPORT + +#endif /* defined(BORINGSSL_SHARED_LIBRARY) */ + +/* CRYPTO_THREADID is a dummy value. */ +typedef int CRYPTO_THREADID; + +typedef int ASN1_BOOLEAN; +typedef int ASN1_NULL; +typedef struct ASN1_ITEM_st ASN1_ITEM; +typedef struct asn1_object_st ASN1_OBJECT; +typedef struct asn1_pctx_st ASN1_PCTX; +typedef struct asn1_string_st ASN1_BIT_STRING; +typedef struct asn1_string_st ASN1_BMPSTRING; +typedef struct asn1_string_st ASN1_ENUMERATED; +typedef struct asn1_string_st ASN1_GENERALIZEDTIME; +typedef struct asn1_string_st ASN1_GENERALSTRING; +typedef struct asn1_string_st ASN1_IA5STRING; +typedef struct asn1_string_st ASN1_INTEGER; +typedef struct asn1_string_st ASN1_OCTET_STRING; +typedef struct asn1_string_st ASN1_PRINTABLESTRING; +typedef struct asn1_string_st ASN1_STRING; +typedef struct asn1_string_st ASN1_T61STRING; +typedef struct asn1_string_st ASN1_TIME; +typedef struct asn1_string_st ASN1_UNIVERSALSTRING; +typedef struct asn1_string_st ASN1_UTCTIME; +typedef struct asn1_string_st ASN1_UTF8STRING; +typedef struct asn1_string_st ASN1_VISIBLESTRING; + +typedef struct AUTHORITY_KEYID_st AUTHORITY_KEYID; +typedef struct DIST_POINT_st DIST_POINT; +typedef struct ISSUING_DIST_POINT_st ISSUING_DIST_POINT; +typedef struct NAME_CONSTRAINTS_st NAME_CONSTRAINTS; +typedef struct X509_POLICY_CACHE_st X509_POLICY_CACHE; +typedef struct X509_POLICY_LEVEL_st X509_POLICY_LEVEL; +typedef struct X509_POLICY_NODE_st X509_POLICY_NODE; +typedef struct X509_POLICY_TREE_st X509_POLICY_TREE; +typedef struct X509_algor_st X509_ALGOR; +typedef struct X509_crl_st X509_CRL; +typedef struct X509_pubkey_st X509_PUBKEY; +typedef struct bignum_ctx BN_CTX; +typedef struct bignum_st BIGNUM; +typedef struct bio_method_st BIO_METHOD; +typedef struct bio_st BIO; +typedef struct bn_gencb_st BN_GENCB; +typedef struct bn_mont_ctx_st BN_MONT_CTX; +typedef struct buf_mem_st BUF_MEM; +typedef struct cbb_st CBB; +typedef struct cbs_st CBS; +typedef struct cmac_ctx_st CMAC_CTX; +typedef struct conf_st CONF; +typedef struct conf_value_st CONF_VALUE; +typedef struct dh_method DH_METHOD; +typedef struct dh_st DH; +typedef struct dsa_method DSA_METHOD; +typedef struct dsa_st DSA; +typedef struct ec_key_st EC_KEY; +typedef struct ecdsa_method_st ECDSA_METHOD; +typedef struct ecdsa_sig_st ECDSA_SIG; +typedef struct engine_st ENGINE; +typedef struct env_md_ctx_st EVP_MD_CTX; +typedef struct env_md_st EVP_MD; +typedef struct evp_aead_st EVP_AEAD; +typedef struct evp_cipher_ctx_st EVP_CIPHER_CTX; +typedef struct evp_cipher_st EVP_CIPHER; +typedef struct evp_pkey_asn1_method_st EVP_PKEY_ASN1_METHOD; +typedef struct evp_pkey_ctx_st EVP_PKEY_CTX; +typedef struct evp_pkey_method_st EVP_PKEY_METHOD; +typedef struct evp_pkey_st EVP_PKEY; +typedef struct hmac_ctx_st HMAC_CTX; +typedef struct md4_state_st MD4_CTX; +typedef struct md5_state_st MD5_CTX; +typedef struct pkcs8_priv_key_info_st PKCS8_PRIV_KEY_INFO; +typedef struct pkcs12_st PKCS12; +typedef struct rand_meth_st RAND_METHOD; +typedef struct rc4_key_st RC4_KEY; +typedef struct rsa_meth_st RSA_METHOD; +typedef struct rsa_st RSA; +typedef struct sha256_state_st SHA256_CTX; +typedef struct sha512_state_st SHA512_CTX; +typedef struct sha_state_st SHA_CTX; +typedef struct ssl_ctx_st SSL_CTX; +typedef struct ssl_st SSL; +typedef struct st_ERR_FNS ERR_FNS; +typedef struct v3_ext_ctx X509V3_CTX; +typedef struct x509_crl_method_st X509_CRL_METHOD; +typedef struct x509_revoked_st X509_REVOKED; +typedef struct x509_st X509; +typedef struct x509_store_ctx_st X509_STORE_CTX; +typedef struct x509_store_st X509_STORE; +typedef void *OPENSSL_BLOCK; + + +#if defined(__cplusplus) +} /* extern C */ +#endif + +#endif /* OPENSSL_HEADER_BASE_H */ diff --git a/phonelibs/boringssl/include/openssl/base64.h b/phonelibs/boringssl/include/openssl/base64.h new file mode 100644 index 00000000000000..7aee9907f9239b --- /dev/null +++ b/phonelibs/boringssl/include/openssl/base64.h @@ -0,0 +1,179 @@ +/* Copyright (C) 1995-1998 Eric Young (eay@cryptsoft.com) + * All rights reserved. + * + * This package is an SSL implementation written + * by Eric Young (eay@cryptsoft.com). + * The implementation was written so as to conform with Netscapes SSL. + * + * This library is free for commercial and non-commercial use as long as + * the following conditions are aheared to. The following conditions + * apply to all code found in this distribution, be it the RC4, RSA, + * lhash, DES, etc., code; not just the SSL code. The SSL documentation + * included with this distribution is covered by the same copyright terms + * except that the holder is Tim Hudson (tjh@cryptsoft.com). + * + * Copyright remains Eric Young's, and as such any Copyright notices in + * the code are not to be removed. + * If this package is used in a product, Eric Young should be given attribution + * as the author of the parts of the library used. + * This can be in the form of a textual message at program startup or + * in documentation (online or textual) provided with the package. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must 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. All advertising materials mentioning features or use of this software + * must display the following acknowledgement: + * "This product includes cryptographic software written by + * Eric Young (eay@cryptsoft.com)" + * The word 'cryptographic' can be left out if the rouines from the library + * being used are not cryptographic related :-). + * 4. If you include any Windows specific code (or a derivative thereof) from + * the apps directory (application code) you must include an acknowledgement: + * "This product includes software written by Tim Hudson (tjh@cryptsoft.com)" + * + * THIS SOFTWARE IS PROVIDED BY ERIC YOUNG ``AS IS'' AND + * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHOR OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (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 licence and distribution terms for any publically available version or + * derivative of this code cannot be changed. i.e. this code cannot simply be + * copied and put under another distribution licence + * [including the GNU Public Licence.] */ + +#ifndef OPENSSL_HEADER_BASE64_H +#define OPENSSL_HEADER_BASE64_H + +#include + +#if defined(__cplusplus) +extern "C" { +#endif + + +/* base64 functions. + * + * For historical reasons, these functions have the EVP_ prefix but just do + * base64 encoding and decoding. */ + + +typedef struct evp_encode_ctx_st EVP_ENCODE_CTX; + + +/* Encoding */ + +/* EVP_EncodeInit initialises |*ctx|, which is typically stack + * allocated, for an encoding operation. + * + * NOTE: The encoding operation breaks its output with newlines every + * 64 characters of output (48 characters of input). Use + * EVP_EncodeBlock to encode raw base64. */ +OPENSSL_EXPORT void EVP_EncodeInit(EVP_ENCODE_CTX *ctx); + +/* EVP_EncodeUpdate encodes |in_len| bytes from |in| and writes an encoded + * version of them to |out| and sets |*out_len| to the number of bytes written. + * Some state may be contained in |ctx| so |EVP_EncodeFinal| must be used to + * flush it before using the encoded data. */ +OPENSSL_EXPORT void EVP_EncodeUpdate(EVP_ENCODE_CTX *ctx, uint8_t *out, + int *out_len, const uint8_t *in, + size_t in_len); + +/* EVP_EncodeFinal flushes any remaining output bytes from |ctx| to |out| and + * sets |*out_len| to the number of bytes written. */ +OPENSSL_EXPORT void EVP_EncodeFinal(EVP_ENCODE_CTX *ctx, uint8_t *out, + int *out_len); + +/* EVP_EncodeBlock encodes |src_len| bytes from |src| and writes the + * result to |dst| with a trailing NUL. It returns the number of bytes + * written, not including this trailing NUL. */ +OPENSSL_EXPORT size_t EVP_EncodeBlock(uint8_t *dst, const uint8_t *src, + size_t src_len); + +/* EVP_EncodedLength sets |*out_len| to the number of bytes that will be needed + * to call |EVP_EncodeBlock| on an input of length |len|. This includes the + * final NUL that |EVP_EncodeBlock| writes. It returns one on success or zero + * on error. */ +OPENSSL_EXPORT int EVP_EncodedLength(size_t *out_len, size_t len); + + +/* Decoding */ + +/* EVP_DecodedLength sets |*out_len| to the maximum number of bytes + * that will be needed to call |EVP_DecodeBase64| on an input of + * length |len|. */ +OPENSSL_EXPORT int EVP_DecodedLength(size_t *out_len, size_t len); + +/* EVP_DecodeBase64 decodes |in_len| bytes from base64 and writes + * |*out_len| bytes to |out|. |max_out| is the size of the output + * buffer. If it is not enough for the maximum output size, the + * operation fails. */ +OPENSSL_EXPORT int EVP_DecodeBase64(uint8_t *out, size_t *out_len, + size_t max_out, const uint8_t *in, + size_t in_len); + +/* EVP_DecodeInit initialises |*ctx|, which is typically stack allocated, for + * a decoding operation. + * + * TODO(davidben): This isn't a straight-up base64 decode either. Document + * and/or fix exactly what's going on here; maximum line length and such. */ +OPENSSL_EXPORT void EVP_DecodeInit(EVP_ENCODE_CTX *ctx); + +/* EVP_DecodeUpdate decodes |in_len| bytes from |in| and writes the decoded + * data to |out| and sets |*out_len| to the number of bytes written. Some state + * may be contained in |ctx| so |EVP_DecodeFinal| must be used to flush it + * before using the encoded data. + * + * It returns -1 on error, one if a full line of input was processed and zero + * if the line was short (i.e. it was the last line). */ +OPENSSL_EXPORT int EVP_DecodeUpdate(EVP_ENCODE_CTX *ctx, uint8_t *out, + int *out_len, const uint8_t *in, + size_t in_len); + +/* EVP_DecodeFinal flushes any remaining output bytes from |ctx| to |out| and + * sets |*out_len| to the number of bytes written. It returns one on success + * and minus one on error. */ +OPENSSL_EXPORT int EVP_DecodeFinal(EVP_ENCODE_CTX *ctx, uint8_t *out, + int *out_len); + +/* Deprecated: EVP_DecodeBlock encodes |src_len| bytes from |src| and + * writes the result to |dst|. It returns the number of bytes written + * or -1 on error. + * + * WARNING: EVP_DecodeBlock's return value does not take padding into + * account. It also strips leading whitespace and trailing + * whitespace. */ +OPENSSL_EXPORT int EVP_DecodeBlock(uint8_t *dst, const uint8_t *src, + size_t src_len); + + +struct evp_encode_ctx_st { + unsigned num; /* number saved in a partial encode/decode */ + unsigned length; /* The length is either the output line length + * (in input bytes) or the shortest input line + * length that is ok. Once decoding begins, + * the length is adjusted up each time a longer + * line is decoded */ + uint8_t enc_data[80]; /* data to encode */ + unsigned line_num; /* number read on current line */ + int expect_nl; +}; + + +#if defined(__cplusplus) +} /* extern C */ +#endif + +#endif /* OPENSSL_HEADER_BASE64_H */ diff --git a/phonelibs/boringssl/include/openssl/bio.h b/phonelibs/boringssl/include/openssl/bio.h new file mode 100644 index 00000000000000..872465750b5aa7 --- /dev/null +++ b/phonelibs/boringssl/include/openssl/bio.h @@ -0,0 +1,910 @@ +/* Copyright (C) 1995-1998 Eric Young (eay@cryptsoft.com) + * All rights reserved. + * + * This package is an SSL implementation written + * by Eric Young (eay@cryptsoft.com). + * The implementation was written so as to conform with Netscapes SSL. + * + * This library is free for commercial and non-commercial use as long as + * the following conditions are aheared to. The following conditions + * apply to all code found in this distribution, be it the RC4, RSA, + * lhash, DES, etc., code; not just the SSL code. The SSL documentation + * included with this distribution is covered by the same copyright terms + * except that the holder is Tim Hudson (tjh@cryptsoft.com). + * + * Copyright remains Eric Young's, and as such any Copyright notices in + * the code are not to be removed. + * If this package is used in a product, Eric Young should be given attribution + * as the author of the parts of the library used. + * This can be in the form of a textual message at program startup or + * in documentation (online or textual) provided with the package. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must 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. All advertising materials mentioning features or use of this software + * must display the following acknowledgement: + * "This product includes cryptographic software written by + * Eric Young (eay@cryptsoft.com)" + * The word 'cryptographic' can be left out if the rouines from the library + * being used are not cryptographic related :-). + * 4. If you include any Windows specific code (or a derivative thereof) from + * the apps directory (application code) you must include an acknowledgement: + * "This product includes software written by Tim Hudson (tjh@cryptsoft.com)" + * + * THIS SOFTWARE IS PROVIDED BY ERIC YOUNG ``AS IS'' AND + * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHOR OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (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 licence and distribution terms for any publically available version or + * derivative of this code cannot be changed. i.e. this code cannot simply be + * copied and put under another distribution licence + * [including the GNU Public Licence.] */ + +#ifndef OPENSSL_HEADER_BIO_H +#define OPENSSL_HEADER_BIO_H + +#include + +#include /* For FILE */ + +#include /* for ERR_print_errors_fp */ +#include +#include +#include + +#if defined(__cplusplus) +extern "C" { +#endif + + +/* BIO abstracts over a file-descriptor like interface. */ + + +/* Allocation and freeing. */ + +DEFINE_STACK_OF(BIO); + +/* BIO_new creates a new BIO with the given type and a reference count of one. + * It returns the fresh |BIO|, or NULL on error. */ +OPENSSL_EXPORT BIO *BIO_new(const BIO_METHOD *type); + +/* BIO_free decrements the reference count of |bio|. If the reference count + * drops to zero, it (optionally) calls the BIO's callback with |BIO_CB_FREE|, + * frees the ex_data and then, if the BIO has a destroy callback for the + * method, calls it. Finally it frees |bio| itself. It then repeats that for + * the next BIO in the chain, if any. + * + * It returns one on success or zero otherwise. */ +OPENSSL_EXPORT int BIO_free(BIO *bio); + +/* BIO_vfree performs the same actions as |BIO_free|, but has a void return + * value. This is provided for API-compat. + * + * TODO(fork): remove. */ +OPENSSL_EXPORT void BIO_vfree(BIO *bio); + +/* BIO_up_ref increments the reference count of |bio| and returns it. */ +OPENSSL_EXPORT BIO *BIO_up_ref(BIO *bio); + + +/* Basic I/O. */ + +/* BIO_read attempts to read |len| bytes into |data|. It returns the number of + * bytes read, zero on EOF, or a negative number on error. */ +OPENSSL_EXPORT int BIO_read(BIO *bio, void *data, int len); + +/* BIO_gets "reads a line" from |bio| and puts at most |size| bytes into |buf|. + * It returns the number of bytes read or a negative number on error. The + * phrase "reads a line" is in quotes in the previous sentence because the + * exact operation depends on the BIO's method. For example, a digest BIO will + * return the digest in response to a |BIO_gets| call. + * + * TODO(fork): audit the set of BIOs that we end up needing. If all actually + * return a line for this call, remove the warning above. */ +OPENSSL_EXPORT int BIO_gets(BIO *bio, char *buf, int size); + +/* BIO_write writes |len| bytes from |data| to BIO. It returns the number of + * bytes written or a negative number on error. */ +OPENSSL_EXPORT int BIO_write(BIO *bio, const void *data, int len); + +/* BIO_puts writes a NUL terminated string from |buf| to |bio|. It returns the + * number of bytes written or a negative number on error. */ +OPENSSL_EXPORT int BIO_puts(BIO *bio, const char *buf); + +/* BIO_flush flushes any buffered output. It returns one on success and zero + * otherwise. */ +OPENSSL_EXPORT int BIO_flush(BIO *bio); + + +/* Low-level control functions. + * + * These are generic functions for sending control requests to a BIO. In + * general one should use the wrapper functions like |BIO_get_close|. */ + +/* BIO_ctrl sends the control request |cmd| to |bio|. The |cmd| argument should + * be one of the |BIO_C_*| values. */ +OPENSSL_EXPORT long BIO_ctrl(BIO *bio, int cmd, long larg, void *parg); + +/* BIO_ptr_ctrl acts like |BIO_ctrl| but passes the address of a |void*| + * pointer as |parg| and returns the value that is written to it, or NULL if + * the control request returns <= 0. */ +OPENSSL_EXPORT char *BIO_ptr_ctrl(BIO *bp, int cmd, long larg); + +/* BIO_int_ctrl acts like |BIO_ctrl| but passes the address of a copy of |iarg| + * as |parg|. */ +OPENSSL_EXPORT long BIO_int_ctrl(BIO *bp, int cmd, long larg, int iarg); + +/* BIO_reset resets |bio| to its initial state, the precise meaning of which + * depends on the concrete type of |bio|. It returns one on success and zero + * otherwise. */ +OPENSSL_EXPORT int BIO_reset(BIO *bio); + +/* BIO_set_flags ORs |flags| with |bio->flags|. */ +OPENSSL_EXPORT void BIO_set_flags(BIO *bio, int flags); + +/* BIO_test_flags returns |bio->flags| AND |flags|. */ +OPENSSL_EXPORT int BIO_test_flags(const BIO *bio, int flags); + +/* BIO_should_read returns non-zero if |bio| encountered a temporary error + * while reading (i.e. EAGAIN), indicating that the caller should retry the + * read. */ +OPENSSL_EXPORT int BIO_should_read(const BIO *bio); + +/* BIO_should_write returns non-zero if |bio| encountered a temporary error + * while writing (i.e. EAGAIN), indicating that the caller should retry the + * write. */ +OPENSSL_EXPORT int BIO_should_write(const BIO *bio); + +/* BIO_should_retry returns non-zero if the reason that caused a failed I/O + * operation is temporary and thus the operation should be retried. Otherwise, + * it was a permanent error and it returns zero. */ +OPENSSL_EXPORT int BIO_should_retry(const BIO *bio); + +/* BIO_should_io_special returns non-zero if |bio| encountered a temporary + * error while performing a special I/O operation, indicating that the caller + * should retry. The operation that caused the error is returned by + * |BIO_get_retry_reason|. */ +OPENSSL_EXPORT int BIO_should_io_special(const BIO *bio); + +/* BIO_RR_SSL_X509_LOOKUP indicates that an SSL BIO blocked because the SSL + * library returned with SSL_ERROR_WANT_X509_LOOKUP. + * + * TODO(fork): remove. */ +#define BIO_RR_SSL_X509_LOOKUP 0x01 + +/* BIO_RR_CONNECT indicates that a connect would have blocked */ +#define BIO_RR_CONNECT 0x02 + +/* BIO_RR_ACCEPT indicates that an accept would have blocked */ +#define BIO_RR_ACCEPT 0x03 + +/* BIO_RR_SSL_CHANNEL_ID_LOOKUP indicates that the ChannelID code cannot find + * a private key for a TLS connection. */ +#define BIO_RR_SSL_CHANNEL_ID_LOOKUP 0x04 + +/* BIO_get_retry_reason returns the special I/O operation that needs to be + * retried. The return value is one of the |BIO_RR_*| values. */ +OPENSSL_EXPORT int BIO_get_retry_reason(const BIO *bio); + +/* BIO_clear_flags ANDs |bio->flags| with the bitwise-complement of |flags|. */ +OPENSSL_EXPORT void BIO_clear_flags(BIO *bio, int flags); + +/* BIO_set_retry_read sets the |BIO_FLAGS_READ| and |BIO_FLAGS_SHOULD_RETRY| + * flags on |bio|. */ +OPENSSL_EXPORT void BIO_set_retry_read(BIO *bio); + +/* BIO_set_retry_read sets the |BIO_FLAGS_WRITE| and |BIO_FLAGS_SHOULD_RETRY| + * flags on |bio|. */ +OPENSSL_EXPORT void BIO_set_retry_write(BIO *bio); + +/* BIO_get_retry_flags gets the |BIO_FLAGS_READ|, |BIO_FLAGS_WRITE|, + * |BIO_FLAGS_IO_SPECIAL| and |BIO_FLAGS_SHOULD_RETRY| flags from |bio|. */ +OPENSSL_EXPORT int BIO_get_retry_flags(BIO *bio); + +/* BIO_clear_retry_flags clears the |BIO_FLAGS_READ|, |BIO_FLAGS_WRITE|, + * |BIO_FLAGS_IO_SPECIAL| and |BIO_FLAGS_SHOULD_RETRY| flags from |bio|. */ +OPENSSL_EXPORT void BIO_clear_retry_flags(BIO *bio); + +/* BIO_method_type returns the type of |bio|, which is one of the |BIO_TYPE_*| + * values. */ +OPENSSL_EXPORT int BIO_method_type(const BIO *bio); + +/* bio_info_cb is the type of a callback function that can be called for most + * BIO operations. The |event| argument is one of |BIO_CB_*| and can be ORed + * with |BIO_CB_RETURN| if the callback is being made after the operation in + * question. In that case, |return_value| will contain the return value from + * the operation. */ +typedef long (*bio_info_cb)(BIO *bio, int event, const char *parg, int cmd, + long larg, long return_value); + +/* BIO_callback_ctrl allows the callback function to be manipulated. The |cmd| + * arg will generally be |BIO_CTRL_SET_CALLBACK| but arbitary command values + * can be interpreted by the |BIO|. */ +OPENSSL_EXPORT long BIO_callback_ctrl(BIO *bio, int cmd, bio_info_cb fp); + +/* BIO_pending returns the number of bytes pending to be read. */ +OPENSSL_EXPORT size_t BIO_pending(const BIO *bio); + +/* BIO_ctrl_pending calls |BIO_pending| and exists only for compatibility with + * OpenSSL. */ +OPENSSL_EXPORT size_t BIO_ctrl_pending(const BIO *bio); + +/* BIO_wpending returns the number of bytes pending to be written. */ +OPENSSL_EXPORT size_t BIO_wpending(const BIO *bio); + +/* BIO_set_close sets the close flag for |bio|. The meaning of which depends on + * the type of |bio| but, for example, a memory BIO interprets the close flag + * as meaning that it owns its buffer. It returns one on success and zero + * otherwise. */ +OPENSSL_EXPORT int BIO_set_close(BIO *bio, int close_flag); + +/* BIO_set_callback sets a callback function that will be called before and + * after most operations. See the comment above |bio_info_cb|. */ +OPENSSL_EXPORT void BIO_set_callback(BIO *bio, bio_info_cb callback_func); + +/* BIO_set_callback_arg sets the opaque pointer value that can be read within a + * callback with |BIO_get_callback_arg|. */ +OPENSSL_EXPORT void BIO_set_callback_arg(BIO *bio, char *arg); + +/* BIO_get_callback_arg returns the last value of the opaque callback pointer + * set by |BIO_set_callback_arg|. */ +OPENSSL_EXPORT char *BIO_get_callback_arg(const BIO *bio); + +/* BIO_number_read returns the number of bytes that have been read from + * |bio|. */ +OPENSSL_EXPORT size_t BIO_number_read(const BIO *bio); + +/* BIO_number_written returns the number of bytes that have been written to + * |bio|. */ +OPENSSL_EXPORT size_t BIO_number_written(const BIO *bio); + + +/* Managing chains of BIOs. + * + * BIOs can be put into chains where the output of one is used as the input of + * the next etc. The most common case is a buffering BIO, which accepts and + * buffers writes until flushed into the next BIO in the chain. */ + +/* BIO_push adds |appended_bio| to the end of the chain with |bio| at the head. + * It returns |bio|. Note that |appended_bio| may be the head of a chain itself + * and thus this function can be used to join two chains. + * + * BIO_push takes ownership of the caller's reference to |appended_bio|. */ +OPENSSL_EXPORT BIO *BIO_push(BIO *bio, BIO *appended_bio); + +/* BIO_pop removes |bio| from the head of a chain and returns the next BIO in + * the chain, or NULL if there is no next BIO. + * + * The caller takes ownership of the chain's reference to |bio|. */ +OPENSSL_EXPORT BIO *BIO_pop(BIO *bio); + +/* BIO_next returns the next BIO in the chain after |bio|, or NULL if there is + * no such BIO. */ +OPENSSL_EXPORT BIO *BIO_next(BIO *bio); + +/* BIO_free_all calls |BIO_free|. + * + * TODO(fork): update callers and remove. */ +OPENSSL_EXPORT void BIO_free_all(BIO *bio); + +/* BIO_find_type walks a chain of BIOs and returns the first that matches + * |type|, which is one of the |BIO_TYPE_*| values. */ +OPENSSL_EXPORT BIO *BIO_find_type(BIO *bio, int type); + +/* BIO_copy_next_retry sets the retry flags and |retry_reason| of |bio| from + * the next BIO in the chain. */ +OPENSSL_EXPORT void BIO_copy_next_retry(BIO *bio); + + +/* Printf functions. + * + * These functions are versions of printf functions that output to a BIO rather + * than a FILE. */ +#ifdef __GNUC__ +#define __bio_h__attr__ __attribute__ +#else +#define __bio_h__attr__(x) +#endif +OPENSSL_EXPORT int BIO_printf(BIO *bio, const char *format, ...) + __bio_h__attr__((__format__(__printf__, 2, 3))); +#undef __bio_h__attr__ + + +/* Utility functions. */ + +/* BIO_indent prints min(|indent|, |max_indent|) spaces. It returns one on + * success and zero otherwise. */ +OPENSSL_EXPORT int BIO_indent(BIO *bio, unsigned indent, unsigned max_indent); + +/* BIO_hexdump writes a hex dump of |data| to |bio|. Each line will be indented + * by |indent| spaces. */ +OPENSSL_EXPORT int BIO_hexdump(BIO *bio, const uint8_t *data, size_t len, + unsigned indent); + +/* BIO_print_errors prints the current contents of the error stack to |bio| + * using human readable strings where possible. */ +OPENSSL_EXPORT void BIO_print_errors(BIO *bio); + +/* BIO_read_asn1 reads a single ASN.1 object from |bio|. If successful it sets + * |*out| to be an allocated buffer (that should be freed with |OPENSSL_free|), + * |*out_size| to the length, in bytes, of that buffer and returns one. + * Otherwise it returns zero. + * + * If the length of the object is greater than |max_len| or 2^32 then the + * function will fail. Long-form tags are not supported. If the length of the + * object is indefinite the full contents of |bio| are read, unless it would be + * greater than |max_len|, in which case the function fails. + * + * If the function fails then some unknown amount of data may have been read + * from |bio|. */ +OPENSSL_EXPORT int BIO_read_asn1(BIO *bio, uint8_t **out, size_t *out_len, + size_t max_len); + + +/* Memory BIOs. + * + * Memory BIOs can be used as a read-only source (with |BIO_new_mem_buf|) or a + * writable sink (with |BIO_new|, |BIO_s_mem| and |BIO_get_mem_buf|). Data + * written to a writable, memory BIO can be recalled by reading from it. + * + * Calling |BIO_reset| on a read-only BIO resets it to the original contents. + * On a writable BIO, it clears any data. + * + * If the close flag is set to |BIO_NOCLOSE| (not the default) then the + * underlying |BUF_MEM| will not be freed when the |BIO| is freed. + * + * Memory BIOs support |BIO_gets| and |BIO_puts|. + * + * |BIO_eof| is true if no data is in the BIO. + * + * |BIO_ctrl_pending| returns the number of bytes currently stored. */ + +/* BIO_s_mem returns a |BIO_METHOD| that uses a in-memory buffer. */ +OPENSSL_EXPORT const BIO_METHOD *BIO_s_mem(void); + +/* BIO_new_mem_buf creates BIO that reads and writes from |len| bytes at |buf|. + * It does not take ownership of |buf|. It returns the BIO or NULL on error. + * + * If |len| is negative, then |buf| is treated as a NUL-terminated string, but + * don't depend on this in new code. */ +OPENSSL_EXPORT BIO *BIO_new_mem_buf(void *buf, int len); + +/* BIO_mem_contents sets |*out_contents| to point to the current contents of + * |bio| and |*out_len| to contain the length of that data. It returns one on + * success and zero otherwise. */ +OPENSSL_EXPORT int BIO_mem_contents(const BIO *bio, + const uint8_t **out_contents, + size_t *out_len); + +/* BIO_get_mem_data sets |*contents| to point to the current contents of |bio| + * and returns the length of the data. + * + * WARNING: don't use this, use |BIO_mem_contents|. A return value of zero from + * this function can mean either that it failed or that the memory buffer is + * empty. */ +OPENSSL_EXPORT long BIO_get_mem_data(BIO *bio, char **contents); + +/* BIO_get_mem_ptr sets |*out| to a BUF_MEM containing the current contents of + * |bio|. It returns one on success or zero on error. */ +OPENSSL_EXPORT int BIO_get_mem_ptr(BIO *bio, BUF_MEM **out); + +/* BIO_set_mem_buf sets |b| as the contents of |bio|. If |take_ownership| is + * non-zero, then |b| will be freed when |bio| is closed. Returns one on + * success or zero otherwise. */ +OPENSSL_EXPORT int BIO_set_mem_buf(BIO *bio, BUF_MEM *b, int take_ownership); + +/* BIO_set_mem_eof_return sets the value that will be returned from reading + * |bio| when empty. If |eof_value| is zero then an empty memory BIO will + * return EOF (that is it will return zero and |BIO_should_retry| will be + * false). If |eof_value| is non zero then it will return |eof_value| when it + * is empty and it will set the read retry flag (that is |BIO_read_retry| is + * true). To avoid ambiguity with a normal positive return value, |eof_value| + * should be set to a negative value, typically -1. + * + * For a read-only BIO, the default is zero (EOF). For a writable BIO, the + * default is -1 so that additional data can be written once exhausted. */ +OPENSSL_EXPORT int BIO_set_mem_eof_return(BIO *bio, int eof_value); + + +/* File descriptor BIOs. + * + * File descriptor BIOs are wrappers around the system's |read| and |write| + * functions. If the close flag is set then then |close| is called on the + * underlying file descriptor when the BIO is freed. + * + * |BIO_reset| attempts to seek the file pointer to the start of file using + * |lseek|. + * + * |BIO_seek| sets the file pointer to position |off| from start of file using + * |lseek|. + * + * |BIO_tell| returns the current file position. */ + +/* BIO_s_fd returns a |BIO_METHOD| for file descriptor fds. */ +OPENSSL_EXPORT const BIO_METHOD *BIO_s_fd(void); + +/* BIO_new_fd creates a new file descriptor BIO wrapping |fd|. If |close_flag| + * is non-zero, then |fd| will be closed when the BIO is. */ +OPENSSL_EXPORT BIO *BIO_new_fd(int fd, int close_flag); + +/* BIO_set_fd sets the file descriptor of |bio| to |fd|. If |close_flag| is + * non-zero then |fd| will be closed when |bio| is. It returns one on success + * or zero on error. */ +OPENSSL_EXPORT int BIO_set_fd(BIO *bio, int fd, int close_flag); + +/* BIO_get_fd sets |*out_fd| to the file descriptor currently in use by |bio|. + * It returns one on success and zero on error. */ +OPENSSL_EXPORT int BIO_get_fd(BIO *bio, int *out_fd); + + +/* File BIOs. + * + * File BIOs are wrappers around a C |FILE| object. + * + * |BIO_flush| on a file BIO calls |fflush| on the wrapped stream. + * + * |BIO_reset| attempts to seek the file pointer to the start of file using + * |fseek|. + * + * |BIO_seek| sets the file pointer to the given position from the start of + * file using |fseek|. + * + * |BIO_eof| calls |feof|. + * + * Setting the close flag causes |fclose| to be called on the stream when the + * BIO is freed. */ + +/* BIO_s_file returns a BIO_METHOD that wraps a |FILE|. */ +OPENSSL_EXPORT const BIO_METHOD *BIO_s_file(void); + +/* BIO_new_file creates a file BIO by opening |filename| with the given mode. + * See the |fopen| manual page for details of the mode argument. */ +OPENSSL_EXPORT BIO *BIO_new_file(const char *filename, const char *mode); + +/* BIO_new_fp creates a new file BIO that wraps the given |FILE|. If + * |close_flag| is |BIO_CLOSE|, then |fclose| will be called on |stream| when + * the BIO is closed. */ +OPENSSL_EXPORT BIO *BIO_new_fp(FILE *stream, int close_flag); + +/* BIO_get_fp sets |*out_file| to the current |FILE| for |bio|. It returns one + * on success and zero otherwise. */ +OPENSSL_EXPORT int BIO_get_fp(BIO *bio, FILE **out_file); + +/* BIO_set_fp sets the |FILE| for |bio|. If |close_flag| is |BIO_CLOSE| then + * |fclose| will be called on |file| when |bio| is closed. It returns one on + * sucess and zero otherwise. */ +OPENSSL_EXPORT int BIO_set_fp(BIO *bio, FILE *file, int close_flag); + +/* BIO_read_filename opens |filename| for reading and sets the result as the + * |FILE| for |bio|. It returns one on success and zero otherwise. The |FILE| + * will be closed when |bio| is freed. */ +OPENSSL_EXPORT int BIO_read_filename(BIO *bio, const char *filename); + +/* BIO_write_filename opens |filename| for writing and sets the result as the + * |FILE| for |bio|. It returns one on success and zero otherwise. The |FILE| + * will be closed when |bio| is freed. */ +OPENSSL_EXPORT int BIO_write_filename(BIO *bio, const char *filename); + +/* BIO_append_filename opens |filename| for appending and sets the result as + * the |FILE| for |bio|. It returns one on success and zero otherwise. The + * |FILE| will be closed when |bio| is freed. */ +OPENSSL_EXPORT int BIO_append_filename(BIO *bio, const char *filename); + +/* BIO_rw_filename opens |filename| for reading and writing and sets the result + * as the |FILE| for |bio|. It returns one on success and zero otherwise. The + * |FILE| will be closed when |bio| is freed. */ +OPENSSL_EXPORT int BIO_rw_filename(BIO *bio, const char *filename); + + +/* Buffer BIOs. + * + * Buffer BIOs are a filter-type BIO, i.e. they are designed to be used in a + * chain of BIOs. They provide buffering to reduce the number of operations on + * the underlying BIOs. */ + +OPENSSL_EXPORT const BIO_METHOD *BIO_f_buffer(void); + +/* BIO_set_read_buffer_size sets the size, in bytes, of the read buffer and + * clears it. It returns one on success and zero on failure. */ +OPENSSL_EXPORT int BIO_set_read_buffer_size(BIO *bio, int buffer_size); + +/* BIO_set_write_buffer_size sets the size, in bytes, of the write buffer and + * clears it. It returns one on success and zero on failure. */ +OPENSSL_EXPORT int BIO_set_write_buffer_size(BIO *bio, int buffer_size); + + +/* Socket BIOs. */ + +OPENSSL_EXPORT const BIO_METHOD *BIO_s_socket(void); + +/* BIO_new_socket allocates and initialises a fresh BIO which will read and + * write to the socket |fd|. If |close_flag| is |BIO_CLOSE| then closing the + * BIO will close |fd|. It returns the fresh |BIO| or NULL on error. */ +OPENSSL_EXPORT BIO *BIO_new_socket(int fd, int close_flag); + + +/* Connect BIOs. + * + * A connection BIO creates a network connection and transfers data over the + * resulting socket. */ + +OPENSSL_EXPORT const BIO_METHOD *BIO_s_connect(void); + +/* BIO_new_connect returns a BIO that connects to the given hostname and port. + * The |host_and_optional_port| argument should be of the form + * "www.example.com" or "www.example.com:443". If the port is omitted, it must + * be provided with |BIO_set_conn_port|. + * + * It returns the new BIO on success, or NULL on error. */ +OPENSSL_EXPORT BIO *BIO_new_connect(const char *host_and_optional_port); + +/* BIO_set_conn_hostname sets |host_and_optional_port| as the hostname and + * optional port that |bio| will connect to. If the port is omitted, it must be + * provided with |BIO_set_conn_port|. + * + * It returns one on success and zero otherwise. */ +OPENSSL_EXPORT int BIO_set_conn_hostname(BIO *bio, + const char *host_and_optional_port); + +/* BIO_set_conn_port sets |port_str| as the port or service name that |bio| + * will connect to. It returns one on success and zero otherwise. */ +OPENSSL_EXPORT int BIO_set_conn_port(BIO *bio, const char *port_str); + +/* BIO_set_nbio sets whether |bio| will use non-blocking I/O operations. It + * returns one on success and zero otherwise. */ +OPENSSL_EXPORT int BIO_set_nbio(BIO *bio, int on); + + +/* Datagram BIOs. + * + * TODO(fork): not implemented. */ + +#define BIO_CTRL_DGRAM_QUERY_MTU 40 /* as kernel for current MTU */ + +#define BIO_CTRL_DGRAM_SET_MTU 42 /* set cached value for MTU. want to use + this if asking the kernel fails */ + +#define BIO_CTRL_DGRAM_MTU_EXCEEDED 43 /* check whether the MTU was exceed in + the previous write operation. */ + +#define BIO_CTRL_DGRAM_SET_NEXT_TIMEOUT \ + 45 /* Next DTLS handshake timeout to adjust socket timeouts */ + +#define BIO_CTRL_DGRAM_GET_PEER 46 + +#define BIO_CTRL_DGRAM_GET_FALLBACK_MTU 47 + + +/* BIO Pairs. + * + * BIO pairs provide a "loopback" like system: a pair of BIOs where data + * written to one can be read from the other and vice versa. */ + +/* BIO_new_bio_pair sets |*out1| and |*out2| to two freshly created BIOs where + * data written to one can be read from the other and vice versa. The + * |writebuf1| argument gives the size of the buffer used in |*out1| and + * |writebuf2| for |*out2|. It returns one on success and zero on error. */ +OPENSSL_EXPORT int BIO_new_bio_pair(BIO **out1, size_t writebuf1, BIO **out2, + size_t writebuf2); + +/* BIO_new_bio_pair_external_buf is the same as |BIO_new_bio_pair| with the + * difference that the caller keeps ownership of the write buffers + * |ext_writebuf1_len| and |ext_writebuf2_len|. This is useful when using zero + * copy API for read and write operations, in cases where the buffers need to + * outlive the BIO pairs. It returns one on success and zero on error. */ +OPENSSL_EXPORT int BIO_new_bio_pair_external_buf(BIO** bio1_p, + size_t writebuf1_len, + uint8_t* ext_writebuf1, + BIO** bio2_p, + size_t writebuf2_len, + uint8_t* ext_writebuf2); + +/* BIO_ctrl_get_read_request returns the number of bytes that the other side of + * |bio| tried (unsuccessfully) to read. */ +OPENSSL_EXPORT size_t BIO_ctrl_get_read_request(BIO *bio); + +/* BIO_ctrl_get_write_guarantee returns the number of bytes that |bio| (which + * must have been returned by |BIO_new_bio_pair|) will accept on the next + * |BIO_write| call. */ +OPENSSL_EXPORT size_t BIO_ctrl_get_write_guarantee(BIO *bio); + +/* BIO_shutdown_wr marks |bio| as closed, from the point of view of the other + * side of the pair. Future |BIO_write| calls on |bio| will fail. It returns + * one on success and zero otherwise. */ +OPENSSL_EXPORT int BIO_shutdown_wr(BIO *bio); + + +/* Zero copy versions of BIO_read and BIO_write for BIO pairs. */ + +/* BIO_zero_copy_get_read_buf initiates a zero copy read operation. + * |out_read_buf| is set to the internal read buffer, and |out_buf_offset| is + * set to the current read position of |out_read_buf|. The number of bytes + * available for read from |out_read_buf| + |out_buf_offset| is returned in + * |out_available_bytes|. Note that this function might report fewer bytes + * available than |BIO_pending|, if the internal ring buffer is wrapped. It + * returns one on success. In case of error it returns zero and pushes to the + * error stack. + * + * The zero copy read operation is completed by calling + * |BIO_zero_copy_get_read_buf_done|. Neither |BIO_zero_copy_get_read_buf| nor + * any other I/O read operation may be called while a zero copy read operation + * is active. */ +OPENSSL_EXPORT int BIO_zero_copy_get_read_buf(BIO* bio, + uint8_t** out_read_buf, + size_t* out_buf_offset, + size_t* out_available_bytes); + +/* BIO_zero_copy_get_read_buf_done must be called after reading from a BIO using + * |BIO_zero_copy_get_read_buf| to finish the read operation. The |bytes_read| + * argument is the number of bytes read. + * + * It returns one on success. In case of error it returns zero and pushes to the + * error stack. */ +OPENSSL_EXPORT int BIO_zero_copy_get_read_buf_done(BIO* bio, size_t bytes_read); + +/* BIO_zero_copy_get_write_buf_done initiates a zero copy write operation. + * |out_write_buf| is set to to the internal write buffer, and |out_buf_offset| + * is set to the current write position of |out_write_buf|. + * The number of bytes available for write from |out_write_buf| + + * |out_buf_offset| is returned in |out_available_bytes|. Note that this + * function might report fewer bytes available than + * |BIO_ctrl_get_write_guarantee|, if the internal buffer is wrapped. It returns + * one on success. In case of error it returns zero and pushes to the error + * stack. + * + * The zero copy write operation is completed by calling + * |BIO_zero_copy_write_buf_done|. Neither |BIO_zero_copy_get_write_buf| + * nor any other I/O write operation may be called while a zero copy write + * operation is active. */ +OPENSSL_EXPORT int BIO_zero_copy_get_write_buf(BIO* bio, + uint8_t** out_write_buf, + size_t* out_buf_offset, + size_t* out_available_bytes); + +/* BIO_zero_copy_write_buf_done must be called after writing to a BIO using + * |BIO_zero_copy_get_write_buf_done| to finish the write operation. The + * |bytes_written| argument gives the number of bytes written. + * + * It returns one on success. In case of error it returns zero and pushes to the + * error stack. */ +OPENSSL_EXPORT int BIO_zero_copy_get_write_buf_done(BIO* bio, + size_t bytes_written); + + +/* BIO_NOCLOSE and |BIO_CLOSE| can be used as symbolic arguments when a "close + * flag" is passed to a BIO function. */ +#define BIO_NOCLOSE 0 +#define BIO_CLOSE 1 + +/* These are passed to the BIO callback */ +#define BIO_CB_FREE 0x01 +#define BIO_CB_READ 0x02 +#define BIO_CB_WRITE 0x03 +#define BIO_CB_PUTS 0x04 +#define BIO_CB_GETS 0x05 +#define BIO_CB_CTRL 0x06 + +/* The callback is called before and after the underling operation, + * The BIO_CB_RETURN flag indicates if it is after the call */ +#define BIO_CB_RETURN 0x80 + +/* These are values of the |cmd| argument to |BIO_ctrl|. */ +#define BIO_CTRL_RESET 1 /* opt - rewind/zero etc */ +#define BIO_CTRL_EOF 2 /* opt - are we at the eof */ +#define BIO_CTRL_INFO 3 /* opt - extra tit-bits */ +#define BIO_CTRL_SET 4 /* man - set the 'IO' type */ +#define BIO_CTRL_GET 5 /* man - get the 'IO' type */ +#define BIO_CTRL_GET_CLOSE 8 /* man - set the 'close' on free */ +#define BIO_CTRL_SET_CLOSE 9 /* man - set the 'close' on free */ +#define BIO_CTRL_PENDING 10 /* opt - is their more data buffered */ +#define BIO_CTRL_FLUSH 11 /* opt - 'flush' buffered output */ +#define BIO_CTRL_WPENDING 13 /* opt - number of bytes still to write */ +/* callback is int cb(BIO *bio,state,ret); */ +#define BIO_CTRL_SET_CALLBACK 14 /* opt - set callback function */ +#define BIO_CTRL_GET_CALLBACK 15 /* opt - set callback function */ +#define BIO_CTRL_SET_FILENAME 30 /* BIO_s_file special */ + + +/* Android compatibility section. + * + * A previous version of BoringSSL used in Android renamed ERR_print_errors_fp + * to BIO_print_errors_fp. It has subsequently been renamed back to + * ERR_print_errors_fp. */ +#define BIO_print_errors_fp ERR_print_errors_fp + + +/* Private functions */ + +#define BIO_FLAGS_READ 0x01 +#define BIO_FLAGS_WRITE 0x02 +#define BIO_FLAGS_IO_SPECIAL 0x04 +#define BIO_FLAGS_RWS (BIO_FLAGS_READ | BIO_FLAGS_WRITE | BIO_FLAGS_IO_SPECIAL) +#define BIO_FLAGS_SHOULD_RETRY 0x08 +#define BIO_FLAGS_BASE64_NO_NL 0x100 +/* This is used with memory BIOs: it means we shouldn't free up or change the + * data in any way. */ +#define BIO_FLAGS_MEM_RDONLY 0x200 + +/* These are the 'types' of BIOs */ +#define BIO_TYPE_NONE 0 +#define BIO_TYPE_MEM (1 | 0x0400) +#define BIO_TYPE_FILE (2 | 0x0400) +#define BIO_TYPE_FD (4 | 0x0400 | 0x0100) +#define BIO_TYPE_SOCKET (5 | 0x0400 | 0x0100) +#define BIO_TYPE_NULL (6 | 0x0400) +#define BIO_TYPE_SSL (7 | 0x0200) +#define BIO_TYPE_MD (8 | 0x0200) /* passive filter */ +#define BIO_TYPE_BUFFER (9 | 0x0200) /* filter */ +#define BIO_TYPE_CIPHER (10 | 0x0200) /* filter */ +#define BIO_TYPE_BASE64 (11 | 0x0200) /* filter */ +#define BIO_TYPE_CONNECT (12 | 0x0400 | 0x0100) /* socket - connect */ +#define BIO_TYPE_ACCEPT (13 | 0x0400 | 0x0100) /* socket for accept */ +#define BIO_TYPE_PROXY_CLIENT (14 | 0x0200) /* client proxy BIO */ +#define BIO_TYPE_PROXY_SERVER (15 | 0x0200) /* server proxy BIO */ +#define BIO_TYPE_NBIO_TEST (16 | 0x0200) /* server proxy BIO */ +#define BIO_TYPE_NULL_FILTER (17 | 0x0200) +#define BIO_TYPE_BER (18 | 0x0200) /* BER -> bin filter */ +#define BIO_TYPE_BIO (19 | 0x0400) /* (half a) BIO pair */ +#define BIO_TYPE_LINEBUFFER (20 | 0x0200) /* filter */ +#define BIO_TYPE_DGRAM (21 | 0x0400 | 0x0100) +#define BIO_TYPE_ASN1 (22 | 0x0200) /* filter */ +#define BIO_TYPE_COMP (23 | 0x0200) /* filter */ + +#define BIO_TYPE_DESCRIPTOR 0x0100 /* socket, fd, connect or accept */ +#define BIO_TYPE_FILTER 0x0200 +#define BIO_TYPE_SOURCE_SINK 0x0400 + +struct bio_method_st { + int type; + const char *name; + int (*bwrite)(BIO *, const char *, int); + int (*bread)(BIO *, char *, int); + /* TODO(fork): remove bputs. */ + int (*bputs)(BIO *, const char *); + int (*bgets)(BIO *, char *, int); + long (*ctrl)(BIO *, int, long, void *); + int (*create)(BIO *); + int (*destroy)(BIO *); + long (*callback_ctrl)(BIO *, int, bio_info_cb); +}; + +struct bio_st { + const BIO_METHOD *method; + /* bio, mode, argp, argi, argl, ret */ + long (*callback)(struct bio_st *, int, const char *, int, long, long); + char *cb_arg; /* first argument for the callback */ + + /* init is non-zero if this |BIO| has been initialised. */ + int init; + /* shutdown is often used by specific |BIO_METHOD|s to determine whether + * they own some underlying resource. This flag can often by controlled by + * |BIO_set_close|. For example, whether an fd BIO closes the underlying fd + * when it, itself, is closed. */ + int shutdown; + int flags; + int retry_reason; + /* num is a BIO-specific value. For example, in fd BIOs it's used to store a + * file descriptor. */ + int num; + CRYPTO_refcount_t references; + void *ptr; + /* next_bio points to the next |BIO| in a chain. This |BIO| owns a reference + * to |next_bio|. */ + struct bio_st *next_bio; /* used by filter BIOs */ + size_t num_read, num_write; +}; + +#define BIO_C_SET_CONNECT 100 +#define BIO_C_DO_STATE_MACHINE 101 +#define BIO_C_SET_NBIO 102 +#define BIO_C_SET_PROXY_PARAM 103 +#define BIO_C_SET_FD 104 +#define BIO_C_GET_FD 105 +#define BIO_C_SET_FILE_PTR 106 +#define BIO_C_GET_FILE_PTR 107 +#define BIO_C_SET_FILENAME 108 +#define BIO_C_SET_SSL 109 +#define BIO_C_GET_SSL 110 +#define BIO_C_SET_MD 111 +#define BIO_C_GET_MD 112 +#define BIO_C_GET_CIPHER_STATUS 113 +#define BIO_C_SET_BUF_MEM 114 +#define BIO_C_GET_BUF_MEM_PTR 115 +#define BIO_C_GET_BUFF_NUM_LINES 116 +#define BIO_C_SET_BUFF_SIZE 117 +#define BIO_C_SET_ACCEPT 118 +#define BIO_C_SSL_MODE 119 +#define BIO_C_GET_MD_CTX 120 +#define BIO_C_GET_PROXY_PARAM 121 +#define BIO_C_SET_BUFF_READ_DATA 122 /* data to read first */ +#define BIO_C_GET_CONNECT 123 +#define BIO_C_GET_ACCEPT 124 +#define BIO_C_SET_SSL_RENEGOTIATE_BYTES 125 +#define BIO_C_GET_SSL_NUM_RENEGOTIATES 126 +#define BIO_C_SET_SSL_RENEGOTIATE_TIMEOUT 127 +#define BIO_C_FILE_SEEK 128 +#define BIO_C_GET_CIPHER_CTX 129 +#define BIO_C_SET_BUF_MEM_EOF_RETURN 130/*return end of input value*/ +#define BIO_C_SET_BIND_MODE 131 +#define BIO_C_GET_BIND_MODE 132 +#define BIO_C_FILE_TELL 133 +#define BIO_C_GET_SOCKS 134 +#define BIO_C_SET_SOCKS 135 + +#define BIO_C_SET_WRITE_BUF_SIZE 136/* for BIO_s_bio */ +#define BIO_C_GET_WRITE_BUF_SIZE 137 +#define BIO_C_GET_WRITE_GUARANTEE 140 +#define BIO_C_GET_READ_REQUEST 141 +#define BIO_C_SHUTDOWN_WR 142 +#define BIO_C_NREAD0 143 +#define BIO_C_NREAD 144 +#define BIO_C_NWRITE0 145 +#define BIO_C_NWRITE 146 +#define BIO_C_RESET_READ_REQUEST 147 +#define BIO_C_SET_MD_CTX 148 + +#define BIO_C_SET_PREFIX 149 +#define BIO_C_GET_PREFIX 150 +#define BIO_C_SET_SUFFIX 151 +#define BIO_C_GET_SUFFIX 152 + +#define BIO_C_SET_EX_ARG 153 +#define BIO_C_GET_EX_ARG 154 + + +#if defined(__cplusplus) +} /* extern C */ +#endif + +#define BIO_F_BIO_callback_ctrl 100 +#define BIO_F_BIO_ctrl 101 +#define BIO_F_BIO_new 102 +#define BIO_F_BIO_new_file 103 +#define BIO_F_BIO_new_mem_buf 104 +#define BIO_F_BIO_zero_copy_get_read_buf 105 +#define BIO_F_BIO_zero_copy_get_read_buf_done 106 +#define BIO_F_BIO_zero_copy_get_write_buf 107 +#define BIO_F_BIO_zero_copy_get_write_buf_done 108 +#define BIO_F_bio_io 109 +#define BIO_F_bio_make_pair 110 +#define BIO_F_bio_write 111 +#define BIO_F_buffer_ctrl 112 +#define BIO_F_conn_ctrl 113 +#define BIO_F_conn_state 114 +#define BIO_F_file_ctrl 115 +#define BIO_F_file_read 116 +#define BIO_F_mem_write 117 +#define BIO_F_BIO_printf 118 +#define BIO_R_BAD_FOPEN_MODE 100 +#define BIO_R_BROKEN_PIPE 101 +#define BIO_R_CONNECT_ERROR 102 +#define BIO_R_ERROR_SETTING_NBIO 103 +#define BIO_R_INVALID_ARGUMENT 104 +#define BIO_R_IN_USE 105 +#define BIO_R_KEEPALIVE 106 +#define BIO_R_NBIO_CONNECT_ERROR 107 +#define BIO_R_NO_HOSTNAME_SPECIFIED 108 +#define BIO_R_NO_PORT_SPECIFIED 109 +#define BIO_R_NO_SUCH_FILE 110 +#define BIO_R_NULL_PARAMETER 111 +#define BIO_R_SYS_LIB 112 +#define BIO_R_UNABLE_TO_CREATE_SOCKET 113 +#define BIO_R_UNINITIALIZED 114 +#define BIO_R_UNSUPPORTED_METHOD 115 +#define BIO_R_WRITE_TO_READ_ONLY_BIO 116 + +#endif /* OPENSSL_HEADER_BIO_H */ diff --git a/phonelibs/boringssl/include/openssl/blowfish.h b/phonelibs/boringssl/include/openssl/blowfish.h new file mode 100644 index 00000000000000..fa60d5336fcb07 --- /dev/null +++ b/phonelibs/boringssl/include/openssl/blowfish.h @@ -0,0 +1,93 @@ +/* Copyright (C) 1995-1998 Eric Young (eay@cryptsoft.com) + * All rights reserved. + * + * This package is an SSL implementation written + * by Eric Young (eay@cryptsoft.com). + * The implementation was written so as to conform with Netscapes SSL. + * + * This library is free for commercial and non-commercial use as long as + * the following conditions are aheared to. The following conditions + * apply to all code found in this distribution, be it the RC4, RSA, + * lhash, DES, etc., code; not just the SSL code. The SSL documentation + * included with this distribution is covered by the same copyright terms + * except that the holder is Tim Hudson (tjh@cryptsoft.com). + * + * Copyright remains Eric Young's, and as such any Copyright notices in + * the code are not to be removed. + * If this package is used in a product, Eric Young should be given attribution + * as the author of the parts of the library used. + * This can be in the form of a textual message at program startup or + * in documentation (online or textual) provided with the package. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must 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. All advertising materials mentioning features or use of this software + * must display the following acknowledgement: + * "This product includes cryptographic software written by + * Eric Young (eay@cryptsoft.com)" + * The word 'cryptographic' can be left out if the rouines from the library + * being used are not cryptographic related :-). + * 4. If you include any Windows specific code (or a derivative thereof) from + * the apps directory (application code) you must include an acknowledgement: + * "This product includes software written by Tim Hudson (tjh@cryptsoft.com)" + * + * THIS SOFTWARE IS PROVIDED BY ERIC YOUNG ``AS IS'' AND + * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHOR OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (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 licence and distribution terms for any publically available version or + * derivative of this code cannot be changed. i.e. this code cannot simply be + * copied and put under another distribution licence + * [including the GNU Public Licence.] */ + +#ifndef OPENSSL_HEADER_BLOWFISH_H +#define OPENSSL_HEADER_BLOWFISH_H + +#include + +#ifdef __cplusplus +extern "C" { +#endif + + +#define BF_ENCRYPT 1 +#define BF_DECRYPT 0 + +#define BF_ROUNDS 16 +#define BF_BLOCK 8 + +typedef struct bf_key_st { + uint32_t P[BF_ROUNDS + 2]; + uint32_t S[4 * 256]; +} BF_KEY; + +OPENSSL_EXPORT void BF_set_key(BF_KEY *key, size_t len, const uint8_t *data); +OPENSSL_EXPORT void BF_encrypt(uint32_t *data, const BF_KEY *key); +OPENSSL_EXPORT void BF_decrypt(uint32_t *data, const BF_KEY *key); + +OPENSSL_EXPORT void BF_ecb_encrypt(const uint8_t *in, uint8_t *out, + const BF_KEY *key, int enc); +OPENSSL_EXPORT void BF_cbc_encrypt(const uint8_t *in, uint8_t *out, long length, + const BF_KEY *schedule, uint8_t *ivec, + int enc); + + +#ifdef __cplusplus +} +#endif + +#endif /* OPENSSL_HEADER_BLOWFISH_H */ diff --git a/phonelibs/boringssl/include/openssl/bn.h b/phonelibs/boringssl/include/openssl/bn.h new file mode 100644 index 00000000000000..ec1c8ff5c32d1f --- /dev/null +++ b/phonelibs/boringssl/include/openssl/bn.h @@ -0,0 +1,875 @@ +/* Copyright (C) 1995-1997 Eric Young (eay@cryptsoft.com) + * All rights reserved. + * + * This package is an SSL implementation written + * by Eric Young (eay@cryptsoft.com). + * The implementation was written so as to conform with Netscapes SSL. + * + * This library is free for commercial and non-commercial use as long as + * the following conditions are aheared to. The following conditions + * apply to all code found in this distribution, be it the RC4, RSA, + * lhash, DES, etc., code; not just the SSL code. The SSL documentation + * included with this distribution is covered by the same copyright terms + * except that the holder is Tim Hudson (tjh@cryptsoft.com). + * + * Copyright remains Eric Young's, and as such any Copyright notices in + * the code are not to be removed. + * If this package is used in a product, Eric Young should be given attribution + * as the author of the parts of the library used. + * This can be in the form of a textual message at program startup or + * in documentation (online or textual) provided with the package. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must 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. All advertising materials mentioning features or use of this software + * must display the following acknowledgement: + * "This product includes cryptographic software written by + * Eric Young (eay@cryptsoft.com)" + * The word 'cryptographic' can be left out if the rouines from the library + * being used are not cryptographic related :-). + * 4. If you include any Windows specific code (or a derivative thereof) from + * the apps directory (application code) you must include an acknowledgement: + * "This product includes software written by Tim Hudson (tjh@cryptsoft.com)" + * + * THIS SOFTWARE IS PROVIDED BY ERIC YOUNG ``AS IS'' AND + * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHOR OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (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 licence and distribution terms for any publically available version or + * derivative of this code cannot be changed. i.e. this code cannot simply be + * copied and put under another distribution licence + * [including the GNU Public Licence.] + */ +/* ==================================================================== + * Copyright (c) 1998-2006 The OpenSSL Project. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * + * 3. All advertising materials mentioning features or use of this + * software must display the following acknowledgment: + * "This product includes software developed by the OpenSSL Project + * for use in the OpenSSL Toolkit. (http://www.openssl.org/)" + * + * 4. The names "OpenSSL Toolkit" and "OpenSSL Project" must not be used to + * endorse or promote products derived from this software without + * prior written permission. For written permission, please contact + * openssl-core@openssl.org. + * + * 5. Products derived from this software may not be called "OpenSSL" + * nor may "OpenSSL" appear in their names without prior written + * permission of the OpenSSL Project. + * + * 6. Redistributions of any form whatsoever must retain the following + * acknowledgment: + * "This product includes software developed by the OpenSSL Project + * for use in the OpenSSL Toolkit (http://www.openssl.org/)" + * + * THIS SOFTWARE IS PROVIDED BY THE OpenSSL PROJECT ``AS IS'' AND ANY + * EXPRESSED OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR + * PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE OpenSSL PROJECT OR + * ITS CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, + * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT + * NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + * STRICT LIABILITY, OR TORT (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 product includes cryptographic software written by Eric Young + * (eay@cryptsoft.com). This product includes software written by Tim + * Hudson (tjh@cryptsoft.com). + * + */ +/* ==================================================================== + * Copyright 2002 Sun Microsystems, Inc. ALL RIGHTS RESERVED. + * + * Portions of the attached software ("Contribution") are developed by + * SUN MICROSYSTEMS, INC., and are contributed to the OpenSSL project. + * + * The Contribution is licensed pursuant to the Eric Young open source + * license provided above. + * + * The binary polynomial arithmetic software is originally written by + * Sheueling Chang Shantz and Douglas Stebila of Sun Microsystems + * Laboratories. */ + +#ifndef OPENSSL_HEADER_BN_H +#define OPENSSL_HEADER_BN_H + +#include +#include + +#include /* for PRIu64 and friends */ +#include /* for FILE* */ + +#if defined(__cplusplus) +extern "C" { +#endif + + +/* BN provides support for working with arbitary sized integers. For example, + * although the largest integer supported by the compiler might be 64 bits, BN + * will allow you to work with numbers until you run out of memory. */ + + +/* BN_ULONG is the native word size when working with big integers. + * + * Note: on some platforms, inttypes.h does not define print format macros in + * C++ unless |__STDC_FORMAT_MACROS| defined. As this is a public header, bn.h + * does not define |__STDC_FORMAT_MACROS| itself. C++ source files which use the + * FMT macros must define it externally. */ +#if defined(OPENSSL_64_BIT) +#define BN_ULONG uint64_t +#define BN_BITS2 64 +#define BN_DEC_FMT1 "%" PRIu64 +#define BN_DEC_FMT2 "%019" PRIu64 +#define BN_HEX_FMT1 "%" PRIx64 +#elif defined(OPENSSL_32_BIT) +#define BN_ULONG uint32_t +#define BN_BITS2 32 +#define BN_DEC_FMT1 "%" PRIu32 +#define BN_DEC_FMT2 "%09" PRIu32 +#define BN_HEX_FMT1 "%" PRIx32 +#else +#error "Must define either OPENSSL_32_BIT or OPENSSL_64_BIT" +#endif + + +/* Allocation and freeing. */ + +/* BN_new creates a new, allocated BIGNUM and initialises it. */ +OPENSSL_EXPORT BIGNUM *BN_new(void); + +/* BN_init initialises a stack allocated |BIGNUM|. */ +OPENSSL_EXPORT void BN_init(BIGNUM *bn); + +/* BN_free frees the data referenced by |bn| and, if |bn| was originally + * allocated on the heap, frees |bn| also. */ +OPENSSL_EXPORT void BN_free(BIGNUM *bn); + +/* BN_clear_free erases and frees the data referenced by |bn| and, if |bn| was + * originally allocated on the heap, frees |bn| also. */ +OPENSSL_EXPORT void BN_clear_free(BIGNUM *bn); + +/* BN_dup allocates a new BIGNUM and sets it equal to |src|. It returns the + * allocated BIGNUM on success or NULL otherwise. */ +OPENSSL_EXPORT BIGNUM *BN_dup(const BIGNUM *src); + +/* BN_copy sets |dest| equal to |src| and returns |dest|. */ +OPENSSL_EXPORT BIGNUM *BN_copy(BIGNUM *dest, const BIGNUM *src); + +/* BN_clear sets |bn| to zero and erases the old data. */ +OPENSSL_EXPORT void BN_clear(BIGNUM *bn); + +/* BN_value_one returns a static BIGNUM with value 1. */ +OPENSSL_EXPORT const BIGNUM *BN_value_one(void); + +/* BN_with_flags initialises a stack allocated |BIGNUM| with pointers to the + * contents of |in| but with |flags| ORed into the flags field. + * + * Note: the two BIGNUMs share state and so |out| should /not/ be passed to + * |BN_free|. */ +OPENSSL_EXPORT void BN_with_flags(BIGNUM *out, const BIGNUM *in, int flags); + + +/* Basic functions. */ + +/* BN_num_bits returns the minimum number of bits needed to represent the + * absolute value of |bn|. */ +OPENSSL_EXPORT unsigned BN_num_bits(const BIGNUM *bn); + +/* BN_num_bytes returns the minimum number of bytes needed to represent the + * absolute value of |bn|. */ +OPENSSL_EXPORT unsigned BN_num_bytes(const BIGNUM *bn); + +/* BN_zero sets |bn| to zero. */ +OPENSSL_EXPORT void BN_zero(BIGNUM *bn); + +/* BN_one sets |bn| to one. It returns one on success or zero on allocation + * failure. */ +OPENSSL_EXPORT int BN_one(BIGNUM *bn); + +/* BN_set_word sets |bn| to |value|. It returns one on success or zero on + * allocation failure. */ +OPENSSL_EXPORT int BN_set_word(BIGNUM *bn, BN_ULONG value); + +/* BN_set_negative sets the sign of |bn|. */ +OPENSSL_EXPORT void BN_set_negative(BIGNUM *bn, int sign); + +/* BN_is_negative returns one if |bn| is negative and zero otherwise. */ +OPENSSL_EXPORT int BN_is_negative(const BIGNUM *bn); + +/* BN_get_flags returns |bn->flags| & |flags|. */ +OPENSSL_EXPORT int BN_get_flags(const BIGNUM *bn, int flags); + +/* BN_set_flags sets |flags| on |bn|. */ +OPENSSL_EXPORT void BN_set_flags(BIGNUM *bn, int flags); + + +/* Conversion functions. */ + +/* BN_bin2bn sets |*ret| to the value of |len| bytes from |in|, interpreted as + * a big-endian number, and returns |ret|. If |ret| is NULL then a fresh + * |BIGNUM| is allocated and returned. It returns NULL on allocation + * failure. */ +OPENSSL_EXPORT BIGNUM *BN_bin2bn(const uint8_t *in, size_t len, BIGNUM *ret); + +/* BN_bn2bin serialises the absolute value of |in| to |out| as a big-endian + * integer, which must have |BN_num_bytes| of space available. It returns the + * number of bytes written. */ +OPENSSL_EXPORT size_t BN_bn2bin(const BIGNUM *in, uint8_t *out); + +/* BN_bn2bin_padded serialises the absolute value of |in| to |out| as a + * big-endian integer. The integer is padded with leading zeros up to size + * |len|. If |len| is smaller than |BN_num_bytes|, the function fails and + * returns 0. Otherwise, it returns 1. */ +OPENSSL_EXPORT int BN_bn2bin_padded(uint8_t *out, size_t len, const BIGNUM *in); + +/* BN_bn2hex returns an allocated string that contains a NUL-terminated, hex + * representation of |bn|. If |bn| is negative, the first char in the resulting + * string will be '-'. Returns NULL on allocation failure. */ +OPENSSL_EXPORT char *BN_bn2hex(const BIGNUM *bn); + +/* BN_hex2bn parses the leading hex number from |in|, which may be proceeded by + * a '-' to indicate a negative number and may contain trailing, non-hex data. + * If |outp| is not NULL, it constructs a BIGNUM equal to the hex number and + * stores it in |*outp|. If |*outp| is NULL then it allocates a new BIGNUM and + * updates |*outp|. It returns the number of bytes of |in| processed or zero on + * error. */ +OPENSSL_EXPORT int BN_hex2bn(BIGNUM **outp, const char *in); + +/* BN_bn2dec returns an allocated string that contains a NUL-terminated, + * decimal representation of |bn|. If |bn| is negative, the first char in the + * resulting string will be '-'. Returns NULL on allocation failure. */ +OPENSSL_EXPORT char *BN_bn2dec(const BIGNUM *a); + +/* BN_dec2bn parses the leading decimal number from |in|, which may be + * proceeded by a '-' to indicate a negative number and may contain trailing, + * non-decimal data. If |outp| is not NULL, it constructs a BIGNUM equal to the + * decimal number and stores it in |*outp|. If |*outp| is NULL then it + * allocates a new BIGNUM and updates |*outp|. It returns the number of bytes + * of |in| processed or zero on error. */ +OPENSSL_EXPORT int BN_dec2bn(BIGNUM **outp, const char *in); + +/* BN_asc2bn acts like |BN_dec2bn| or |BN_hex2bn| depending on whether |in| + * begins with "0X" or "0x" (indicating hex) or not (indicating decimal). A + * leading '-' is still permitted and comes before the optional 0X/0x. It + * returns one on success or zero on error. */ +OPENSSL_EXPORT int BN_asc2bn(BIGNUM **outp, const char *in); + +/* BN_print writes a hex encoding of |a| to |bio|. It returns one on success + * and zero on error. */ +OPENSSL_EXPORT int BN_print(BIO *bio, const BIGNUM *a); + +/* BN_print_fp acts like |BIO_print|, but wraps |fp| in a |BIO| first. */ +OPENSSL_EXPORT int BN_print_fp(FILE *fp, const BIGNUM *a); + +/* BN_get_word returns the absolute value of |bn| as a single word. If |bn| is + * too large to be represented as a single word, the maximum possible value + * will be returned. */ +OPENSSL_EXPORT BN_ULONG BN_get_word(const BIGNUM *bn); + + +/* Internal functions. + * + * These functions are useful for code that is doing low-level manipulations of + * BIGNUM values. However, be sure that no other function in this file does + * what you want before turning to these. */ + +/* bn_correct_top decrements |bn->top| until |bn->d[top-1]| is non-zero or + * until |top| is zero. */ +OPENSSL_EXPORT void bn_correct_top(BIGNUM *bn); + +/* bn_wexpand ensures that |bn| has at least |words| works of space without + * altering its value. It returns one on success or zero on allocation + * failure. */ +OPENSSL_EXPORT BIGNUM *bn_wexpand(BIGNUM *bn, unsigned words); + + +/* BIGNUM pools. + * + * Certain BIGNUM operations need to use many temporary variables and + * allocating and freeing them can be quite slow. Thus such opertions typically + * take a |BN_CTX| parameter, which contains a pool of |BIGNUMs|. The |ctx| + * argument to a public function may be NULL, in which case a local |BN_CTX| + * will be created just for the lifetime of that call. + * + * A function must call |BN_CTX_start| first. Then, |BN_CTX_get| may be called + * repeatedly to obtain temporary |BIGNUM|s. All |BN_CTX_get| calls must be made + * before calling any other functions that use the |ctx| as an argument. + * + * Finally, |BN_CTX_end| must be called before returning from the function. + * When |BN_CTX_end| is called, the |BIGNUM| pointers obtained from + * |BN_CTX_get| become invalid. */ + +/* BN_CTX_new returns a new, empty BN_CTX or NULL on allocation failure. */ +OPENSSL_EXPORT BN_CTX *BN_CTX_new(void); + +/* BN_CTX_free frees all BIGNUMs contained in |ctx| and then frees |ctx| + * itself. */ +OPENSSL_EXPORT void BN_CTX_free(BN_CTX *ctx); + +/* BN_CTX_start "pushes" a new entry onto the |ctx| stack and allows future + * calls to |BN_CTX_get|. */ +OPENSSL_EXPORT void BN_CTX_start(BN_CTX *ctx); + +/* BN_CTX_get returns a new |BIGNUM|, or NULL on allocation failure. Once + * |BN_CTX_get| has returned NULL, all future calls will also return NULL until + * |BN_CTX_end| is called. */ +OPENSSL_EXPORT BIGNUM *BN_CTX_get(BN_CTX *ctx); + +/* BN_CTX_end invalidates all |BIGNUM|s returned from |BN_CTX_get| since the + * matching |BN_CTX_start| call. */ +OPENSSL_EXPORT void BN_CTX_end(BN_CTX *ctx); + + +/* Simple arithmetic */ + +/* BN_add sets |r| = |a| + |b|, where |r| may be the same pointer as either |a| + * or |b|. It returns one on success and zero on allocation failure. */ +OPENSSL_EXPORT int BN_add(BIGNUM *r, const BIGNUM *a, const BIGNUM *b); + +/* BN_uadd sets |r| = |a| + |b|, where |a| and |b| are non-negative and |r| may + * be the same pointer as either |a| or |b|. It returns one on success and zero + * on allocation failure. */ +OPENSSL_EXPORT int BN_uadd(BIGNUM *r, const BIGNUM *a, const BIGNUM *b); + +/* BN_add_word adds |w| to |a|. It returns one on success and zero otherwise. */ +OPENSSL_EXPORT int BN_add_word(BIGNUM *a, BN_ULONG w); + +/* BN_sub sets |r| = |a| - |b|, where |r| must be a distinct pointer from |a| + * and |b|. It returns one on success and zero on allocation failure. */ +OPENSSL_EXPORT int BN_sub(BIGNUM *r, const BIGNUM *a, const BIGNUM *b); + +/* BN_usub sets |r| = |a| - |b|, where |a| and |b| are non-negative integers, + * |b| < |a| and |r| must be a distinct pointer from |a| and |b|. It returns + * one on success and zero on allocation failure. */ +OPENSSL_EXPORT int BN_usub(BIGNUM *r, const BIGNUM *a, const BIGNUM *b); + +/* BN_sub_word subtracts |w| from |a|. It returns one on success and zero on + * allocation failure. */ +OPENSSL_EXPORT int BN_sub_word(BIGNUM *a, BN_ULONG w); + +/* BN_mul sets |r| = |a| * |b|, where |r| may be the same pointer as |a| or + * |b|. Returns one on success and zero otherwise. */ +OPENSSL_EXPORT int BN_mul(BIGNUM *r, const BIGNUM *a, const BIGNUM *b, + BN_CTX *ctx); + +/* BN_mul_word sets |bn| = |bn| * |w|. It returns one on success or zero on + * allocation failure. */ +OPENSSL_EXPORT int BN_mul_word(BIGNUM *bn, BN_ULONG w); + +/* BN_sqr sets |r| = |a|^2 (i.e. squares), where |r| may be the same pointer as + * |a|. Returns one on success and zero otherwise. This is more efficient than + * BN_mul(r, a, a, ctx). */ +OPENSSL_EXPORT int BN_sqr(BIGNUM *r, const BIGNUM *a, BN_CTX *ctx); + +/* BN_div divides |numerator| by |divisor| and places the result in |quotient| + * and the remainder in |rem|. Either of |quotient| or |rem| may be NULL, in + * which case the respective value is not returned. The result is rounded + * towards zero; thus if |numerator| is negative, the remainder will be zero or + * negative. It returns one on success or zero on error. */ +OPENSSL_EXPORT int BN_div(BIGNUM *quotient, BIGNUM *rem, + const BIGNUM *numerator, const BIGNUM *divisor, + BN_CTX *ctx); + +/* BN_div_word sets |numerator| = |numerator|/|divisor| and returns the + * remainder or (BN_ULONG)-1 on error. */ +OPENSSL_EXPORT BN_ULONG BN_div_word(BIGNUM *numerator, BN_ULONG divisor); + +/* BN_sqrt sets |*out_sqrt| (which may be the same |BIGNUM| as |in|) to the + * square root of |in|, using |ctx|. It returns one on success or zero on + * error. Negative numbers and non-square numbers will result in an error with + * appropriate errors on the error queue. */ +OPENSSL_EXPORT int BN_sqrt(BIGNUM *out_sqrt, const BIGNUM *in, BN_CTX *ctx); + + +/* Comparison functions */ + +/* BN_cmp returns a value less than, equal to or greater than zero if |a| is + * less than, equal to or greater than |b|, respectively. */ +OPENSSL_EXPORT int BN_cmp(const BIGNUM *a, const BIGNUM *b); + +/* BN_ucmp returns a value less than, equal to or greater than zero if the + * absolute value of |a| is less than, equal to or greater than the absolute + * value of |b|, respectively. */ +OPENSSL_EXPORT int BN_ucmp(const BIGNUM *a, const BIGNUM *b); + +/* BN_abs_is_word returns one if the absolute value of |bn| equals |w| and zero + * otherwise. */ +OPENSSL_EXPORT int BN_abs_is_word(const BIGNUM *bn, BN_ULONG w); + +/* BN_is_zero returns one if |bn| is zero and zero otherwise. */ +OPENSSL_EXPORT int BN_is_zero(const BIGNUM *bn); + +/* BN_is_one returns one if |bn| equals one and zero otherwise. */ +OPENSSL_EXPORT int BN_is_one(const BIGNUM *bn); + +/* BN_is_word returns one if |bn| is exactly |w| and zero otherwise. */ +OPENSSL_EXPORT int BN_is_word(const BIGNUM *bn, BN_ULONG w); + +/* BN_is_odd returns one if |bn| is odd and zero otherwise. */ +OPENSSL_EXPORT int BN_is_odd(const BIGNUM *bn); + + +/* Bitwise operations. */ + +/* BN_lshift sets |r| equal to |a| << n. The |a| and |r| arguments may be the + * same |BIGNUM|. It returns one on success and zero on allocation failure. */ +OPENSSL_EXPORT int BN_lshift(BIGNUM *r, const BIGNUM *a, int n); + +/* BN_lshift1 sets |r| equal to |a| << 1, where |r| and |a| may be the same + * pointer. It returns one on success and zero on allocation failure. */ +OPENSSL_EXPORT int BN_lshift1(BIGNUM *r, const BIGNUM *a); + +/* BN_rshift sets |r| equal to |a| >> n, where |r| and |a| may be the same + * pointer. It returns one on success and zero on allocation failure. */ +OPENSSL_EXPORT int BN_rshift(BIGNUM *r, const BIGNUM *a, int n); + +/* BN_rshift1 sets |r| equal to |a| >> 1, where |r| and |a| may be the same + * pointer. It returns one on success and zero on allocation failure. */ +OPENSSL_EXPORT int BN_rshift1(BIGNUM *r, const BIGNUM *a); + +/* BN_set_bit sets the |n|th, least-significant bit in |a|. For example, if |a| + * is 2 then setting bit zero will make it 3. It returns one on success or zero + * on allocation failure. */ +OPENSSL_EXPORT int BN_set_bit(BIGNUM *a, int n); + +/* BN_clear_bit clears the |n|th, least-significant bit in |a|. For example, if + * |a| is 3, clearing bit zero will make it two. It returns one on success or + * zero on allocation failure. */ +OPENSSL_EXPORT int BN_clear_bit(BIGNUM *a, int n); + +/* BN_is_bit_set returns the value of the |n|th, least-significant bit in |a|, + * or zero if the bit doesn't exist. */ +OPENSSL_EXPORT int BN_is_bit_set(const BIGNUM *a, int n); + +/* BN_mask_bits truncates |a| so that it is only |n| bits long. It returns one + * on success or zero if |n| is greater than the length of |a| already. */ +OPENSSL_EXPORT int BN_mask_bits(BIGNUM *a, int n); + + +/* Modulo arithmetic. */ + +/* BN_mod_word returns |a| mod |w|. */ +OPENSSL_EXPORT BN_ULONG BN_mod_word(const BIGNUM *a, BN_ULONG w); + +/* BN_mod is a helper macro that calls |BN_div| and discards the quotient. */ +#define BN_mod(rem, numerator, divisor, ctx) \ + BN_div(NULL, (rem), (numerator), (divisor), (ctx)) + +/* BN_nnmod is a non-negative modulo function. It acts like |BN_mod|, but 0 <= + * |rem| < |divisor| is always true. It returns one on success and zero on + * error. */ +OPENSSL_EXPORT int BN_nnmod(BIGNUM *rem, const BIGNUM *numerator, + const BIGNUM *divisor, BN_CTX *ctx); + +/* BN_mod_add sets |r| = |a| + |b| mod |m|. It returns one on success and zero + * on error. */ +OPENSSL_EXPORT int BN_mod_add(BIGNUM *r, const BIGNUM *a, const BIGNUM *b, + const BIGNUM *m, BN_CTX *ctx); + +/* BN_mod_add_quick acts like |BN_mod_add| but requires that |a| and |b| be + * non-negative and less than |m|. */ +OPENSSL_EXPORT int BN_mod_add_quick(BIGNUM *r, const BIGNUM *a, const BIGNUM *b, + const BIGNUM *m); + +/* BN_mod_sub sets |r| = |a| - |b| mod |m|. It returns one on success and zero + * on error. */ +OPENSSL_EXPORT int BN_mod_sub(BIGNUM *r, const BIGNUM *a, const BIGNUM *b, + const BIGNUM *m, BN_CTX *ctx); + +/* BN_mod_sub_quick acts like |BN_mod_sub| but requires that |a| and |b| be + * non-negative and less than |m|. */ +OPENSSL_EXPORT int BN_mod_sub_quick(BIGNUM *r, const BIGNUM *a, const BIGNUM *b, + const BIGNUM *m); + +/* BN_mod_mul sets |r| = |a|*|b| mod |m|. It returns one on success and zero + * on error. */ +OPENSSL_EXPORT int BN_mod_mul(BIGNUM *r, const BIGNUM *a, const BIGNUM *b, + const BIGNUM *m, BN_CTX *ctx); + +/* BN_mod_mul sets |r| = |a|^2 mod |m|. It returns one on success and zero + * on error. */ +OPENSSL_EXPORT int BN_mod_sqr(BIGNUM *r, const BIGNUM *a, const BIGNUM *m, + BN_CTX *ctx); + +/* BN_mod_lshift sets |r| = (|a| << n) mod |m|, where |r| and |a| may be the + * same pointer. It returns one on success and zero on error. */ +OPENSSL_EXPORT int BN_mod_lshift(BIGNUM *r, const BIGNUM *a, int n, + const BIGNUM *m, BN_CTX *ctx); + +/* BN_mod_lshift_quick acts like |BN_mod_lshift| but requires that |a| be + * non-negative and less than |m|. */ +OPENSSL_EXPORT int BN_mod_lshift_quick(BIGNUM *r, const BIGNUM *a, int n, + const BIGNUM *m); + +/* BN_mod_lshift1 sets |r| = (|a| << 1) mod |m|, where |r| and |a| may be the + * same pointer. It returns one on success and zero on error. */ +OPENSSL_EXPORT int BN_mod_lshift1(BIGNUM *r, const BIGNUM *a, const BIGNUM *m, + BN_CTX *ctx); + +/* BN_mod_lshift1_quick acts like |BN_mod_lshift1| but requires that |a| be + * non-negative and less than |m|. */ +OPENSSL_EXPORT int BN_mod_lshift1_quick(BIGNUM *r, const BIGNUM *a, + const BIGNUM *m); + +/* BN_mod_sqrt returns a |BIGNUM|, r, such that r^2 == a (mod p). */ +OPENSSL_EXPORT BIGNUM *BN_mod_sqrt(BIGNUM *in, const BIGNUM *a, const BIGNUM *p, + BN_CTX *ctx); + + +/* Random and prime number generation. */ + +/* BN_rand sets |rnd| to a random number of length |bits|. If |top| is zero, the + * most-significant bit, if any, will be set. If |top| is one, the two most + * significant bits, if any, will be set. + * + * If |top| is -1 then no extra action will be taken and |BN_num_bits(rnd)| may + * not equal |bits| if the most significant bits randomly ended up as zeros. + * + * If |bottom| is non-zero, the least-significant bit, if any, will be set. The + * function returns one on success or zero otherwise. */ +OPENSSL_EXPORT int BN_rand(BIGNUM *rnd, int bits, int top, int bottom); + +/* BN_pseudo_rand is an alias for |BN_rand|. */ +OPENSSL_EXPORT int BN_pseudo_rand(BIGNUM *rnd, int bits, int top, int bottom); + +/* BN_rand_range sets |rnd| to a random value [0..range). It returns one on + * success and zero otherwise. */ +OPENSSL_EXPORT int BN_rand_range(BIGNUM *rnd, const BIGNUM *range); + +/* BN_pseudo_rand_range is an alias for BN_rand_range. */ +OPENSSL_EXPORT int BN_pseudo_rand_range(BIGNUM *rnd, const BIGNUM *range); + +/* BN_generate_dsa_nonce generates a random number 0 <= out < range. Unlike + * BN_rand_range, it also includes the contents of |priv| and |message| in the + * generation so that an RNG failure isn't fatal as long as |priv| remains + * secret. This is intended for use in DSA and ECDSA where an RNG weakness + * leads directly to private key exposure unless this function is used. + * It returns one on success and zero on error. */ +OPENSSL_EXPORT int BN_generate_dsa_nonce(BIGNUM *out, const BIGNUM *range, + const BIGNUM *priv, + const uint8_t *message, + size_t message_len, BN_CTX *ctx); + +/* BN_GENCB holds a callback function that is used by generation functions that + * can take a very long time to complete. Use |BN_GENCB_set| to initialise a + * |BN_GENCB| structure. + * + * The callback receives the address of that |BN_GENCB| structure as its last + * argument and the user is free to put an arbitary pointer in |arg|. The other + * arguments are set as follows: + * event=BN_GENCB_GENERATED, n=i: after generating the i'th possible prime + * number. + * event=BN_GENCB_PRIME_TEST, n=-1: when finished trial division primality + * checks. + * event=BN_GENCB_PRIME_TEST, n=i: when the i'th primality test has finished. + * + * The callback can return zero to abort the generation progress or one to + * allow it to continue. + * + * When other code needs to call a BN generation function it will often take a + * BN_GENCB argument and may call the function with other argument values. */ +#define BN_GENCB_GENERATED 0 +#define BN_GENCB_PRIME_TEST 1 + +struct bn_gencb_st { + void *arg; /* callback-specific data */ + int (*callback)(int event, int n, struct bn_gencb_st *); +}; + +/* BN_GENCB_set configures |callback| to call |f| and sets |callout->arg| to + * |arg|. */ +OPENSSL_EXPORT void BN_GENCB_set(BN_GENCB *callback, + int (*f)(int event, int n, + struct bn_gencb_st *), + void *arg); + +/* BN_GENCB_call calls |callback|, if not NULL, and returns the return value of + * the callback, or 1 if |callback| is NULL. */ +OPENSSL_EXPORT int BN_GENCB_call(BN_GENCB *callback, int event, int n); + +/* BN_generate_prime_ex sets |ret| to a prime number of |bits| length. If safe + * is non-zero then the prime will be such that (ret-1)/2 is also a prime. + * (This is needed for Diffie-Hellman groups to ensure that the only subgroups + * are of size 2 and (p-1)/2.). + * + * If |add| is not NULL, the prime will fulfill the condition |ret| % |add| == + * |rem| in order to suit a given generator. (If |rem| is NULL then |ret| % + * |add| == 1.) + * + * If |cb| is not NULL, it will be called during processing to give an + * indication of progress. See the comments for |BN_GENCB|. It returns one on + * success and zero otherwise. */ +OPENSSL_EXPORT int BN_generate_prime_ex(BIGNUM *ret, int bits, int safe, + const BIGNUM *add, const BIGNUM *rem, + BN_GENCB *cb); + +/* BN_prime_checks is magic value that can be used as the |checks| argument to + * the primality testing functions in order to automatically select a number of + * Miller-Rabin checks that gives a false positive rate of ~2^{-80}. */ +#define BN_prime_checks 0 + +/* BN_primality_test sets |*is_probably_prime| to one if |candidate| is + * probably a prime number by the Miller-Rabin test or zero if it's certainly + * not. + * + * If |do_trial_division| is non-zero then |candidate| will be tested against a + * list of small primes before Miller-Rabin tests. The probability of this + * function returning a false positive is 2^{2*checks}. If |checks| is + * |BN_prime_checks| then a value that results in approximately 2^{-80} false + * positive probability is used. If |cb| is not NULL then it is called during + * the checking process. See the comment above |BN_GENCB|. + * + * The function returns one on success and zero on error. + * + * (If you are unsure whether you want |do_trial_division|, don't set it.) */ +OPENSSL_EXPORT int BN_primality_test(int *is_probably_prime, + const BIGNUM *candidate, int checks, + BN_CTX *ctx, int do_trial_division, + BN_GENCB *cb); + +/* BN_is_prime_fasttest_ex returns one if |candidate| is probably a prime + * number by the Miller-Rabin test, zero if it's certainly not and -1 on error. + * + * If |do_trial_division| is non-zero then |candidate| will be tested against a + * list of small primes before Miller-Rabin tests. The probability of this + * function returning one when |candidate| is composite is 2^{2*checks}. If + * |checks| is |BN_prime_checks| then a value that results in approximately + * 2^{-80} false positive probability is used. If |cb| is not NULL then it is + * called during the checking process. See the comment above |BN_GENCB|. + * + * WARNING: deprecated. Use |BN_primality_test|. */ +OPENSSL_EXPORT int BN_is_prime_fasttest_ex(const BIGNUM *candidate, int checks, + BN_CTX *ctx, int do_trial_division, + BN_GENCB *cb); + +/* BN_is_prime_ex acts the same as |BN_is_prime_fasttest_ex| with + * |do_trial_division| set to zero. + * + * WARNING: deprecated: Use |BN_primality_test|. */ +OPENSSL_EXPORT int BN_is_prime_ex(const BIGNUM *candidate, int checks, + BN_CTX *ctx, BN_GENCB *cb); + + +/* Number theory functions */ + +/* BN_gcd sets |r| = gcd(|a|, |b|). It returns one on success and zero + * otherwise. */ +OPENSSL_EXPORT int BN_gcd(BIGNUM *r, const BIGNUM *a, const BIGNUM *b, + BN_CTX *ctx); + +/* BN_mod_inverse sets |out| equal to |a|^-1, mod |n|. If either of |a| or |n| + * have |BN_FLG_CONSTTIME| set then the operation is performed in constant + * time. If |out| is NULL, a fresh BIGNUM is allocated. It returns the result + * or NULL on error. */ +OPENSSL_EXPORT BIGNUM *BN_mod_inverse(BIGNUM *out, const BIGNUM *a, + const BIGNUM *n, BN_CTX *ctx); + +/* BN_kronecker returns the Kronecker symbol of |a| and |b| (which is -1, 0 or + * 1), or -2 on error. */ +OPENSSL_EXPORT int BN_kronecker(const BIGNUM *a, const BIGNUM *b, BN_CTX *ctx); + + +/* Montgomery arithmetic. */ + +/* BN_MONT_CTX contains the precomputed values needed to work in a specific + * Montgomery domain. */ + +/* BN_MONT_CTX_new returns a fresh BN_MONT_CTX or NULL on allocation failure. */ +OPENSSL_EXPORT BN_MONT_CTX *BN_MONT_CTX_new(void); + +/* BN_MONT_CTX_init initialises a stack allocated |BN_MONT_CTX|. */ +OPENSSL_EXPORT void BN_MONT_CTX_init(BN_MONT_CTX *mont); + +/* BN_MONT_CTX_free frees the contexts of |mont| and, if it was originally + * allocated with |BN_MONT_CTX_new|, |mont| itself. */ +OPENSSL_EXPORT void BN_MONT_CTX_free(BN_MONT_CTX *mont); + +/* BN_MONT_CTX_copy sets |to| equal to |from|. It returns |to| on success or + * NULL on error. */ +OPENSSL_EXPORT BN_MONT_CTX *BN_MONT_CTX_copy(BN_MONT_CTX *to, + BN_MONT_CTX *from); + +/* BN_MONT_CTX_set sets up a Montgomery context given the modulus, |mod|. It + * returns one on success and zero on error. */ +OPENSSL_EXPORT int BN_MONT_CTX_set(BN_MONT_CTX *mont, const BIGNUM *mod, + BN_CTX *ctx); + +/* BN_MONT_CTX_set_locked takes |lock| and checks whether |*pmont| is NULL. If + * so, it creates a new |BN_MONT_CTX| and sets the modulus for it to |mod|. It + * then stores it as |*pmont| and returns it, or NULL on error. + * + * If |*pmont| is already non-NULL then the existing value is returned. */ +BN_MONT_CTX *BN_MONT_CTX_set_locked(BN_MONT_CTX **pmont, CRYPTO_MUTEX *lock, + const BIGNUM *mod, BN_CTX *bn_ctx); + +/* BN_to_montgomery sets |ret| equal to |a| in the Montgomery domain. It + * returns one on success and zero on error. */ +OPENSSL_EXPORT int BN_to_montgomery(BIGNUM *ret, const BIGNUM *a, + const BN_MONT_CTX *mont, BN_CTX *ctx); + +/* BN_from_montgomery sets |ret| equal to |a| * R^-1, i.e. translates values + * out of the Montgomery domain. It returns one on success or zero on error. */ +OPENSSL_EXPORT int BN_from_montgomery(BIGNUM *ret, const BIGNUM *a, + const BN_MONT_CTX *mont, BN_CTX *ctx); + +/* BN_mod_mul_montgomery set |r| equal to |a| * |b|, in the Montgomery domain. + * Both |a| and |b| must already be in the Montgomery domain (by + * |BN_to_montgomery|). It returns one on success or zero on error. */ +OPENSSL_EXPORT int BN_mod_mul_montgomery(BIGNUM *r, const BIGNUM *a, + const BIGNUM *b, + const BN_MONT_CTX *mont, BN_CTX *ctx); + + +/* Exponentiation. */ + +/* BN_exp sets |r| equal to |a|^{|p|}. It does so with a square-and-multiply + * algorithm that leaks side-channel information. It returns one on success or + * zero otherwise. */ +OPENSSL_EXPORT int BN_exp(BIGNUM *r, const BIGNUM *a, const BIGNUM *p, + BN_CTX *ctx); + +/* BN_mod_exp sets |r| equal to |a|^{|p|} mod |m|. It does so with the best + * algorithm for the values provided and can run in constant time if + * |BN_FLG_CONSTTIME| is set for |p|. It returns one on success or zero + * otherwise. */ +OPENSSL_EXPORT int BN_mod_exp(BIGNUM *r, const BIGNUM *a, const BIGNUM *p, + const BIGNUM *m, BN_CTX *ctx); + +OPENSSL_EXPORT int BN_mod_exp_mont(BIGNUM *r, const BIGNUM *a, const BIGNUM *p, + const BIGNUM *m, BN_CTX *ctx, + BN_MONT_CTX *m_ctx); + +OPENSSL_EXPORT int BN_mod_exp_mont_consttime(BIGNUM *rr, const BIGNUM *a, + const BIGNUM *p, const BIGNUM *m, + BN_CTX *ctx, BN_MONT_CTX *in_mont); + +OPENSSL_EXPORT int BN_mod_exp_mont_word(BIGNUM *r, BN_ULONG a, const BIGNUM *p, + const BIGNUM *m, BN_CTX *ctx, + BN_MONT_CTX *m_ctx); +OPENSSL_EXPORT int BN_mod_exp2_mont(BIGNUM *r, const BIGNUM *a1, + const BIGNUM *p1, const BIGNUM *a2, + const BIGNUM *p2, const BIGNUM *m, + BN_CTX *ctx, BN_MONT_CTX *m_ctx); + + +/* Private functions */ + +struct bignum_st { + BN_ULONG *d; /* Pointer to an array of 'BN_BITS2' bit chunks in little-endian + order. */ + int top; /* Index of last used element in |d|, plus one. */ + int dmax; /* Size of |d|, in words. */ + int neg; /* one if the number is negative */ + int flags; /* bitmask of BN_FLG_* values */ +}; + +struct bn_mont_ctx_st { + BIGNUM RR; /* used to convert to montgomery form */ + BIGNUM N; /* The modulus */ + BIGNUM Ni; /* R*(1/R mod N) - N*Ni = 1 + * (Ni is only stored for bignum algorithm) */ + BN_ULONG n0[2]; /* least significant word(s) of Ni; + (type changed with 0.9.9, was "BN_ULONG n0;" before) */ + int flags; + int ri; /* number of bits in R */ +}; + +OPENSSL_EXPORT unsigned BN_num_bits_word(BN_ULONG l); + +#define BN_FLG_MALLOCED 0x01 +#define BN_FLG_STATIC_DATA 0x02 +/* avoid leaking exponent information through timing, BN_mod_exp_mont() will + * call BN_mod_exp_mont_consttime, BN_div() will call BN_div_no_branch, + * BN_mod_inverse() will call BN_mod_inverse_no_branch. */ +#define BN_FLG_CONSTTIME 0x04 + + +/* Android compatibility section. + * + * These functions are declared, temporarily, for Android because + * wpa_supplicant will take a little time to sync with upstream. Outside of + * Android they'll have no definition. */ + +OPENSSL_EXPORT BIGNUM *get_rfc3526_prime_1536(BIGNUM *bn); + + +#if defined(__cplusplus) +} /* extern C */ +#endif + +#define BN_F_BN_CTX_get 100 +#define BN_F_BN_CTX_new 101 +#define BN_F_BN_CTX_start 102 +#define BN_F_BN_bn2dec 103 +#define BN_F_BN_bn2hex 104 +#define BN_F_BN_div 105 +#define BN_F_BN_div_recp 106 +#define BN_F_BN_exp 107 +#define BN_F_BN_generate_dsa_nonce 108 +#define BN_F_BN_generate_prime_ex 109 +#define BN_F_BN_mod_exp2_mont 110 +#define BN_F_BN_mod_exp_mont 111 +#define BN_F_BN_mod_exp_mont_consttime 112 +#define BN_F_BN_mod_exp_mont_word 113 +#define BN_F_BN_mod_inverse 114 +#define BN_F_BN_mod_inverse_no_branch 115 +#define BN_F_BN_mod_lshift_quick 116 +#define BN_F_BN_mod_sqrt 117 +#define BN_F_BN_new 118 +#define BN_F_BN_rand 119 +#define BN_F_BN_rand_range 120 +#define BN_F_BN_sqrt 121 +#define BN_F_BN_usub 122 +#define BN_F_bn_wexpand 123 +#define BN_F_mod_exp_recp 124 +#define BN_F_BN_lshift 125 +#define BN_F_BN_rshift 126 +#define BN_R_ARG2_LT_ARG3 100 +#define BN_R_BAD_RECIPROCAL 101 +#define BN_R_BIGNUM_TOO_LONG 102 +#define BN_R_BITS_TOO_SMALL 103 +#define BN_R_CALLED_WITH_EVEN_MODULUS 104 +#define BN_R_DIV_BY_ZERO 105 +#define BN_R_EXPAND_ON_STATIC_BIGNUM_DATA 106 +#define BN_R_INPUT_NOT_REDUCED 107 +#define BN_R_INVALID_RANGE 108 +#define BN_R_NEGATIVE_NUMBER 109 +#define BN_R_NOT_A_SQUARE 110 +#define BN_R_NOT_INITIALIZED 111 +#define BN_R_NO_INVERSE 112 +#define BN_R_PRIVATE_KEY_TOO_LARGE 113 +#define BN_R_P_IS_NOT_PRIME 114 +#define BN_R_TOO_MANY_ITERATIONS 115 +#define BN_R_TOO_MANY_TEMPORARY_VARIABLES 116 + +#endif /* OPENSSL_HEADER_BN_H */ diff --git a/phonelibs/boringssl/include/openssl/buf.h b/phonelibs/boringssl/include/openssl/buf.h new file mode 100644 index 00000000000000..2b36ce40585c33 --- /dev/null +++ b/phonelibs/boringssl/include/openssl/buf.h @@ -0,0 +1,123 @@ +/* Copyright (C) 1995-1998 Eric Young (eay@cryptsoft.com) + * All rights reserved. + * + * This package is an SSL implementation written + * by Eric Young (eay@cryptsoft.com). + * The implementation was written so as to conform with Netscapes SSL. + * + * This library is free for commercial and non-commercial use as long as + * the following conditions are aheared to. The following conditions + * apply to all code found in this distribution, be it the RC4, RSA, + * lhash, DES, etc., code; not just the SSL code. The SSL documentation + * included with this distribution is covered by the same copyright terms + * except that the holder is Tim Hudson (tjh@cryptsoft.com). + * + * Copyright remains Eric Young's, and as such any Copyright notices in + * the code are not to be removed. + * If this package is used in a product, Eric Young should be given attribution + * as the author of the parts of the library used. + * This can be in the form of a textual message at program startup or + * in documentation (online or textual) provided with the package. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must 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. All advertising materials mentioning features or use of this software + * must display the following acknowledgement: + * "This product includes cryptographic software written by + * Eric Young (eay@cryptsoft.com)" + * The word 'cryptographic' can be left out if the rouines from the library + * being used are not cryptographic related :-). + * 4. If you include any Windows specific code (or a derivative thereof) from + * the apps directory (application code) you must include an acknowledgement: + * "This product includes software written by Tim Hudson (tjh@cryptsoft.com)" + * + * THIS SOFTWARE IS PROVIDED BY ERIC YOUNG ``AS IS'' AND + * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHOR OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (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 licence and distribution terms for any publically available version or + * derivative of this code cannot be changed. i.e. this code cannot simply be + * copied and put under another distribution licence + * [including the GNU Public Licence.] */ + +#ifndef OPENSSL_HEADER_BUFFER_H +#define OPENSSL_HEADER_BUFFER_H + +#include + +#if defined(__cplusplus) +extern "C" { +#endif + + +/* Memory and string functions, see also mem.h. */ + + +/* BUF_MEM is a generic buffer object used by OpenSSL. */ +struct buf_mem_st { + size_t length; /* current number of bytes */ + char *data; + size_t max; /* size of buffer */ +}; + +/* BUF_MEM_new creates a new BUF_MEM which has no allocated data buffer. */ +OPENSSL_EXPORT BUF_MEM *BUF_MEM_new(void); + +/* BUF_MEM_free frees |buf->data| if needed and then frees |buf| itself. */ +OPENSSL_EXPORT void BUF_MEM_free(BUF_MEM *buf); + +/* BUF_MEM_grow ensures that |buf| has length |len| and allocates memory if + * needed. If the length of |buf| increased, the new bytes are filled with + * zeros. It returns the length of |buf|, or zero if there's an error. */ +OPENSSL_EXPORT size_t BUF_MEM_grow(BUF_MEM *buf, size_t len); + +/* BUF_MEM_grow_clean acts the same as |BUF_MEM_grow|, but clears the previous + * contents of memory if reallocing. */ +OPENSSL_EXPORT size_t BUF_MEM_grow_clean(BUF_MEM *str, size_t len); + +/* BUF_strdup returns an allocated, duplicate of |str|. */ +OPENSSL_EXPORT char *BUF_strdup(const char *str); + +/* BUF_strnlen returns the number of characters in |str|, excluding the NUL + * byte, but at most |max_len|. This function never reads more than |max_len| + * bytes from |str|. */ +OPENSSL_EXPORT size_t BUF_strnlen(const char *str, size_t max_len); + +/* BUF_strndup returns an allocated, duplicate of |str|, which is, at most, + * |size| bytes. The result is always NUL terminated. */ +OPENSSL_EXPORT char *BUF_strndup(const char *str, size_t size); + +/* BUF_memdup returns an allocated, duplicate of |size| bytes from |data|. */ +OPENSSL_EXPORT void *BUF_memdup(const void *data, size_t size); + +/* BUF_strlcpy acts like strlcpy(3). */ +OPENSSL_EXPORT size_t BUF_strlcpy(char *dst, const char *src, size_t dst_size); + +/* BUF_strlcat acts like strlcat(3). */ +OPENSSL_EXPORT size_t BUF_strlcat(char *dst, const char *src, size_t size); + + +#if defined(__cplusplus) +} /* extern C */ +#endif + +#define BUF_F_BUF_MEM_new 100 +#define BUF_F_BUF_memdup 101 +#define BUF_F_BUF_strndup 102 +#define BUF_F_buf_mem_grow 103 + +#endif /* OPENSSL_HEADER_BUFFER_H */ diff --git a/phonelibs/boringssl/include/openssl/buffer.h b/phonelibs/boringssl/include/openssl/buffer.h new file mode 100644 index 00000000000000..c6b721c277b4a9 --- /dev/null +++ b/phonelibs/boringssl/include/openssl/buffer.h @@ -0,0 +1,18 @@ +/* Copyright (c) 2015, Google Inc. + * + * Permission to use, copy, modify, and/or distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY + * SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN ACTION + * OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF OR IN + * CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. */ + +/* This header is provided in order to make compiling against code that expects + OpenSSL easier. */ + +#include "buf.h" diff --git a/phonelibs/boringssl/include/openssl/bytestring.h b/phonelibs/boringssl/include/openssl/bytestring.h new file mode 100644 index 00000000000000..9963426ca3f1db --- /dev/null +++ b/phonelibs/boringssl/include/openssl/bytestring.h @@ -0,0 +1,325 @@ +/* Copyright (c) 2014, Google Inc. + * + * Permission to use, copy, modify, and/or distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY + * SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN ACTION + * OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF OR IN + * CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. */ + +#ifndef OPENSSL_HEADER_BYTESTRING_H +#define OPENSSL_HEADER_BYTESTRING_H + +#include + +#if defined(__cplusplus) +extern "C" { +#endif + + +/* Bytestrings are used for parsing and building TLS and ASN.1 messages. + * + * A "CBS" (CRYPTO ByteString) represents a string of bytes in memory and + * provides utility functions for safely parsing length-prefixed structures + * like TLS and ASN.1 from it. + * + * A "CBB" (CRYPTO ByteBuilder) is a memory buffer that grows as needed and + * provides utility functions for building length-prefixed messages. */ + + +/* CRYPTO ByteString */ + +struct cbs_st { + const uint8_t *data; + size_t len; +}; + +/* CBS_init sets |cbs| to point to |data|. It does not take ownership of + * |data|. */ +OPENSSL_EXPORT void CBS_init(CBS *cbs, const uint8_t *data, size_t len); + +/* CBS_skip advances |cbs| by |len| bytes. It returns one on success and zero + * otherwise. */ +OPENSSL_EXPORT int CBS_skip(CBS *cbs, size_t len); + +/* CBS_data returns a pointer to the contents of |cbs|. */ +OPENSSL_EXPORT const uint8_t *CBS_data(const CBS *cbs); + +/* CBS_len returns the number of bytes remaining in |cbs|. */ +OPENSSL_EXPORT size_t CBS_len(const CBS *cbs); + +/* CBS_stow copies the current contents of |cbs| into |*out_ptr| and + * |*out_len|. If |*out_ptr| is not NULL, the contents are freed with + * OPENSSL_free. It returns one on success and zero on allocation failure. On + * success, |*out_ptr| should be freed with OPENSSL_free. If |cbs| is empty, + * |*out_ptr| will be NULL. */ +OPENSSL_EXPORT int CBS_stow(const CBS *cbs, uint8_t **out_ptr, size_t *out_len); + +/* CBS_strdup copies the current contents of |cbs| into |*out_ptr| as a + * NUL-terminated C string. If |*out_ptr| is not NULL, the contents are freed + * with OPENSSL_free. It returns one on success and zero on allocation + * failure. On success, |*out_ptr| should be freed with OPENSSL_free. + * + * NOTE: If |cbs| contains NUL bytes, the string will be truncated. Call + * |CBS_contains_zero_byte(cbs)| to check for NUL bytes. */ +OPENSSL_EXPORT int CBS_strdup(const CBS *cbs, char **out_ptr); + +/* CBS_contains_zero_byte returns one if the current contents of |cbs| contains + * a NUL byte and zero otherwise. */ +OPENSSL_EXPORT int CBS_contains_zero_byte(const CBS *cbs); + +/* CBS_mem_equal compares the current contents of |cbs| with the |len| bytes + * starting at |data|. If they're equal, it returns one, otherwise zero. If the + * lengths match, it uses a constant-time comparison. */ +OPENSSL_EXPORT int CBS_mem_equal(const CBS *cbs, const uint8_t *data, + size_t len); + +/* CBS_get_u8 sets |*out| to the next uint8_t from |cbs| and advances |cbs|. It + * returns one on success and zero on error. */ +OPENSSL_EXPORT int CBS_get_u8(CBS *cbs, uint8_t *out); + +/* CBS_get_u16 sets |*out| to the next, big-endian uint16_t from |cbs| and + * advances |cbs|. It returns one on success and zero on error. */ +OPENSSL_EXPORT int CBS_get_u16(CBS *cbs, uint16_t *out); + +/* CBS_get_u24 sets |*out| to the next, big-endian 24-bit value from |cbs| and + * advances |cbs|. It returns one on success and zero on error. */ +OPENSSL_EXPORT int CBS_get_u24(CBS *cbs, uint32_t *out); + +/* CBS_get_u32 sets |*out| to the next, big-endian uint32_t value from |cbs| + * and advances |cbs|. It returns one on success and zero on error. */ +OPENSSL_EXPORT int CBS_get_u32(CBS *cbs, uint32_t *out); + +/* CBS_get_bytes sets |*out| to the next |len| bytes from |cbs| and advances + * |cbs|. It returns one on success and zero on error. */ +OPENSSL_EXPORT int CBS_get_bytes(CBS *cbs, CBS *out, size_t len); + +/* CBS_get_u8_length_prefixed sets |*out| to the contents of an 8-bit, + * length-prefixed value from |cbs| and advances |cbs| over it. It returns one + * on success and zero on error. */ +OPENSSL_EXPORT int CBS_get_u8_length_prefixed(CBS *cbs, CBS *out); + +/* CBS_get_u16_length_prefixed sets |*out| to the contents of a 16-bit, + * big-endian, length-prefixed value from |cbs| and advances |cbs| over it. It + * returns one on success and zero on error. */ +OPENSSL_EXPORT int CBS_get_u16_length_prefixed(CBS *cbs, CBS *out); + +/* CBS_get_u24_length_prefixed sets |*out| to the contents of a 24-bit, + * big-endian, length-prefixed value from |cbs| and advances |cbs| over it. It + * returns one on success and zero on error. */ +OPENSSL_EXPORT int CBS_get_u24_length_prefixed(CBS *cbs, CBS *out); + + +/* Parsing ASN.1 */ + +#define CBS_ASN1_BOOLEAN 0x1 +#define CBS_ASN1_INTEGER 0x2 +#define CBS_ASN1_BITSTRING 0x3 +#define CBS_ASN1_OCTETSTRING 0x4 +#define CBS_ASN1_OBJECT 0x6 +#define CBS_ASN1_ENUMERATED 0xa +#define CBS_ASN1_SEQUENCE (0x10 | CBS_ASN1_CONSTRUCTED) +#define CBS_ASN1_SET (0x11 | CBS_ASN1_CONSTRUCTED) + +#define CBS_ASN1_CONSTRUCTED 0x20 +#define CBS_ASN1_CONTEXT_SPECIFIC 0x80 + +/* CBS_get_asn1 sets |*out| to the contents of DER-encoded, ASN.1 element (not + * including tag and length bytes) and advances |cbs| over it. The ASN.1 + * element must match |tag_value|. It returns one on success and zero + * on error. + * + * Tag numbers greater than 30 are not supported (i.e. short form only). */ +OPENSSL_EXPORT int CBS_get_asn1(CBS *cbs, CBS *out, unsigned tag_value); + +/* CBS_get_asn1_element acts like |CBS_get_asn1| but |out| will include the + * ASN.1 header bytes too. */ +OPENSSL_EXPORT int CBS_get_asn1_element(CBS *cbs, CBS *out, unsigned tag_value); + +/* CBS_peek_asn1_tag looks ahead at the next ASN.1 tag and returns one + * if the next ASN.1 element on |cbs| would have tag |tag_value|. If + * |cbs| is empty or the tag does not match, it returns zero. Note: if + * it returns one, CBS_get_asn1 may still fail if the rest of the + * element is malformed. */ +OPENSSL_EXPORT int CBS_peek_asn1_tag(const CBS *cbs, unsigned tag_value); + +/* CBS_get_any_asn1_element sets |*out| to contain the next ASN.1 element from + * |*cbs| (including header bytes) and advances |*cbs|. It sets |*out_tag| to + * the tag number and |*out_header_len| to the length of the ASN.1 header. Each + * of |out|, |out_tag|, and |out_header_len| may be NULL to ignore the value. + * + * Tag numbers greater than 30 are not supported (i.e. short form only). */ +OPENSSL_EXPORT int CBS_get_any_asn1_element(CBS *cbs, CBS *out, + unsigned *out_tag, + size_t *out_header_len); + +/* CBS_get_asn1_uint64 gets an ASN.1 INTEGER from |cbs| using |CBS_get_asn1| + * and sets |*out| to its value. It returns one on success and zero on error, + * where error includes the integer being negative, or too large to represent + * in 64 bits. */ +OPENSSL_EXPORT int CBS_get_asn1_uint64(CBS *cbs, uint64_t *out); + +/* CBS_get_optional_asn1 gets an optional explicitly-tagged element + * from |cbs| tagged with |tag| and sets |*out| to its contents. If + * present, it sets |*out_present| to one, otherwise zero. It returns + * one on success, whether or not the element was present, and zero on + * decode failure. */ +OPENSSL_EXPORT int CBS_get_optional_asn1(CBS *cbs, CBS *out, int *out_present, + unsigned tag); + +/* CBS_get_optional_asn1_octet_string gets an optional + * explicitly-tagged OCTET STRING from |cbs|. If present, it sets + * |*out| to the string and |*out_present| to one. Otherwise, it sets + * |*out| to empty and |*out_present| to zero. |out_present| may be + * NULL. It returns one on success, whether or not the element was + * present, and zero on decode failure. */ +OPENSSL_EXPORT int CBS_get_optional_asn1_octet_string(CBS *cbs, CBS *out, + int *out_present, + unsigned tag); + +/* CBS_get_optional_asn1_uint64 gets an optional explicitly-tagged + * INTEGER from |cbs|. If present, it sets |*out| to the + * value. Otherwise, it sets |*out| to |default_value|. It returns one + * on success, whether or not the element was present, and zero on + * decode failure. */ +OPENSSL_EXPORT int CBS_get_optional_asn1_uint64(CBS *cbs, uint64_t *out, + unsigned tag, + uint64_t default_value); + +/* CBS_get_optional_asn1_bool gets an optional, explicitly-tagged BOOLEAN from + * |cbs|. If present, it sets |*out| to either zero or one, based on the + * boolean. Otherwise, it sets |*out| to |default_value|. It returns one on + * success, whether or not the element was present, and zero on decode + * failure. */ +OPENSSL_EXPORT int CBS_get_optional_asn1_bool(CBS *cbs, int *out, unsigned tag, + int default_value); + + +/* CRYPTO ByteBuilder. + * + * |CBB| objects allow one to build length-prefixed serialisations. A |CBB| + * object is associated with a buffer and new buffers are created with + * |CBB_init|. Several |CBB| objects can point at the same buffer when a + * length-prefix is pending, however only a single |CBB| can be 'current' at + * any one time. For example, if one calls |CBB_add_u8_length_prefixed| then + * the new |CBB| points at the same buffer as the original. But if the original + * |CBB| is used then the length prefix is written out and the new |CBB| must + * not be used again. + * + * If one needs to force a length prefix to be written out because a |CBB| is + * going out of scope, use |CBB_flush|. */ + +struct cbb_buffer_st { + uint8_t *buf; + size_t len; /* The number of valid bytes. */ + size_t cap; /* The size of buf. */ + char can_resize; /* One iff |buf| is owned by this object. If not then |buf| + cannot be resized. */ +}; + +struct cbb_st { + struct cbb_buffer_st *base; + /* offset is the offset from the start of |base->buf| to the position of any + * pending length-prefix. */ + size_t offset; + /* child points to a child CBB if a length-prefix is pending. */ + struct cbb_st *child; + /* pending_len_len contains the number of bytes in a pending length-prefix, + * or zero if no length-prefix is pending. */ + uint8_t pending_len_len; + char pending_is_asn1; + /* is_top_level is true iff this is a top-level |CBB| (as opposed to a child + * |CBB|). Top-level objects are valid arguments for |CBB_finish|. */ + char is_top_level; +}; + +/* CBB_init initialises |cbb| with |initial_capacity|. Since a |CBB| grows as + * needed, the |initial_capacity| is just a hint. It returns one on success or + * zero on error. */ +OPENSSL_EXPORT int CBB_init(CBB *cbb, size_t initial_capacity); + +/* CBB_init_fixed initialises |cbb| to write to |len| bytes at |buf|. Since + * |buf| cannot grow, trying to write more than |len| bytes will cause CBB + * functions to fail. It returns one on success or zero on error. */ +OPENSSL_EXPORT int CBB_init_fixed(CBB *cbb, uint8_t *buf, size_t len); + +/* CBB_cleanup frees all resources owned by |cbb| and other |CBB| objects + * writing to the same buffer. This should be used in an error case where a + * serialisation is abandoned. */ +OPENSSL_EXPORT void CBB_cleanup(CBB *cbb); + +/* CBB_finish completes any pending length prefix and sets |*out_data| to a + * malloced buffer and |*out_len| to the length of that buffer. The caller + * takes ownership of the buffer and, unless the buffer was fixed with + * |CBB_init_fixed|, must call |OPENSSL_free| when done. + * + * It can only be called on a "top level" |CBB|, i.e. one initialised with + * |CBB_init| or |CBB_init_fixed|. It returns one on success and zero on + * error. */ +OPENSSL_EXPORT int CBB_finish(CBB *cbb, uint8_t **out_data, size_t *out_len); + +/* CBB_flush causes any pending length prefixes to be written out and any child + * |CBB| objects of |cbb| to be invalidated. It returns one on success or zero + * on error. */ +OPENSSL_EXPORT int CBB_flush(CBB *cbb); + +/* CBB_add_u8_length_prefixed sets |*out_contents| to a new child of |cbb|. The + * data written to |*out_contents| will be prefixed in |cbb| with an 8-bit + * length. It returns one on success or zero on error. */ +OPENSSL_EXPORT int CBB_add_u8_length_prefixed(CBB *cbb, CBB *out_contents); + +/* CBB_add_u16_length_prefixed sets |*out_contents| to a new child of |cbb|. + * The data written to |*out_contents| will be prefixed in |cbb| with a 16-bit, + * big-endian length. It returns one on success or zero on error. */ +OPENSSL_EXPORT int CBB_add_u16_length_prefixed(CBB *cbb, CBB *out_contents); + +/* CBB_add_u24_length_prefixed sets |*out_contents| to a new child of |cbb|. + * The data written to |*out_contents| will be prefixed in |cbb| with a 24-bit, + * big-endian length. It returns one on success or zero on error. */ +OPENSSL_EXPORT int CBB_add_u24_length_prefixed(CBB *cbb, CBB *out_contents); + +/* CBB_add_asn sets |*out_contents| to a |CBB| into which the contents of an + * ASN.1 object can be written. The |tag| argument will be used as the tag for + * the object. Passing in |tag| number 31 will return in an error since only + * single octet identifiers are supported. It returns one on success or zero + * on error. */ +OPENSSL_EXPORT int CBB_add_asn1(CBB *cbb, CBB *out_contents, uint8_t tag); + +/* CBB_add_bytes appends |len| bytes from |data| to |cbb|. It returns one on + * success and zero otherwise. */ +OPENSSL_EXPORT int CBB_add_bytes(CBB *cbb, const uint8_t *data, size_t len); + +/* CBB_add_space appends |len| bytes to |cbb| and sets |*out_data| to point to + * the beginning of that space. The caller must then write |len| bytes of + * actual contents to |*out_data|. It returns one on success and zero + * otherwise. */ +OPENSSL_EXPORT int CBB_add_space(CBB *cbb, uint8_t **out_data, size_t len); + +/* CBB_add_u8 appends an 8-bit number from |value| to |cbb|. It returns one on + * success and zero otherwise. */ +OPENSSL_EXPORT int CBB_add_u8(CBB *cbb, uint8_t value); + +/* CBB_add_u8 appends a 16-bit, big-endian number from |value| to |cbb|. It + * returns one on success and zero otherwise. */ +OPENSSL_EXPORT int CBB_add_u16(CBB *cbb, uint16_t value); + +/* CBB_add_u24 appends a 24-bit, big-endian number from |value| to |cbb|. It + * returns one on success and zero otherwise. */ +OPENSSL_EXPORT int CBB_add_u24(CBB *cbb, uint32_t value); + +/* CBB_add_asn1_uint64 writes an ASN.1 INTEGER into |cbb| using |CBB_add_asn1| + * and writes |value| in its contents. It returns one on success and zero on + * error. */ +OPENSSL_EXPORT int CBB_add_asn1_uint64(CBB *cbb, uint64_t value); + + +#if defined(__cplusplus) +} /* extern C */ +#endif + +#endif /* OPENSSL_HEADER_BYTESTRING_H */ diff --git a/phonelibs/boringssl/include/openssl/cast.h b/phonelibs/boringssl/include/openssl/cast.h new file mode 100644 index 00000000000000..802172394e5b12 --- /dev/null +++ b/phonelibs/boringssl/include/openssl/cast.h @@ -0,0 +1,96 @@ +/* Copyright (C) 1995-1998 Eric Young (eay@cryptsoft.com) + * All rights reserved. + * + * This package is an SSL implementation written + * by Eric Young (eay@cryptsoft.com). + * The implementation was written so as to conform with Netscapes SSL. + * + * This library is free for commercial and non-commercial use as long as + * the following conditions are aheared to. The following conditions + * apply to all code found in this distribution, be it the RC4, RSA, + * lhash, DES, etc., code; not just the SSL code. The SSL documentation + * included with this distribution is covered by the same copyright terms + * except that the holder is Tim Hudson (tjh@cryptsoft.com). + * + * Copyright remains Eric Young's, and as such any Copyright notices in + * the code are not to be removed. + * If this package is used in a product, Eric Young should be given attribution + * as the author of the parts of the library used. + * This can be in the form of a textual message at program startup or + * in documentation (online or textual) provided with the package. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must 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. All advertising materials mentioning features or use of this software + * must display the following acknowledgement: + * "This product includes cryptographic software written by + * Eric Young (eay@cryptsoft.com)" + * The word 'cryptographic' can be left out if the rouines from the library + * being used are not cryptographic related :-). + * 4. If you include any Windows specific code (or a derivative thereof) from + * the apps directory (application code) you must include an acknowledgement: + * "This product includes software written by Tim Hudson (tjh@cryptsoft.com)" + * + * THIS SOFTWARE IS PROVIDED BY ERIC YOUNG ``AS IS'' AND + * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHOR OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (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 licence and distribution terms for any publically available version or + * derivative of this code cannot be changed. i.e. this code cannot simply be + * copied and put under another distribution licence + * [including the GNU Public Licence.] */ + +#ifndef OPENSSL_HEADER_CAST_H +#define OPENSSL_HEADER_CAST_H + +#include + +#ifdef __cplusplus +extern "C" { +#endif + + +#define CAST_ENCRYPT 1 +#define CAST_DECRYPT 0 + +#define CAST_BLOCK 8 +#define CAST_KEY_LENGTH 16 + +typedef struct cast_key_st { + uint32_t data[32]; + int short_key; /* Use reduced rounds for short key */ +} CAST_KEY; + +OPENSSL_EXPORT void CAST_set_key(CAST_KEY *key, size_t len, + const uint8_t *data); +OPENSSL_EXPORT void CAST_ecb_encrypt(const uint8_t *in, uint8_t *out, + const CAST_KEY *key, int enc); +OPENSSL_EXPORT void CAST_encrypt(uint32_t *data, const CAST_KEY *key); +OPENSSL_EXPORT void CAST_decrypt(uint32_t *data, const CAST_KEY *key); +OPENSSL_EXPORT void CAST_cbc_encrypt(const uint8_t *in, uint8_t *out, + long length, const CAST_KEY *ks, + uint8_t *iv, int enc); + +OPENSSL_EXPORT void CAST_cfb64_encrypt(const uint8_t *in, uint8_t *out, + long length, const CAST_KEY *schedule, + uint8_t *ivec, int *num, int enc); + +#ifdef __cplusplus +} +#endif + +#endif /* OPENSSL_HEADER_CAST_H */ diff --git a/phonelibs/boringssl/include/openssl/chacha.h b/phonelibs/boringssl/include/openssl/chacha.h new file mode 100644 index 00000000000000..ce53d49fdaefed --- /dev/null +++ b/phonelibs/boringssl/include/openssl/chacha.h @@ -0,0 +1,37 @@ +/* Copyright (c) 2014, Google Inc. + * + * Permission to use, copy, modify, and/or distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY + * SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN ACTION + * OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF OR IN + * CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. */ + +#ifndef OPENSSL_HEADER_CHACHA_H +#define OPENSSL_HEADER_CHACHA_H + +#include + +#ifdef __cplusplus +extern "C" { +#endif + + +/* CRYPTO_chacha_20 encrypts |in_len| bytes from |in| with the given key and + * nonce and writes the result to |out|, which may be equal to |in|. The + * initial block counter is specified by |counter|. */ +void CRYPTO_chacha_20(uint8_t *out, const uint8_t *in, + size_t in_len, const uint8_t key[32], + const uint8_t nonce[8], size_t counter); + + +#if defined(__cplusplus) +} /* extern C */ +#endif + +#endif /* OPENSSL_HEADER_CHACHA_H */ diff --git a/phonelibs/boringssl/include/openssl/cipher.h b/phonelibs/boringssl/include/openssl/cipher.h new file mode 100644 index 00000000000000..3e496f15b50e9a --- /dev/null +++ b/phonelibs/boringssl/include/openssl/cipher.h @@ -0,0 +1,598 @@ +/* Copyright (C) 1995-1998 Eric Young (eay@cryptsoft.com) + * All rights reserved. + * + * This package is an SSL implementation written + * by Eric Young (eay@cryptsoft.com). + * The implementation was written so as to conform with Netscapes SSL. + * + * This library is free for commercial and non-commercial use as long as + * the following conditions are aheared to. The following conditions + * apply to all code found in this distribution, be it the RC4, RSA, + * lhash, DES, etc., code; not just the SSL code. The SSL documentation + * included with this distribution is covered by the same copyright terms + * except that the holder is Tim Hudson (tjh@cryptsoft.com). + * + * Copyright remains Eric Young's, and as such any Copyright notices in + * the code are not to be removed. + * If this package is used in a product, Eric Young should be given attribution + * as the author of the parts of the library used. + * This can be in the form of a textual message at program startup or + * in documentation (online or textual) provided with the package. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must 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. All advertising materials mentioning features or use of this software + * must display the following acknowledgement: + * "This product includes cryptographic software written by + * Eric Young (eay@cryptsoft.com)" + * The word 'cryptographic' can be left out if the rouines from the library + * being used are not cryptographic related :-). + * 4. If you include any Windows specific code (or a derivative thereof) from + * the apps directory (application code) you must include an acknowledgement: + * "This product includes software written by Tim Hudson (tjh@cryptsoft.com)" + * + * THIS SOFTWARE IS PROVIDED BY ERIC YOUNG ``AS IS'' AND + * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHOR OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (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 licence and distribution terms for any publically available version or + * derivative of this code cannot be changed. i.e. this code cannot simply be + * copied and put under another distribution licence + * [including the GNU Public Licence.] */ + +#ifndef OPENSSL_HEADER_CIPHER_H +#define OPENSSL_HEADER_CIPHER_H + +#include + +#if defined(__cplusplus) +extern "C" { +#endif + + +/* Ciphers. */ + + +/* Cipher primitives. + * + * The following functions return |EVP_CIPHER| objects that implement the named + * cipher algorithm. */ + +OPENSSL_EXPORT const EVP_CIPHER *EVP_rc4(void); + +OPENSSL_EXPORT const EVP_CIPHER *EVP_des_cbc(void); +OPENSSL_EXPORT const EVP_CIPHER *EVP_des_ecb(void); +OPENSSL_EXPORT const EVP_CIPHER *EVP_des_ede3_cbc(void); + +OPENSSL_EXPORT const EVP_CIPHER *EVP_aes_128_ecb(void); +OPENSSL_EXPORT const EVP_CIPHER *EVP_aes_128_cbc(void); +OPENSSL_EXPORT const EVP_CIPHER *EVP_aes_128_ctr(void); +OPENSSL_EXPORT const EVP_CIPHER *EVP_aes_128_ofb(void); + +OPENSSL_EXPORT const EVP_CIPHER *EVP_aes_256_ecb(void); +OPENSSL_EXPORT const EVP_CIPHER *EVP_aes_256_cbc(void); +OPENSSL_EXPORT const EVP_CIPHER *EVP_aes_256_ctr(void); +OPENSSL_EXPORT const EVP_CIPHER *EVP_aes_256_ofb(void); + +/* Deprecated AES-GCM implementations that set |EVP_CIPH_FLAG_CUSTOM_CIPHER|. + * Use |EVP_aead_aes_128_gcm| and |EVP_aead_aes_256_gcm| instead. */ +OPENSSL_EXPORT const EVP_CIPHER *EVP_aes_128_gcm(void); +OPENSSL_EXPORT const EVP_CIPHER *EVP_aes_256_gcm(void); + +/* Deprecated 192-bit version of AES. */ +OPENSSL_EXPORT const EVP_CIPHER *EVP_aes_192_ecb(void); +OPENSSL_EXPORT const EVP_CIPHER *EVP_aes_192_cbc(void); +OPENSSL_EXPORT const EVP_CIPHER *EVP_aes_192_ctr(void); +OPENSSL_EXPORT const EVP_CIPHER *EVP_aes_192_gcm(void); + +/* EVP_enc_null returns a 'cipher' that passes plaintext through as + * ciphertext. */ +OPENSSL_EXPORT const EVP_CIPHER *EVP_enc_null(void); + +/* EVP_rc2_40_cbc returns a cipher that implements 40-bit RC2 in CBC mode. This + * is obviously very, very weak and is included only in order to read PKCS#12 + * files, which often encrypt the certificate chain using this cipher. It is + * deliberately not exported. */ +const EVP_CIPHER *EVP_rc2_40_cbc(void); + +/* EVP_get_cipherbynid returns the cipher corresponding to the given NID, or + * NULL if no such cipher is known. */ +OPENSSL_EXPORT const EVP_CIPHER *EVP_get_cipherbynid(int nid); + + +/* Cipher context allocation. + * + * An |EVP_CIPHER_CTX| represents the state of an encryption or decryption in + * progress. */ + +/* EVP_CIPHER_CTX_init initialises an, already allocated, |EVP_CIPHER_CTX|. */ +OPENSSL_EXPORT void EVP_CIPHER_CTX_init(EVP_CIPHER_CTX *ctx); + +/* EVP_CIPHER_CTX_new allocates a fresh |EVP_CIPHER_CTX|, calls + * |EVP_CIPHER_CTX_init| and returns it, or NULL on allocation failure. */ +OPENSSL_EXPORT EVP_CIPHER_CTX *EVP_CIPHER_CTX_new(void); + +/* EVP_CIPHER_CTX_cleanup frees any memory referenced by |ctx|. It returns + * one. */ +OPENSSL_EXPORT int EVP_CIPHER_CTX_cleanup(EVP_CIPHER_CTX *ctx); + +/* EVP_CIPHER_CTX_free calls |EVP_CIPHER_CTX_cleanup| on |ctx| and then frees + * |ctx| itself. */ +OPENSSL_EXPORT void EVP_CIPHER_CTX_free(EVP_CIPHER_CTX *ctx); + +/* EVP_CIPHER_CTX_copy sets |out| to be a duplicate of the current state of + * |in|. The |out| argument must have been previously initialised. */ +OPENSSL_EXPORT int EVP_CIPHER_CTX_copy(EVP_CIPHER_CTX *out, + const EVP_CIPHER_CTX *in); + + +/* Cipher context configuration. */ + +/* EVP_CipherInit_ex configures |ctx| for a fresh encryption (or decryption, if + * |enc| is zero) operation using |cipher|. If |ctx| has been previously + * configured with a cipher then |cipher|, |key| and |iv| may be |NULL| and + * |enc| may be -1 to reuse the previous values. The operation will use |key| + * as the key and |iv| as the IV (if any). These should have the correct + * lengths given by |EVP_CIPHER_key_length| and |EVP_CIPHER_iv_length|. It + * returns one on success and zero on error. */ +OPENSSL_EXPORT int EVP_CipherInit_ex(EVP_CIPHER_CTX *ctx, + const EVP_CIPHER *cipher, ENGINE *engine, + const uint8_t *key, const uint8_t *iv, + int enc); + +/* EVP_EncryptInit_ex calls |EVP_CipherInit_ex| with |enc| equal to one. */ +OPENSSL_EXPORT int EVP_EncryptInit_ex(EVP_CIPHER_CTX *ctx, + const EVP_CIPHER *cipher, ENGINE *impl, + const uint8_t *key, const uint8_t *iv); + +/* EVP_DecryptInit_ex calls |EVP_CipherInit_ex| with |enc| equal to zero. */ +OPENSSL_EXPORT int EVP_DecryptInit_ex(EVP_CIPHER_CTX *ctx, + const EVP_CIPHER *cipher, ENGINE *impl, + const uint8_t *key, const uint8_t *iv); + + +/* Cipher operations. */ + +/* EVP_EncryptUpdate encrypts |in_len| bytes from |in| to |out|. The number + * of output bytes may be up to |in_len| plus the block length minus one and + * |out| must have sufficient space. The number of bytes actually output is + * written to |*out_len|. It returns one on success and zero otherwise. */ +OPENSSL_EXPORT int EVP_EncryptUpdate(EVP_CIPHER_CTX *ctx, uint8_t *out, + int *out_len, const uint8_t *in, + int in_len); + +/* EVP_EncryptFinal_ex writes at most a block of ciphertext to |out| and sets + * |*out_len| to the number of bytes written. If padding is enabled (the + * default) then standard padding is applied to create the final block. If + * padding is disabled (with |EVP_CIPHER_CTX_set_padding|) then any partial + * block remaining will cause an error. The function returns one on success and + * zero otherwise. */ +OPENSSL_EXPORT int EVP_EncryptFinal_ex(EVP_CIPHER_CTX *ctx, uint8_t *out, + int *out_len); + +/* EVP_DecryptUpdate decrypts |in_len| bytes from |in| to |out|. The number of + * output bytes may be up to |in_len| plus the block length minus one and |out| + * must have sufficient space. The number of bytes actually output is written + * to |*out_len|. It returns one on success and zero otherwise. */ +OPENSSL_EXPORT int EVP_DecryptUpdate(EVP_CIPHER_CTX *ctx, uint8_t *out, + int *out_len, const uint8_t *in, + int in_len); + +/* EVP_DecryptFinal_ex writes at most a block of ciphertext to |out| and sets + * |*out_len| to the number of bytes written. If padding is enabled (the + * default) then padding is removed from the final block. + * + * WARNING: it is unsafe to call this function with unauthenticted + * ciphertext if padding is enabled. */ +OPENSSL_EXPORT int EVP_DecryptFinal_ex(EVP_CIPHER_CTX *ctx, unsigned char *out, + int *out_len); + +/* EVP_Cipher performs a one-shot encryption/decryption operation. No partial + * blocks are maintained between calls. However, any internal cipher state is + * still updated. For CBC-mode ciphers, the IV is updated to the final + * ciphertext block. For stream ciphers, the stream is advanced past the bytes + * used. It returns one on success and zero otherwise, unless |EVP_CIPHER_flags| + * has |EVP_CIPH_FLAG_CUSTOM_CIPHER| set. Then it returns the number of bytes + * written or -1 on error. + * + * WARNING: this differs from the usual return value convention when using + * |EVP_CIPH_FLAG_CUSTOM_CIPHER|. + * + * TODO(davidben): The normal ciphers currently never fail, even if, e.g., + * |in_len| is not a multiple of the block size for CBC-mode decryption. The + * input just gets rounded up while the output gets truncated. This should + * either be officially documented or fail. */ +OPENSSL_EXPORT int EVP_Cipher(EVP_CIPHER_CTX *ctx, uint8_t *out, + const uint8_t *in, size_t in_len); + +/* EVP_CipherUpdate calls either |EVP_EncryptUpdate| or |EVP_DecryptUpdate| + * depending on how |ctx| has been setup. */ +OPENSSL_EXPORT int EVP_CipherUpdate(EVP_CIPHER_CTX *ctx, uint8_t *out, + int *out_len, const uint8_t *in, + int in_len); + +/* EVP_CipherFinal_ex calls either |EVP_EncryptFinal_ex| or + * |EVP_DecryptFinal_ex| depending on how |ctx| has been setup. */ +OPENSSL_EXPORT int EVP_CipherFinal_ex(EVP_CIPHER_CTX *ctx, uint8_t *out, + int *out_len); + + +/* Cipher context accessors. */ + +/* EVP_CIPHER_CTX_cipher returns the |EVP_CIPHER| underlying |ctx|, or NULL if + * none has been set. */ +OPENSSL_EXPORT const EVP_CIPHER *EVP_CIPHER_CTX_cipher( + const EVP_CIPHER_CTX *ctx); + +/* EVP_CIPHER_CTX_nid returns a NID identifying the |EVP_CIPHER| underlying + * |ctx| (e.g. |NID_aes_128_gcm|). It will crash if no cipher has been + * configured. */ +OPENSSL_EXPORT int EVP_CIPHER_CTX_nid(const EVP_CIPHER_CTX *ctx); + +/* EVP_CIPHER_CTX_block_size returns the block size, in bytes, of the cipher + * underlying |ctx|, or one if the cipher is a stream cipher. It will crash if + * no cipher has been configured. */ +OPENSSL_EXPORT unsigned EVP_CIPHER_CTX_block_size(const EVP_CIPHER_CTX *ctx); + +/* EVP_CIPHER_CTX_key_length returns the key size, in bytes, of the cipher + * underlying |ctx| or zero if no cipher has been configured. */ +OPENSSL_EXPORT unsigned EVP_CIPHER_CTX_key_length(const EVP_CIPHER_CTX *ctx); + +/* EVP_CIPHER_CTX_iv_length returns the IV size, in bytes, of the cipher + * underlying |ctx|. It will crash if no cipher has been configured. */ +OPENSSL_EXPORT unsigned EVP_CIPHER_CTX_iv_length(const EVP_CIPHER_CTX *ctx); + +/* EVP_CIPHER_CTX_get_app_data returns the opaque, application data pointer for + * |ctx|, or NULL if none has been set. */ +OPENSSL_EXPORT void *EVP_CIPHER_CTX_get_app_data(const EVP_CIPHER_CTX *ctx); + +/* EVP_CIPHER_CTX_set_app_data sets the opaque, application data pointer for + * |ctx| to |data|. */ +OPENSSL_EXPORT void EVP_CIPHER_CTX_set_app_data(EVP_CIPHER_CTX *ctx, + void *data); + +/* EVP_CIPHER_CTX_flags returns a value which is the OR of zero or more + * |EVP_CIPH_*| flags. It will crash if no cipher has been configured. */ +OPENSSL_EXPORT uint32_t EVP_CIPHER_CTX_flags(const EVP_CIPHER_CTX *ctx); + +/* EVP_CIPHER_CTX_mode returns one of the |EVP_CIPH_*| cipher mode values + * enumerated below. It will crash if no cipher has been configured. */ +OPENSSL_EXPORT uint32_t EVP_CIPHER_CTX_mode(const EVP_CIPHER_CTX *ctx); + +/* EVP_CIPHER_CTX_ctrl is an |ioctl| like function. The |command| argument + * should be one of the |EVP_CTRL_*| values. The |arg| and |ptr| arguments are + * specific to the command in question. */ +OPENSSL_EXPORT int EVP_CIPHER_CTX_ctrl(EVP_CIPHER_CTX *ctx, int command, + int arg, void *ptr); + +/* EVP_CIPHER_CTX_set_padding sets whether padding is enabled for |ctx| and + * returns one. Pass a non-zero |pad| to enable padding (the default) or zero + * to disable. */ +OPENSSL_EXPORT int EVP_CIPHER_CTX_set_padding(EVP_CIPHER_CTX *ctx, int pad); + +/* EVP_CIPHER_CTX_set_key_length sets the key length for |ctx|. This is only + * valid for ciphers that can take a variable length key. It returns one on + * success and zero on error. */ +OPENSSL_EXPORT int EVP_CIPHER_CTX_set_key_length(EVP_CIPHER_CTX *ctx, unsigned key_len); + + +/* Cipher accessors. */ + +/* EVP_CIPHER_nid returns a NID identifing |cipher|. (For example, + * |NID_aes_128_gcm|.) */ +OPENSSL_EXPORT int EVP_CIPHER_nid(const EVP_CIPHER *cipher); + +/* EVP_CIPHER_block_size returns the block size, in bytes, for |cipher|, or one + * if |cipher| is a stream cipher. */ +OPENSSL_EXPORT unsigned EVP_CIPHER_block_size(const EVP_CIPHER *cipher); + +/* EVP_CIPHER_key_length returns the key size, in bytes, for |cipher|. If + * |cipher| can take a variable key length then this function returns the + * default key length and |EVP_CIPHER_flags| will return a value with + * |EVP_CIPH_VARIABLE_LENGTH| set. */ +OPENSSL_EXPORT unsigned EVP_CIPHER_key_length(const EVP_CIPHER *cipher); + +/* EVP_CIPHER_iv_length returns the IV size, in bytes, of |cipher|, or zero if + * |cipher| doesn't take an IV. */ +OPENSSL_EXPORT unsigned EVP_CIPHER_iv_length(const EVP_CIPHER *cipher); + +/* EVP_CIPHER_flags returns a value which is the OR of zero or more + * |EVP_CIPH_*| flags. */ +OPENSSL_EXPORT uint32_t EVP_CIPHER_flags(const EVP_CIPHER *cipher); + +/* EVP_CIPHER_mode returns one of the cipher mode values enumerated below. */ +OPENSSL_EXPORT uint32_t EVP_CIPHER_mode(const EVP_CIPHER *cipher); + + +/* Key derivation. */ + +/* EVP_BytesToKey generates a key and IV for the cipher |type| by iterating + * |md| |count| times using |data| and |salt|. On entry, the |key| and |iv| + * buffers must have enough space to hold a key and IV for |type|. It returns + * the length of the key on success or zero on error. */ +OPENSSL_EXPORT int EVP_BytesToKey(const EVP_CIPHER *type, const EVP_MD *md, + const uint8_t *salt, const uint8_t *data, + size_t data_len, unsigned count, uint8_t *key, + uint8_t *iv); + + +/* Cipher modes (for |EVP_CIPHER_mode|). */ + +#define EVP_CIPH_STREAM_CIPHER 0x0 +#define EVP_CIPH_ECB_MODE 0x1 +#define EVP_CIPH_CBC_MODE 0x2 +#define EVP_CIPH_CFB_MODE 0x3 +#define EVP_CIPH_OFB_MODE 0x4 +#define EVP_CIPH_CTR_MODE 0x5 +#define EVP_CIPH_GCM_MODE 0x6 + + +/* Cipher flags (for |EVP_CIPHER_flags|). */ + +/* EVP_CIPH_VARIABLE_LENGTH indicates that the cipher takes a variable length + * key. */ +#define EVP_CIPH_VARIABLE_LENGTH 0x40 + +/* EVP_CIPH_ALWAYS_CALL_INIT indicates that the |init| function for the cipher + * should always be called when initialising a new operation, even if the key + * is NULL to indicate that the same key is being used. */ +#define EVP_CIPH_ALWAYS_CALL_INIT 0x80 + +/* EVP_CIPH_CUSTOM_IV indicates that the cipher manages the IV itself rather + * than keeping it in the |iv| member of |EVP_CIPHER_CTX|. */ +#define EVP_CIPH_CUSTOM_IV 0x100 + +/* EVP_CIPH_CTRL_INIT indicates that EVP_CTRL_INIT should be used when + * initialising an |EVP_CIPHER_CTX|. */ +#define EVP_CIPH_CTRL_INIT 0x200 + +/* EVP_CIPH_FLAG_CUSTOM_CIPHER indicates that the cipher manages blocking + * itself. This causes EVP_(En|De)crypt_ex to be simple wrapper functions. */ +#define EVP_CIPH_FLAG_CUSTOM_CIPHER 0x400 + +/* EVP_CIPH_FLAG_AEAD_CIPHER specifies that the cipher is an AEAD. This is an + * older version of the proper AEAD interface. See aead.h for the current + * one. */ +#define EVP_CIPH_FLAG_AEAD_CIPHER 0x800 + +/* EVP_CIPH_CUSTOM_COPY indicates that the |ctrl| callback should be called + * with |EVP_CTRL_COPY| at the end of normal |EVP_CIPHER_CTX_copy| + * processing. */ +#define EVP_CIPH_CUSTOM_COPY 0x1000 + + +/* Deprecated functions */ + +/* EVP_CipherInit acts like EVP_CipherInit_ex except that |EVP_CIPHER_CTX_init| + * is called on |cipher| first, if |cipher| is not NULL. */ +OPENSSL_EXPORT int EVP_CipherInit(EVP_CIPHER_CTX *ctx, const EVP_CIPHER *cipher, + const uint8_t *key, const uint8_t *iv, + int enc); + +/* EVP_EncryptInit calls |EVP_CipherInit| with |enc| equal to one. */ +OPENSSL_EXPORT int EVP_EncryptInit(EVP_CIPHER_CTX *ctx, + const EVP_CIPHER *cipher, const uint8_t *key, + const uint8_t *iv); + +/* EVP_DecryptInit calls |EVP_CipherInit| with |enc| equal to zero. */ +OPENSSL_EXPORT int EVP_DecryptInit(EVP_CIPHER_CTX *ctx, + const EVP_CIPHER *cipher, const uint8_t *key, + const uint8_t *iv); + +/* EVP_add_cipher_alias does nothing and returns one. */ +OPENSSL_EXPORT int EVP_add_cipher_alias(const char *a, const char *b); + +/* EVP_get_cipherbyname returns an |EVP_CIPHER| given a human readable name in + * |name|, or NULL if the name is unknown. */ +OPENSSL_EXPORT const EVP_CIPHER *EVP_get_cipherbyname(const char *name); + + +/* Private functions. */ + +/* EVP_CIPH_NO_PADDING disables padding in block ciphers. */ +#define EVP_CIPH_NO_PADDING 0x800 + +/* EVP_CIPHER_CTX_ctrl commands. */ +#define EVP_CTRL_INIT 0x0 +#define EVP_CTRL_SET_KEY_LENGTH 0x1 +#define EVP_CTRL_GET_RC2_KEY_BITS 0x2 +#define EVP_CTRL_SET_RC2_KEY_BITS 0x3 +#define EVP_CTRL_GET_RC5_ROUNDS 0x4 +#define EVP_CTRL_SET_RC5_ROUNDS 0x5 +#define EVP_CTRL_RAND_KEY 0x6 +#define EVP_CTRL_PBE_PRF_NID 0x7 +#define EVP_CTRL_COPY 0x8 +#define EVP_CTRL_GCM_SET_IVLEN 0x9 +#define EVP_CTRL_GCM_GET_TAG 0x10 +#define EVP_CTRL_GCM_SET_TAG 0x11 +#define EVP_CTRL_GCM_SET_IV_FIXED 0x12 +#define EVP_CTRL_GCM_IV_GEN 0x13 +#define EVP_CTRL_AEAD_SET_MAC_KEY 0x17 +/* Set the GCM invocation field, decrypt only */ +#define EVP_CTRL_GCM_SET_IV_INV 0x18 + +/* GCM TLS constants */ +/* Length of fixed part of IV derived from PRF */ +#define EVP_GCM_TLS_FIXED_IV_LEN 4 +/* Length of explicit part of IV part of TLS records */ +#define EVP_GCM_TLS_EXPLICIT_IV_LEN 8 +/* Length of tag for TLS */ +#define EVP_GCM_TLS_TAG_LEN 16 + +#define EVP_MAX_KEY_LENGTH 64 +#define EVP_MAX_IV_LENGTH 16 +#define EVP_MAX_BLOCK_LENGTH 32 + +struct evp_cipher_ctx_st { + /* cipher contains the underlying cipher for this context. */ + const EVP_CIPHER *cipher; + + /* app_data is a pointer to opaque, user data. */ + void *app_data; /* application stuff */ + + /* cipher_data points to the |cipher| specific state. */ + void *cipher_data; + + /* key_len contains the length of the key, which may differ from + * |cipher->key_len| if the cipher can take a variable key length. */ + unsigned key_len; + + /* encrypt is one if encrypting and zero if decrypting. */ + int encrypt; + + /* flags contains the OR of zero or more |EVP_CIPH_*| flags, above. */ + uint32_t flags; + + /* oiv contains the original IV value. */ + uint8_t oiv[EVP_MAX_IV_LENGTH]; + + /* iv contains the current IV value, which may have been updated. */ + uint8_t iv[EVP_MAX_IV_LENGTH]; + + /* buf contains a partial block which is used by, for example, CTR mode to + * store unused keystream bytes. */ + uint8_t buf[EVP_MAX_BLOCK_LENGTH]; + + /* buf_len contains the number of bytes of a partial block contained in + * |buf|. */ + int buf_len; + + /* num contains the number of bytes of |iv| which are valid for modes that + * manage partial blocks themselves. */ + int num; + + /* final_used is non-zero if the |final| buffer contains plaintext. */ + int final_used; + + /* block_mask contains |cipher->block_size| minus one. (The block size + * assumed to be a power of two.) */ + int block_mask; + + uint8_t final[EVP_MAX_BLOCK_LENGTH]; /* possible final block */ +} /* EVP_CIPHER_CTX */; + +typedef struct evp_cipher_info_st { + const EVP_CIPHER *cipher; + unsigned char iv[EVP_MAX_IV_LENGTH]; +} EVP_CIPHER_INFO; + +struct evp_cipher_st { + /* type contains a NID identifing the cipher. (e.g. NID_aes_128_gcm.) */ + int nid; + + /* block_size contains the block size, in bytes, of the cipher, or 1 for a + * stream cipher. */ + unsigned block_size; + + /* key_len contains the key size, in bytes, for the cipher. If the cipher + * takes a variable key size then this contains the default size. */ + unsigned key_len; + + /* iv_len contains the IV size, in bytes, or zero if inapplicable. */ + unsigned iv_len; + + /* ctx_size contains the size, in bytes, of the per-key context for this + * cipher. */ + unsigned ctx_size; + + /* flags contains the OR of a number of flags. See |EVP_CIPH_*|. */ + uint32_t flags; + + /* app_data is a pointer to opaque, user data. */ + void *app_data; + + int (*init)(EVP_CIPHER_CTX *ctx, const uint8_t *key, const uint8_t *iv, + int enc); + + int (*cipher)(EVP_CIPHER_CTX *ctx, uint8_t *out, const uint8_t *in, + size_t inl); + + /* cleanup, if non-NULL, releases memory associated with the context. It is + * called if |EVP_CTRL_INIT| succeeds. Note that |init| may not have been + * called at this point. */ + void (*cleanup)(EVP_CIPHER_CTX *); + + int (*ctrl)(EVP_CIPHER_CTX *, int type, int arg, void *ptr); +}; + + +#if defined(__cplusplus) +} /* extern C */ +#endif + +#define CIPHER_F_EVP_AEAD_CTX_init 100 +#define CIPHER_F_EVP_AEAD_CTX_open 101 +#define CIPHER_F_EVP_AEAD_CTX_seal 102 +#define CIPHER_F_EVP_CIPHER_CTX_copy 103 +#define CIPHER_F_EVP_CIPHER_CTX_ctrl 104 +#define CIPHER_F_EVP_CIPHER_CTX_set_key_length 105 +#define CIPHER_F_EVP_CipherInit_ex 106 +#define CIPHER_F_EVP_DecryptFinal_ex 107 +#define CIPHER_F_EVP_EncryptFinal_ex 108 +#define CIPHER_F_aead_aes_gcm_init 109 +#define CIPHER_F_aead_aes_gcm_open 110 +#define CIPHER_F_aead_aes_gcm_seal 111 +#define CIPHER_F_aead_aes_key_wrap_init 112 +#define CIPHER_F_aead_aes_key_wrap_open 113 +#define CIPHER_F_aead_aes_key_wrap_seal 114 +#define CIPHER_F_aead_chacha20_poly1305_init 115 +#define CIPHER_F_aead_chacha20_poly1305_open 116 +#define CIPHER_F_aead_chacha20_poly1305_seal 117 +#define CIPHER_F_aead_rc4_md5_tls_init 118 +#define CIPHER_F_aead_rc4_md5_tls_open 119 +#define CIPHER_F_aead_rc4_md5_tls_seal 120 +#define CIPHER_F_aead_ssl3_ensure_cipher_init 121 +#define CIPHER_F_aead_ssl3_init 122 +#define CIPHER_F_aead_ssl3_open 123 +#define CIPHER_F_aead_ssl3_seal 124 +#define CIPHER_F_aead_tls_ensure_cipher_init 125 +#define CIPHER_F_aead_tls_init 126 +#define CIPHER_F_aead_tls_open 127 +#define CIPHER_F_aead_tls_seal 128 +#define CIPHER_F_aes_init_key 129 +#define CIPHER_F_aesni_init_key 130 +#define CIPHER_F_EVP_AEAD_CTX_init_with_direction 131 +#define CIPHER_F_aead_aes_ctr_hmac_sha256_init 132 +#define CIPHER_F_aead_aes_ctr_hmac_sha256_open 133 +#define CIPHER_F_aead_aes_ctr_hmac_sha256_seal 134 +#define CIPHER_R_AES_KEY_SETUP_FAILED 100 +#define CIPHER_R_BAD_DECRYPT 101 +#define CIPHER_R_BAD_KEY_LENGTH 102 +#define CIPHER_R_BUFFER_TOO_SMALL 103 +#define CIPHER_R_CTRL_NOT_IMPLEMENTED 104 +#define CIPHER_R_CTRL_OPERATION_NOT_IMPLEMENTED 105 +#define CIPHER_R_DATA_NOT_MULTIPLE_OF_BLOCK_LENGTH 106 +#define CIPHER_R_INITIALIZATION_ERROR 107 +#define CIPHER_R_INPUT_NOT_INITIALIZED 108 +#define CIPHER_R_INVALID_AD_SIZE 109 +#define CIPHER_R_INVALID_KEY_LENGTH 110 +#define CIPHER_R_INVALID_NONCE_SIZE 111 +#define CIPHER_R_INVALID_OPERATION 112 +#define CIPHER_R_IV_TOO_LARGE 113 +#define CIPHER_R_NO_CIPHER_SET 114 +#define CIPHER_R_OUTPUT_ALIASES_INPUT 115 +#define CIPHER_R_TAG_TOO_LARGE 116 +#define CIPHER_R_TOO_LARGE 117 +#define CIPHER_R_UNSUPPORTED_AD_SIZE 118 +#define CIPHER_R_UNSUPPORTED_INPUT_SIZE 119 +#define CIPHER_R_UNSUPPORTED_KEY_SIZE 120 +#define CIPHER_R_UNSUPPORTED_NONCE_SIZE 121 +#define CIPHER_R_UNSUPPORTED_TAG_SIZE 122 +#define CIPHER_R_WRONG_FINAL_BLOCK_LENGTH 123 +#define CIPHER_R_NO_DIRECTION_SET 124 + +#endif /* OPENSSL_HEADER_CIPHER_H */ diff --git a/phonelibs/boringssl/include/openssl/cmac.h b/phonelibs/boringssl/include/openssl/cmac.h new file mode 100644 index 00000000000000..183f41bca05630 --- /dev/null +++ b/phonelibs/boringssl/include/openssl/cmac.h @@ -0,0 +1,76 @@ +/* Copyright (c) 2015, Google Inc. + * + * Permission to use, copy, modify, and/or distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY + * SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN ACTION + * OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF OR IN + * CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. */ + +#ifndef OPENSSL_HEADER_CMAC_H +#define OPENSSL_HEADER_CMAC_H + +#include + +#if defined(__cplusplus) +extern "C" { +#endif + + +/* CMAC. + * + * CMAC is a MAC based on AES-CBC and defined in + * https://tools.ietf.org/html/rfc4493#section-2.3. */ + + +/* One-shot functions. */ + +/* AES_CMAC calculates the 16-byte, CMAC authenticator of |in_len| bytes of + * |in| and writes it to |out|. The |key_len| may be 16 or 32 bytes to select + * between AES-128 and AES-256. It returns one on success or zero on error. */ +OPENSSL_EXPORT int AES_CMAC(uint8_t out[16], const uint8_t *key, size_t key_len, + const uint8_t *in, size_t in_len); + + +/* Incremental interface. */ + +/* CMAC_CTX_new allocates a fresh |CMAC_CTX| and returns it, or NULL on + * error. */ +OPENSSL_EXPORT CMAC_CTX *CMAC_CTX_new(void); + +/* CMAC_CTX_free frees a |CMAC_CTX|. */ +OPENSSL_EXPORT void CMAC_CTX_free(CMAC_CTX *ctx); + +/* CMAC_Init configures |ctx| to use the given |key| and |cipher|. The CMAC RFC + * only specifies the use of AES-128 thus |key_len| should be 16 and |cipher| + * should be |EVP_aes_128_cbc()|. However, this implementation also supports + * AES-256 by setting |key_len| to 32 and |cipher| to |EVP_aes_256_cbc()|. The + * |engine| argument is ignored. + * + * It returns one on success or zero on error. */ +OPENSSL_EXPORT int CMAC_Init(CMAC_CTX *ctx, const void *key, size_t key_len, + const EVP_CIPHER *cipher, ENGINE *engine); + + +/* CMAC_Reset resets |ctx| so that a fresh message can be authenticated. */ +OPENSSL_EXPORT int CMAC_Reset(CMAC_CTX *ctx); + +/* CMAC_Update processes |in_len| bytes of message from |in|. It returns one on + * success or zero on error. */ +OPENSSL_EXPORT int CMAC_Update(CMAC_CTX *ctx, const uint8_t *in, size_t in_len); + +/* CMAC_Final sets |*out_len| to 16 and, if |out| is not NULL, writes 16 bytes + * of authenticator to it. It returns one on success or zero on error. */ +OPENSSL_EXPORT int CMAC_Final(CMAC_CTX *ctx, uint8_t *out, size_t *out_len); + + +#if defined(__cplusplus) +} /* extern C */ +#endif + +#endif /* OPENSSL_HEADER_CBC_H */ diff --git a/phonelibs/boringssl/include/openssl/conf.h b/phonelibs/boringssl/include/openssl/conf.h new file mode 100644 index 00000000000000..84fc94f99e5b63 --- /dev/null +++ b/phonelibs/boringssl/include/openssl/conf.h @@ -0,0 +1,149 @@ +/* Copyright (C) 1995-1998 Eric Young (eay@cryptsoft.com) + * All rights reserved. + * + * This package is an SSL implementation written + * by Eric Young (eay@cryptsoft.com). + * The implementation was written so as to conform with Netscapes SSL. + * + * This library is free for commercial and non-commercial use as long as + * the following conditions are aheared to. The following conditions + * apply to all code found in this distribution, be it the RC4, RSA, + * lhash, DES, etc., code; not just the SSL code. The SSL documentation + * included with this distribution is covered by the same copyright terms + * except that the holder is Tim Hudson (tjh@cryptsoft.com). + * + * Copyright remains Eric Young's, and as such any Copyright notices in + * the code are not to be removed. + * If this package is used in a product, Eric Young should be given attribution + * as the author of the parts of the library used. + * This can be in the form of a textual message at program startup or + * in documentation (online or textual) provided with the package. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must 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. All advertising materials mentioning features or use of this software + * must display the following acknowledgement: + * "This product includes cryptographic software written by + * Eric Young (eay@cryptsoft.com)" + * The word 'cryptographic' can be left out if the rouines from the library + * being used are not cryptographic related :-). + * 4. If you include any Windows specific code (or a derivative thereof) from + * the apps directory (application code) you must include an acknowledgement: + * "This product includes software written by Tim Hudson (tjh@cryptsoft.com)" + * + * THIS SOFTWARE IS PROVIDED BY ERIC YOUNG ``AS IS'' AND + * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHOR OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (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 licence and distribution terms for any publically available version or + * derivative of this code cannot be changed. i.e. this code cannot simply be + * copied and put under another distribution licence + * [including the GNU Public Licence.] */ + +#ifndef OPENSSL_HEADER_CONF_H +#define OPENSSL_HEADER_CONF_H + +#include + +#include +#include + +#if defined(__cplusplus) +extern "C" { +#endif + + +/* Config files look like: + * + * # Comment + * + * # This key is in the default section. + * key=value + * + * [section_name] + * key2=value2 + * + * Config files are representated by a |CONF|. */ + +struct conf_value_st { + char *section; + char *name; + char *value; +}; + +struct conf_st { + LHASH_OF(CONF_VALUE) *data; +}; + + +/* NCONF_new returns a fresh, empty |CONF|, or NULL on error. The |method| + * argument must be NULL. */ +CONF *NCONF_new(void *method); + +/* NCONF_free frees all the data owned by |conf| and then |conf| itself. */ +void NCONF_free(CONF *conf); + +/* NCONF_load parses the file named |filename| and adds the values found to + * |conf|. It returns one on success and zero on error. In the event of an + * error, if |out_error_line| is not NULL, |*out_error_line| is set to the + * number of the line that contained the error. */ +int NCONF_load(CONF *conf, const char *filename, long *out_error_line); + +/* NCONF_load_bio acts like |NCONF_load| but reads from |bio| rather than from + * a named file. */ +int NCONF_load_bio(CONF *conf, BIO *bio, long *out_error_line); + +/* NCONF_get_section returns a stack of values for a given section in |conf|. + * If |section| is NULL, the default section is returned. It returns NULL on + * error. */ +STACK_OF(CONF_VALUE) *NCONF_get_section(const CONF *conf, const char *section); + +/* NCONF_get_string returns the value of the key |name|, in section |section|. + * The |section| argument may be NULL to indicate the default section. It + * returns the value or NULL on error. */ +const char *NCONF_get_string(const CONF *conf, const char *section, + const char *name); + + +/* Utility functions */ + +/* CONF_parse_list takes a list separated by 'sep' and calls |list_cb| giving + * the start and length of each member, optionally stripping leading and + * trailing whitespace. This can be used to parse comma separated lists for + * example. If |list_cb| returns <= 0, then the iteration is halted and that + * value is returned immediately. Otherwise it returns one. Note that |list_cb| + * may be called on an empty member. */ +int CONF_parse_list(const char *list, char sep, int remove_whitespace, + int (*list_cb)(const char *elem, int len, void *usr), + void *arg); + +#if defined(__cplusplus) +} /* extern C */ +#endif + +#define CONF_F_CONF_parse_list 100 +#define CONF_F_NCONF_load 101 +#define CONF_F_def_load_bio 102 +#define CONF_F_str_copy 103 +#define CONF_R_LIST_CANNOT_BE_NULL 100 +#define CONF_R_MISSING_CLOSE_SQUARE_BRACKET 101 +#define CONF_R_MISSING_EQUAL_SIGN 102 +#define CONF_R_NO_CLOSE_BRACE 103 +#define CONF_R_UNABLE_TO_CREATE_NEW_SECTION 104 +#define CONF_R_VARIABLE_HAS_NO_VALUE 105 + +#endif /* OPENSSL_HEADER_THREAD_H */ diff --git a/phonelibs/boringssl/include/openssl/cpu.h b/phonelibs/boringssl/include/openssl/cpu.h new file mode 100644 index 00000000000000..83ec473fabcb8f --- /dev/null +++ b/phonelibs/boringssl/include/openssl/cpu.h @@ -0,0 +1,121 @@ +/* Copyright (C) 1995-1998 Eric Young (eay@cryptsoft.com) + * All rights reserved. + * + * This package is an SSL implementation written + * by Eric Young (eay@cryptsoft.com). + * The implementation was written so as to conform with Netscapes SSL. + * + * This library is free for commercial and non-commercial use as long as + * the following conditions are aheared to. The following conditions + * apply to all code found in this distribution, be it the RC4, RSA, + * lhash, DES, etc., code; not just the SSL code. The SSL documentation + * included with this distribution is covered by the same copyright terms + * except that the holder is Tim Hudson (tjh@cryptsoft.com). + * + * Copyright remains Eric Young's, and as such any Copyright notices in + * the code are not to be removed. + * If this package is used in a product, Eric Young should be given attribution + * as the author of the parts of the library used. + * This can be in the form of a textual message at program startup or + * in documentation (online or textual) provided with the package. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must 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. All advertising materials mentioning features or use of this software + * must display the following acknowledgement: + * "This product includes cryptographic software written by + * Eric Young (eay@cryptsoft.com)" + * The word 'cryptographic' can be left out if the rouines from the library + * being used are not cryptographic related :-). + * 4. If you include any Windows specific code (or a derivative thereof) from + * the apps directory (application code) you must include an acknowledgement: + * "This product includes software written by Tim Hudson (tjh@cryptsoft.com)" + * + * THIS SOFTWARE IS PROVIDED BY ERIC YOUNG ``AS IS'' AND + * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHOR OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (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 licence and distribution terms for any publically available version or + * derivative of this code cannot be changed. i.e. this code cannot simply be + * copied and put under another distribution licence + * [including the GNU Public Licence.] + * + * This product includes cryptographic software written by Eric Young + * (eay@cryptsoft.com). This product includes software written by Tim + * Hudson (tjh@cryptsoft.com). */ + +#ifndef OPENSSL_HEADER_CPU_H +#define OPENSSL_HEADER_CPU_H + +#include + +#if defined(__cplusplus) +extern "C" { +#endif + + +/* Runtime CPU feature support */ + + +#if defined(OPENSSL_X86) || defined(OPENSSL_X86_64) +/* OPENSSL_ia32cap_P contains the Intel CPUID bits when running on an x86 or + * x86-64 system. + * + * Index 0: + * EDX for CPUID where EAX = 1 + * Bit 30 is used to indicate an Intel CPU + * Index 1: + * ECX for CPUID where EAX = 1 + * Index 2: + * EBX for CPUID where EAX = 7 + * + * Note: the CPUID bits are pre-adjusted for the OSXSAVE bit and the YMM and XMM + * bits in XCR0, so it is not necessary to check those. */ +extern uint32_t OPENSSL_ia32cap_P[4]; +#endif + +#if defined(OPENSSL_ARM) || defined(OPENSSL_AARCH64) +/* CRYPTO_is_NEON_capable returns true if the current CPU has a NEON unit. Note + * that |OPENSSL_armcap_P| also exists and contains the same information in a + * form that's easier for assembly to use. */ +OPENSSL_EXPORT char CRYPTO_is_NEON_capable(void); + +/* CRYPTO_set_NEON_capable sets the return value of |CRYPTO_is_NEON_capable|. + * By default, unless the code was compiled with |-mfpu=neon|, NEON is assumed + * not to be present. It is not autodetected. Calling this with a zero + * argument also causes |CRYPTO_is_NEON_functional| to return false. */ +OPENSSL_EXPORT void CRYPTO_set_NEON_capable(char neon_capable); + +/* CRYPTO_is_NEON_functional returns true if the current CPU has a /working/ + * NEON unit. Some phones have a NEON unit, but the Poly1305 NEON code causes + * it to fail. See https://code.google.com/p/chromium/issues/detail?id=341598 */ +OPENSSL_EXPORT char CRYPTO_is_NEON_functional(void); + +/* CRYPTO_set_NEON_functional sets the "NEON functional" flag. For + * |CRYPTO_is_NEON_functional| to return true, both this flag and the NEON flag + * must be true. By default NEON is assumed to be functional if the code was + * compiled with |-mfpu=neon| or if |CRYPTO_set_NEON_capable| has been called + * with a non-zero argument. */ +OPENSSL_EXPORT void CRYPTO_set_NEON_functional(char neon_functional); +#endif /* OPENSSL_ARM */ + + +#if defined(__cplusplus) +} /* extern C */ +#endif + +#endif /* OPENSSL_HEADER_CPU_H */ diff --git a/phonelibs/boringssl/include/openssl/crypto.h b/phonelibs/boringssl/include/openssl/crypto.h new file mode 100644 index 00000000000000..3af1547d87ebbc --- /dev/null +++ b/phonelibs/boringssl/include/openssl/crypto.h @@ -0,0 +1,63 @@ +/* Copyright (c) 2014, Google Inc. + * + * Permission to use, copy, modify, and/or distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY + * SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN ACTION + * OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF OR IN + * CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. */ + +#ifndef OPENSSL_HEADER_CRYPTO_H +#define OPENSSL_HEADER_CRYPTO_H + +#include + +/* Upstream OpenSSL defines |OPENSSL_malloc|, etc., in crypto.h rather than + * mem.h. */ +#include + + +#if defined(__cplusplus) +extern "C" { +#endif + + +/* crypto.h contains functions for initializing the crypto library. */ + + +/* CRYPTO_library_init initializes the crypto library. It must be called if the + * library is built with BORINGSSL_NO_STATIC_INITIALIZER. Otherwise, it does + * nothing and a static initializer is used instead. */ +OPENSSL_EXPORT void CRYPTO_library_init(void); + + +/* Deprecated functions. */ + +#define OPENSSL_VERSION_TEXT "BoringSSL" + +#define SSLEAY_VERSION 0 + +/* SSLeay_version is a compatibility function that returns the string + * "BoringSSL". */ +OPENSSL_EXPORT const char *SSLeay_version(int unused); + +/* SSLeay is a compatibility function that returns OPENSSL_VERSION_NUMBER from + * base.h. */ +OPENSSL_EXPORT unsigned long SSLeay(void); + + +#if defined(__cplusplus) +} /* extern C */ +#endif + +#define CRYPTO_F_CRYPTO_get_ex_new_index 100 +#define CRYPTO_F_CRYPTO_set_ex_data 101 +#define CRYPTO_F_get_class 102 +#define CRYPTO_F_get_func_pointers 103 + +#endif /* OPENSSL_HEADER_CRYPTO_H */ diff --git a/phonelibs/boringssl/include/openssl/des.h b/phonelibs/boringssl/include/openssl/des.h new file mode 100644 index 00000000000000..6e1b0cfe5f76da --- /dev/null +++ b/phonelibs/boringssl/include/openssl/des.h @@ -0,0 +1,149 @@ +/* Copyright (C) 1995-1998 Eric Young (eay@cryptsoft.com) + * All rights reserved. + * + * This package is an SSL implementation written + * by Eric Young (eay@cryptsoft.com). + * The implementation was written so as to conform with Netscapes SSL. + * + * This library is free for commercial and non-commercial use as long as + * the following conditions are aheared to. The following conditions + * apply to all code found in this distribution, be it the RC4, RSA, + * lhash, DES, etc., code; not just the SSL code. The SSL documentation + * included with this distribution is covered by the same copyright terms + * except that the holder is Tim Hudson (tjh@cryptsoft.com). + * + * Copyright remains Eric Young's, and as such any Copyright notices in + * the code are not to be removed. + * If this package is used in a product, Eric Young should be given attribution + * as the author of the parts of the library used. + * This can be in the form of a textual message at program startup or + * in documentation (online or textual) provided with the package. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must 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. All advertising materials mentioning features or use of this software + * must display the following acknowledgement: + * "This product includes cryptographic software written by + * Eric Young (eay@cryptsoft.com)" + * The word 'cryptographic' can be left out if the rouines from the library + * being used are not cryptographic related :-). + * 4. If you include any Windows specific code (or a derivative thereof) from + * the apps directory (application code) you must include an acknowledgement: + * "This product includes software written by Tim Hudson (tjh@cryptsoft.com)" + * + * THIS SOFTWARE IS PROVIDED BY ERIC YOUNG ``AS IS'' AND + * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHOR OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (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 licence and distribution terms for any publically available version or + * derivative of this code cannot be changed. i.e. this code cannot simply be + * copied and put under another distribution licence + * [including the GNU Public Licence.] */ + +#ifndef OPENSSL_HEADER_DES_H +#define OPENSSL_HEADER_DES_H + +#include + +#if defined(__cplusplus) +extern "C" { +#endif + + +/* DES. */ + + +typedef struct DES_cblock_st { + uint8_t bytes[8]; +} DES_cblock; + +typedef struct DES_ks { + union { + DES_cblock cblock; + /* make sure things are correct size on machines with + * 8 byte longs */ + uint32_t deslong[2]; + } ks[16]; +} DES_key_schedule; + + +#define DES_KEY_SZ (sizeof(DES_cblock)) +#define DES_SCHEDULE_SZ (sizeof(DES_key_schedule)) + +#define DES_ENCRYPT 1 +#define DES_DECRYPT 0 + +#define DES_CBC_MODE 0 +#define DES_PCBC_MODE 1 + +/* DES_set_key performs a key schedule and initialises |schedule| with |key|. */ +OPENSSL_EXPORT void DES_set_key(const DES_cblock *key, + DES_key_schedule *schedule); + +/* DES_set_odd_parity sets the parity bits (the least-significant bits in each + * byte) of |key| given the other bits in each byte. */ +OPENSSL_EXPORT void DES_set_odd_parity(DES_cblock *key); + +/* DES_ecb_encrypt encrypts (or decrypts, if |is_encrypt| is |DES_DECRYPT|) a + * single DES block (8 bytes) from in to out, using the key configured in + * |schedule|. */ +OPENSSL_EXPORT void DES_ecb_encrypt(const DES_cblock *in, DES_cblock *out, + const DES_key_schedule *schedule, + int is_encrypt); + +/* DES_ncbc_encrypt encrypts (or decrypts, if |enc| is |DES_DECRYPT|) |len| + * bytes from |in| to |out| with DES in CBC mode. */ +OPENSSL_EXPORT void DES_ncbc_encrypt(const uint8_t *in, uint8_t *out, + size_t len, + const DES_key_schedule *schedule, + DES_cblock *ivec, int enc); + +/* DES_ecb3_encrypt encrypts (or decrypts, if |enc| is |DES_DECRYPT|) a single + * block (8 bytes) of data from |input| to |output| using 3DES. */ +OPENSSL_EXPORT void DES_ecb3_encrypt(const DES_cblock *input, + DES_cblock *output, + const DES_key_schedule *ks1, + const DES_key_schedule *ks2, + const DES_key_schedule *ks3, + int enc); + +/* DES_ede3_cbc_encrypt encrypts (or decrypts, if |enc| is |DES_DECRYPT|) |len| + * bytes from |in| to |out| with 3DES in CBC mode. 3DES uses three keys, thus + * the function takes three different |DES_key_schedule|s. */ +OPENSSL_EXPORT void DES_ede3_cbc_encrypt(const uint8_t *in, uint8_t *out, + size_t len, + const DES_key_schedule *ks1, + const DES_key_schedule *ks2, + const DES_key_schedule *ks3, + DES_cblock *ivec, int enc); + +/* DES_ede2_cbc_encrypt encrypts (or decrypts, if |enc| is |DES_DECRYPT|) |len| + * bytes from |in| to |out| with 3DES in CBC mode. With this keying option, the + * first and third 3DES keys are identical. Thus, this function takes only two + * different |DES_key_schedule|s. */ +OPENSSL_EXPORT void DES_ede2_cbc_encrypt(const uint8_t *in, uint8_t *out, + size_t len, + const DES_key_schedule *ks1, + const DES_key_schedule *ks2, + DES_cblock *ivec, int enc); + + +#if defined(__cplusplus) +} /* extern C */ +#endif + +#endif /* OPENSSL_HEADER_DES_H */ diff --git a/phonelibs/boringssl/include/openssl/dh.h b/phonelibs/boringssl/include/openssl/dh.h new file mode 100644 index 00000000000000..17574d51edf5b1 --- /dev/null +++ b/phonelibs/boringssl/include/openssl/dh.h @@ -0,0 +1,274 @@ +/* Copyright (C) 1995-1998 Eric Young (eay@cryptsoft.com) + * All rights reserved. + * + * This package is an SSL implementation written + * by Eric Young (eay@cryptsoft.com). + * The implementation was written so as to conform with Netscapes SSL. + * + * This library is free for commercial and non-commercial use as long as + * the following conditions are aheared to. The following conditions + * apply to all code found in this distribution, be it the RC4, RSA, + * lhash, DES, etc., code; not just the SSL code. The SSL documentation + * included with this distribution is covered by the same copyright terms + * except that the holder is Tim Hudson (tjh@cryptsoft.com). + * + * Copyright remains Eric Young's, and as such any Copyright notices in + * the code are not to be removed. + * If this package is used in a product, Eric Young should be given attribution + * as the author of the parts of the library used. + * This can be in the form of a textual message at program startup or + * in documentation (online or textual) provided with the package. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must 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. All advertising materials mentioning features or use of this software + * must display the following acknowledgement: + * "This product includes cryptographic software written by + * Eric Young (eay@cryptsoft.com)" + * The word 'cryptographic' can be left out if the rouines from the library + * being used are not cryptographic related :-). + * 4. If you include any Windows specific code (or a derivative thereof) from + * the apps directory (application code) you must include an acknowledgement: + * "This product includes software written by Tim Hudson (tjh@cryptsoft.com)" + * + * THIS SOFTWARE IS PROVIDED BY ERIC YOUNG ``AS IS'' AND + * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHOR OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (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 licence and distribution terms for any publically available version or + * derivative of this code cannot be changed. i.e. this code cannot simply be + * copied and put under another distribution licence + * [including the GNU Public Licence.] */ + +#ifndef OPENSSL_HEADER_DH_H +#define OPENSSL_HEADER_DH_H + +#include + +#include +#include +#include + +#if defined(__cplusplus) +extern "C" { +#endif + + +/* DH contains functions for performing Diffie-Hellman key agreement in + * multiplicative groups. */ + + +/* Allocation and destruction. */ + +/* DH_new returns a new, empty DH object or NULL on error. */ +OPENSSL_EXPORT DH *DH_new(void); + +/* DH_new_method acts the same as |DH_new| but takes an explicit |ENGINE|. */ +OPENSSL_EXPORT DH *DH_new_method(const ENGINE *engine); + +/* DH_free decrements the reference count of |dh| and frees it if the reference + * count drops to zero. */ +OPENSSL_EXPORT void DH_free(DH *dh); + +/* DH_up_ref increments the reference count of |dh|. */ +OPENSSL_EXPORT int DH_up_ref(DH *dh); + + +/* Standard parameters. + * + * These functions return new DH objects with standard parameters configured + * that use the given ENGINE, which may be NULL. They return NULL on allocation + * failure. */ + +/* These parameters are taken from RFC 5114. */ + +OPENSSL_EXPORT DH *DH_get_1024_160(const ENGINE *engine); +OPENSSL_EXPORT DH *DH_get_2048_224(const ENGINE *engine); +OPENSSL_EXPORT DH *DH_get_2048_256(const ENGINE *engine); + + +/* Parameter generation. */ + +#define DH_GENERATOR_2 2 +#define DH_GENERATOR_5 5 + +/* DH_generate_parameters_ex generates a suitable Diffie-Hellman group with a + * prime that is |prime_bits| long and stores it in |dh|. The generator of the + * group will be |generator|, which should be |DH_GENERATOR_2| unless there's a + * good reason to use a different value. The |cb| argument contains a callback + * function that will be called during the generation. See the documentation in + * |bn.h| about this. In addition to the callback invocations from |BN|, |cb| + * will also be called with |event| equal to three when the generation is + * complete. */ +OPENSSL_EXPORT int DH_generate_parameters_ex(DH *dh, int prime_bits, + int generator, BN_GENCB *cb); + + +/* Diffie-Hellman operations. */ + +/* DH_generate_key generates a new, random, private key and stores it in + * |dh|. It returns one on success and zero on error. */ +OPENSSL_EXPORT int DH_generate_key(DH *dh); + +/* DH_compute_key calculates the shared key between |dh| and |peers_key| and + * writes it as a big-endian integer into |out|, which must have |DH_size| + * bytes of space. It returns the number of bytes written, or a negative number + * on error. */ +OPENSSL_EXPORT int DH_compute_key(uint8_t *out, const BIGNUM *peers_key, + DH *dh); + + +/* Utility functions. */ + +/* DH_size returns the number of bytes in the DH group's prime. */ +OPENSSL_EXPORT int DH_size(const DH *dh); + +/* DH_num_bits returns the minimum number of bits needed to represent the + * absolute value of the DH group's prime. */ +OPENSSL_EXPORT unsigned DH_num_bits(const DH *dh); + +#define DH_CHECK_P_NOT_PRIME 0x01 +#define DH_CHECK_P_NOT_SAFE_PRIME 0x02 +#define DH_CHECK_UNABLE_TO_CHECK_GENERATOR 0x04 +#define DH_CHECK_NOT_SUITABLE_GENERATOR 0x08 +#define DH_CHECK_Q_NOT_PRIME 0x10 +#define DH_CHECK_INVALID_Q_VALUE 0x20 +#define DH_CHECK_INVALID_J_VALUE 0x40 + +/* These are compatibility defines. */ +#define DH_NOT_SUITABLE_GENERATOR DH_CHECK_NOT_SUITABLE_GENERATOR +#define DH_UNABLE_TO_CHECK_GENERATOR DH_CHECK_UNABLE_TO_CHECK_GENERATOR + +/* DH_check checks the suitability of |dh| as a Diffie-Hellman group. and sets + * |DH_CHECK_*| flags in |*out_flags| if it finds any errors. It returns one if + * |*out_flags| was successfully set and zero on error. + * + * Note: these checks may be quite computationally expensive. */ +OPENSSL_EXPORT int DH_check(const DH *dh, int *out_flags); + +#define DH_CHECK_PUBKEY_TOO_SMALL 1 +#define DH_CHECK_PUBKEY_TOO_LARGE 2 + +/* DH_check_pub_key checks the suitability of |pub_key| as a public key for the + * DH group in |dh| and sets |DH_CHECK_PUBKEY_*| flags in |*out_flags| if it + * finds any errors. It returns one if |*out_flags| was successfully set and + * zero on error. */ +OPENSSL_EXPORT int DH_check_pub_key(const DH *dh, const BIGNUM *pub_key, + int *out_flags); + +/* DHparams_dup allocates a fresh |DH| and copies the parameters from |dh| into + * it. It returns the new |DH| or NULL on error. */ +OPENSSL_EXPORT DH *DHparams_dup(const DH *dh); + + +/* ASN.1 functions. */ + +/* d2i_DHparams parses an ASN.1, DER encoded Diffie-Hellman parameters + * structure from |len| bytes at |*inp|. If |ret| is not NULL then, on exit, a + * pointer to the result is in |*ret|. If |*ret| is already non-NULL on entry + * then the result is written directly into |*ret|, otherwise a fresh |DH| is + * allocated. On successful exit, |*inp| is advanced past the DER structure. It + * returns the result or NULL on error. */ +OPENSSL_EXPORT DH *d2i_DHparams(DH **ret, const unsigned char **inp, long len); + +/* i2d_DHparams marshals |in| to an ASN.1, DER structure. If |outp| is not NULL + * then the result is written to |*outp| and |*outp| is advanced just past the + * output. It returns the number of bytes in the result, whether written or + * not, or a negative value on error. */ +OPENSSL_EXPORT int i2d_DHparams(const DH *in, unsigned char **outp); + + +/* ex_data functions. + * + * See |ex_data.h| for details. */ + +OPENSSL_EXPORT int DH_get_ex_new_index(long argl, void *argp, + CRYPTO_EX_new *new_func, + CRYPTO_EX_dup *dup_func, + CRYPTO_EX_free *free_func); +OPENSSL_EXPORT int DH_set_ex_data(DH *d, int idx, void *arg); +OPENSSL_EXPORT void *DH_get_ex_data(DH *d, int idx); + + +/* dh_method contains function pointers to override the implementation of DH. + * See |engine.h| for details. */ +struct dh_method { + struct openssl_method_common_st common; + + /* app_data is an opaque pointer for the method to use. */ + void *app_data; + + /* init is called just before the return of |DH_new_method|. It returns one + * on success or zero on error. */ + int (*init)(DH *dh); + + /* finish is called before |dh| is destructed. */ + void (*finish)(DH *dh); + + /* generate_parameters is called by |DH_generate_parameters_ex|. */ + int (*generate_parameters)(DH *dh, int prime_bits, int generator, + BN_GENCB *cb); + + /* generate_parameters is called by |DH_generate_key|. */ + int (*generate_key)(DH *dh); + + /* compute_key is called by |DH_compute_key|. */ + int (*compute_key)(DH *dh, uint8_t *out, const BIGNUM *pub_key); +}; + +struct dh_st { + DH_METHOD *meth; + + BIGNUM *p; + BIGNUM *g; + BIGNUM *pub_key; /* g^x */ + BIGNUM *priv_key; /* x */ + + /* priv_length contains the length, in bits, of the private value. If zero, + * the private value will be the same length as |p|. */ + unsigned priv_length; + + CRYPTO_MUTEX method_mont_p_lock; + BN_MONT_CTX *method_mont_p; + + /* Place holders if we want to do X9.42 DH */ + BIGNUM *q; + BIGNUM *j; + unsigned char *seed; + int seedlen; + BIGNUM *counter; + + int flags; + CRYPTO_refcount_t references; + CRYPTO_EX_DATA ex_data; +}; + + +#if defined(__cplusplus) +} /* extern C */ +#endif + +#define DH_F_DH_new_method 100 +#define DH_F_compute_key 101 +#define DH_F_generate_key 102 +#define DH_F_generate_parameters 103 +#define DH_R_BAD_GENERATOR 100 +#define DH_R_INVALID_PUBKEY 101 +#define DH_R_MODULUS_TOO_LARGE 102 +#define DH_R_NO_PRIVATE_VALUE 103 + +#endif /* OPENSSL_HEADER_DH_H */ diff --git a/phonelibs/boringssl/include/openssl/digest.h b/phonelibs/boringssl/include/openssl/digest.h new file mode 100644 index 00000000000000..2ea4ec4d7d3dda --- /dev/null +++ b/phonelibs/boringssl/include/openssl/digest.h @@ -0,0 +1,265 @@ +/* Copyright (C) 1995-1998 Eric Young (eay@cryptsoft.com) + * All rights reserved. + * + * This package is an SSL implementation written + * by Eric Young (eay@cryptsoft.com). + * The implementation was written so as to conform with Netscapes SSL. + * + * This library is free for commercial and non-commercial use as long as + * the following conditions are aheared to. The following conditions + * apply to all code found in this distribution, be it the RC4, RSA, + * lhash, DES, etc., code; not just the SSL code. The SSL documentation + * included with this distribution is covered by the same copyright terms + * except that the holder is Tim Hudson (tjh@cryptsoft.com). + * + * Copyright remains Eric Young's, and as such any Copyright notices in + * the code are not to be removed. + * If this package is used in a product, Eric Young should be given attribution + * as the author of the parts of the library used. + * This can be in the form of a textual message at program startup or + * in documentation (online or textual) provided with the package. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must 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. All advertising materials mentioning features or use of this software + * must display the following acknowledgement: + * "This product includes cryptographic software written by + * Eric Young (eay@cryptsoft.com)" + * The word 'cryptographic' can be left out if the rouines from the library + * being used are not cryptographic related :-). + * 4. If you include any Windows specific code (or a derivative thereof) from + * the apps directory (application code) you must include an acknowledgement: + * "This product includes software written by Tim Hudson (tjh@cryptsoft.com)" + * + * THIS SOFTWARE IS PROVIDED BY ERIC YOUNG ``AS IS'' AND + * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHOR OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (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 licence and distribution terms for any publically available version or + * derivative of this code cannot be changed. i.e. this code cannot simply be + * copied and put under another distribution licence + * [including the GNU Public Licence.] */ + +#ifndef OPENSSL_HEADER_DIGEST_H +#define OPENSSL_HEADER_DIGEST_H + +#include + +#if defined(__cplusplus) +extern "C" { +#endif + + +/* Digest functions. + * + * An EVP_MD abstracts the details of a specific hash function allowing code to + * deal with the concept of a "hash function" without needing to know exactly + * which hash function it is. */ + + +/* Hash algorithms. + * + * The following functions return |EVP_MD| objects that implement the named hash + * function. */ + +OPENSSL_EXPORT const EVP_MD *EVP_md4(void); +OPENSSL_EXPORT const EVP_MD *EVP_md5(void); +OPENSSL_EXPORT const EVP_MD *EVP_sha1(void); +OPENSSL_EXPORT const EVP_MD *EVP_sha224(void); +OPENSSL_EXPORT const EVP_MD *EVP_sha256(void); +OPENSSL_EXPORT const EVP_MD *EVP_sha384(void); +OPENSSL_EXPORT const EVP_MD *EVP_sha512(void); + +/* EVP_md5_sha1 is a TLS-specific |EVP_MD| which computes the concatenation of + * MD5 and SHA-1, as used in TLS 1.1 and below. */ +OPENSSL_EXPORT const EVP_MD *EVP_md5_sha1(void); + +/* EVP_get_digestbynid returns an |EVP_MD| for the given NID, or NULL if no + * such digest is known. */ +OPENSSL_EXPORT const EVP_MD *EVP_get_digestbynid(int nid); + +/* EVP_get_digestbyobj returns an |EVP_MD| for the given |ASN1_OBJECT|, or NULL + * if no such digest is known. */ +OPENSSL_EXPORT const EVP_MD *EVP_get_digestbyobj(const ASN1_OBJECT *obj); + + +/* Digest contexts. + * + * An EVP_MD_CTX represents the state of a specific digest operation in + * progress. */ + +/* EVP_MD_CTX_init initialises an, already allocated, |EVP_MD_CTX|. */ +OPENSSL_EXPORT void EVP_MD_CTX_init(EVP_MD_CTX *ctx); + +/* EVP_MD_CTX_create allocates and initialises a fresh |EVP_MD_CTX| and returns + * it, or NULL on allocation failure. */ +OPENSSL_EXPORT EVP_MD_CTX *EVP_MD_CTX_create(void); + +/* EVP_MD_CTX_cleanup frees any resources owned by |ctx| and resets it to a + * freshly initialised state. It does not free |ctx| itself. It returns one. */ +OPENSSL_EXPORT int EVP_MD_CTX_cleanup(EVP_MD_CTX *ctx); + +/* EVP_MD_CTX_destroy calls |EVP_MD_CTX_cleanup| and then frees |ctx| itself. */ +OPENSSL_EXPORT void EVP_MD_CTX_destroy(EVP_MD_CTX *ctx); + +/* EVP_MD_CTX_copy_ex sets |out|, which must already be initialised, to be a + * copy of |in|. It returns one on success and zero on error. */ +OPENSSL_EXPORT int EVP_MD_CTX_copy_ex(EVP_MD_CTX *out, const EVP_MD_CTX *in); + + +/* Digest operations. */ + +/* EVP_DigestInit_ex configures |ctx|, which must already have been + * initialised, for a fresh hashing operation using |type|. It returns one on + * success and zero otherwise. */ +OPENSSL_EXPORT int EVP_DigestInit_ex(EVP_MD_CTX *ctx, const EVP_MD *type, + ENGINE *engine); + +/* EVP_DigestInit acts like |EVP_DigestInit_ex| except that |ctx| is + * initialised before use. */ +OPENSSL_EXPORT int EVP_DigestInit(EVP_MD_CTX *ctx, const EVP_MD *type); + +/* EVP_DigestUpdate hashes |len| bytes from |data| into the hashing operation + * in |ctx|. It returns one. */ +OPENSSL_EXPORT int EVP_DigestUpdate(EVP_MD_CTX *ctx, const void *data, + size_t len); + +/* EVP_MAX_MD_SIZE is the largest digest size supported. Functions that output + * a digest generally require the buffer have at least this much space. */ +#define EVP_MAX_MD_SIZE 64 /* SHA-512 is the longest so far. */ + +/* EVP_DigestFinal_ex finishes the digest in |ctx| and writes the output to + * |md_out|. At most |EVP_MAX_MD_SIZE| bytes are written. If |out_size| is not + * NULL then |*out_size| is set to the number of bytes written. It returns one. + * After this call, the hash cannot be updated or finished again until + * |EVP_DigestInit_ex| is called to start another hashing operation. */ +OPENSSL_EXPORT int EVP_DigestFinal_ex(EVP_MD_CTX *ctx, uint8_t *md_out, + unsigned int *out_size); + +/* EVP_DigestFinal acts like |EVP_DigestFinal_ex| except that + * |EVP_MD_CTX_cleanup| is called on |ctx| before returning. */ +OPENSSL_EXPORT int EVP_DigestFinal(EVP_MD_CTX *ctx, uint8_t *md_out, + unsigned int *out_size); + +/* EVP_Digest performs a complete hashing operation in one call. It hashes + * |len| bytes from |data| and writes the digest to |md_out|. At most + * |EVP_MAX_MD_SIZE| bytes are written. If |out_size| is not NULL then + * |*out_size| is set to the number of bytes written. It returns one on success + * and zero otherwise. */ +OPENSSL_EXPORT int EVP_Digest(const void *data, size_t len, uint8_t *md_out, + unsigned int *md_out_size, const EVP_MD *type, + ENGINE *impl); + + +/* Digest function accessors. + * + * These functions allow code to learn details about an abstract hash + * function. */ + +/* EVP_MD_type returns a NID identifing |md|. (For example, |NID_sha256|.) */ +OPENSSL_EXPORT int EVP_MD_type(const EVP_MD *md); + +/* EVP_MD_flags returns the flags for |md|, which is a set of |EVP_MD_FLAG_*| + * values, ORed together. */ +OPENSSL_EXPORT uint32_t EVP_MD_flags(const EVP_MD *md); + +/* EVP_MD_size returns the digest size of |md|, in bytes. */ +OPENSSL_EXPORT size_t EVP_MD_size(const EVP_MD *md); + +/* EVP_MD_block_size returns the native block-size of |md|. */ +OPENSSL_EXPORT size_t EVP_MD_block_size(const EVP_MD *md); + +/* EVP_MD_FLAG_PKEY_DIGEST indicates the the digest function is used with a + * specific public key in order to verify signatures. (For example, + * EVP_dss1.) */ +#define EVP_MD_FLAG_PKEY_DIGEST 1 + +/* EVP_MD_FLAG_DIGALGID_ABSENT indicates that the parameter type in an X.509 + * DigestAlgorithmIdentifier representing this digest function should be + * undefined rather than NULL. */ +#define EVP_MD_FLAG_DIGALGID_ABSENT 2 + + +/* Deprecated functions. */ + +/* EVP_MD_CTX_copy sets |out|, which must /not/ be initialised, to be a copy of + * |in|. It returns one on success and zero on error. */ +OPENSSL_EXPORT int EVP_MD_CTX_copy(EVP_MD_CTX *out, const EVP_MD_CTX *in); + +/* EVP_add_digest does nothing and returns one. It exists only for + * compatibility with OpenSSL. */ +OPENSSL_EXPORT int EVP_add_digest(const EVP_MD *digest); + +/* EVP_get_cipherbyname returns an |EVP_MD| given a human readable name in + * |name|, or NULL if the name is unknown. */ +OPENSSL_EXPORT const EVP_MD *EVP_get_digestbyname(const char *); + + +/* Digest operation accessors. */ + +/* EVP_MD_CTX_md returns the underlying digest function, or NULL if one has not + * been set. */ +OPENSSL_EXPORT const EVP_MD *EVP_MD_CTX_md(const EVP_MD_CTX *ctx); + +/* EVP_MD_CTX_size returns the digest size of |ctx|. It will crash if a digest + * hasn't been set on |ctx|. */ +OPENSSL_EXPORT unsigned EVP_MD_CTX_size(const EVP_MD_CTX *ctx); + +/* EVP_MD_CTX_block_size returns the block size of the digest function used by + * |ctx|. It will crash if a digest hasn't been set on |ctx|. */ +OPENSSL_EXPORT unsigned EVP_MD_CTX_block_size(const EVP_MD_CTX *ctx); + +/* EVP_MD_CTX_type returns a NID describing the digest function used by |ctx|. + * (For example, |NID_sha256|.) It will crash if a digest hasn't been set on + * |ctx|. */ +OPENSSL_EXPORT int EVP_MD_CTX_type(const EVP_MD_CTX *ctx); + + +struct evp_md_pctx_ops; + +struct env_md_ctx_st { + /* digest is the underlying digest function, or NULL if not set. */ + const EVP_MD *digest; + /* flags is the OR of a number of |EVP_MD_CTX_FLAG_*| values. */ + uint32_t flags; + /* md_data points to a block of memory that contains the hash-specific + * context. */ + void *md_data; + /* update is usually copied from |digest->update| but can differ in some + * cases, i.e. HMAC. + * TODO(davidben): Remove this hook once |EVP_PKEY_HMAC| is gone. */ + void (*update)(EVP_MD_CTX *ctx, const void *data, size_t count); + + /* pctx is an opaque (at this layer) pointer to additional context that + * EVP_PKEY functions may store in this object. */ + EVP_PKEY_CTX *pctx; + + /* pctx_ops, if not NULL, points to a vtable that contains functions to + * manipulate |pctx|. */ + const struct evp_md_pctx_ops *pctx_ops; +} /* EVP_MD_CTX */; + + +#if defined(__cplusplus) +} /* extern C */ +#endif + +#define DIGEST_F_EVP_DigestInit_ex 100 +#define DIGEST_F_EVP_MD_CTX_copy_ex 101 +#define DIGEST_R_INPUT_NOT_INITIALIZED 100 + +#endif /* OPENSSL_HEADER_DIGEST_H */ diff --git a/phonelibs/boringssl/include/openssl/dsa.h b/phonelibs/boringssl/include/openssl/dsa.h new file mode 100644 index 00000000000000..7274e4c8c90d29 --- /dev/null +++ b/phonelibs/boringssl/include/openssl/dsa.h @@ -0,0 +1,379 @@ +/* Copyright (C) 1995-1998 Eric Young (eay@cryptsoft.com) + * All rights reserved. + * + * This package is an SSL implementation written + * by Eric Young (eay@cryptsoft.com). + * The implementation was written so as to conform with Netscapes SSL. + * + * This library is free for commercial and non-commercial use as long as + * the following conditions are aheared to. The following conditions + * apply to all code found in this distribution, be it the RC4, RSA, + * lhash, DES, etc., code; not just the SSL code. The SSL documentation + * included with this distribution is covered by the same copyright terms + * except that the holder is Tim Hudson (tjh@cryptsoft.com). + * + * Copyright remains Eric Young's, and as such any Copyright notices in + * the code are not to be removed. + * If this package is used in a product, Eric Young should be given attribution + * as the author of the parts of the library used. + * This can be in the form of a textual message at program startup or + * in documentation (online or textual) provided with the package. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must 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. All advertising materials mentioning features or use of this software + * must display the following acknowledgement: + * "This product includes cryptographic software written by + * Eric Young (eay@cryptsoft.com)" + * The word 'cryptographic' can be left out if the rouines from the library + * being used are not cryptographic related :-). + * 4. If you include any Windows specific code (or a derivative thereof) from + * the apps directory (application code) you must include an acknowledgement: + * "This product includes software written by Tim Hudson (tjh@cryptsoft.com)" + * + * THIS SOFTWARE IS PROVIDED BY ERIC YOUNG ``AS IS'' AND + * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHOR OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (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 licence and distribution terms for any publically available version or + * derivative of this code cannot be changed. i.e. this code cannot simply be + * copied and put under another distribution licence + * [including the GNU Public Licence.] + * + * The DSS routines are based on patches supplied by + * Steven Schoch . */ + +#ifndef OPENSSL_HEADER_DSA_H +#define OPENSSL_HEADER_DSA_H + +#include + +#include +#include +#include + +#if defined(__cplusplus) +extern "C" { +#endif + + +/* DSA contains functions for signing and verifing with the Digital Signature + * Algorithm. */ + + +/* Allocation and destruction. */ + +/* DSA_new returns a new, empty DSA object or NULL on error. */ +OPENSSL_EXPORT DSA *DSA_new(void); + +/* DSA_new_method acts the same as |DH_new| but takes an explicit |ENGINE|. */ +OPENSSL_EXPORT DSA *DSA_new_method(const ENGINE *engine); + +/* DSA_free decrements the reference count of |dsa| and frees it if the + * reference count drops to zero. */ +OPENSSL_EXPORT void DSA_free(DSA *dsa); + +/* DSA_up_ref increments the reference count of |dsa|. */ +OPENSSL_EXPORT int DSA_up_ref(DSA *dsa); + + +/* Parameter generation. */ + +/* DSA_generate_parameters_ex generates a set of DSA parameters by following + * the procedure given in FIPS 186-4, appendix A. + * (http://nvlpubs.nist.gov/nistpubs/FIPS/NIST.FIPS.186-4.pdf) + * + * The larger prime will have a length of |bits| (e.g. 2048). The |seed| value + * allows others to generate and verify the same parameters and should be + * random input which is kept for reference. If |out_counter| or |out_h| are + * not NULL then the counter and h value used in the generation are written to + * them. + * + * The |cb| argument is passed to |BN_generate_prime_ex| and is thus called + * during the generation process in order to indicate progress. See the + * comments for that function for details. In addition to the calls made by + * |BN_generate_prime_ex|, |DSA_generate_parameters_ex| will call it with + * |event| equal to 2 and 3 at different stages of the process. + * + * It returns one on success and zero otherwise. */ +OPENSSL_EXPORT int DSA_generate_parameters_ex(DSA *dsa, unsigned bits, + const uint8_t *seed, + size_t seed_len, int *out_counter, + unsigned long *out_h, + BN_GENCB *cb); + +/* DSAparams_dup returns a freshly allocated |DSA| that contains a copy of the + * parameters from |dsa|. It returns NULL on error. */ +OPENSSL_EXPORT DSA *DSAparams_dup(const DSA *dsa); + + +/* Key generation. */ + +/* DSA_generate_key generates a public/private key pair in |dsa|, which must + * already have parameters setup. It returns one on success and zero on + * error. */ +OPENSSL_EXPORT int DSA_generate_key(DSA *dsa); + + +/* Signatures. */ + +/* DSA_SIG contains a DSA signature as a pair of integers. */ +typedef struct DSA_SIG_st { + BIGNUM *r, *s; +} DSA_SIG; + +/* DSA_SIG_new returns a freshly allocated, DIG_SIG structure or NULL on error. + * Both |r| and |s| in the signature will be NULL. */ +OPENSSL_EXPORT DSA_SIG *DSA_SIG_new(void); + +/* DSA_SIG_free frees the contents of |sig| and then frees |sig| itself. */ +OPENSSL_EXPORT void DSA_SIG_free(DSA_SIG *sig); + +/* DSA_do_sign returns a signature of the hash in |digest| by the key in |dsa| + * and returns an allocated, DSA_SIG structure, or NULL on error. */ +OPENSSL_EXPORT DSA_SIG *DSA_do_sign(const uint8_t *digest, size_t digest_len, + DSA *dsa); + +/* DSA_do_verify verifies that |sig| is a valid signature, by the public key in + * |dsa|, of the hash in |digest|. It returns one if so, zero if invalid and -1 + * on error. + * + * WARNING: do not use. This function returns -1 for error, 0 for invalid and 1 + * for valid. However, this is dangerously different to the usual OpenSSL + * convention and could be a disaster if a user did |if (DSA_do_verify(...))|. + * Because of this, |DSA_check_signature| is a safer version of this. + * + * TODO(fork): deprecate. */ +OPENSSL_EXPORT int DSA_do_verify(const uint8_t *digest, size_t digest_len, + DSA_SIG *sig, const DSA *dsa); + +/* DSA_do_check_signature sets |*out_valid| to zero. Then it verifies that |sig| + * is a valid signature, by the public key in |dsa| of the hash in |digest| + * and, if so, it sets |*out_valid| to one. + * + * It returns one if it was able to verify the signature as valid or invalid, + * and zero on error. */ +OPENSSL_EXPORT int DSA_do_check_signature(int *out_valid, const uint8_t *digest, + size_t digest_len, DSA_SIG *sig, + const DSA *dsa); + + +/* ASN.1 signatures. + * + * These functions also perform DSA signature operations, but deal with ASN.1 + * encoded signatures as opposed to raw |BIGNUM|s. If you don't know what + * encoding a DSA signature is in, it's probably ASN.1. */ + +/* DSA_sign signs |digest| with the key in |dsa| and writes the resulting + * signature, in ASN.1 form, to |out_sig| and the length of the signature to + * |*out_siglen|. There must be, at least, |DSA_size(dsa)| bytes of space in + * |out_sig|. It returns one on success and zero otherwise. + * + * (The |type| argument is ignored.) */ +OPENSSL_EXPORT int DSA_sign(int type, const uint8_t *digest, size_t digest_len, + uint8_t *out_sig, unsigned int *out_siglen, + DSA *dsa); + +/* DSA_verify verifies that |sig| is a valid, ASN.1 signature, by the public + * key in |dsa|, of the hash in |digest|. It returns one if so, zero if invalid + * and -1 on error. + * + * (The |type| argument is ignored.) + * + * WARNING: do not use. This function returns -1 for error, 0 for invalid and 1 + * for valid. However, this is dangerously different to the usual OpenSSL + * convention and could be a disaster if a user did |if (DSA_do_verify(...))|. + * Because of this, |DSA_check_signature| is a safer version of this. + * + * TODO(fork): deprecate. */ +OPENSSL_EXPORT int DSA_verify(int type, const uint8_t *digest, + size_t digest_len, const uint8_t *sig, + size_t sig_len, const DSA *dsa); + +/* DSA_check_signature sets |*out_valid| to zero. Then it verifies that |sig| + * is a valid, ASN.1 signature, by the public key in |dsa|, of the hash in + * |digest|. If so, it sets |*out_valid| to one. + * + * It returns one if it was able to verify the signature as valid or invalid, + * and zero on error. */ +OPENSSL_EXPORT int DSA_check_signature(int *out_valid, const uint8_t *digest, + size_t digest_len, const uint8_t *sig, + size_t sig_len, const DSA *dsa); + +/* DSA_size returns the size, in bytes, of an ASN.1 encoded, DSA signature + * generated by |dsa|. Parameters must already have been setup in |dsa|. */ +OPENSSL_EXPORT int DSA_size(const DSA *dsa); + + +/* ASN.1 encoding. */ + +/* d2i_DSA_SIG parses an ASN.1, DER-encoded, DSA signature from |len| bytes at + * |*inp|. If |out_sig| is not NULL then, on exit, a pointer to the result is + * in |*out_sig|. If |*out_sig| is already non-NULL on entry then the result is + * written directly into |*out_sig|, otherwise a fresh |DSA_SIG| is allocated. + * On successful exit, |*inp| is advanced past the DER structure. It returns + * the result or NULL on error. */ +OPENSSL_EXPORT DSA_SIG *d2i_DSA_SIG(DSA_SIG **out_sig, const uint8_t **inp, + long len); + +/* i2d_DSA_SIG marshals |in| to an ASN.1, DER structure. If |outp| is not NULL + * then the result is written to |*outp| and |*outp| is advanced just past the + * output. It returns the number of bytes in the result, whether written or not, + * or a negative value on error. */ +OPENSSL_EXPORT int i2d_DSA_SIG(const DSA_SIG *in, uint8_t **outp); + +/* d2i_DSAPublicKey parses an ASN.1, DER-encoded, DSA public key from |len| + * bytes at |*inp|. If |out| is not NULL then, on exit, a pointer to the result + * is in |*out|. If |*out| is already non-NULL on entry then the result is + * written directly into |*out|, otherwise a fresh |DSA| is allocated. On + * successful exit, |*inp| is advanced past the DER structure. It returns the + * result or NULL on error. */ +OPENSSL_EXPORT DSA *d2i_DSAPublicKey(DSA **out, const uint8_t **inp, long len); + +/* i2d_DSAPublicKey marshals a public key from |in| to an ASN.1, DER structure. + * If |outp| is not NULL then the result is written to |*outp| and |*outp| is + * advanced just past the output. It returns the number of bytes in the result, + * whether written or not, or a negative value on error. */ +OPENSSL_EXPORT int i2d_DSAPublicKey(const DSA *in, unsigned char **outp); + +/* d2i_DSAPrivateKey parses an ASN.1, DER-encoded, DSA private key from |len| + * bytes at |*inp|. If |out| is not NULL then, on exit, a pointer to the result + * is in |*out|. If |*out| is already non-NULL on entry then the result is + * written directly into |*out|, otherwise a fresh |DSA| is allocated. On + * successful exit, |*inp| is advanced past the DER structure. It returns the + * result or NULL on error. */ +OPENSSL_EXPORT DSA *d2i_DSAPrivateKey(DSA **out, const uint8_t **inp, long len); + +/* i2d_DSAPrivateKey marshals a private key from |in| to an ASN.1, DER structure. + * If |outp| is not NULL then the result is written to |*outp| and |*outp| is + * advanced just past the output. It returns the number of bytes in the result, + * whether written or not, or a negative value on error. */ +OPENSSL_EXPORT int i2d_DSAPrivateKey(const DSA *in, unsigned char **outp); + +/* d2i_DSAparams parses ASN.1, DER-encoded, DSA parameters from |len| bytes at + * |*inp|. If |out| is not NULL then, on exit, a pointer to the result is in + * |*out|. If |*out| is already non-NULL on entry then the result is written + * directly into |*out|, otherwise a fresh |DSA| is allocated. On successful + * exit, |*inp| is advanced past the DER structure. It returns the result or + * NULL on error. */ +OPENSSL_EXPORT DSA *d2i_DSAparams(DSA **out, const uint8_t **inp, long len); + +/* i2d_DSAparams marshals DSA parameters from |in| to an ASN.1, DER structure. + * If |outp| is not NULL then the result is written to |*outp| and |*outp| is + * advanced just past the output. It returns the number of bytes in the result, + * whether written or not, or a negative value on error. */ +OPENSSL_EXPORT int i2d_DSAparams(const DSA *in, unsigned char **outp); + + +/* Precomputation. */ + +/* DSA_sign_setup precomputes the message independent part of the DSA signature + * and writes them to |*out_kinv| and |*out_r|. Returns one on success, zero on + * error. + * + * TODO(fork): decide what to do with this. Since making DSA* opaque there's no + * way for the user to install them. Also, it forces the DSA* not to be const + * when passing to the signing function. */ +OPENSSL_EXPORT int DSA_sign_setup(const DSA *dsa, BN_CTX *ctx, + BIGNUM **out_kinv, BIGNUM **out_r); + + +/* Conversion. */ + +/* DSA_dup_DH returns a |DH| constructed from the parameters of |dsa|. This is + * sometimes needed when Diffie-Hellman parameters are stored in the form of + * DSA parameters. It returns an allocated |DH| on success or NULL on error. */ +OPENSSL_EXPORT DH *DSA_dup_DH(const DSA *dsa); + + +/* ex_data functions. + * + * See |ex_data.h| for details. */ + +OPENSSL_EXPORT int DSA_get_ex_new_index(long argl, void *argp, + CRYPTO_EX_new *new_func, + CRYPTO_EX_dup *dup_func, + CRYPTO_EX_free *free_func); +OPENSSL_EXPORT int DSA_set_ex_data(DSA *d, int idx, void *arg); +OPENSSL_EXPORT void *DSA_get_ex_data(const DSA *d, int idx); + + +struct dsa_method { + struct openssl_method_common_st common; + + void *app_data; + + int (*init)(DSA *dsa); + int (*finish)(DSA *dsa); + + DSA_SIG *(*sign)(const uint8_t *digest, size_t digest_len, DSA *dsa); + + int (*sign_setup)(const DSA *dsa, BN_CTX *ctx_in, BIGNUM **kinvp, BIGNUM **rp, + const uint8_t *digest, size_t digest_len); + + int (*verify)(int *out_valid, const uint8_t *digest, size_t digest_len, + DSA_SIG *sig, const DSA *dsa); + + /* generate_parameters, if non-NULL, is used to generate DSA parameters. */ + int (*generate_parameters)(DSA *dsa, unsigned bits, const uint8_t *seed, + size_t seed_len, int *counter_ret, + unsigned long *h_ret, BN_GENCB *cb); + + /* keygen, if non-NULL, is used to generate DSA keys. */ + int (*keygen)(DSA *dsa); +}; + +struct dsa_st { + long version; + int write_params; + BIGNUM *p; + BIGNUM *q; /* == 20 */ + BIGNUM *g; + + BIGNUM *pub_key; /* y public key */ + BIGNUM *priv_key; /* x private key */ + + BIGNUM *kinv; /* Signing pre-calc */ + BIGNUM *r; /* Signing pre-calc */ + + int flags; + /* Normally used to cache montgomery values */ + CRYPTO_MUTEX method_mont_p_lock; + BN_MONT_CTX *method_mont_p; + CRYPTO_refcount_t references; + CRYPTO_EX_DATA ex_data; + DSA_METHOD *meth; + /* functional reference if 'meth' is ENGINE-provided */ + ENGINE *engine; +}; + + +#if defined(__cplusplus) +} /* extern C */ +#endif + +#define DSA_F_DSA_new_method 100 +#define DSA_F_dsa_sig_cb 101 +#define DSA_F_sign 102 +#define DSA_F_sign_setup 103 +#define DSA_F_verify 104 +#define DSA_R_BAD_Q_VALUE 100 +#define DSA_R_MISSING_PARAMETERS 101 +#define DSA_R_MODULUS_TOO_LARGE 102 +#define DSA_R_NEED_NEW_SETUP_VALUES 103 + +#endif /* OPENSSL_HEADER_DSA_H */ diff --git a/phonelibs/boringssl/include/openssl/dtls1.h b/phonelibs/boringssl/include/openssl/dtls1.h new file mode 100644 index 00000000000000..38ca801cb1044e --- /dev/null +++ b/phonelibs/boringssl/include/openssl/dtls1.h @@ -0,0 +1,16 @@ +/* Copyright (c) 2015, Google Inc. + * + * Permission to use, copy, modify, and/or distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY + * SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN ACTION + * OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF OR IN + * CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. */ + +/* This header is provided in order to make compiling against code that expects + OpenSSL easier. */ diff --git a/phonelibs/boringssl/include/openssl/ec.h b/phonelibs/boringssl/include/openssl/ec.h new file mode 100644 index 00000000000000..25b455185e7503 --- /dev/null +++ b/phonelibs/boringssl/include/openssl/ec.h @@ -0,0 +1,433 @@ +/* Originally written by Bodo Moeller for the OpenSSL project. + * ==================================================================== + * Copyright (c) 1998-2005 The OpenSSL Project. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * + * 3. All advertising materials mentioning features or use of this + * software must display the following acknowledgment: + * "This product includes software developed by the OpenSSL Project + * for use in the OpenSSL Toolkit. (http://www.openssl.org/)" + * + * 4. The names "OpenSSL Toolkit" and "OpenSSL Project" must not be used to + * endorse or promote products derived from this software without + * prior written permission. For written permission, please contact + * openssl-core@openssl.org. + * + * 5. Products derived from this software may not be called "OpenSSL" + * nor may "OpenSSL" appear in their names without prior written + * permission of the OpenSSL Project. + * + * 6. Redistributions of any form whatsoever must retain the following + * acknowledgment: + * "This product includes software developed by the OpenSSL Project + * for use in the OpenSSL Toolkit (http://www.openssl.org/)" + * + * THIS SOFTWARE IS PROVIDED BY THE OpenSSL PROJECT ``AS IS'' AND ANY + * EXPRESSED OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR + * PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE OpenSSL PROJECT OR + * ITS CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, + * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT + * NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + * STRICT LIABILITY, OR TORT (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 product includes cryptographic software written by Eric Young + * (eay@cryptsoft.com). This product includes software written by Tim + * Hudson (tjh@cryptsoft.com). + * + */ +/* ==================================================================== + * Copyright 2002 Sun Microsystems, Inc. ALL RIGHTS RESERVED. + * + * Portions of the attached software ("Contribution") are developed by + * SUN MICROSYSTEMS, INC., and are contributed to the OpenSSL project. + * + * The Contribution is licensed pursuant to the OpenSSL open source + * license provided above. + * + * The elliptic curve binary polynomial software is originally written by + * Sheueling Chang Shantz and Douglas Stebila of Sun Microsystems + * Laboratories. */ + +#ifndef OPENSSL_HEADER_EC_H +#define OPENSSL_HEADER_EC_H + +#include + +#if defined(__cplusplus) +extern "C" { +#endif + + +/* Low-level operations on elliptic curves. */ + + +typedef struct ec_group_st EC_GROUP; +typedef struct ec_point_st EC_POINT; + +/** Enum for the point conversion form as defined in X9.62 (ECDSA) + * for the encoding of a elliptic curve point (x,y) */ +typedef enum { + /** the point is encoded as z||x, where the octet z specifies + * which solution of the quadratic equation y is */ + POINT_CONVERSION_COMPRESSED = 2, + /** the point is encoded as z||x||y, where z is the octet 0x02 */ + POINT_CONVERSION_UNCOMPRESSED = 4 +} point_conversion_form_t; + + +/* Elliptic curve groups. */ + +/* EC_GROUP_new_by_curve_name returns a fresh EC_GROUP object for the elliptic + * curve specified by |nid|, or NULL on error. + * + * The supported NIDs are: + * NID_secp224r1, + * NID_X9_62_prime256v1, + * NID_secp384r1, + * NID_secp521r1 */ +OPENSSL_EXPORT EC_GROUP *EC_GROUP_new_by_curve_name(int nid); + +/* EC_GROUP_free frees |group| and the data that it points to. */ +OPENSSL_EXPORT void EC_GROUP_free(EC_GROUP *group); + +/* EC_GROUP_dup returns a fresh |EC_GROUP| which is equal to |a| or NULL on + * error. */ +OPENSSL_EXPORT EC_GROUP *EC_GROUP_dup(const EC_GROUP *a); + +/* EC_GROUP_cmp returns zero if |a| and |b| are the same group and non-zero + * otherwise. */ +OPENSSL_EXPORT int EC_GROUP_cmp(const EC_GROUP *a, const EC_GROUP *b, + BN_CTX *ignored); + +/* EC_GROUP_get0_generator returns a pointer to the internal |EC_POINT| object + * in |group| that specifies the generator for the group. */ +OPENSSL_EXPORT const EC_POINT *EC_GROUP_get0_generator(const EC_GROUP *group); + +/* EC_GROUP_get_order sets |*order| to the order of |group|, if it's not + * NULL. It returns one on success and zero otherwise. |ctx| is ignored. */ +OPENSSL_EXPORT int EC_GROUP_get_order(const EC_GROUP *group, BIGNUM *order, + BN_CTX *ctx); + +/* EC_GROUP_get_cofactor sets |*cofactor| to the cofactor of |group| using + * |ctx|, if it's not NULL. It returns one on success and zero otherwise. */ +OPENSSL_EXPORT int EC_GROUP_get_cofactor(const EC_GROUP *group, + BIGNUM *cofactor, BN_CTX *ctx); + +/* EC_GROUP_get_curve_GFp gets various parameters about a group. It sets + * |*out_p| to the order of the coordinate field and |*out_a| and |*out_b| to + * the parameters of the curve when expressed as y² = x³ + ax + b. Any of the + * output parameters can be NULL. It returns one on success and zero on + * error. */ +OPENSSL_EXPORT int EC_GROUP_get_curve_GFp(const EC_GROUP *group, BIGNUM *out_p, + BIGNUM *out_a, BIGNUM *out_b, + BN_CTX *ctx); + +/* EC_GROUP_get_curve_name returns a NID that identifies |group|. */ +OPENSSL_EXPORT int EC_GROUP_get_curve_name(const EC_GROUP *group); + +/* EC_GROUP_get_degree returns the number of bits needed to represent an + * element of the field underlying |group|. */ +OPENSSL_EXPORT int EC_GROUP_get_degree(const EC_GROUP *group); + +/* EC_GROUP_precompute_mult precomputes multiplies of the generator in order to + * speed up operations that involve calculating generator multiples. It returns + * one on sucess and zero otherwise. If |ctx| is not NULL, it may be used. */ +OPENSSL_EXPORT int EC_GROUP_precompute_mult(EC_GROUP *group, BN_CTX *ctx); + +/* EC_GROUP_have_precompute_mult returns one if |group| contains precomputed + * generator multiples. */ +OPENSSL_EXPORT int EC_GROUP_have_precompute_mult(const EC_GROUP *group); + + +/* Points on elliptic curves. */ + +/* EC_POINT_new returns a fresh |EC_POINT| object in the given group, or NULL + * on error. */ +OPENSSL_EXPORT EC_POINT *EC_POINT_new(const EC_GROUP *group); + +/* EC_POINT_free frees |point| and the data that it points to. */ +OPENSSL_EXPORT void EC_POINT_free(EC_POINT *point); + +/* EC_POINT_clear_free clears the data that |point| points to, frees it and + * then frees |point| itself. */ +OPENSSL_EXPORT void EC_POINT_clear_free(EC_POINT *point); + +/* EC_POINT_copy sets |*dest| equal to |*src|. It returns one on success and + * zero otherwise. */ +OPENSSL_EXPORT int EC_POINT_copy(EC_POINT *dest, const EC_POINT *src); + +/* EC_POINT_dup returns a fresh |EC_POINT| that contains the same values as + * |src|, or NULL on error. */ +OPENSSL_EXPORT EC_POINT *EC_POINT_dup(const EC_POINT *src, + const EC_GROUP *group); + +/* EC_POINT_set_to_infinity sets |point| to be the "point at infinity" for the + * given group. */ +OPENSSL_EXPORT int EC_POINT_set_to_infinity(const EC_GROUP *group, + EC_POINT *point); + +/* EC_POINT_is_at_infinity returns one iff |point| is the point at infinity and + * zero otherwise. */ +OPENSSL_EXPORT int EC_POINT_is_at_infinity(const EC_GROUP *group, + const EC_POINT *point); + +/* EC_POINT_is_on_curve returns one if |point| is an element of |group| and + * zero otheriwse. If |ctx| is non-NULL, it may be used. */ +OPENSSL_EXPORT int EC_POINT_is_on_curve(const EC_GROUP *group, + const EC_POINT *point, BN_CTX *ctx); + +/* EC_POINT_cmp returns zero if |a| is equal to |b|, greater than zero is + * non-equal and -1 on error. If |ctx| is not NULL, it may be used. */ +OPENSSL_EXPORT int EC_POINT_cmp(const EC_GROUP *group, const EC_POINT *a, + const EC_POINT *b, BN_CTX *ctx); + +/* EC_POINT_make_affine converts |point| to affine form, internally. It returns + * one on success and zero otherwise. If |ctx| is not NULL, it may be used. */ +OPENSSL_EXPORT int EC_POINT_make_affine(const EC_GROUP *group, EC_POINT *point, + BN_CTX *ctx); + +/* EC_POINTs_make_affine converts |num| points from |points| to affine form, + * internally. It returns one on success and zero otherwise. If |ctx| is not + * NULL, it may be used. */ +OPENSSL_EXPORT int EC_POINTs_make_affine(const EC_GROUP *group, size_t num, + EC_POINT *points[], BN_CTX *ctx); + + +/* Point conversion. */ + +/* EC_POINT_get_affine_coordinates_GFp sets |x| and |y| to the affine value of + * |point| using |ctx|, if it's not NULL. It returns one on success and zero + * otherwise. */ +OPENSSL_EXPORT int EC_POINT_get_affine_coordinates_GFp(const EC_GROUP *group, + const EC_POINT *point, + BIGNUM *x, BIGNUM *y, + BN_CTX *ctx); + +/* EC_POINT_set_affine_coordinates sets the value of |p| to be (|x|, |y|). The + * |ctx| argument may be used if not NULL. */ +OPENSSL_EXPORT int EC_POINT_set_affine_coordinates_GFp(const EC_GROUP *group, + EC_POINT *point, + const BIGNUM *x, + const BIGNUM *y, + BN_CTX *ctx); + +/* EC_POINT_point2oct serialises |point| into the X9.62 form given by |form| + * into, at most, |len| bytes at |buf|. It returns the number of bytes written + * or zero on error if |buf| is non-NULL, else the number of bytes needed. The + * |ctx| argument may be used if not NULL. */ +OPENSSL_EXPORT size_t EC_POINT_point2oct(const EC_GROUP *group, + const EC_POINT *point, + point_conversion_form_t form, + uint8_t *buf, size_t len, BN_CTX *ctx); + +/* EC_POINT_oct2point sets |point| from |len| bytes of X9.62 format + * serialisation in |buf|. It returns one on success and zero otherwise. The + * |ctx| argument may be used if not NULL. */ +OPENSSL_EXPORT int EC_POINT_oct2point(const EC_GROUP *group, EC_POINT *point, + const uint8_t *buf, size_t len, + BN_CTX *ctx); + +/* EC_POINT_set_compressed_coordinates_GFp sets |point| to equal the point with + * the given |x| coordinate and the y coordinate specified by |y_bit| (see + * X9.62). It returns one on success and zero otherwise. */ +OPENSSL_EXPORT int EC_POINT_set_compressed_coordinates_GFp( + const EC_GROUP *group, EC_POINT *point, const BIGNUM *x, int y_bit, + BN_CTX *ctx); + + +/* Group operations. */ + +/* EC_POINT_add sets |r| equal to |a| plus |b|. It returns one on success and + * zero otherwise. If |ctx| is not NULL, it may be used. */ +OPENSSL_EXPORT int EC_POINT_add(const EC_GROUP *group, EC_POINT *r, + const EC_POINT *a, const EC_POINT *b, + BN_CTX *ctx); + +/* EC_POINT_dbl sets |r| equal to |a| plus |a|. It returns one on success and + * zero otherwise. If |ctx| is not NULL, it may be used. */ +OPENSSL_EXPORT int EC_POINT_dbl(const EC_GROUP *group, EC_POINT *r, + const EC_POINT *a, BN_CTX *ctx); + +/* EC_POINT_dbl sets |a| equal to minus |a|. It returns one on success and zero + * otherwise. If |ctx| is not NULL, it may be used. */ +OPENSSL_EXPORT int EC_POINT_invert(const EC_GROUP *group, EC_POINT *a, + BN_CTX *ctx); + +/* EC_POINT_mul sets r = generator*n + q*m. It returns one on success and zero + * otherwise. If |ctx| is not NULL, it may be used. */ +OPENSSL_EXPORT int EC_POINT_mul(const EC_GROUP *group, EC_POINT *r, + const BIGNUM *n, const EC_POINT *q, + const BIGNUM *m, BN_CTX *ctx); + +/* EC_POINTs_mul sets r = generator*n + sum(p[i]*m[i]). It returns one on + * success and zero otherwise. If |ctx| is not NULL, it may be used. */ +OPENSSL_EXPORT int EC_POINTs_mul(const EC_GROUP *group, EC_POINT *r, + const BIGNUM *n, size_t num, + const EC_POINT *p[], const BIGNUM *m[], + BN_CTX *ctx); + + +/* Deprecated functions. */ + +/* EC_GROUP_new_curve_GFp creates a new, arbitrary elliptic curve group based + * on the equation y² = x³ + a·x + b. It returns the new group or NULL on + * error. + * + * |EC_GROUP|s returned by this function will always compare as unequal via + * |EC_GROUP_cmp| (even to themselves). |EC_GROUP_get_curve_name| will always + * return |NID_undef|. */ +OPENSSL_EXPORT EC_GROUP *EC_GROUP_new_curve_GFp(const BIGNUM *p, + const BIGNUM *a, + const BIGNUM *b, BN_CTX *ctx); + +/* EC_GROUP_set_generator sets the generator for |group| to |generator|, which + * must have the given order and cofactor. This should only be used with + * |EC_GROUP| objects returned by |EC_GROUP_new_curve_GFp|. */ +OPENSSL_EXPORT int EC_GROUP_set_generator(EC_GROUP *group, + const EC_POINT *generator, + const BIGNUM *order, + const BIGNUM *cofactor); + +/* EC_GROUP_set_asn1_flag does nothing. */ +OPENSSL_EXPORT void EC_GROUP_set_asn1_flag(EC_GROUP *group, int flag); + +#define OPENSSL_EC_NAMED_CURVE 0 + +typedef struct ec_method_st EC_METHOD; + +/* EC_GROUP_method_of returns NULL. */ +OPENSSL_EXPORT const EC_METHOD *EC_GROUP_method_of(const EC_GROUP *group); + +/* EC_METHOD_get_field_type returns NID_X9_62_prime_field. */ +OPENSSL_EXPORT int EC_METHOD_get_field_type(const EC_METHOD *meth); + +/* EC_GROUP_set_point_conversion_form aborts the process if |form| is not + * |POINT_CONVERSION_UNCOMPRESSED| and otherwise does nothing. */ +OPENSSL_EXPORT void EC_GROUP_set_point_conversion_form( + EC_GROUP *group, point_conversion_form_t form); + + +/* Old code expects to get EC_KEY from ec.h. */ +#if !defined(OPENSSL_HEADER_EC_KEY_H) +#include +#endif + + +#if defined(__cplusplus) +} /* extern C */ +#endif + +#define EC_F_EC_GROUP_copy 100 +#define EC_F_EC_GROUP_get_curve_GFp 101 +#define EC_F_EC_GROUP_get_degree 102 +#define EC_F_EC_GROUP_new_by_curve_name 103 +#define EC_F_EC_KEY_check_key 104 +#define EC_F_EC_KEY_copy 105 +#define EC_F_EC_KEY_generate_key 106 +#define EC_F_EC_KEY_new_method 107 +#define EC_F_EC_KEY_set_public_key_affine_coordinates 108 +#define EC_F_EC_POINT_add 109 +#define EC_F_EC_POINT_cmp 110 +#define EC_F_EC_POINT_copy 111 +#define EC_F_EC_POINT_dbl 112 +#define EC_F_EC_POINT_dup 113 +#define EC_F_EC_POINT_get_affine_coordinates_GFp 114 +#define EC_F_EC_POINT_invert 115 +#define EC_F_EC_POINT_is_at_infinity 116 +#define EC_F_EC_POINT_is_on_curve 117 +#define EC_F_EC_POINT_make_affine 118 +#define EC_F_EC_POINT_new 119 +#define EC_F_EC_POINT_oct2point 120 +#define EC_F_EC_POINT_point2oct 121 +#define EC_F_EC_POINT_set_affine_coordinates_GFp 122 +#define EC_F_EC_POINT_set_compressed_coordinates_GFp 123 +#define EC_F_EC_POINT_set_to_infinity 124 +#define EC_F_EC_POINTs_make_affine 125 +#define EC_F_compute_wNAF 126 +#define EC_F_d2i_ECPKParameters 127 +#define EC_F_d2i_ECParameters 128 +#define EC_F_d2i_ECPrivateKey 129 +#define EC_F_ec_GFp_mont_field_decode 130 +#define EC_F_ec_GFp_mont_field_encode 131 +#define EC_F_ec_GFp_mont_field_mul 132 +#define EC_F_ec_GFp_mont_field_set_to_one 133 +#define EC_F_ec_GFp_mont_field_sqr 134 +#define EC_F_ec_GFp_mont_group_set_curve 135 +#define EC_F_ec_GFp_simple_group_check_discriminant 136 +#define EC_F_ec_GFp_simple_group_set_curve 137 +#define EC_F_ec_GFp_simple_make_affine 138 +#define EC_F_ec_GFp_simple_oct2point 139 +#define EC_F_ec_GFp_simple_point2oct 140 +#define EC_F_ec_GFp_simple_point_get_affine_coordinates 141 +#define EC_F_ec_GFp_simple_point_set_affine_coordinates 142 +#define EC_F_ec_GFp_simple_points_make_affine 143 +#define EC_F_ec_GFp_simple_set_compressed_coordinates 144 +#define EC_F_ec_asn1_group2pkparameters 145 +#define EC_F_ec_asn1_pkparameters2group 146 +#define EC_F_ec_group_new 147 +#define EC_F_ec_group_new_curve_GFp 148 +#define EC_F_ec_group_new_from_data 149 +#define EC_F_ec_point_set_Jprojective_coordinates_GFp 150 +#define EC_F_ec_pre_comp_new 151 +#define EC_F_ec_wNAF_mul 152 +#define EC_F_ec_wNAF_precompute_mult 153 +#define EC_F_i2d_ECPKParameters 154 +#define EC_F_i2d_ECParameters 155 +#define EC_F_i2d_ECPrivateKey 156 +#define EC_F_i2o_ECPublicKey 157 +#define EC_F_o2i_ECPublicKey 158 +#define EC_F_BN_to_felem 159 +#define EC_F_ec_GFp_nistp256_group_set_curve 160 +#define EC_F_ec_GFp_nistp256_point_get_affine_coordinates 161 +#define EC_F_ec_GFp_nistp256_points_mul 162 +#define EC_F_ec_group_copy 163 +#define EC_F_nistp256_pre_comp_new 164 +#define EC_F_EC_KEY_new_by_curve_name 165 +#define EC_F_EC_GROUP_new_curve_GFp 166 +#define EC_R_BUFFER_TOO_SMALL 100 +#define EC_R_COORDINATES_OUT_OF_RANGE 101 +#define EC_R_D2I_ECPKPARAMETERS_FAILURE 102 +#define EC_R_EC_GROUP_NEW_BY_NAME_FAILURE 103 +#define EC_R_GROUP2PKPARAMETERS_FAILURE 104 +#define EC_R_I2D_ECPKPARAMETERS_FAILURE 105 +#define EC_R_INCOMPATIBLE_OBJECTS 106 +#define EC_R_INVALID_COMPRESSED_POINT 107 +#define EC_R_INVALID_COMPRESSION_BIT 108 +#define EC_R_INVALID_ENCODING 109 +#define EC_R_INVALID_FIELD 110 +#define EC_R_INVALID_FORM 111 +#define EC_R_INVALID_GROUP_ORDER 112 +#define EC_R_INVALID_PRIVATE_KEY 113 +#define EC_R_MISSING_PARAMETERS 114 +#define EC_R_MISSING_PRIVATE_KEY 115 +#define EC_R_NON_NAMED_CURVE 116 +#define EC_R_NOT_INITIALIZED 117 +#define EC_R_PKPARAMETERS2GROUP_FAILURE 118 +#define EC_R_POINT_AT_INFINITY 119 +#define EC_R_POINT_IS_NOT_ON_CURVE 120 +#define EC_R_SLOT_FULL 121 +#define EC_R_UNDEFINED_GENERATOR 122 +#define EC_R_UNKNOWN_GROUP 123 +#define EC_R_UNKNOWN_ORDER 124 +#define EC_R_WRONG_ORDER 125 +#define EC_R_BIGNUM_OUT_OF_RANGE 126 +#define EC_R_WRONG_CURVE_PARAMETERS 127 + +#endif /* OPENSSL_HEADER_EC_H */ diff --git a/phonelibs/boringssl/include/openssl/ec_key.h b/phonelibs/boringssl/include/openssl/ec_key.h new file mode 100644 index 00000000000000..ee64030b8efca9 --- /dev/null +++ b/phonelibs/boringssl/include/openssl/ec_key.h @@ -0,0 +1,286 @@ +/* Originally written by Bodo Moeller for the OpenSSL project. + * ==================================================================== + * Copyright (c) 1998-2005 The OpenSSL Project. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * + * 3. All advertising materials mentioning features or use of this + * software must display the following acknowledgment: + * "This product includes software developed by the OpenSSL Project + * for use in the OpenSSL Toolkit. (http://www.openssl.org/)" + * + * 4. The names "OpenSSL Toolkit" and "OpenSSL Project" must not be used to + * endorse or promote products derived from this software without + * prior written permission. For written permission, please contact + * openssl-core@openssl.org. + * + * 5. Products derived from this software may not be called "OpenSSL" + * nor may "OpenSSL" appear in their names without prior written + * permission of the OpenSSL Project. + * + * 6. Redistributions of any form whatsoever must retain the following + * acknowledgment: + * "This product includes software developed by the OpenSSL Project + * for use in the OpenSSL Toolkit (http://www.openssl.org/)" + * + * THIS SOFTWARE IS PROVIDED BY THE OpenSSL PROJECT ``AS IS'' AND ANY + * EXPRESSED OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR + * PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE OpenSSL PROJECT OR + * ITS CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, + * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT + * NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + * STRICT LIABILITY, OR TORT (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 product includes cryptographic software written by Eric Young + * (eay@cryptsoft.com). This product includes software written by Tim + * Hudson (tjh@cryptsoft.com). + * + */ +/* ==================================================================== + * Copyright 2002 Sun Microsystems, Inc. ALL RIGHTS RESERVED. + * + * Portions of the attached software ("Contribution") are developed by + * SUN MICROSYSTEMS, INC., and are contributed to the OpenSSL project. + * + * The Contribution is licensed pursuant to the OpenSSL open source + * license provided above. + * + * The elliptic curve binary polynomial software is originally written by + * Sheueling Chang Shantz and Douglas Stebila of Sun Microsystems + * Laboratories. */ + +#ifndef OPENSSL_HEADER_EC_KEY_H +#define OPENSSL_HEADER_EC_KEY_H + +#include + +#include +#include +#include + +#if defined(__cplusplus) +extern "C" { +#endif + + +/* ec_key.h contains functions that handle elliptic-curve points that are + * public/private keys. */ + + +/* EC key objects. */ + +/* EC_KEY_new returns a fresh |EC_KEY| object or NULL on error. */ +OPENSSL_EXPORT EC_KEY *EC_KEY_new(void); + +/* EC_KEY_new_method acts the same as |EC_KEY_new|, but takes an explicit + * |ENGINE|. */ +OPENSSL_EXPORT EC_KEY *EC_KEY_new_method(const ENGINE *engine); + +/* EC_KEY_new_by_curve_name returns a fresh EC_KEY for group specified by |nid| + * or NULL on error. */ +OPENSSL_EXPORT EC_KEY *EC_KEY_new_by_curve_name(int nid); + +/* EC_KEY_free frees all the data owned by |key| and |key| itself. */ +OPENSSL_EXPORT void EC_KEY_free(EC_KEY *key); + +/* EC_KEY_copy sets |dst| equal to |src| and returns |dst| or NULL on error. */ +OPENSSL_EXPORT EC_KEY *EC_KEY_copy(EC_KEY *dst, const EC_KEY *src); + +/* EC_KEY_dup returns a fresh copy of |src| or NULL on error. */ +OPENSSL_EXPORT EC_KEY *EC_KEY_dup(const EC_KEY *src); + +/* EC_KEY_up_ref increases the reference count of |key|. It returns one on + * success and zero otherwise. */ +OPENSSL_EXPORT int EC_KEY_up_ref(EC_KEY *key); + +/* EC_KEY_is_opaque returns one if |key| is opaque and doesn't expose its key + * material. Otherwise it return zero. */ +OPENSSL_EXPORT int EC_KEY_is_opaque(const EC_KEY *key); + +/* EC_KEY_get0_group returns a pointer to the |EC_GROUP| object inside |key|. */ +OPENSSL_EXPORT const EC_GROUP *EC_KEY_get0_group(const EC_KEY *key); + +/* EC_KEY_set_group sets the |EC_GROUP| object that |key| will use to |group|. + * It returns one on success and zero otherwise. */ +OPENSSL_EXPORT int EC_KEY_set_group(EC_KEY *key, const EC_GROUP *group); + +/* EC_KEY_get0_private_key returns a pointer to the private key inside |key|. */ +OPENSSL_EXPORT const BIGNUM *EC_KEY_get0_private_key(const EC_KEY *key); + +/* EC_KEY_set_private_key sets the private key of |key| to |priv|. It returns + * one on success and zero otherwise. */ +OPENSSL_EXPORT int EC_KEY_set_private_key(EC_KEY *key, const BIGNUM *prv); + +/* EC_KEY_get0_public_key returns a pointer to the public key point inside + * |key|. */ +OPENSSL_EXPORT const EC_POINT *EC_KEY_get0_public_key(const EC_KEY *key); + +/* EC_KEY_set_public_key sets the public key of |key| to |pub|, by copying it. + * It returns one on success and zero otherwise. */ +OPENSSL_EXPORT int EC_KEY_set_public_key(EC_KEY *key, const EC_POINT *pub); + +#define EC_PKEY_NO_PARAMETERS 0x001 +#define EC_PKEY_NO_PUBKEY 0x002 + +/* EC_KEY_get_enc_flags returns the encoding flags for |key|, which is a + * bitwise-OR of |EC_PKEY_*| values. */ +OPENSSL_EXPORT unsigned EC_KEY_get_enc_flags(const EC_KEY *key); + +/* EC_KEY_set_enc_flags sets the encoding flags for |key|, which is a + * bitwise-OR of |EC_PKEY_*| values. */ +OPENSSL_EXPORT void EC_KEY_set_enc_flags(EC_KEY *key, unsigned flags); + +/* EC_KEY_get_conv_form returns the conversation form that will be used by + * |key|. */ +OPENSSL_EXPORT point_conversion_form_t EC_KEY_get_conv_form(const EC_KEY *key); + +/* EC_KEY_set_conv_form sets the conversion form to be used by |key|. */ +OPENSSL_EXPORT void EC_KEY_set_conv_form(EC_KEY *key, + point_conversion_form_t cform); + +/* EC_KEY_precompute_mult precomputes multiplies of the generator of the + * underlying group in order to speed up operations that calculate generator + * multiples. If |ctx| is not NULL, it may be used. It returns one on success + * and zero otherwise. */ +OPENSSL_EXPORT int EC_KEY_precompute_mult(EC_KEY *key, BN_CTX *ctx); + +/* EC_KEY_check_key performs several checks on |key| (possibly including an + * expensive check that the public key is in the primary subgroup). It returns + * one if all checks pass and zero otherwise. If it returns zero then detail + * about the problem can be found on the error stack. */ +OPENSSL_EXPORT int EC_KEY_check_key(const EC_KEY *key); + +/* EC_KEY_set_public_key_affine_coordinates sets the public key in |key| to + * (|x|, |y|). It returns one on success and zero otherwise. */ +OPENSSL_EXPORT int EC_KEY_set_public_key_affine_coordinates(EC_KEY *key, + BIGNUM *x, + BIGNUM *y); + + +/* Key generation. */ + +/* EC_KEY_generate_key generates a random, private key, calculates the + * corresponding public key and stores both in |key|. It returns one on success + * or zero otherwise. */ +OPENSSL_EXPORT int EC_KEY_generate_key(EC_KEY *key); + + +/* Serialisation. */ + +/* d2i_ECPrivateKey parses an ASN.1, DER-encoded, private key from |len| bytes + * at |*inp|. If |out_key| is not NULL then, on exit, a pointer to the result + * is in |*out_key|. If |*out_key| is already non-NULL on entry then the result + * is written directly into |*out_key|, otherwise a fresh |EC_KEY| is + * allocated. On successful exit, |*inp| is advanced past the DER structure. It + * returns the result or NULL on error. */ +OPENSSL_EXPORT EC_KEY *d2i_ECPrivateKey(EC_KEY **out_key, const uint8_t **inp, + long len); + +/* i2d_ECParameters marshals an EC private key from |key| to an ASN.1, DER + * structure. If |outp| is not NULL then the result is written to |*outp| and + * |*outp| is advanced just past the output. It returns the number of bytes in + * the result, whether written or not, or a negative value on error. */ +OPENSSL_EXPORT int i2d_ECPrivateKey(const EC_KEY *key, uint8_t **outp); + +/* d2i_ECParameters parses an ASN.1, DER-encoded, set of EC parameters from + * |len| bytes at |*inp|. If |out_key| is not NULL then, on exit, a pointer to + * the result is in |*out_key|. If |*out_key| is already non-NULL on entry then + * the result is written directly into |*out_key|, otherwise a fresh |EC_KEY| + * is allocated. On successful exit, |*inp| is advanced past the DER structure. + * It returns the result or NULL on error. */ +OPENSSL_EXPORT EC_KEY *d2i_ECParameters(EC_KEY **out_key, const uint8_t **inp, + long len); + +/* i2d_ECParameters marshals EC parameters from |key| to an ASN.1, DER + * structure. If |outp| is not NULL then the result is written to |*outp| and + * |*outp| is advanced just past the output. It returns the number of bytes in + * the result, whether written or not, or a negative value on error. */ +OPENSSL_EXPORT int i2d_ECParameters(const EC_KEY *key, uint8_t **outp); + +/* o2i_ECPublicKey parses an EC point from |len| bytes at |*inp| into + * |*out_key|. Note that this differs from the d2i format in that |*out_key| + * must be non-NULL. On successful exit, |*inp| is advanced past the DER + * structure. It returns |*out_key| or NULL on error. */ +OPENSSL_EXPORT EC_KEY *o2i_ECPublicKey(EC_KEY **out_key, const uint8_t **inp, + long len); + +/* i2o_ECPublicKey marshals an EC point from |key|. If |outp| is not NULL then + * the result is written to |*outp| and |*outp| is advanced just past the + * output. It returns the number of bytes in the result, whether written or + * not, or a negative value on error. */ +OPENSSL_EXPORT int i2o_ECPublicKey(const EC_KEY *key, unsigned char **outp); + + +/* ex_data functions. + * + * These functions are wrappers. See |ex_data.h| for details. */ + +OPENSSL_EXPORT int EC_KEY_get_ex_new_index(long argl, void *argp, + CRYPTO_EX_new *new_func, + CRYPTO_EX_dup *dup_func, + CRYPTO_EX_free *free_func); +OPENSSL_EXPORT int EC_KEY_set_ex_data(EC_KEY *r, int idx, void *arg); +OPENSSL_EXPORT void *EC_KEY_get_ex_data(const EC_KEY *r, int idx); + + +/* ECDSA method. */ + +/* ECDSA_FLAG_OPAQUE specifies that this ECDSA_METHOD does not expose its key + * material. This may be set if, for instance, it is wrapping some other crypto + * API, like a platform key store. */ +#define ECDSA_FLAG_OPAQUE 1 + +/* ecdsa_method_st is a structure of function pointers for implementing ECDSA. + * See engine.h. */ +struct ecdsa_method_st { + struct openssl_method_common_st common; + + void *app_data; + + int (*init)(EC_KEY *key); + int (*finish)(EC_KEY *key); + + /* group_order_size returns the number of bytes needed to represent the order + * of the group. This is used to calculate the maximum size of an ECDSA + * signature in |ECDSA_size|. */ + size_t (*group_order_size)(const EC_KEY *key); + + /* sign matches the arguments and behaviour of |ECDSA_sign|. */ + int (*sign)(const uint8_t *digest, size_t digest_len, uint8_t *sig, + unsigned int *sig_len, EC_KEY *eckey); + + /* verify matches the arguments and behaviour of |ECDSA_verify|. */ + int (*verify)(const uint8_t *digest, size_t digest_len, const uint8_t *sig, + size_t sig_len, EC_KEY *eckey); + + int flags; +}; + + +/* Deprecated functions. */ + +/* EC_KEY_set_asn1_flag does nothing. */ +OPENSSL_EXPORT void EC_KEY_set_asn1_flag(EC_KEY *key, int flag); + + +#if defined(__cplusplus) +} /* extern C */ +#endif + +#endif /* OPENSSL_HEADER_EC_KEY_H */ diff --git a/phonelibs/boringssl/include/openssl/ecdh.h b/phonelibs/boringssl/include/openssl/ecdh.h new file mode 100644 index 00000000000000..27a85781275ddf --- /dev/null +++ b/phonelibs/boringssl/include/openssl/ecdh.h @@ -0,0 +1,103 @@ +/* ==================================================================== + * Copyright 2002 Sun Microsystems, Inc. ALL RIGHTS RESERVED. + * + * The Elliptic Curve Public-Key Crypto Library (ECC Code) included + * herein is developed by SUN MICROSYSTEMS, INC., and is contributed + * to the OpenSSL project. + * + * The ECC Code is licensed pursuant to the OpenSSL open source + * license provided below. + * + * The ECDH software is originally written by Douglas Stebila of + * Sun Microsystems Laboratories. + * + */ +/* ==================================================================== + * Copyright (c) 2000-2002 The OpenSSL Project. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * + * 3. All advertising materials mentioning features or use of this + * software must display the following acknowledgment: + * "This product includes software developed by the OpenSSL Project + * for use in the OpenSSL Toolkit. (http://www.OpenSSL.org/)" + * + * 4. The names "OpenSSL Toolkit" and "OpenSSL Project" must not be used to + * endorse or promote products derived from this software without + * prior written permission. For written permission, please contact + * licensing@OpenSSL.org. + * + * 5. Products derived from this software may not be called "OpenSSL" + * nor may "OpenSSL" appear in their names without prior written + * permission of the OpenSSL Project. + * + * 6. Redistributions of any form whatsoever must retain the following + * acknowledgment: + * "This product includes software developed by the OpenSSL Project + * for use in the OpenSSL Toolkit (http://www.OpenSSL.org/)" + * + * THIS SOFTWARE IS PROVIDED BY THE OpenSSL PROJECT ``AS IS'' AND ANY + * EXPRESSED OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR + * PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE OpenSSL PROJECT OR + * ITS CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, + * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT + * NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + * STRICT LIABILITY, OR TORT (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 product includes cryptographic software written by Eric Young + * (eay@cryptsoft.com). This product includes software written by Tim + * Hudson (tjh@cryptsoft.com). */ + +#ifndef OPENSSL_HEADER_ECDH_H +#define OPENSSL_HEADER_ECDH_H + +#include + +#include + +#if defined(__cplusplus) +extern "C" { +#endif + + +/* Elliptic curve Diffie-Hellman. */ + + +/* ECDH_compute_key calculates the shared key between |pub_key| and |priv_key|. + * If |KDF| is not NULL, then it is called with the bytes of the shared key and + * the parameter |out|. When |KDF| returns, the value of |*outlen| becomes the + * return value. Otherwise, as many bytes of the shared key as will fit are + * copied directly to, at most, |outlen| bytes at |out|. It returns the number + * of bytes written to |out|, or -1 on error. */ +OPENSSL_EXPORT int ECDH_compute_key(void *out, size_t outlen, + const EC_POINT *pub_key, EC_KEY *priv_key, + void *(*KDF)(const void *in, size_t inlen, + void *out, size_t *outlen)); + + +#if defined(__cplusplus) +} /* extern C */ +#endif + +#define ECDH_F_ECDH_compute_key 100 +#define ECDH_R_KDF_FAILED 100 +#define ECDH_R_NO_PRIVATE_VALUE 101 +#define ECDH_R_POINT_ARITHMETIC_FAILURE 102 + +#endif /* OPENSSL_HEADER_ECDH_H */ diff --git a/phonelibs/boringssl/include/openssl/ecdsa.h b/phonelibs/boringssl/include/openssl/ecdsa.h new file mode 100644 index 00000000000000..e04546345660c3 --- /dev/null +++ b/phonelibs/boringssl/include/openssl/ecdsa.h @@ -0,0 +1,182 @@ +/* ==================================================================== + * Copyright (c) 1998-2005 The OpenSSL Project. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * + * 3. All advertising materials mentioning features or use of this + * software must display the following acknowledgment: + * "This product includes software developed by the OpenSSL Project + * for use in the OpenSSL Toolkit. (http://www.OpenSSL.org/)" + * + * 4. The names "OpenSSL Toolkit" and "OpenSSL Project" must not be used to + * endorse or promote products derived from this software without + * prior written permission. For written permission, please contact + * openssl-core@OpenSSL.org. + * + * 5. Products derived from this software may not be called "OpenSSL" + * nor may "OpenSSL" appear in their names without prior written + * permission of the OpenSSL Project. + * + * 6. Redistributions of any form whatsoever must retain the following + * acknowledgment: + * "This product includes software developed by the OpenSSL Project + * for use in the OpenSSL Toolkit (http://www.OpenSSL.org/)" + * + * THIS SOFTWARE IS PROVIDED BY THE OpenSSL PROJECT ``AS IS'' AND ANY + * EXPRESSED OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR + * PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE OpenSSL PROJECT OR + * ITS CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, + * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT + * NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + * STRICT LIABILITY, OR TORT (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 product includes cryptographic software written by Eric Young + * (eay@cryptsoft.com). This product includes software written by Tim + * Hudson (tjh@cryptsoft.com). */ + +#ifndef OPENSSL_HEADER_ECDSA_H +#define OPENSSL_HEADER_ECDSA_H + +#include + +#include + +#if defined(__cplusplus) +extern "C" { +#endif + + +/* ECDSA contains functions for signing and verifying with the Digital Signature + * Algorithm over elliptic curves. */ + + +/* Signing and verifing. */ + +/* ECDSA_sign signs |digest_len| bytes from |digest| with |key| and writes the + * resulting signature to |sig|, which must have |ECDSA_size(key)| bytes of + * space. On successful exit, |*sig_len| is set to the actual number of bytes + * written. The |type| argument should be zero. It returns one on success and + * zero otherwise. */ +OPENSSL_EXPORT int ECDSA_sign(int type, const uint8_t *digest, + size_t digest_len, uint8_t *sig, + unsigned int *sig_len, EC_KEY *key); + +/* ECDSA_verify verifies that |sig_len| bytes from |sig| constitute a valid + * signature by |key| of |digest|. (The |type| argument should be zero.) It + * returns one on success or zero if the signature is invalid or an error + * occured. */ +OPENSSL_EXPORT int ECDSA_verify(int type, const uint8_t *digest, + size_t digest_len, const uint8_t *sig, + size_t sig_len, EC_KEY *key); + +/* ECDSA_size returns the maximum size of an ECDSA signature using |key|. It + * returns zero on error. */ +OPENSSL_EXPORT size_t ECDSA_size(const EC_KEY *key); + + +/* Low-level signing and verification. + * + * Low-level functions handle signatures as |ECDSA_SIG| structures which allow + * the two values in an ECDSA signature to be handled separately. */ + +struct ecdsa_sig_st { + BIGNUM *r; + BIGNUM *s; +}; + +/* ECDSA_SIG_new returns a fresh |ECDSA_SIG| structure or NULL on error. */ +OPENSSL_EXPORT ECDSA_SIG *ECDSA_SIG_new(void); + +/* ECDSA_SIG_free frees |sig| its member |BIGNUM|s. */ +OPENSSL_EXPORT void ECDSA_SIG_free(ECDSA_SIG *sig); + +/* ECDSA_sign signs |digest_len| bytes from |digest| with |key| and returns the + * resulting signature structure, or NULL on error. */ +OPENSSL_EXPORT ECDSA_SIG *ECDSA_do_sign(const uint8_t *digest, + size_t digest_len, EC_KEY *key); + +/* ECDSA_verify verifies that |sig| constitutes a valid signature by |key| of + * |digest|. It returns one on success or zero if the signature is invalid or + * on error. */ +OPENSSL_EXPORT int ECDSA_do_verify(const uint8_t *digest, size_t digest_len, + const ECDSA_SIG *sig, EC_KEY *key); + + +/* Signing with precomputation. + * + * Parts of the ECDSA signature can be independent of the message to be signed + * thus it's possible to precompute them and reduce the signing latency. + * + * TODO(fork): remove support for this as it cannot support safe-randomness. */ + +/* ECDSA_sign_setup precomputes parts of an ECDSA signing operation. It sets + * |*kinv| and |*rp| to the precomputed values and uses the |ctx| argument, if + * not NULL. It returns one on success and zero otherwise. */ +OPENSSL_EXPORT int ECDSA_sign_setup(EC_KEY *eckey, BN_CTX *ctx, BIGNUM **kinv, + BIGNUM **rp); + +/* ECDSA_do_sign_ex is the same as |ECDSA_do_sign| but takes precomputed values + * as generated by |ECDSA_sign_setup|. */ +OPENSSL_EXPORT ECDSA_SIG *ECDSA_do_sign_ex(const uint8_t *digest, + size_t digest_len, + const BIGNUM *kinv, const BIGNUM *rp, + EC_KEY *eckey); + +/* ECDSA_sign_ex is the same as |ECDSA_sign| but takes precomputed values as + * generated by |ECDSA_sign_setup|. */ +OPENSSL_EXPORT int ECDSA_sign_ex(int type, const uint8_t *digest, + size_t digest_len, uint8_t *sig, + unsigned int *sig_len, const BIGNUM *kinv, + const BIGNUM *rp, EC_KEY *eckey); + + +/* ASN.1 functions. */ + +/* d2i_ECDSA_SIG parses an ASN.1, DER-encoded, signature from |len| bytes at + * |*inp|. If |out| is not NULL then, on exit, a pointer to the result is in + * |*out|. If |*out| is already non-NULL on entry then the result is written + * directly into |*out|, otherwise a fresh |ECDSA_SIG| is allocated. On + * successful exit, |*inp| is advanced past the DER structure. It returns the + * result or NULL on error. */ +OPENSSL_EXPORT ECDSA_SIG *d2i_ECDSA_SIG(ECDSA_SIG **out, const uint8_t **inp, + long len); + +/* i2d_ECDSA_SIG marshals a signature from |sig| to an ASN.1, DER + * structure. If |outp| is not NULL then the result is written to |*outp| and + * |*outp| is advanced just past the output. It returns the number of bytes in + * the result, whether written or not, or a negative value on error. */ +OPENSSL_EXPORT int i2d_ECDSA_SIG(const ECDSA_SIG *sig, uint8_t **outp); + + +#if defined(__cplusplus) +} /* extern C */ +#endif + +#define ECDSA_F_ECDSA_do_sign_ex 100 +#define ECDSA_F_ECDSA_do_verify 101 +#define ECDSA_F_ECDSA_sign_ex 102 +#define ECDSA_F_digest_to_bn 103 +#define ECDSA_F_ecdsa_sign_setup 104 +#define ECDSA_R_BAD_SIGNATURE 100 +#define ECDSA_R_MISSING_PARAMETERS 101 +#define ECDSA_R_NEED_NEW_SETUP_VALUES 102 +#define ECDSA_R_NOT_IMPLEMENTED 103 +#define ECDSA_R_RANDOM_NUMBER_GENERATION_FAILED 104 + +#endif /* OPENSSL_HEADER_ECDSA_H */ diff --git a/phonelibs/boringssl/include/openssl/engine.h b/phonelibs/boringssl/include/openssl/engine.h new file mode 100644 index 00000000000000..d3d278a69b77a4 --- /dev/null +++ b/phonelibs/boringssl/include/openssl/engine.h @@ -0,0 +1,107 @@ +/* Copyright (c) 2014, Google Inc. + * + * Permission to use, copy, modify, and/or distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY + * SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN ACTION + * OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF OR IN + * CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. */ + +#ifndef OPENSSL_HEADER_ENGINE_H +#define OPENSSL_HEADER_ENGINE_H + +#include + +#if defined(__cplusplus) +extern "C" { +#endif + + +/* Engines are collections of methods. Methods are tables of function pointers, + * defined for certain algorithms, that allow operations on those algorithms to + * be overridden via a callback. This can be used, for example, to implement an + * RSA* that forwards operations to a hardware module. + * + * Methods are reference counted but |ENGINE|s are not. When creating a method, + * you should zero the whole structure and fill in the function pointers that + * you wish before setting it on an |ENGINE|. Any functions pointers that + * are NULL indicate that the default behaviour should be used. */ + + +/* Allocation and destruction. */ + +/* ENGINE_new returns an empty ENGINE that uses the default method for all + * algorithms. */ +OPENSSL_EXPORT ENGINE *ENGINE_new(void); + +/* ENGINE_free decrements the reference counts for all methods linked from + * |engine| and frees |engine| itself. */ +OPENSSL_EXPORT void ENGINE_free(ENGINE *engine); + + +/* Method accessors. + * + * Method accessors take a method pointer and the size of the structure. The + * size allows for ABI compatibility in the case that the method structure is + * extended with extra elements at the end. Methods are always copied by the + * set functions. + * + * Set functions return one on success and zero on allocation failure. */ + +OPENSSL_EXPORT int ENGINE_set_DH_method(ENGINE *engine, const DH_METHOD *method, + size_t method_size); +OPENSSL_EXPORT DH_METHOD *ENGINE_get_DH_method(const ENGINE *engine); + +OPENSSL_EXPORT int ENGINE_set_DSA_method(ENGINE *engine, + const DSA_METHOD *method, + size_t method_size); +OPENSSL_EXPORT DSA_METHOD *ENGINE_get_DSA_method(const ENGINE *engine); + +OPENSSL_EXPORT int ENGINE_set_RSA_method(ENGINE *engine, + const RSA_METHOD *method, + size_t method_size); +OPENSSL_EXPORT RSA_METHOD *ENGINE_get_RSA_method(const ENGINE *engine); + +OPENSSL_EXPORT int ENGINE_set_ECDSA_method(ENGINE *engine, + const ECDSA_METHOD *method, + size_t method_size); +OPENSSL_EXPORT ECDSA_METHOD *ENGINE_get_ECDSA_method(const ENGINE *engine); + + +/* Generic method functions. + * + * These functions take a void* type but actually operate on all method + * structures. */ + +/* METHOD_ref increments the reference count of |method|. This is a no-op for + * now because all methods are currently static. */ +void METHOD_ref(void *method); + +/* METHOD_unref decrements the reference count of |method| and frees it if the + * reference count drops to zero. This is a no-op for now because all methods + * are currently static. */ +void METHOD_unref(void *method); + + +/* Private functions. */ + +/* openssl_method_common_st contains the common part of all method structures. + * This must be the first member of all method structures. */ +struct openssl_method_common_st { + int references; /* dummy – not used. */ + char is_static; +}; + + +#if defined(__cplusplus) +} /* extern C */ +#endif + +#define ENGINE_R_OPERATION_NOT_SUPPORTED 100 + +#endif /* OPENSSL_HEADER_ENGINE_H */ diff --git a/phonelibs/boringssl/include/openssl/err.h b/phonelibs/boringssl/include/openssl/err.h new file mode 100644 index 00000000000000..30dc4afe9b9a54 --- /dev/null +++ b/phonelibs/boringssl/include/openssl/err.h @@ -0,0 +1,509 @@ +/* Copyright (C) 1995-1998 Eric Young (eay@cryptsoft.com) + * All rights reserved. + * + * This package is an SSL implementation written + * by Eric Young (eay@cryptsoft.com). + * The implementation was written so as to conform with Netscapes SSL. + * + * This library is free for commercial and non-commercial use as long as + * the following conditions are aheared to. The following conditions + * apply to all code found in this distribution, be it the RC4, RSA, + * lhash, DES, etc., code; not just the SSL code. The SSL documentation + * included with this distribution is covered by the same copyright terms + * except that the holder is Tim Hudson (tjh@cryptsoft.com). + * + * Copyright remains Eric Young's, and as such any Copyright notices in + * the code are not to be removed. + * If this package is used in a product, Eric Young should be given attribution + * as the author of the parts of the library used. + * This can be in the form of a textual message at program startup or + * in documentation (online or textual) provided with the package. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must 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. All advertising materials mentioning features or use of this software + * must display the following acknowledgement: + * "This product includes cryptographic software written by + * Eric Young (eay@cryptsoft.com)" + * The word 'cryptographic' can be left out if the rouines from the library + * being used are not cryptographic related :-). + * 4. If you include any Windows specific code (or a derivative thereof) from + * the apps directory (application code) you must include an acknowledgement: + * "This product includes software written by Tim Hudson (tjh@cryptsoft.com)" + * + * THIS SOFTWARE IS PROVIDED BY ERIC YOUNG ``AS IS'' AND + * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHOR OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (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 licence and distribution terms for any publically available version or + * derivative of this code cannot be changed. i.e. this code cannot simply be + * copied and put under another distribution licence + * [including the GNU Public Licence.] + */ +/* ==================================================================== + * Copyright (c) 1998-2006 The OpenSSL Project. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * + * 3. All advertising materials mentioning features or use of this + * software must display the following acknowledgment: + * "This product includes software developed by the OpenSSL Project + * for use in the OpenSSL Toolkit. (http://www.openssl.org/)" + * + * 4. The names "OpenSSL Toolkit" and "OpenSSL Project" must not be used to + * endorse or promote products derived from this software without + * prior written permission. For written permission, please contact + * openssl-core@openssl.org. + * + * 5. Products derived from this software may not be called "OpenSSL" + * nor may "OpenSSL" appear in their names without prior written + * permission of the OpenSSL Project. + * + * 6. Redistributions of any form whatsoever must retain the following + * acknowledgment: + * "This product includes software developed by the OpenSSL Project + * for use in the OpenSSL Toolkit (http://www.openssl.org/)" + * + * THIS SOFTWARE IS PROVIDED BY THE OpenSSL PROJECT ``AS IS'' AND ANY + * EXPRESSED OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR + * PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE OpenSSL PROJECT OR + * ITS CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, + * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT + * NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + * STRICT LIABILITY, OR TORT (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 product includes cryptographic software written by Eric Young + * (eay@cryptsoft.com). This product includes software written by Tim + * Hudson (tjh@cryptsoft.com). */ + +#ifndef OPENSSL_HEADER_ERR_H +#define OPENSSL_HEADER_ERR_H + +#include + +#include + +#if defined(__cplusplus) +extern "C" { +#endif + + +/* Error queue handling functions. + * + * Errors in OpenSSL are generally signalled by the return value of a function. + * When a function fails it may add an entry to a per-thread error queue, + * which is managed by the functions in this header. + * + * Each error contains: + * 1) The library (i.e. ec, pem, rsa) which created it. + * 2) A function identifier and reason code. + * 3) The file and line number of the call that added the error. + * 4) A pointer to some error specific data, which may be NULL. + * + * The library identifier, function identifier and reason code are packed in a + * uint32_t and there exist various functions for unpacking it. + * + * The typical behaviour is that an error will occur deep in a call queue and + * that code will push an error onto the error queue. As the error queue + * unwinds, other functions will push their own errors. Thus, the "least + * recent" error is the most specific and the other errors will provide a + * backtrace of sorts. */ + + +/* Startup and shutdown. */ + +/* ERR_load_BIO_strings does nothing. + * + * TODO(fork): remove. libjingle calls this. */ +OPENSSL_EXPORT void ERR_load_BIO_strings(void); + +/* ERR_load_ERR_strings does nothing. */ +OPENSSL_EXPORT void ERR_load_ERR_strings(void); + +/* ERR_load_crypto_strings does nothing. */ +OPENSSL_EXPORT void ERR_load_crypto_strings(void); + +/* ERR_free_strings does nothing. */ +OPENSSL_EXPORT void ERR_free_strings(void); + + +/* Reading and formatting errors. */ + +/* ERR_get_error gets the packed error code for the least recent error and + * removes that error from the queue. If there are no errors in the queue then + * it returns zero. */ +OPENSSL_EXPORT uint32_t ERR_get_error(void); + +/* ERR_get_error_line acts like |ERR_get_error|, except that the file and line + * number of the call that added the error are also returned. */ +OPENSSL_EXPORT uint32_t ERR_get_error_line(const char **file, int *line); + +/* ERR_get_error_line_data acts like |ERR_get_error_line|, but also returns the + * error-specific data pointer and flags. The flags are a bitwise-OR of + * |ERR_FLAG_*| values. The error-specific data is owned by the error queue + * and the pointer becomes invalid after the next call that affects the same + * thread's error queue. If |*flags| contains |ERR_FLAG_STRING| then |*data| is + * human-readable. */ +OPENSSL_EXPORT uint32_t ERR_get_error_line_data(const char **file, int *line, + const char **data, int *flags); + +/* The "peek" functions act like the |ERR_get_error| functions, above, but they + * do not remove the error from the queue. */ +OPENSSL_EXPORT uint32_t ERR_peek_error(void); +OPENSSL_EXPORT uint32_t ERR_peek_error_line(const char **file, int *line); +OPENSSL_EXPORT uint32_t ERR_peek_error_line_data(const char **file, int *line, + const char **data, int *flags); + +/* The "peek last" functions act like the "peek" functions, above, except that + * they return the most recent error. */ +OPENSSL_EXPORT uint32_t ERR_peek_last_error(void); +OPENSSL_EXPORT uint32_t ERR_peek_last_error_line(const char **file, int *line); +OPENSSL_EXPORT uint32_t ERR_peek_last_error_line_data(const char **file, + int *line, + const char **data, + int *flags); + +/* ERR_error_string generates a human-readable string representing + * |packed_error|, places it at |buf| (which must be at least + * ERR_ERROR_STRING_BUF_LEN bytes long) and returns |buf|. If |buf| is NULL, + * the error string is placed in a static buffer which is returned. (The static + * buffer may be overridden by concurrent calls in other threads so this form + * is deprecated.) + * + * The string will have the following format: + * + * error:[error code]:[library name]:[function name]:[reason string] + * + * error code is an 8 digit hexadecimal number; library name, function name + * and reason string are ASCII text. + * + * TODO(fork): remove in favour of |ERR_error_string_n|. */ +OPENSSL_EXPORT char *ERR_error_string(uint32_t packed_error, char *buf); +#define ERR_ERROR_STRING_BUF_LEN 256 + +/* ERR_error_string_n is a variant of |ERR_error_string| that writes at most + * len characters (including the terminating NUL) and truncates the string if + * necessary. If |len| is greater than zero then |buf| is always NUL + * terminated. */ +OPENSSL_EXPORT void ERR_error_string_n(uint32_t packed_error, char *buf, + size_t len); + +/* ERR_lib_error_string returns a string representation of the library that + * generated |packed_error|. */ +OPENSSL_EXPORT const char *ERR_lib_error_string(uint32_t packed_error); + +/* ERR_func_error_string returns a string representation of the function that + * generated |packed_error|. */ +OPENSSL_EXPORT const char *ERR_func_error_string(uint32_t packed_error); + +/* ERR_reason_error_string returns a string representation of the reason for + * |packed_error|. */ +OPENSSL_EXPORT const char *ERR_reason_error_string(uint32_t packed_error); + +/* ERR_print_errors_callback_t is the type of a function used by + * |ERR_print_errors_cb|. It takes a pointer to a human readable string (and + * its length) that describes an entry in the error queue. The |ctx| argument + * is an opaque pointer given to |ERR_print_errors_cb|. + * + * It should return one on success or zero on error, which will stop the + * iteration over the error queue. */ +typedef int (*ERR_print_errors_callback_t)(const char *str, size_t len, + void *ctx); + +/* ERR_print_errors_cb calls |callback| with a string representation of each + * error in the current thread's error queue, from the least recent to the most + * recent error. + * + * The string will have the following format (which differs from + * |ERR_error_string|): + * + * [thread id]:error:[error code]:[library name]:[function name]: + * [reason string]:[file]:[line number]:[optional string data] + * + * (All in one line.) + * + * The callback can return one to continue the iteration or zero to stop it. + * The |ctx| argument is an opaque value that is passed through to the + * callback. */ +OPENSSL_EXPORT void ERR_print_errors_cb(ERR_print_errors_callback_t callback, + void *ctx); + + +/* ERR_print_errors_fp prints the current contents of the error stack to |file| + * using human readable strings where possible. */ +OPENSSL_EXPORT void ERR_print_errors_fp(FILE *file); + +/* Clearing errors. */ + +/* ERR_clear_error clears the error queue for the current thread. */ +OPENSSL_EXPORT void ERR_clear_error(void); + +/* ERR_remove_thread_state clears the error queue for the current thread if + * |tid| is NULL. Otherwise it calls |assert(0)|, because it's no longer + * possible to delete the error queue for other threads. + * + * Error queues are thread-local data and are deleted automatically. You do not + * need to call this function. Use |ERR_clear_error|. */ +OPENSSL_EXPORT void ERR_remove_thread_state(const CRYPTO_THREADID *tid); + + +/* Custom errors. */ + +/* ERR_get_next_error_library returns a value suitable for passing as the + * |library| argument to |ERR_put_error|. This is intended for code that wishes + * to push its own, non-standard errors to the error queue. */ +OPENSSL_EXPORT int ERR_get_next_error_library(void); + + +/* Deprecated functions. */ + +/* |ERR_remove_state| calls |ERR_clear_error|. */ +OPENSSL_EXPORT void ERR_remove_state(unsigned long pid); + + +/* Private functions. */ + +/* ERR_clear_system_error clears the system's error value (i.e. errno). */ +OPENSSL_EXPORT void ERR_clear_system_error(void); + +/* OPENSSL_PUT_ERROR is used by OpenSSL code to add an error to the error + * queue. */ +#define OPENSSL_PUT_ERROR(library, func, reason) \ + ERR_put_error(ERR_LIB_##library, library##_F_##func, reason, __FILE__, \ + __LINE__) + +/* OPENSSL_PUT_SYSTEM_ERROR is used by OpenSSL code to add an error from the + * operating system to the error queue. */ +/* TODO(fork): include errno. */ +#define OPENSSL_PUT_SYSTEM_ERROR(func) \ + ERR_put_error(ERR_LIB_SYS, SYS_F_##func, 0, __FILE__, __LINE__); + +/* ERR_put_error adds an error to the error queue, dropping the least recent + * error if neccessary for space reasons. */ +OPENSSL_EXPORT void ERR_put_error(int library, int func, int reason, + const char *file, unsigned line); + +/* ERR_add_error_data takes a variable number (|count|) of const char* + * pointers, concatenates them and sets the result as the data on the most + * recent error. */ +OPENSSL_EXPORT void ERR_add_error_data(unsigned count, ...); + +/* ERR_add_error_dataf takes a printf-style format and arguments, and sets the + * result as the data on the most recent error. */ +OPENSSL_EXPORT void ERR_add_error_dataf(const char *format, ...); + +/* ERR_set_mark "marks" the most recent error for use with |ERR_pop_to_mark|. + * It returns one if an error was marked and zero if there are no errors. */ +OPENSSL_EXPORT int ERR_set_mark(void); + +/* ERR_pop_to_mark removes errors from the most recent to the least recent + * until (and not including) a "marked" error. It returns zero if no marked + * error was found (and thus all errors were removed) and one otherwise. Errors + * are marked using |ERR_set_mark|. */ +OPENSSL_EXPORT int ERR_pop_to_mark(void); + +struct err_error_st { + /* file contains the filename where the error occured. */ + const char *file; + /* data contains optional data. It must be freed with |OPENSSL_free| if + * |flags&ERR_FLAG_MALLOCED|. */ + char *data; + /* packed contains the error library, function and reason, as packed by + * ERR_PACK. */ + uint32_t packed; + /* line contains the line number where the error occured. */ + uint16_t line; + /* flags contains a bitwise-OR of ERR_FLAG_* values. */ + uint8_t flags; +}; + +/* ERR_FLAG_STRING means that the |data| member is a NUL-terminated string that + * can be printed. */ +#define ERR_FLAG_STRING 1 +/* ERR_TXT_STRING is provided for compatibility with code that assumes that + * it's using OpenSSL. */ +#define ERR_TXT_STRING ERR_FLAG_STRING + +/* ERR_FLAG_PUBLIC_MASK is applied to the flags field before it is returned + * from functions like |ERR_get_error_line_data|. */ +#define ERR_FLAG_PUBLIC_MASK 0xf + +/* The following flag values are internal and are masked when flags are + * returned from functions like |ERR_get_error_line_data|. */ + +/* ERR_FLAG_MALLOCED means the the |data| member must be freed when no longer + * needed. */ +#define ERR_FLAG_MALLOCED 16 +/* ERR_FLAG_MARK is used to indicate a reversion point in the queue. See + * |ERR_pop_to_mark|. */ +#define ERR_FLAG_MARK 32 + +/* ERR_NUM_ERRORS is the limit of the number of errors in the queue. */ +#define ERR_NUM_ERRORS 16 + +/* ERR_STATE contains the per-thread, error queue. */ +typedef struct err_state_st { + /* errors contains the ERR_NUM_ERRORS most recent errors, organised as a ring + * buffer. */ + struct err_error_st errors[ERR_NUM_ERRORS]; + /* top contains the index one past the most recent error. If |top| equals + * |bottom| then the queue is empty. */ + unsigned top; + /* bottom contains the index of the last error in the queue. */ + unsigned bottom; + + /* to_free, if not NULL, contains a pointer owned by this structure that was + * previously a |data| pointer of one of the elements of |errors|. */ + void *to_free; +} ERR_STATE; + +enum { + ERR_LIB_NONE = 1, + ERR_LIB_SYS, + ERR_LIB_BN, + ERR_LIB_RSA, + ERR_LIB_DH, + ERR_LIB_EVP, + ERR_LIB_BUF, + ERR_LIB_OBJ, + ERR_LIB_PEM, + ERR_LIB_DSA, + ERR_LIB_X509, + ERR_LIB_ASN1, + ERR_LIB_CONF, + ERR_LIB_CRYPTO, + ERR_LIB_EC, + ERR_LIB_SSL, + ERR_LIB_BIO, + ERR_LIB_PKCS7, + ERR_LIB_PKCS8, + ERR_LIB_X509V3, + ERR_LIB_RAND, + ERR_LIB_ENGINE, + ERR_LIB_OCSP, + ERR_LIB_UI, + ERR_LIB_COMP, + ERR_LIB_ECDSA, + ERR_LIB_ECDH, + ERR_LIB_HMAC, + ERR_LIB_DIGEST, + ERR_LIB_CIPHER, + ERR_LIB_USER, + ERR_LIB_HKDF, + ERR_NUM_LIBS +}; + +#define ERR_R_SYS_LIB ERR_LIB_SYS +#define ERR_R_BN_LIB ERR_LIB_BN +#define ERR_R_RSA_LIB ERR_LIB_RSA +#define ERR_R_DH_LIB ERR_LIB_DH +#define ERR_R_EVP_LIB ERR_LIB_EVP +#define ERR_R_BUF_LIB ERR_LIB_BUF +#define ERR_R_OBJ_LIB ERR_LIB_OBJ +#define ERR_R_PEM_LIB ERR_LIB_PEM +#define ERR_R_DSA_LIB ERR_LIB_DSA +#define ERR_R_X509_LIB ERR_LIB_X509 +#define ERR_R_ASN1_LIB ERR_LIB_ASN1 +#define ERR_R_CONF_LIB ERR_LIB_CONF +#define ERR_R_CRYPTO_LIB ERR_LIB_CRYPTO +#define ERR_R_EC_LIB ERR_LIB_EC +#define ERR_R_SSL_LIB ERR_LIB_SSL +#define ERR_R_BIO_LIB ERR_LIB_BIO +#define ERR_R_PKCS7_LIB ERR_LIB_PKCS7 +#define ERR_R_PKCS8_LIB ERR_LIB_PKCS8 +#define ERR_R_X509V3_LIB ERR_LIB_X509V3 +#define ERR_R_RAND_LIB ERR_LIB_RAND +#define ERR_R_DSO_LIB ERR_LIB_DSO +#define ERR_R_ENGINE_LIB ERR_LIB_ENGINE +#define ERR_R_OCSP_LIB ERR_LIB_OCSP +#define ERR_R_UI_LIB ERR_LIB_UI +#define ERR_R_COMP_LIB ERR_LIB_COMP +#define ERR_R_ECDSA_LIB ERR_LIB_ECDSA +#define ERR_R_ECDH_LIB ERR_LIB_ECDH +#define ERR_R_STORE_LIB ERR_LIB_STORE +#define ERR_R_FIPS_LIB ERR_LIB_FIPS +#define ERR_R_CMS_LIB ERR_LIB_CMS +#define ERR_R_TS_LIB ERR_LIB_TS +#define ERR_R_HMAC_LIB ERR_LIB_HMAC +#define ERR_R_JPAKE_LIB ERR_LIB_JPAKE +#define ERR_R_USER_LIB ERR_LIB_USER +#define ERR_R_DIGEST_LIB ERR_LIB_DIGEST +#define ERR_R_CIPHER_LIB ERR_LIB_CIPHER +#define ERR_R_HKDF_LIB ERR_LIB_HKDF + +/* Global reasons. */ +#define ERR_R_FATAL 64 +#define ERR_R_MALLOC_FAILURE (1 | ERR_R_FATAL) +#define ERR_R_SHOULD_NOT_HAVE_BEEN_CALLED (2 | ERR_R_FATAL) +#define ERR_R_PASSED_NULL_PARAMETER (3 | ERR_R_FATAL) +#define ERR_R_INTERNAL_ERROR (4 | ERR_R_FATAL) +#define ERR_R_OVERFLOW (5 | ERR_R_FATAL) + +/* System error functions */ +#define SYS_F_fopen 100 +#define SYS_F_fclose 101 +#define SYS_F_fread 102 +#define SYS_F_fwrite 103 +#define SYS_F_socket 104 +#define SYS_F_setsockopt 105 +#define SYS_F_connect 106 +#define SYS_F_getaddrinfo 107 + +#define ERR_PACK(lib, func, reason) \ + (((((uint32_t)lib) & 0xff) << 24) | ((((uint32_t)func) & 0xfff) << 12) | \ + ((((uint32_t)reason) & 0xfff))) + +#define ERR_GET_LIB(packed_error) ((int)(((packed_error) >> 24) & 0xff)) +#define ERR_GET_FUNC(packed_error) ((int)(((packed_error) >> 12) & 0xfff)) +#define ERR_GET_REASON(packed_error) ((int)((packed_error) & 0xfff)) + +/* OPENSSL_DECLARE_ERROR_REASON is used by util/make_errors.h (which generates + * the error defines) to recognise that an additional reason value is needed. + * This is needed when the reason value is used outside of an + * |OPENSSL_PUT_ERROR| macro. The resulting define will be + * ${lib}_R_${reason}. */ +#define OPENSSL_DECLARE_ERROR_REASON(lib, reason) + +/* OPENSSL_DECLARE_ERROR_FUNCTION is used by util/make_errors.h (which + * generates the error * defines to recognise that an additional function value + * is needed. This is * needed when the function value is used outside of an + * |OPENSSL_PUT_ERROR| * macro. The resulting define will be + * ${lib}_F_${reason}. */ +#define OPENSSL_DECLARE_ERROR_FUNCTION(lib, function_name) + + +#if defined(__cplusplus) +} /* extern C */ +#endif + +#endif /* OPENSSL_HEADER_ERR_H */ diff --git a/phonelibs/boringssl/include/openssl/evp.h b/phonelibs/boringssl/include/openssl/evp.h new file mode 100644 index 00000000000000..490a9514c33281 --- /dev/null +++ b/phonelibs/boringssl/include/openssl/evp.h @@ -0,0 +1,826 @@ +/* Copyright (C) 1995-1998 Eric Young (eay@cryptsoft.com) + * All rights reserved. + * + * This package is an SSL implementation written + * by Eric Young (eay@cryptsoft.com). + * The implementation was written so as to conform with Netscapes SSL. + * + * This library is free for commercial and non-commercial use as long as + * the following conditions are aheared to. The following conditions + * apply to all code found in this distribution, be it the RC4, RSA, + * lhash, DES, etc., code; not just the SSL code. The SSL documentation + * included with this distribution is covered by the same copyright terms + * except that the holder is Tim Hudson (tjh@cryptsoft.com). + * + * Copyright remains Eric Young's, and as such any Copyright notices in + * the code are not to be removed. + * If this package is used in a product, Eric Young should be given attribution + * as the author of the parts of the library used. + * This can be in the form of a textual message at program startup or + * in documentation (online or textual) provided with the package. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must 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. All advertising materials mentioning features or use of this software + * must display the following acknowledgement: + * "This product includes cryptographic software written by + * Eric Young (eay@cryptsoft.com)" + * The word 'cryptographic' can be left out if the rouines from the library + * being used are not cryptographic related :-). + * 4. If you include any Windows specific code (or a derivative thereof) from + * the apps directory (application code) you must include an acknowledgement: + * "This product includes software written by Tim Hudson (tjh@cryptsoft.com)" + * + * THIS SOFTWARE IS PROVIDED BY ERIC YOUNG ``AS IS'' AND + * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHOR OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (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 licence and distribution terms for any publically available version or + * derivative of this code cannot be changed. i.e. this code cannot simply be + * copied and put under another distribution licence + * [including the GNU Public Licence.] */ + +#ifndef OPENSSL_HEADER_EVP_H +#define OPENSSL_HEADER_EVP_H + +#include + +#include + +/* OpenSSL included digest and cipher functions in this header so we include + * them for users that still expect that. + * + * TODO(fork): clean up callers so that they include what they use. */ +#include +#include +#include +#include + +#if defined(__cplusplus) +extern "C" { +#endif + + +/* EVP abstracts over public/private key algorithms. */ + + +/* Public key objects. */ + +/* EVP_PKEY_new creates a new, empty public-key object and returns it or NULL + * on allocation failure. */ +OPENSSL_EXPORT EVP_PKEY *EVP_PKEY_new(void); + +/* EVP_PKEY_free frees all data referenced by |pkey| and then frees |pkey| + * itself. */ +OPENSSL_EXPORT void EVP_PKEY_free(EVP_PKEY *pkey); + +/* EVP_PKEY_up_ref increments the reference count of |pkey| and returns it. */ +OPENSSL_EXPORT EVP_PKEY *EVP_PKEY_up_ref(EVP_PKEY *pkey); + +/* EVP_PKEY_is_opaque returns one if |pkey| is opaque. Opaque keys are backed by + * custom implementations which do not expose key material and parameters. It is + * an error to attempt to duplicate, export, or compare an opaque key. */ +OPENSSL_EXPORT int EVP_PKEY_is_opaque(const EVP_PKEY *pkey); + +/* EVP_PKEY_supports_digest returns one if |pkey| supports digests of + * type |md|. This is intended for use with EVP_PKEYs backing custom + * implementations which can't sign all digests. */ +OPENSSL_EXPORT int EVP_PKEY_supports_digest(const EVP_PKEY *pkey, + const EVP_MD *md); + +/* EVP_PKEY_cmp compares |a| and |b| and returns one if they are equal, zero if + * not and a negative number on error. + * + * WARNING: this differs from the traditional return value of a "cmp" + * function. */ +OPENSSL_EXPORT int EVP_PKEY_cmp(const EVP_PKEY *a, const EVP_PKEY *b); + +/* EVP_PKEY_copy_parameters sets the parameters of |to| to equal the parameters + * of |from|. It returns one on success and zero on error. */ +OPENSSL_EXPORT int EVP_PKEY_copy_parameters(EVP_PKEY *to, const EVP_PKEY *from); + +/* EVP_PKEY_missing_parameters returns one if |pkey| is missing needed + * parameters or zero if not, or if the algorithm doesn't take parameters. */ +OPENSSL_EXPORT int EVP_PKEY_missing_parameters(const EVP_PKEY *pkey); + +/* EVP_PKEY_size returns the maximum size, in bytes, of a signature signed by + * |pkey|. For an RSA key, this returns the number of bytes needed to represent + * the modulus. For an EC key, this returns the maximum size of a DER-encoded + * ECDSA signature. */ +OPENSSL_EXPORT int EVP_PKEY_size(const EVP_PKEY *pkey); + +/* EVP_PKEY_bits returns the "size", in bits, of |pkey|. For an RSA key, this + * returns the bit length of the modulus. For an EC key, this returns the bit + * length of the group order. */ +OPENSSL_EXPORT int EVP_PKEY_bits(EVP_PKEY *pkey); + +/* EVP_PKEY_id returns the type of |pkey|, which is one of the |EVP_PKEY_*| + * values. */ +OPENSSL_EXPORT int EVP_PKEY_id(const EVP_PKEY *pkey); + +/* EVP_PKEY_type returns a canonicalised form of |NID|. For example, + * |EVP_PKEY_RSA2| will be turned into |EVP_PKEY_RSA|. */ +OPENSSL_EXPORT int EVP_PKEY_type(int nid); + +/* Deprecated: EVP_PKEY_new_mac_key allocates a fresh |EVP_PKEY| of the given + * type (e.g. |EVP_PKEY_HMAC|), sets |mac_key| as the MAC key and "generates" a + * new key, suitable for signing. It returns the fresh |EVP_PKEY|, or NULL on + * error. Use |HMAC_CTX| directly instead. */ +OPENSSL_EXPORT EVP_PKEY *EVP_PKEY_new_mac_key(int type, ENGINE *engine, + const uint8_t *mac_key, + size_t mac_key_len); + + +/* Getting and setting concrete public key types. + * + * The following functions get and set the underlying public key in an + * |EVP_PKEY| object. The |set1| functions take an additional reference to the + * underlying key and return one on success or zero on error. The |assign| + * functions adopt the caller's reference. The getters return a fresh reference + * to the underlying object. */ + +OPENSSL_EXPORT int EVP_PKEY_set1_RSA(EVP_PKEY *pkey, RSA *key); +OPENSSL_EXPORT int EVP_PKEY_assign_RSA(EVP_PKEY *pkey, RSA *key); +OPENSSL_EXPORT RSA *EVP_PKEY_get1_RSA(EVP_PKEY *pkey); + +OPENSSL_EXPORT int EVP_PKEY_set1_DSA(EVP_PKEY *pkey, struct dsa_st *key); +OPENSSL_EXPORT int EVP_PKEY_assign_DSA(EVP_PKEY *pkey, DSA *key); +OPENSSL_EXPORT struct dsa_st *EVP_PKEY_get1_DSA(EVP_PKEY *pkey); + +OPENSSL_EXPORT int EVP_PKEY_set1_EC_KEY(EVP_PKEY *pkey, struct ec_key_st *key); +OPENSSL_EXPORT int EVP_PKEY_assign_EC_KEY(EVP_PKEY *pkey, EC_KEY *key); +OPENSSL_EXPORT struct ec_key_st *EVP_PKEY_get1_EC_KEY(EVP_PKEY *pkey); + +OPENSSL_EXPORT int EVP_PKEY_set1_DH(EVP_PKEY *pkey, struct dh_st *key); +OPENSSL_EXPORT int EVP_PKEY_assign_DH(EVP_PKEY *pkey, DH *key); +OPENSSL_EXPORT struct dh_st *EVP_PKEY_get1_DH(EVP_PKEY *pkey); + +#define EVP_PKEY_NONE NID_undef +#define EVP_PKEY_RSA NID_rsaEncryption +#define EVP_PKEY_RSA2 NID_rsa +#define EVP_PKEY_DSA NID_dsa +#define EVP_PKEY_DH NID_dhKeyAgreement +#define EVP_PKEY_DHX NID_dhpublicnumber +#define EVP_PKEY_EC NID_X9_62_id_ecPublicKey + +/* Deprecated: Use |HMAC_CTX| directly instead. */ +#define EVP_PKEY_HMAC NID_hmac + +/* EVP_PKEY_assign sets the underlying key of |pkey| to |key|, which must be of + * the given type. The |type| argument should be one of the |EVP_PKEY_*| + * values. */ +OPENSSL_EXPORT int EVP_PKEY_assign(EVP_PKEY *pkey, int type, void *key); + +/* EVP_PKEY_set_type sets the type of |pkey| to |type|, which should be one of + * the |EVP_PKEY_*| values. It returns one if sucessful or zero otherwise. If + * |pkey| is NULL, it simply reports whether the type is known. */ +OPENSSL_EXPORT int EVP_PKEY_set_type(EVP_PKEY *pkey, int type); + +/* EVP_PKEY_cmp_parameters compares the parameters of |a| and |b|. It returns + * one if they match, zero if not, or a negative number of on error. + * + * WARNING: the return value differs from the usual return value convention. */ +OPENSSL_EXPORT int EVP_PKEY_cmp_parameters(const EVP_PKEY *a, + const EVP_PKEY *b); + + +/* ASN.1 functions */ + +/* d2i_PrivateKey parses an ASN.1, DER-encoded, private key from |len| bytes at + * |*inp|. If |out| is not NULL then, on exit, a pointer to the result is in + * |*out|. If |*out| is already non-NULL on entry then the result is written + * directly into |*out|, otherwise a fresh |EVP_PKEY| is allocated. On + * successful exit, |*inp| is advanced past the DER structure. It returns the + * result or NULL on error. */ +OPENSSL_EXPORT EVP_PKEY *d2i_PrivateKey(int type, EVP_PKEY **out, + const uint8_t **inp, long len); + +/* d2i_AutoPrivateKey acts the same as |d2i_PrivateKey|, but detects the type + * of the private key. */ +OPENSSL_EXPORT EVP_PKEY *d2i_AutoPrivateKey(EVP_PKEY **out, const uint8_t **inp, + long len); + +/* i2d_PrivateKey marshals a private key from |key| to an ASN.1, DER + * structure. If |outp| is not NULL then the result is written to |*outp| and + * |*outp| is advanced just past the output. It returns the number of bytes in + * the result, whether written or not, or a negative value on error. */ +OPENSSL_EXPORT int i2d_PrivateKey(const EVP_PKEY *key, uint8_t **outp); + +/* i2d_PublicKey marshals a public key from |key| to an ASN.1, DER + * structure. If |outp| is not NULL then the result is written to |*outp| and + * |*outp| is advanced just past the output. It returns the number of bytes in + * the result, whether written or not, or a negative value on error. */ +OPENSSL_EXPORT int i2d_PublicKey(EVP_PKEY *key, uint8_t **outp); + + +/* Signing */ + +/* EVP_DigestSignInit sets up |ctx| for a signing operation with |type| and + * |pkey|. The |ctx| argument must have been initialised with + * |EVP_MD_CTX_init|. If |pctx| is not NULL, the |EVP_PKEY_CTX| of the signing + * operation will be written to |*pctx|; this can be used to set alternative + * signing options. + * + * It returns one on success, or zero on error. */ +OPENSSL_EXPORT int EVP_DigestSignInit(EVP_MD_CTX *ctx, EVP_PKEY_CTX **pctx, + const EVP_MD *type, ENGINE *e, + EVP_PKEY *pkey); + +/* EVP_DigestSignUpdate appends |len| bytes from |data| to the data which will + * be signed in |EVP_DigestSignFinal|. It returns one. */ +OPENSSL_EXPORT int EVP_DigestSignUpdate(EVP_MD_CTX *ctx, const void *data, + size_t len); + +/* EVP_DigestSignFinal signs the data that has been included by one or more + * calls to |EVP_DigestSignUpdate|. If |out_sig| is NULL then |*out_sig_len| is + * set to the maximum number of output bytes. Otherwise, on entry, + * |*out_sig_len| must contain the length of the |out_sig| buffer. If the call + * is successful, the signature is written to |out_sig| and |*out_sig_len| is + * set to its length. + * + * It returns one on success, or zero on error. */ +OPENSSL_EXPORT int EVP_DigestSignFinal(EVP_MD_CTX *ctx, uint8_t *out_sig, + size_t *out_sig_len); + +/* EVP_DigestSignAlgorithm encodes the signing parameters of |ctx| as an + * AlgorithmIdentifer and saves the result in |algor|. + * + * It returns one on success, or zero on error. + * + * TODO(davidben): This API should eventually lose the dependency on + * crypto/asn1/. */ +OPENSSL_EXPORT int EVP_DigestSignAlgorithm(EVP_MD_CTX *ctx, X509_ALGOR *algor); + + +/* Verifying */ + +/* EVP_DigestVerifyInit sets up |ctx| for a signature verification operation + * with |type| and |pkey|. The |ctx| argument must have been initialised with + * |EVP_MD_CTX_init|. If |pctx| is not NULL, the |EVP_PKEY_CTX| of the signing + * operation will be written to |*pctx|; this can be used to set alternative + * signing options. + * + * It returns one on success, or zero on error. */ +OPENSSL_EXPORT int EVP_DigestVerifyInit(EVP_MD_CTX *ctx, EVP_PKEY_CTX **pctx, + const EVP_MD *type, ENGINE *e, + EVP_PKEY *pkey); + +/* EVP_DigestVerifyInitFromAlgorithm sets up |ctx| for a signature verification + * operation with public key |pkey| and parameters from |algor|. The |ctx| + * argument must have been initialised with |EVP_MD_CTX_init|. + * + * It returns one on success, or zero on error. + * + * TODO(davidben): This API should eventually lose the dependency on + * crypto/asn1/. */ +OPENSSL_EXPORT int EVP_DigestVerifyInitFromAlgorithm(EVP_MD_CTX *ctx, + X509_ALGOR *algor, + EVP_PKEY *pkey); + +/* EVP_DigestVerifyUpdate appends |len| bytes from |data| to the data which + * will be verified by |EVP_DigestVerifyFinal|. It returns one. */ +OPENSSL_EXPORT int EVP_DigestVerifyUpdate(EVP_MD_CTX *ctx, const void *data, + size_t len); + +/* EVP_DigestVerifyFinal verifies that |sig_len| bytes of |sig| are a valid + * signature for the data that has been included by one or more calls to + * |EVP_DigestVerifyUpdate|. It returns one on success and zero otherwise. */ +OPENSSL_EXPORT int EVP_DigestVerifyFinal(EVP_MD_CTX *ctx, const uint8_t *sig, + size_t sig_len); + + +/* Signing (old functions) */ + +/* EVP_SignInit_ex configures |ctx|, which must already have been initialised, + * for a fresh signing operation using the hash function |type|. It returns one + * on success and zero otherwise. + * + * (In order to initialise |ctx|, either obtain it initialised with + * |EVP_MD_CTX_create|, or use |EVP_MD_CTX_init|.) */ +OPENSSL_EXPORT int EVP_SignInit_ex(EVP_MD_CTX *ctx, const EVP_MD *type, + ENGINE *impl); + +/* EVP_SignInit is a deprecated version of |EVP_SignInit_ex|. + * + * TODO(fork): remove. */ +OPENSSL_EXPORT int EVP_SignInit(EVP_MD_CTX *ctx, const EVP_MD *type); + +/* EVP_SignUpdate appends |len| bytes from |data| to the data which will be + * signed in |EVP_SignFinal|. */ +OPENSSL_EXPORT int EVP_SignUpdate(EVP_MD_CTX *ctx, const void *data, + size_t len); + +/* EVP_SignFinal signs the data that has been included by one or more calls to + * |EVP_SignUpdate|, using the key |pkey|, and writes it to |sig|. On entry, + * |sig| must point to at least |EVP_PKEY_size(pkey)| bytes of space. The + * actual size of the signature is written to |*out_sig_len|. + * + * It returns one on success and zero otherwise. + * + * It does not modify |ctx|, thus it's possible to continue to use |ctx| in + * order to sign a longer message. */ +OPENSSL_EXPORT int EVP_SignFinal(const EVP_MD_CTX *ctx, uint8_t *sig, + unsigned int *out_sig_len, EVP_PKEY *pkey); + + +/* Verifying (old functions) */ + +/* EVP_VerifyInit_ex configures |ctx|, which must already have been + * initialised, for a fresh signature verification operation using the hash + * function |type|. It returns one on success and zero otherwise. + * + * (In order to initialise |ctx|, either obtain it initialised with + * |EVP_MD_CTX_create|, or use |EVP_MD_CTX_init|.) */ +OPENSSL_EXPORT int EVP_VerifyInit_ex(EVP_MD_CTX *ctx, const EVP_MD *type, + ENGINE *impl); + +/* EVP_VerifyInit is a deprecated version of |EVP_VerifyInit_ex|. + * + * TODO(fork): remove. */ +OPENSSL_EXPORT int EVP_VerifyInit(EVP_MD_CTX *ctx, const EVP_MD *type); + +/* EVP_VerifyUpdate appends |len| bytes from |data| to the data which will be + * signed in |EVP_VerifyFinal|. */ +OPENSSL_EXPORT int EVP_VerifyUpdate(EVP_MD_CTX *ctx, const void *data, + size_t len); + +/* EVP_VerifyFinal verifies that |sig_len| bytes of |sig| are a valid + * signature, by |pkey|, for the data that has been included by one or more + * calls to |EVP_VerifyUpdate|. + * + * It returns one on success and zero otherwise. + * + * It does not modify |ctx|, thus it's possible to continue to use |ctx| in + * order to sign a longer message. */ +OPENSSL_EXPORT int EVP_VerifyFinal(EVP_MD_CTX *ctx, const uint8_t *sig, + size_t sig_len, EVP_PKEY *pkey); + + +/* Printing */ + +/* EVP_PKEY_print_public prints a textual representation of the public key in + * |pkey| to |out|. Returns one on success or zero otherwise. */ +OPENSSL_EXPORT int EVP_PKEY_print_public(BIO *out, const EVP_PKEY *pkey, + int indent, ASN1_PCTX *pctx); + +/* EVP_PKEY_print_public prints a textual representation of the private key in + * |pkey| to |out|. Returns one on success or zero otherwise. */ +OPENSSL_EXPORT int EVP_PKEY_print_private(BIO *out, const EVP_PKEY *pkey, + int indent, ASN1_PCTX *pctx); + +/* EVP_PKEY_print_public prints a textual representation of the parameters in + * |pkey| to |out|. Returns one on success or zero otherwise. */ +OPENSSL_EXPORT int EVP_PKEY_print_params(BIO *out, const EVP_PKEY *pkey, + int indent, ASN1_PCTX *pctx); + + +/* Password stretching. + * + * Password stretching functions take a low-entropy password and apply a slow + * function that results in a key suitable for use in symmetric + * cryptography. */ + +/* PKCS5_PBKDF2_HMAC computes |iterations| iterations of PBKDF2 of |password| + * and |salt|, using |digest|, and outputs |key_len| bytes to |out_key|. It + * returns one on success and zero on error. */ +OPENSSL_EXPORT int PKCS5_PBKDF2_HMAC(const char *password, size_t password_len, + const uint8_t *salt, size_t salt_len, + unsigned iterations, const EVP_MD *digest, + size_t key_len, uint8_t *out_key); + +/* PKCS5_PBKDF2_HMAC_SHA1 is the same as PKCS5_PBKDF2_HMAC, but with |digest| + * fixed to |EVP_sha1|. */ +OPENSSL_EXPORT int PKCS5_PBKDF2_HMAC_SHA1(const char *password, + size_t password_len, const uint8_t *salt, + size_t salt_len, unsigned iterations, + size_t key_len, uint8_t *out_key); + + +/* Public key contexts. + * + * |EVP_PKEY_CTX| objects hold the context of an operation (e.g. signing or + * encrypting) that uses a public key. */ + +/* EVP_PKEY_CTX_new allocates a fresh |EVP_PKEY_CTX| for use with |pkey|. It + * returns the context or NULL on error. */ +OPENSSL_EXPORT EVP_PKEY_CTX *EVP_PKEY_CTX_new(EVP_PKEY *pkey, ENGINE *e); + +/* EVP_PKEY_CTX_new allocates a fresh |EVP_PKEY_CTX| for a key of type |id| + * (e.g. |EVP_PKEY_HMAC|). This can be used for key generation where + * |EVP_PKEY_CTX_new| can't be used because there isn't an |EVP_PKEY| to pass + * it. It returns the context or NULL on error. */ +OPENSSL_EXPORT EVP_PKEY_CTX *EVP_PKEY_CTX_new_id(int id, ENGINE *e); + +/* EVP_KEY_CTX_free frees |ctx| and the data it owns. */ +OPENSSL_EXPORT void EVP_PKEY_CTX_free(EVP_PKEY_CTX *ctx); + +/* EVP_PKEY_CTX_dup allocates a fresh |EVP_PKEY_CTX| and sets it equal to the + * state of |ctx|. It returns the fresh |EVP_PKEY_CTX| or NULL on error. */ +OPENSSL_EXPORT EVP_PKEY_CTX *EVP_PKEY_CTX_dup(EVP_PKEY_CTX *ctx); + +/* EVP_PKEY_CTX_get0_pkey returns the |EVP_PKEY| associated with |ctx|. */ +OPENSSL_EXPORT EVP_PKEY *EVP_PKEY_CTX_get0_pkey(EVP_PKEY_CTX *ctx); + +/* EVP_PKEY_CTX_set_app_data sets an opaque pointer on |ctx|. */ +OPENSSL_EXPORT void EVP_PKEY_CTX_set_app_data(EVP_PKEY_CTX *ctx, void *data); + +/* EVP_PKEY_CTX_get_app_data returns the opaque pointer from |ctx| that was + * previously set with |EVP_PKEY_CTX_set_app_data|, or NULL if none has been + * set. */ +OPENSSL_EXPORT void *EVP_PKEY_CTX_get_app_data(EVP_PKEY_CTX *ctx); + +/* EVP_PKEY_sign_init initialises an |EVP_PKEY_CTX| for a signing operation. It + * should be called before |EVP_PKEY_sign|. + * + * It returns one on success or zero on error. */ +OPENSSL_EXPORT int EVP_PKEY_sign_init(EVP_PKEY_CTX *ctx); + +/* EVP_PKEY_sign signs |data_len| bytes from |data| using |ctx|. If |sig| is + * NULL, the maximum size of the signature is written to + * |out_sig_len|. Otherwise, |*sig_len| must contain the number of bytes of + * space available at |sig|. If sufficient, the signature will be written to + * |sig| and |*sig_len| updated with the true length. + * + * WARNING: Setting |sig| to NULL only gives the maximum size of the + * signature. The actual signature may be smaller. + * + * It returns one on success or zero on error. (Note: this differs from + * OpenSSL, which can also return negative values to indicate an error. ) */ +OPENSSL_EXPORT int EVP_PKEY_sign(EVP_PKEY_CTX *ctx, uint8_t *sig, + size_t *sig_len, const uint8_t *data, + size_t data_len); + +/* EVP_PKEY_verify_init initialises an |EVP_PKEY_CTX| for a signature + * verification operation. It should be called before |EVP_PKEY_verify|. + * + * It returns one on success or zero on error. */ +OPENSSL_EXPORT int EVP_PKEY_verify_init(EVP_PKEY_CTX *ctx); + +/* EVP_PKEY_verify verifies that |sig_len| bytes from |sig| are a valid signature + * for |data|. + * + * It returns one on success or zero on error. */ +OPENSSL_EXPORT int EVP_PKEY_verify(EVP_PKEY_CTX *ctx, const uint8_t *sig, + size_t sig_len, const uint8_t *data, + size_t data_len); + +/* EVP_PKEY_encrypt_init initialises an |EVP_PKEY_CTX| for an encryption + * operation. It should be called before |EVP_PKEY_encrypt|. + * + * It returns one on success or zero on error. */ +OPENSSL_EXPORT int EVP_PKEY_encrypt_init(EVP_PKEY_CTX *ctx); + +/* EVP_PKEY_encrypt encrypts |in_len| bytes from |in|. If |out| is NULL, the + * maximum size of the ciphertext is written to |out_len|. Otherwise, |*out_len| + * must contain the number of bytes of space available at |out|. If sufficient, + * the ciphertext will be written to |out| and |*out_len| updated with the true + * length. + * + * WARNING: Setting |out| to NULL only gives the maximum size of the + * ciphertext. The actual ciphertext may be smaller. + * + * It returns one on success or zero on error. */ +OPENSSL_EXPORT int EVP_PKEY_encrypt(EVP_PKEY_CTX *ctx, uint8_t *out, + size_t *out_len, const uint8_t *in, + size_t in_len); + +/* EVP_PKEY_decrypt_init initialises an |EVP_PKEY_CTX| for a decryption + * operation. It should be called before |EVP_PKEY_decrypt|. + * + * It returns one on success or zero on error. */ +OPENSSL_EXPORT int EVP_PKEY_decrypt_init(EVP_PKEY_CTX *ctx); + +/* EVP_PKEY_decrypt decrypts |in_len| bytes from |in|. If |out| is NULL, the + * maximum size of the plaintext is written to |out_len|. Otherwise, |*out_len| + * must contain the number of bytes of space available at |out|. If sufficient, + * the ciphertext will be written to |out| and |*out_len| updated with the true + * length. + * + * WARNING: Setting |out| to NULL only gives the maximum size of the + * plaintext. The actual plaintext may be smaller. + * + * It returns one on success or zero on error. */ +OPENSSL_EXPORT int EVP_PKEY_decrypt(EVP_PKEY_CTX *ctx, uint8_t *out, + size_t *out_len, const uint8_t *in, + size_t in_len); + +/* EVP_PKEY_derive_init initialises an |EVP_PKEY_CTX| for a key derivation + * operation. It should be called before |EVP_PKEY_derive_set_peer| and + * |EVP_PKEY_derive|. + * + * It returns one on success or zero on error. */ +OPENSSL_EXPORT int EVP_PKEY_derive_init(EVP_PKEY_CTX *ctx); + +/* EVP_PKEY_derive_set_peer sets the peer's key to be used for key derivation + * by |ctx| to |peer|. It should be called after |EVP_PKEY_derive_init|. (For + * example, this is used to set the peer's key in (EC)DH.) It returns one on + * success and zero on error. */ +OPENSSL_EXPORT int EVP_PKEY_derive_set_peer(EVP_PKEY_CTX *ctx, EVP_PKEY *peer); + +/* EVP_PKEY_derive derives a shared key between the two keys configured in + * |ctx|. If |key| is non-NULL then, on entry, |out_key_len| must contain the + * amount of space at |key|. If sufficient then the shared key will be written + * to |key| and |*out_key_len| will be set to the length. If |key| is NULL then + * |out_key_len| will be set to the maximum length. + * + * WARNING: Setting |out| to NULL only gives the maximum size of the key. The + * actual key may be smaller. + * + * It returns one on success and zero on error. */ +OPENSSL_EXPORT int EVP_PKEY_derive(EVP_PKEY_CTX *ctx, uint8_t *key, + size_t *out_key_len); + +/* EVP_PKEY_keygen_init initialises an |EVP_PKEY_CTX| for a key generation + * operation. It should be called before |EVP_PKEY_keygen|. + * + * It returns one on success or zero on error. */ +OPENSSL_EXPORT int EVP_PKEY_keygen_init(EVP_PKEY_CTX *ctx); + +/* EVP_PKEY_keygen performs a key generation operation using the values from + * |ctx| and sets |*ppkey| to a fresh |EVP_PKEY| containing the resulting key. + * It returns one on success or zero on error. */ +OPENSSL_EXPORT int EVP_PKEY_keygen(EVP_PKEY_CTX *ctx, EVP_PKEY **ppkey); + + +/* Generic control functions. */ + +/* EVP_PKEY_CTX_set_signature_md sets |md| as the digest to be used in a + * signature operation. It returns one on success or zero on error. */ +OPENSSL_EXPORT int EVP_PKEY_CTX_set_signature_md(EVP_PKEY_CTX *ctx, + const EVP_MD *md); + +/* EVP_PKEY_CTX_get_signature_md sets |*out_md| to the digest to be used in a + * signature operation. It returns one on success or zero on error. */ +OPENSSL_EXPORT int EVP_PKEY_CTX_get_signature_md(EVP_PKEY_CTX *ctx, + const EVP_MD **out_md); + + +/* RSA specific control functions. */ + +/* EVP_PKEY_CTX_set_rsa_padding sets the padding type to use. It should be one + * of the |RSA_*_PADDING| values. Returns one on success or zero on error. */ +OPENSSL_EXPORT int EVP_PKEY_CTX_set_rsa_padding(EVP_PKEY_CTX *ctx, int padding); + +/* EVP_PKEY_CTX_get_rsa_padding sets |*out_padding| to the current padding + * value, which is one of the |RSA_*_PADDING| values. Returns one on success or + * zero on error. */ +OPENSSL_EXPORT int EVP_PKEY_CTX_get_rsa_padding(EVP_PKEY_CTX *ctx, + int *out_padding); + +/* EVP_PKEY_CTX_set_rsa_pss_saltlen sets the length of the salt in a PSS-padded + * signature. A value of -1 cause the salt to be the same length as the digest + * in the signature. A value of -2 causes the salt to be the maximum length + * that will fit. Otherwise the value gives the size of the salt in bytes. + * + * Returns one on success or zero on error. */ +OPENSSL_EXPORT int EVP_PKEY_CTX_set_rsa_pss_saltlen(EVP_PKEY_CTX *ctx, + int salt_len); + +/* EVP_PKEY_CTX_get_rsa_pss_saltlen sets |*out_salt_len| to the salt length of + * a PSS-padded signature. See the documentation for + * |EVP_PKEY_CTX_set_rsa_pss_saltlen| for details of the special values that it + * can take. + * + * Returns one on success or zero on error. */ +OPENSSL_EXPORT int EVP_PKEY_CTX_get_rsa_pss_saltlen(EVP_PKEY_CTX *ctx, + int *out_salt_len); + +/* EVP_PKEY_CTX_set_rsa_keygen_bits sets the size of the desired RSA modulus, + * in bits, for key generation. Returns one on success or zero on + * error. */ +OPENSSL_EXPORT int EVP_PKEY_CTX_set_rsa_keygen_bits(EVP_PKEY_CTX *ctx, + int bits); + +/* EVP_PKEY_CTX_set_rsa_keygen_pubexp sets |e| as the public exponent for key + * generation. Returns one on success or zero on error. */ +OPENSSL_EXPORT int EVP_PKEY_CTX_set_rsa_keygen_pubexp(EVP_PKEY_CTX *ctx, + BIGNUM *e); + +/* EVP_PKEY_CTX_set_rsa_oaep_md sets |md| as the digest used in OAEP padding. + * Returns one on success or zero on error. */ +OPENSSL_EXPORT int EVP_PKEY_CTX_set_rsa_oaep_md(EVP_PKEY_CTX *ctx, + const EVP_MD *md); + +/* EVP_PKEY_CTX_get_rsa_oaep_md sets |*out_md| to the digest function used in + * OAEP padding. Returns one on success or zero on error. */ +OPENSSL_EXPORT int EVP_PKEY_CTX_get_rsa_oaep_md(EVP_PKEY_CTX *ctx, + const EVP_MD **out_md); + +/* EVP_PKEY_CTX_set_rsa_mgf1_md sets |md| as the digest used in MGF1. Returns + * one on success or zero on error. */ +OPENSSL_EXPORT int EVP_PKEY_CTX_set_rsa_mgf1_md(EVP_PKEY_CTX *ctx, + const EVP_MD *md); + +/* EVP_PKEY_CTX_get_rsa_mgf1_md sets |*out_md| to the digest function used in + * MGF1. Returns one on success or zero on error. */ +OPENSSL_EXPORT int EVP_PKEY_CTX_get_rsa_mgf1_md(EVP_PKEY_CTX *ctx, + const EVP_MD **out_md); + +/* EVP_PKEY_CTX_set0_rsa_oaep_label sets |label_len| bytes from |label| as the + * label used in OAEP. DANGER: On success, this call takes ownership of |label| + * and will call |OPENSSL_free| on it when |ctx| is destroyed. + * + * Returns one on success or zero on error. */ +OPENSSL_EXPORT int EVP_PKEY_CTX_set0_rsa_oaep_label(EVP_PKEY_CTX *ctx, + const uint8_t *label, + size_t label_len); + +/* EVP_PKEY_CTX_get0_rsa_oaep_label sets |*out_label| to point to the internal + * buffer containing the OAEP label (which may be NULL) and returns the length + * of the label or a negative value on error. + * + * WARNING: the return value differs from the usual return value convention. */ +OPENSSL_EXPORT int EVP_PKEY_CTX_get0_rsa_oaep_label(EVP_PKEY_CTX *ctx, + const uint8_t **out_label); + + +/* Deprecated functions. */ + +/* EVP_PKEY_dup adds one to the reference count of |pkey| and returns + * |pkey|. + * + * WARNING: this is a |_dup| function that doesn't actually duplicate! Use + * |EVP_PKEY_up_ref| if you want to increment the reference count without + * confusion. */ +OPENSSL_EXPORT EVP_PKEY *EVP_PKEY_dup(EVP_PKEY *pkey); + + +/* Private functions */ + +/* OpenSSL_add_all_algorithms does nothing. */ +OPENSSL_EXPORT void OpenSSL_add_all_algorithms(void); + +/* OpenSSL_add_all_ciphers does nothing. */ +OPENSSL_EXPORT void OpenSSL_add_all_ciphers(void); + +/* OpenSSL_add_all_digests does nothing. */ +OPENSSL_EXPORT void OpenSSL_add_all_digests(void); + +/* EVP_cleanup does nothing. */ +OPENSSL_EXPORT void EVP_cleanup(void); + +/* EVP_PKEY_asn1_find returns the ASN.1 method table for the given |nid|, which + * should be one of the |EVP_PKEY_*| values. It returns NULL if |nid| is + * unknown. */ +OPENSSL_EXPORT const EVP_PKEY_ASN1_METHOD *EVP_PKEY_asn1_find(ENGINE **pengine, + int nid); + +/* TODO(fork): move to PEM? */ +OPENSSL_EXPORT const EVP_PKEY_ASN1_METHOD *EVP_PKEY_asn1_find_str( + ENGINE **pengine, const char *name, size_t len); + +struct evp_pkey_st { + CRYPTO_refcount_t references; + + /* type contains one of the EVP_PKEY_* values or NID_undef and determines + * which element (if any) of the |pkey| union is valid. */ + int type; + + union { + char *ptr; + struct rsa_st *rsa; /* RSA */ + struct dsa_st *dsa; /* DSA */ + struct dh_st *dh; /* DH */ + struct ec_key_st *ec; /* ECC */ + } pkey; + + /* ameth contains a pointer to a method table that contains many ASN.1 + * methods for the key type. */ + const EVP_PKEY_ASN1_METHOD *ameth; +} /* EVP_PKEY */; + + +#if defined(__cplusplus) +} /* extern C */ +#endif + +#define EVP_F_EVP_PKEY_derive_init 108 +#define EVP_F_EVP_PKEY_encrypt 110 +#define EVP_F_EVP_PKEY_encrypt_init 111 +#define EVP_F_EVP_PKEY_get1_DH 112 +#define EVP_F_EVP_PKEY_get1_EC_KEY 114 +#define EVP_F_EVP_PKEY_get1_RSA 115 +#define EVP_F_EVP_PKEY_keygen 116 +#define EVP_F_EVP_PKEY_sign 120 +#define EVP_F_EVP_PKEY_sign_init 121 +#define EVP_F_EVP_PKEY_verify 122 +#define EVP_F_EVP_PKEY_verify_init 123 +#define EVP_F_d2i_AutoPrivateKey 125 +#define EVP_F_d2i_PrivateKey 126 +#define EVP_F_do_EC_KEY_print 127 +#define EVP_F_do_sigver_init 129 +#define EVP_F_eckey_param2type 130 +#define EVP_F_eckey_param_decode 131 +#define EVP_F_eckey_priv_decode 132 +#define EVP_F_eckey_priv_encode 133 +#define EVP_F_eckey_pub_decode 134 +#define EVP_F_eckey_pub_encode 135 +#define EVP_F_eckey_type2param 136 +#define EVP_F_evp_pkey_ctx_new 137 +#define EVP_F_hmac_signctx 138 +#define EVP_F_i2d_PublicKey 139 +#define EVP_F_old_ec_priv_decode 140 +#define EVP_F_old_rsa_priv_decode 141 +#define EVP_F_pkey_ec_ctrl 142 +#define EVP_F_pkey_ec_derive 143 +#define EVP_F_pkey_ec_keygen 144 +#define EVP_F_pkey_ec_paramgen 145 +#define EVP_F_pkey_ec_sign 146 +#define EVP_F_pkey_rsa_ctrl 147 +#define EVP_F_pkey_rsa_decrypt 148 +#define EVP_F_pkey_rsa_encrypt 149 +#define EVP_F_pkey_rsa_sign 150 +#define EVP_F_rsa_algor_to_md 151 +#define EVP_F_rsa_digest_verify_init_from_algorithm 152 +#define EVP_F_rsa_mgf1_to_md 153 +#define EVP_F_rsa_priv_decode 154 +#define EVP_F_rsa_priv_encode 155 +#define EVP_F_rsa_pss_to_ctx 156 +#define EVP_F_rsa_pub_decode 157 +#define EVP_F_pkey_hmac_ctrl 158 +#define EVP_F_EVP_PKEY_CTX_get0_rsa_oaep_label 159 +#define EVP_F_EVP_DigestSignAlgorithm 160 +#define EVP_F_EVP_DigestVerifyInitFromAlgorithm 161 +#define EVP_F_EVP_PKEY_CTX_ctrl 162 +#define EVP_F_EVP_PKEY_CTX_dup 163 +#define EVP_F_EVP_PKEY_copy_parameters 164 +#define EVP_F_EVP_PKEY_decrypt 165 +#define EVP_F_EVP_PKEY_decrypt_init 166 +#define EVP_F_EVP_PKEY_derive 167 +#define EVP_F_EVP_PKEY_derive_set_peer 168 +#define EVP_F_EVP_PKEY_get1_DSA 169 +#define EVP_F_EVP_PKEY_keygen_init 170 +#define EVP_F_EVP_PKEY_new 171 +#define EVP_F_EVP_PKEY_set_type 172 +#define EVP_F_check_padding_md 173 +#define EVP_F_do_dsa_print 174 +#define EVP_F_do_rsa_print 175 +#define EVP_F_dsa_param_decode 176 +#define EVP_F_dsa_priv_decode 177 +#define EVP_F_dsa_priv_encode 178 +#define EVP_F_dsa_pub_decode 179 +#define EVP_F_dsa_pub_encode 180 +#define EVP_F_dsa_sig_print 181 +#define EVP_F_old_dsa_priv_decode 182 +#define EVP_R_BUFFER_TOO_SMALL 100 +#define EVP_R_COMMAND_NOT_SUPPORTED 101 +#define EVP_R_DIFFERENT_KEY_TYPES 104 +#define EVP_R_DIFFERENT_PARAMETERS 105 +#define EVP_R_EXPECTING_AN_EC_KEY_KEY 107 +#define EVP_R_EXPECTING_A_DH_KEY 109 +#define EVP_R_EXPECTING_A_DSA_KEY 110 +#define EVP_R_ILLEGAL_OR_UNSUPPORTED_PADDING_MODE 111 +#define EVP_R_INVALID_CURVE 112 +#define EVP_R_INVALID_DIGEST_LENGTH 113 +#define EVP_R_INVALID_DIGEST_TYPE 114 +#define EVP_R_INVALID_KEYBITS 115 +#define EVP_R_INVALID_MGF1_MD 116 +#define EVP_R_INVALID_PADDING_MODE 118 +#define EVP_R_INVALID_PSS_PARAMETERS 119 +#define EVP_R_INVALID_SALT_LENGTH 121 +#define EVP_R_INVALID_TRAILER 122 +#define EVP_R_KEYS_NOT_SET 123 +#define EVP_R_MISSING_PARAMETERS 124 +#define EVP_R_NO_DEFAULT_DIGEST 125 +#define EVP_R_NO_KEY_SET 126 +#define EVP_R_NO_MDC2_SUPPORT 127 +#define EVP_R_NO_NID_FOR_CURVE 128 +#define EVP_R_NO_OPERATION_SET 129 +#define EVP_R_NO_PARAMETERS_SET 130 +#define EVP_R_OPERATION_NOT_SUPPORTED_FOR_THIS_KEYTYPE 131 +#define EVP_R_OPERATON_NOT_INITIALIZED 132 +#define EVP_R_UNKNOWN_DIGEST 133 +#define EVP_R_UNKNOWN_MASK_DIGEST 134 +#define EVP_R_UNSUPPORTED_ALGORITHM 138 +#define EVP_R_UNSUPPORTED_MASK_ALGORITHM 139 +#define EVP_R_UNSUPPORTED_MASK_PARAMETER 140 +#define EVP_R_EXPECTING_AN_RSA_KEY 141 +#define EVP_R_INVALID_OPERATION 142 +#define EVP_R_DECODE_ERROR 143 +#define EVP_R_INVALID_PSS_SALTLEN 144 +#define EVP_R_UNKNOWN_PUBLIC_KEY_TYPE 145 +#define EVP_R_CONTEXT_NOT_INITIALISED 146 +#define EVP_R_DIGEST_AND_KEY_TYPE_NOT_SUPPORTED 147 +#define EVP_R_WRONG_PUBLIC_KEY_TYPE 148 +#define EVP_R_UNKNOWN_SIGNATURE_ALGORITHM 149 +#define EVP_R_UNKNOWN_MESSAGE_DIGEST_ALGORITHM 150 +#define EVP_R_BN_DECODE_ERROR 151 +#define EVP_R_PARAMETER_ENCODING_ERROR 152 +#define EVP_R_UNSUPPORTED_PUBLIC_KEY_TYPE 153 +#define EVP_R_UNSUPPORTED_SIGNATURE_TYPE 154 + +#endif /* OPENSSL_HEADER_EVP_H */ diff --git a/phonelibs/boringssl/include/openssl/ex_data.h b/phonelibs/boringssl/include/openssl/ex_data.h new file mode 100644 index 00000000000000..2303eb425014e2 --- /dev/null +++ b/phonelibs/boringssl/include/openssl/ex_data.h @@ -0,0 +1,214 @@ +/* Copyright (C) 1995-1998 Eric Young (eay@cryptsoft.com) + * All rights reserved. + * + * This package is an SSL implementation written + * by Eric Young (eay@cryptsoft.com). + * The implementation was written so as to conform with Netscapes SSL. + * + * This library is free for commercial and non-commercial use as long as + * the following conditions are aheared to. The following conditions + * apply to all code found in this distribution, be it the RC4, RSA, + * lhash, DES, etc., code; not just the SSL code. The SSL documentation + * included with this distribution is covered by the same copyright terms + * except that the holder is Tim Hudson (tjh@cryptsoft.com). + * + * Copyright remains Eric Young's, and as such any Copyright notices in + * the code are not to be removed. + * If this package is used in a product, Eric Young should be given attribution + * as the author of the parts of the library used. + * This can be in the form of a textual message at program startup or + * in documentation (online or textual) provided with the package. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must 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. All advertising materials mentioning features or use of this software + * must display the following acknowledgement: + * "This product includes cryptographic software written by + * Eric Young (eay@cryptsoft.com)" + * The word 'cryptographic' can be left out if the rouines from the library + * being used are not cryptographic related :-). + * 4. If you include any Windows specific code (or a derivative thereof) from + * the apps directory (application code) you must include an acknowledgement: + * "This product includes software written by Tim Hudson (tjh@cryptsoft.com)" + * + * THIS SOFTWARE IS PROVIDED BY ERIC YOUNG ``AS IS'' AND + * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHOR OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (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 licence and distribution terms for any publically available version or + * derivative of this code cannot be changed. i.e. this code cannot simply be + * copied and put under another distribution licence + * [including the GNU Public Licence.] + */ +/* ==================================================================== + * Copyright (c) 1998-2001 The OpenSSL Project. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * + * 3. All advertising materials mentioning features or use of this + * software must display the following acknowledgment: + * "This product includes software developed by the OpenSSL Project + * for use in the OpenSSL Toolkit. (http://www.openssl.org/)" + * + * 4. The names "OpenSSL Toolkit" and "OpenSSL Project" must not be used to + * endorse or promote products derived from this software without + * prior written permission. For written permission, please contact + * openssl-core@openssl.org. + * + * 5. Products derived from this software may not be called "OpenSSL" + * nor may "OpenSSL" appear in their names without prior written + * permission of the OpenSSL Project. + * + * 6. Redistributions of any form whatsoever must retain the following + * acknowledgment: + * "This product includes software developed by the OpenSSL Project + * for use in the OpenSSL Toolkit (http://www.openssl.org/)" + * + * THIS SOFTWARE IS PROVIDED BY THE OpenSSL PROJECT ``AS IS'' AND ANY + * EXPRESSED OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR + * PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE OpenSSL PROJECT OR + * ITS CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, + * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT + * NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + * STRICT LIABILITY, OR TORT (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 product includes cryptographic software written by Eric Young + * (eay@cryptsoft.com). This product includes software written by Tim + * Hudson (tjh@cryptsoft.com). */ + +#ifndef OPENSSL_HEADER_EX_DATA_H +#define OPENSSL_HEADER_EX_DATA_H + +#include + +#include + +#if defined(__cplusplus) +extern "C" { +#endif + + +/* ex_data is a mechanism for associating arbitrary extra data with objects. + * For each type of object that supports ex_data, different users can be + * assigned indexes in which to store their data. Each index has callback + * functions that are called when a new object of that type is created, freed + * and duplicated. */ + + +typedef struct crypto_ex_data_st CRYPTO_EX_DATA; + + +/* Type-specific functions. + * + * Each type that supports ex_data provides three functions: */ + +#if 0 /* Sample */ + +/* |TYPE_get_ex_new_index| allocates a new index for |TYPE|. See the + * descriptions of the callback typedefs for details of when they are + * called. Any of the callback arguments may be NULL. The |argl| and |argp| + * arguments are opaque values that are passed to the callbacks. It returns the + * new index or a negative number on error. + * + * TODO(fork): this should follow the standard calling convention. */ +OPENSSL_EXPORT int TYPE_get_ex_new_index(long argl, void *argp, + CRYPTO_EX_new *new_func, + CRYPTO_EX_dup *dup_func, + CRYPTO_EX_free *free_func); + +/* |TYPE_set_ex_data| sets an extra data pointer on |t|. The |index| argument + * should have been returned from a previous call to |TYPE_get_ex_new_index|. */ +OPENSSL_EXPORT int TYPE_set_ex_data(TYPE *t, int index, void *arg); + +/* |TYPE_get_ex_data| returns an extra data pointer for |t|, or NULL if no such + * pointer exists. The |index| argument should have been returned from a + * previous call to |TYPE_get_ex_new_index|. */ +OPENSSL_EXPORT void *TYPE_get_ex_data(const TYPE *t, int index); + +#endif /* Sample */ + + +/* Callback types. */ + +/* CRYPTO_EX_new is the type of a callback function that is called whenever a + * new object of a given class is created. For example, if this callback has + * been passed to |SSL_get_ex_new_index| then it'll be called each time an SSL* + * is created. + * + * The callback is passed the new object (i.e. the SSL*) in |parent|. The + * arguments |argl| and |argp| contain opaque values that were given to + * |CRYPTO_get_ex_new_index|. The callback should return one on success, but + * the value is ignored. + * + * TODO(fork): the |ptr| argument is always NULL, no? */ +typedef int CRYPTO_EX_new(void *parent, void *ptr, CRYPTO_EX_DATA *ad, + int index, long argl, void *argp); + +/* CRYPTO_EX_free is a callback function that is called when an object of the + * class is being destroyed. See |CRYPTO_EX_new| for a discussion of the + * arguments. + * + * If |CRYPTO_get_ex_new_index| was called after the creation of objects of the + * class that this applies to then, when those those objects are destroyed, + * this callback will be called with a NULL value for |ptr|. */ +typedef void CRYPTO_EX_free(void *parent, void *ptr, CRYPTO_EX_DATA *ad, + int index, long argl, void *argp); + +/* CRYPTO_EX_dup is a callback function that is called when an object of the + * class is being copied and thus the ex_data linked to it also needs to be + * copied. On entry, |*from_d| points to the data for this index from the + * original object. When the callback returns, |*from_d| will be set as the + * data for this index in |to|. + * + * If |CRYPTO_get_ex_new_index| was called after the creation of objects of the + * class that this applies to then, when those those objects are copies, this + * callback will be called with a NULL value for |*from_d|. */ +typedef int CRYPTO_EX_dup(CRYPTO_EX_DATA *to, const CRYPTO_EX_DATA *from, + void **from_d, int index, long argl, void *argp); + + +/* Deprecated functions. */ + +/* CRYPTO_cleanup_all_ex_data does nothing. */ +OPENSSL_EXPORT void CRYPTO_cleanup_all_ex_data(void); + +struct crypto_ex_data_st { + STACK_OF(void) *sk; +}; + + +#if defined(__cplusplus) +} /* extern C */ +#endif + +#endif /* OPENSSL_HEADER_EX_DATA_H */ diff --git a/phonelibs/boringssl/include/openssl/hkdf.h b/phonelibs/boringssl/include/openssl/hkdf.h new file mode 100644 index 00000000000000..4091b84beb8eff --- /dev/null +++ b/phonelibs/boringssl/include/openssl/hkdf.h @@ -0,0 +1,45 @@ +/* Copyright (c) 2014, Google Inc. + * + * Permission to use, copy, modify, and/or distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY + * SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN ACTION + * OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF OR IN + * CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. */ + +#ifndef OPENSSL_HEADER_HKDF_H +#define OPENSSL_HEADER_HKDF_H + +#include + +#ifdef __cplusplus +extern "C" { +#endif + + +/* Computes HKDF (as specified by RFC 5869) of initial keying material |secret| + * with |salt| and |info| using |digest|, and outputs |out_len| bytes to + * |out_key|. It returns one on success and zero on error. + * + * HKDF is an Extract-and-Expand algorithm. It does not do any key stretching, + * and as such, is not suited to be used alone to generate a key from a + * password. */ +OPENSSL_EXPORT int HKDF(uint8_t *out_key, size_t out_len, const EVP_MD *digest, + const uint8_t *secret, size_t secret_len, + const uint8_t *salt, size_t salt_len, + const uint8_t *info, size_t info_len); + + +#if defined(__cplusplus) +} /* extern C */ +#endif + +#define HKDF_F_HKDF 100 +#define HKDF_R_OUTPUT_TOO_LARGE 100 + +#endif /* OPENSSL_HEADER_HKDF_H */ diff --git a/phonelibs/boringssl/include/openssl/hmac.h b/phonelibs/boringssl/include/openssl/hmac.h new file mode 100644 index 00000000000000..e521212d4cd254 --- /dev/null +++ b/phonelibs/boringssl/include/openssl/hmac.h @@ -0,0 +1,160 @@ +/* Copyright (C) 1995-1998 Eric Young (eay@cryptsoft.com) + * All rights reserved. + * + * This package is an SSL implementation written + * by Eric Young (eay@cryptsoft.com). + * The implementation was written so as to conform with Netscapes SSL. + * + * This library is free for commercial and non-commercial use as long as + * the following conditions are aheared to. The following conditions + * apply to all code found in this distribution, be it the RC4, RSA, + * lhash, DES, etc., code; not just the SSL code. The SSL documentation + * included with this distribution is covered by the same copyright terms + * except that the holder is Tim Hudson (tjh@cryptsoft.com). + * + * Copyright remains Eric Young's, and as such any Copyright notices in + * the code are not to be removed. + * If this package is used in a product, Eric Young should be given attribution + * as the author of the parts of the library used. + * This can be in the form of a textual message at program startup or + * in documentation (online or textual) provided with the package. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must 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. All advertising materials mentioning features or use of this software + * must display the following acknowledgement: + * "This product includes cryptographic software written by + * Eric Young (eay@cryptsoft.com)" + * The word 'cryptographic' can be left out if the rouines from the library + * being used are not cryptographic related :-). + * 4. If you include any Windows specific code (or a derivative thereof) from + * the apps directory (application code) you must include an acknowledgement: + * "This product includes software written by Tim Hudson (tjh@cryptsoft.com)" + * + * THIS SOFTWARE IS PROVIDED BY ERIC YOUNG ``AS IS'' AND + * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHOR OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (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 licence and distribution terms for any publically available version or + * derivative of this code cannot be changed. i.e. this code cannot simply be + * copied and put under another distribution licence + * [including the GNU Public Licence.] */ + +#ifndef OPENSSL_HEADER_HMAC_H +#define OPENSSL_HEADER_HMAC_H + +#include + +#include + +#if defined(__cplusplus) +extern "C" { +#endif + + +/* HMAC contains functions for constructing PRFs from Merkle–Damgård hash + * functions using HMAC. */ + + +/* One-shot operation. */ + +/* HMAC calculates the HMAC of |data_len| bytes of |data|, using the given key + * and hash function, and writes the result to |out|. On entry, |out| must + * contain |EVP_MAX_MD_SIZE| bytes of space. The actual length of the result is + * written to |*out_len|. It returns |out| or NULL on error. */ +OPENSSL_EXPORT uint8_t *HMAC(const EVP_MD *evp_md, const void *key, + size_t key_len, const uint8_t *data, + size_t data_len, uint8_t *out, + unsigned int *out_len); + + +/* Incremental operation. */ + +/* HMAC_CTX_init initialises |ctx| for use in an HMAC operation. It's assumed + * that HMAC_CTX objects will be allocated on the stack thus no allocation + * function is provided. If needed, allocate |sizeof(HMAC_CTX)| and call + * |HMAC_CTX_init| on it. */ +OPENSSL_EXPORT void HMAC_CTX_init(HMAC_CTX *ctx); + +/* HMAC_CTX_cleanup frees data owned by |ctx|. */ +OPENSSL_EXPORT void HMAC_CTX_cleanup(HMAC_CTX *ctx); + +/* HMAC_Init_ex sets up an initialised |HMAC_CTX| to use |md| as the hash + * function and |key| as the key. For a non-initial call, |md| may be NULL, in + * which case the previous hash function will be used. If the hash function has + * not changed and |key| is NULL, |ctx| reuses the previous key. It returns one + * on success or zero otherwise. + * + * WARNING: NULL and empty keys are ambiguous on non-initial calls. Passing NULL + * |key| but repeating the previous |md| reuses the previous key rather than the + * empty key. */ +OPENSSL_EXPORT int HMAC_Init_ex(HMAC_CTX *ctx, const void *key, size_t key_len, + const EVP_MD *md, ENGINE *impl); + +/* HMAC_Update hashes |data_len| bytes from |data| into the current HMAC + * operation in |ctx|. It returns one. */ +OPENSSL_EXPORT int HMAC_Update(HMAC_CTX *ctx, const uint8_t *data, + size_t data_len); + +/* HMAC_Final completes the HMAC operation in |ctx| and writes the result to + * |out| and the sets |*out_len| to the length of the result. On entry, |out| + * must contain at least |EVP_MAX_MD_SIZE| bytes of space. It returns one on + * success or zero on error. */ +OPENSSL_EXPORT int HMAC_Final(HMAC_CTX *ctx, uint8_t *out, + unsigned int *out_len); + + +/* Utility functions. */ + +/* HMAC_size returns the size, in bytes, of the HMAC that will be produced by + * |ctx|. On entry, |ctx| must have been setup with |HMAC_Init_ex|. */ +OPENSSL_EXPORT size_t HMAC_size(const HMAC_CTX *ctx); + +/* HMAC_CTX_copy_ex sets |dest| equal to |src|. On entry, |dest| must have been + * initialised by calling |HMAC_CTX_init|. It returns one on success and zero + * on error. */ +OPENSSL_EXPORT int HMAC_CTX_copy_ex(HMAC_CTX *dest, const HMAC_CTX *src); + + +/* Deprecated functions. */ + +OPENSSL_EXPORT int HMAC_Init(HMAC_CTX *ctx, const void *key, int key_len, + const EVP_MD *md); + +/* HMAC_CTX_copy calls |HMAC_CTX_init| on |dest| and then sets it equal to + * |src|. On entry, |dest| must /not/ be initialised for an operation with + * |HMAC_Init_ex|. It returns one on success and zero on error. */ +OPENSSL_EXPORT int HMAC_CTX_copy(HMAC_CTX *dest, const HMAC_CTX *src); + + +/* Private functions */ + +#define HMAC_MAX_MD_CBLOCK 128 /* largest known is SHA512 */ + +struct hmac_ctx_st { + const EVP_MD *md; + EVP_MD_CTX md_ctx; + EVP_MD_CTX i_ctx; + EVP_MD_CTX o_ctx; +} /* HMAC_CTX */; + + +#if defined(__cplusplus) +} /* extern C */ +#endif + +#endif /* OPENSSL_HEADER_HMAC_H */ diff --git a/phonelibs/boringssl/include/openssl/lhash.h b/phonelibs/boringssl/include/openssl/lhash.h new file mode 100644 index 00000000000000..d2ee982ebccb4e --- /dev/null +++ b/phonelibs/boringssl/include/openssl/lhash.h @@ -0,0 +1,191 @@ +/* Copyright (C) 1995-1998 Eric Young (eay@cryptsoft.com) * All rights reserved. + * + * This package is an SSL implementation written + * by Eric Young (eay@cryptsoft.com). + * The implementation was written so as to conform with Netscapes SSL. + * + * This library is free for commercial and non-commercial use as long as + * the following conditions are aheared to. The following conditions + * apply to all code found in this distribution, be it the RC4, RSA, + * lhash, DES, etc., code; not just the SSL code. The SSL documentation + * included with this distribution is covered by the same copyright terms + * except that the holder is Tim Hudson (tjh@cryptsoft.com). + * + * Copyright remains Eric Young's, and as such any Copyright notices in + * the code are not to be removed. + * If this package is used in a product, Eric Young should be given attribution + * as the author of the parts of the library used. + * This can be in the form of a textual message at program startup or + * in documentation (online or textual) provided with the package. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must 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. All advertising materials mentioning features or use of this software + * must display the following acknowledgement: + * "This product includes cryptographic software written by + * Eric Young (eay@cryptsoft.com)" + * The word 'cryptographic' can be left out if the rouines from the library + * being used are not cryptographic related :-). + * 4. If you include any Windows specific code (or a derivative thereof) from + * the apps directory (application code) you must include an acknowledgement: + * "This product includes software written by Tim Hudson (tjh@cryptsoft.com)" + * + * THIS SOFTWARE IS PROVIDED BY ERIC YOUNG ``AS IS'' AND + * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHOR OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (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 licence and distribution terms for any publically available version or + * derivative of this code cannot be changed. i.e. this code cannot simply be + * copied and put under another distribution licence + * [including the GNU Public Licence.] */ + +#ifndef OPENSSL_HEADER_LHASH_H +#define OPENSSL_HEADER_LHASH_H + +#include +#include + +#if defined(__cplusplus) +extern "C" { +#endif + + +/* lhash is a traditional, chaining hash table that automatically expands and + * contracts as needed. One should not use the lh_* functions directly, rather + * use the type-safe macro wrappers: + * + * A hash table of a specific type of object has type |LHASH_OF(type)|. This + * can be defined (once) with |DEFINE_LHASH_OF(type)| and declared where needed + * with |DECLARE_LHASH_OF(type)|. For example: + * + * struct foo { + * int bar; + * }; + * + * DEFINE_LHASH_OF(struct foo); + * + * Although note that the hash table will contain /pointers/ to |foo|. + * + * A macro will be defined for each of the lh_* functions below. For + * LHASH_OF(foo), the macros would be lh_foo_new, lh_foo_num_items etc. */ + + +#define LHASH_OF(type) struct lhash_st_##type + +#define DEFINE_LHASH_OF(type) LHASH_OF(type) { int dummy; } + +#define DECLARE_LHASH_OF(type) LHASH_OF(type); + +/* The make_macros.sh script in this directory parses the following lines and + * generates the lhash_macros.h file that contains macros for the following + * types of stacks: + * + * LHASH_OF:ASN1_OBJECT + * LHASH_OF:CONF_VALUE + * LHASH_OF:SSL_SESSION */ + +#define IN_LHASH_H +#include +#undef IN_LHASH_H + + +/* lhash_item_st is an element of a hash chain. It points to the opaque data + * for this element and to the next item in the chain. The linked-list is NULL + * terminated. */ +typedef struct lhash_item_st { + void *data; + struct lhash_item_st *next; + /* hash contains the cached, hash value of |data|. */ + uint32_t hash; +} LHASH_ITEM; + +/* lhash_cmp_func is a comparison function that returns a value equal, or not + * equal, to zero depending on whether |*a| is equal, or not equal to |*b|, + * respectively. Note the difference between this and |stack_cmp_func| in that + * this takes pointers to the objects directly. */ +typedef int (*lhash_cmp_func)(const void *a, const void *b); + +/* lhash_hash_func is a function that maps an object to a uniformly distributed + * uint32_t. */ +typedef uint32_t (*lhash_hash_func)(const void *a); + +typedef struct lhash_st { + /* num_items contains the total number of items in the hash table. */ + size_t num_items; + /* buckets is an array of |num_buckets| pointers. Each points to the head of + * a chain of LHASH_ITEM objects that have the same hash value, mod + * |num_buckets|. */ + LHASH_ITEM **buckets; + /* num_buckets contains the length of |buckets|. This value is always >= + * kMinNumBuckets. */ + size_t num_buckets; + /* callback_depth contains the current depth of |lh_doall| or |lh_doall_arg| + * calls. If non-zero then this suppresses resizing of the |buckets| array, + * which would otherwise disrupt the iteration. */ + unsigned callback_depth; + + lhash_cmp_func comp; + lhash_hash_func hash; +} _LHASH; + +/* lh_new returns a new, empty hash table or NULL on error. If |comp| is NULL, + * |strcmp| will be used. If |hash| is NULL, a generic hash function will be + * used. */ +OPENSSL_EXPORT _LHASH *lh_new(lhash_hash_func hash, lhash_cmp_func comp); + +/* lh_free frees the hash table itself but none of the elements. See + * |lh_doall|. */ +OPENSSL_EXPORT void lh_free(_LHASH *lh); + +/* lh_num_items returns the number of items in |lh|. */ +OPENSSL_EXPORT size_t lh_num_items(const _LHASH *lh); + +/* lh_retrieve finds an element equal to |data| in the hash table and returns + * it. If no such element exists, it returns NULL. */ +OPENSSL_EXPORT void *lh_retrieve(const _LHASH *lh, const void *data); + +/* lh_insert inserts |data| into the hash table. If an existing element is + * equal to |data| (with respect to the comparison function) then |*old_data| + * will be set to that value and it will be replaced. Otherwise, or in the + * event of an error, |*old_data| will be set to NULL. It returns one on + * success or zero in the case of an allocation error. */ +OPENSSL_EXPORT int lh_insert(_LHASH *lh, void **old_data, void *data); + +/* lh_delete removes an element equal to |data| from the hash table and returns + * it. If no such element is found, it returns NULL. */ +OPENSSL_EXPORT void *lh_delete(_LHASH *lh, const void *data); + +/* lh_doall calls |func| on each element of the hash table. + * TODO(fork): rename this */ +OPENSSL_EXPORT void lh_doall(_LHASH *lh, void (*func)(void *)); + +/* lh_doall_arg calls |func| on each element of the hash table and also passes + * |arg| as the second argument. + * TODO(fork): rename this */ +OPENSSL_EXPORT void lh_doall_arg(_LHASH *lh, void (*func)(void *, void *), + void *arg); + +/* lh_strhash is the default hash function which processes NUL-terminated + * strings. */ +OPENSSL_EXPORT uint32_t lh_strhash(const char *c); + + +#if defined(__cplusplus) +} /* extern C */ +#endif + +#endif /* OPENSSL_HEADER_STACK_H */ diff --git a/phonelibs/boringssl/include/openssl/lhash_macros.h b/phonelibs/boringssl/include/openssl/lhash_macros.h new file mode 100644 index 00000000000000..1d981073ea9e7c --- /dev/null +++ b/phonelibs/boringssl/include/openssl/lhash_macros.h @@ -0,0 +1,132 @@ +/* Copyright (c) 2014, Google Inc. + * + * Permission to use, copy, modify, and/or distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY + * SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN ACTION + * OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF OR IN + * CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. */ + +#if !defined(IN_LHASH_H) +#error "Don't include this file directly. Include lhash.h" +#endif + +/* ASN1_OBJECT */ +#define lh_ASN1_OBJECT_new(hash, comp) \ + ((LHASH_OF(ASN1_OBJECT) *)lh_new( \ + CHECKED_CAST(lhash_hash_func, uint32_t (*)(const ASN1_OBJECT *), hash), \ + CHECKED_CAST(lhash_cmp_func, \ + int (*)(const ASN1_OBJECT *a, const ASN1_OBJECT *b), \ + comp))) + +#define lh_ASN1_OBJECT_free(lh) \ + lh_free(CHECKED_CAST(_LHASH *, LHASH_OF(ASN1_OBJECT) *, lh)); + +#define lh_ASN1_OBJECT_num_items(lh) \ + lh_num_items(CHECKED_CAST(_LHASH *, LHASH_OF(ASN1_OBJECT) *, lh)) + +#define lh_ASN1_OBJECT_retrieve(lh, data) \ + ((ASN1_OBJECT *)lh_retrieve( \ + CHECKED_CAST(_LHASH *, LHASH_OF(ASN1_OBJECT) *, lh), \ + CHECKED_CAST(void *, ASN1_OBJECT *, data))) + +#define lh_ASN1_OBJECT_insert(lh, old_data, data) \ + lh_insert(CHECKED_CAST(_LHASH *, LHASH_OF(ASN1_OBJECT) *, lh), \ + CHECKED_CAST(void **, ASN1_OBJECT **, old_data), \ + CHECKED_CAST(void *, ASN1_OBJECT *, data)) + +#define lh_ASN1_OBJECT_delete(lh, data) \ + ((ASN1_OBJECT *)lh_delete( \ + CHECKED_CAST(_LHASH *, LHASH_OF(ASN1_OBJECT) *, lh), \ + CHECKED_CAST(void *, ASN1_OBJECT *, data))) + +#define lh_ASN1_OBJECT_doall(lh, func) \ + lh_doall(CHECKED_CAST(_LHASH *, LHASH_OF(ASN1_OBJECT) *, lh), \ + CHECKED_CAST(void (*)(void *), void (*)(ASN1_OBJECT *), func)); + +#define lh_ASN1_OBJECT_doall_arg(lh, func, arg) \ + lh_doall_arg(CHECKED_CAST(_LHASH *, LHASH_OF(ASN1_OBJECT) *, lh), \ + CHECKED_CAST(void (*)(void *, void *), \ + void (*)(ASN1_OBJECT *, void *), func), \ + arg); + +/* CONF_VALUE */ +#define lh_CONF_VALUE_new(hash, comp) \ + ((LHASH_OF(CONF_VALUE) *)lh_new( \ + CHECKED_CAST(lhash_hash_func, uint32_t (*)(const CONF_VALUE *), hash), \ + CHECKED_CAST(lhash_cmp_func, \ + int (*)(const CONF_VALUE *a, const CONF_VALUE *b), comp))) + +#define lh_CONF_VALUE_free(lh) \ + lh_free(CHECKED_CAST(_LHASH *, LHASH_OF(CONF_VALUE) *, lh)); + +#define lh_CONF_VALUE_num_items(lh) \ + lh_num_items(CHECKED_CAST(_LHASH *, LHASH_OF(CONF_VALUE) *, lh)) + +#define lh_CONF_VALUE_retrieve(lh, data) \ + ((CONF_VALUE *)lh_retrieve( \ + CHECKED_CAST(_LHASH *, LHASH_OF(CONF_VALUE) *, lh), \ + CHECKED_CAST(void *, CONF_VALUE *, data))) + +#define lh_CONF_VALUE_insert(lh, old_data, data) \ + lh_insert(CHECKED_CAST(_LHASH *, LHASH_OF(CONF_VALUE) *, lh), \ + CHECKED_CAST(void **, CONF_VALUE **, old_data), \ + CHECKED_CAST(void *, CONF_VALUE *, data)) + +#define lh_CONF_VALUE_delete(lh, data) \ + ((CONF_VALUE *)lh_delete(CHECKED_CAST(_LHASH *, LHASH_OF(CONF_VALUE) *, lh), \ + CHECKED_CAST(void *, CONF_VALUE *, data))) + +#define lh_CONF_VALUE_doall(lh, func) \ + lh_doall(CHECKED_CAST(_LHASH *, LHASH_OF(CONF_VALUE) *, lh), \ + CHECKED_CAST(void (*)(void *), void (*)(CONF_VALUE *), func)); + +#define lh_CONF_VALUE_doall_arg(lh, func, arg) \ + lh_doall_arg(CHECKED_CAST(_LHASH *, LHASH_OF(CONF_VALUE) *, lh), \ + CHECKED_CAST(void (*)(void *, void *), \ + void (*)(CONF_VALUE *, void *), func), \ + arg); + +/* SSL_SESSION */ +#define lh_SSL_SESSION_new(hash, comp) \ + ((LHASH_OF(SSL_SESSION) *)lh_new( \ + CHECKED_CAST(lhash_hash_func, uint32_t (*)(const SSL_SESSION *), hash), \ + CHECKED_CAST(lhash_cmp_func, \ + int (*)(const SSL_SESSION *a, const SSL_SESSION *b), \ + comp))) + +#define lh_SSL_SESSION_free(lh) \ + lh_free(CHECKED_CAST(_LHASH *, LHASH_OF(SSL_SESSION) *, lh)); + +#define lh_SSL_SESSION_num_items(lh) \ + lh_num_items(CHECKED_CAST(_LHASH *, LHASH_OF(SSL_SESSION) *, lh)) + +#define lh_SSL_SESSION_retrieve(lh, data) \ + ((SSL_SESSION *)lh_retrieve( \ + CHECKED_CAST(_LHASH *, LHASH_OF(SSL_SESSION) *, lh), \ + CHECKED_CAST(void *, SSL_SESSION *, data))) + +#define lh_SSL_SESSION_insert(lh, old_data, data) \ + lh_insert(CHECKED_CAST(_LHASH *, LHASH_OF(SSL_SESSION) *, lh), \ + CHECKED_CAST(void **, SSL_SESSION **, old_data), \ + CHECKED_CAST(void *, SSL_SESSION *, data)) + +#define lh_SSL_SESSION_delete(lh, data) \ + ((SSL_SESSION *)lh_delete( \ + CHECKED_CAST(_LHASH *, LHASH_OF(SSL_SESSION) *, lh), \ + CHECKED_CAST(void *, SSL_SESSION *, data))) + +#define lh_SSL_SESSION_doall(lh, func) \ + lh_doall(CHECKED_CAST(_LHASH *, LHASH_OF(SSL_SESSION) *, lh), \ + CHECKED_CAST(void (*)(void *), void (*)(SSL_SESSION *), func)); + +#define lh_SSL_SESSION_doall_arg(lh, func, arg) \ + lh_doall_arg(CHECKED_CAST(_LHASH *, LHASH_OF(SSL_SESSION) *, lh), \ + CHECKED_CAST(void (*)(void *, void *), \ + void (*)(SSL_SESSION *, void *), func), \ + arg); diff --git a/phonelibs/boringssl/include/openssl/md4.h b/phonelibs/boringssl/include/openssl/md4.h new file mode 100644 index 00000000000000..ce4fa99bb8c010 --- /dev/null +++ b/phonelibs/boringssl/include/openssl/md4.h @@ -0,0 +1,101 @@ +/* Copyright (C) 1995-1998 Eric Young (eay@cryptsoft.com) * All rights reserved. + * + * This package is an SSL implementation written + * by Eric Young (eay@cryptsoft.com). + * The implementation was written so as to conform with Netscapes SSL. + * + * This library is free for commercial and non-commercial use as long as + * the following conditions are aheared to. The following conditions + * apply to all code found in this distribution, be it the RC4, RSA, + * lhash, DES, etc., code; not just the SSL code. The SSL documentation + * included with this distribution is covered by the same copyright terms + * except that the holder is Tim Hudson (tjh@cryptsoft.com). + * + * Copyright remains Eric Young's, and as such any Copyright notices in + * the code are not to be removed. + * If this package is used in a product, Eric Young should be given attribution + * as the author of the parts of the library used. + * This can be in the form of a textual message at program startup or + * in documentation (online or textual) provided with the package. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must 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. All advertising materials mentioning features or use of this software + * must display the following acknowledgement: + * "This product includes cryptographic software written by + * Eric Young (eay@cryptsoft.com)" + * The word 'cryptographic' can be left out if the rouines from the library + * being used are not cryptographic related :-). + * 4. If you include any Windows specific code (or a derivative thereof) from + * the apps directory (application code) you must include an acknowledgement: + * "This product includes software written by Tim Hudson (tjh@cryptsoft.com)" + * + * THIS SOFTWARE IS PROVIDED BY ERIC YOUNG ``AS IS'' AND + * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHOR OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (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 licence and distribution terms for any publically available version or + * derivative of this code cannot be changed. i.e. this code cannot simply be + * copied and put under another distribution licence + * [including the GNU Public Licence.] */ + +#ifndef OPENSSL_HEADER_MD4_H +#define OPENSSL_HEADER_MD4_H + +#include + +#if defined(__cplusplus) +extern "C" { +#endif + + +/* MD4. */ + +/* MD4_CBLOCK is the block size of MD4. */ +#define MD4_CBLOCK 64 + +/* MD4_DIGEST_LENGTH is the length of an MD4 digest. */ +#define MD4_DIGEST_LENGTH 16 + +/* MD41_Init initialises |md4| and returns one. */ +OPENSSL_EXPORT int MD4_Init(MD4_CTX *md4); + +/* MD4_Update adds |len| bytes from |data| to |md4| and returns one. */ +OPENSSL_EXPORT int MD4_Update(MD4_CTX *md4, const void *data, size_t len); + +/* MD4_Final adds the final padding to |md4| and writes the resulting digest to + * |md|, which must have at least |MD4_DIGEST_LENGTH| bytes of space. It + * returns one. */ +OPENSSL_EXPORT int MD4_Final(uint8_t *md, MD4_CTX *md4); + +/* MD4_Transform is a low-level function that performs a single, MD4 block + * transformation using the state from |md4| and 64 bytes from |block|. */ +OPENSSL_EXPORT void MD4_Transform(MD4_CTX *md4, const uint8_t *block); + +struct md4_state_st { + uint32_t A, B, C, D; + uint32_t Nl, Nh; + uint32_t data[16]; + unsigned int num; +}; + + +#if defined(__cplusplus) +} /* extern C */ +#endif + +#endif /* OPENSSL_HEADER_MD4_H */ diff --git a/phonelibs/boringssl/include/openssl/md5.h b/phonelibs/boringssl/include/openssl/md5.h new file mode 100644 index 00000000000000..efedc983debdcd --- /dev/null +++ b/phonelibs/boringssl/include/openssl/md5.h @@ -0,0 +1,106 @@ +/* Copyright (C) 1995-1998 Eric Young (eay@cryptsoft.com) * All rights reserved. + * + * This package is an SSL implementation written + * by Eric Young (eay@cryptsoft.com). + * The implementation was written so as to conform with Netscapes SSL. + * + * This library is free for commercial and non-commercial use as long as + * the following conditions are aheared to. The following conditions + * apply to all code found in this distribution, be it the RC4, RSA, + * lhash, DES, etc., code; not just the SSL code. The SSL documentation + * included with this distribution is covered by the same copyright terms + * except that the holder is Tim Hudson (tjh@cryptsoft.com). + * + * Copyright remains Eric Young's, and as such any Copyright notices in + * the code are not to be removed. + * If this package is used in a product, Eric Young should be given attribution + * as the author of the parts of the library used. + * This can be in the form of a textual message at program startup or + * in documentation (online or textual) provided with the package. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must 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. All advertising materials mentioning features or use of this software + * must display the following acknowledgement: + * "This product includes cryptographic software written by + * Eric Young (eay@cryptsoft.com)" + * The word 'cryptographic' can be left out if the rouines from the library + * being used are not cryptographic related :-). + * 4. If you include any Windows specific code (or a derivative thereof) from + * the apps directory (application code) you must include an acknowledgement: + * "This product includes software written by Tim Hudson (tjh@cryptsoft.com)" + * + * THIS SOFTWARE IS PROVIDED BY ERIC YOUNG ``AS IS'' AND + * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHOR OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (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 licence and distribution terms for any publically available version or + * derivative of this code cannot be changed. i.e. this code cannot simply be + * copied and put under another distribution licence + * [including the GNU Public Licence.] */ + +#ifndef OPENSSL_HEADER_MD5_H +#define OPENSSL_HEADER_MD5_H + +#include + +#if defined(__cplusplus) +extern "C" { +#endif + + +/* MD5. */ + + +/* MD5_CBLOCK is the block size of MD5. */ +#define MD5_CBLOCK 64 + +/* MD5_DIGEST_LENGTH is the length of an MD5 digest. */ +#define MD5_DIGEST_LENGTH 16 + +/* MD51_Init initialises |md5| and returns one. */ +OPENSSL_EXPORT int MD5_Init(MD5_CTX *md5); + +/* MD5_Update adds |len| bytes from |data| to |md5| and returns one. */ +OPENSSL_EXPORT int MD5_Update(MD5_CTX *md5, const void *data, size_t len); + +/* MD5_Final adds the final padding to |md5| and writes the resulting digest to + * |md|, which must have at least |MD5_DIGEST_LENGTH| bytes of space. It + * returns one. */ +OPENSSL_EXPORT int MD5_Final(uint8_t *md, MD5_CTX *md5); + +/* MD5 writes the digest of |len| bytes from |data| to |out| and returns |out|. + * There must be at least |MD5_DIGEST_LENGTH| bytes of space in |out|. */ +OPENSSL_EXPORT uint8_t *MD5(const uint8_t *data, size_t len, uint8_t *out); + +/* MD5_Transform is a low-level function that performs a single, MD5 block + * transformation using the state from |md5| and 64 bytes from |block|. */ +OPENSSL_EXPORT void MD5_Transform(MD5_CTX *md5, const uint8_t *block); + +struct md5_state_st { + uint32_t A, B, C, D; + uint32_t Nl, Nh; + uint32_t data[16]; + unsigned int num; +}; + + +#if defined(__cplusplus) +} /* extern C */ +#endif + +#endif /* OPENSSL_HEADER_MD5_H */ diff --git a/phonelibs/boringssl/include/openssl/mem.h b/phonelibs/boringssl/include/openssl/mem.h new file mode 100644 index 00000000000000..42ec46a073e19f --- /dev/null +++ b/phonelibs/boringssl/include/openssl/mem.h @@ -0,0 +1,139 @@ +/* Copyright (C) 1995-1998 Eric Young (eay@cryptsoft.com) * All rights reserved. + * + * This package is an SSL implementation written + * by Eric Young (eay@cryptsoft.com). + * The implementation was written so as to conform with Netscapes SSL. + * + * This library is free for commercial and non-commercial use as long as + * the following conditions are aheared to. The following conditions + * apply to all code found in this distribution, be it the RC4, RSA, + * lhash, DES, etc., code; not just the SSL code. The SSL documentation + * included with this distribution is covered by the same copyright terms + * except that the holder is Tim Hudson (tjh@cryptsoft.com). + * + * Copyright remains Eric Young's, and as such any Copyright notices in + * the code are not to be removed. + * If this package is used in a product, Eric Young should be given attribution + * as the author of the parts of the library used. + * This can be in the form of a textual message at program startup or + * in documentation (online or textual) provided with the package. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must 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. All advertising materials mentioning features or use of this software + * must display the following acknowledgement: + * "This product includes cryptographic software written by + * Eric Young (eay@cryptsoft.com)" + * The word 'cryptographic' can be left out if the rouines from the library + * being used are not cryptographic related :-). + * 4. If you include any Windows specific code (or a derivative thereof) from + * the apps directory (application code) you must include an acknowledgement: + * "This product includes software written by Tim Hudson (tjh@cryptsoft.com)" + * + * THIS SOFTWARE IS PROVIDED BY ERIC YOUNG ``AS IS'' AND + * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHOR OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (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 licence and distribution terms for any publically available version or + * derivative of this code cannot be changed. i.e. this code cannot simply be + * copied and put under another distribution licence + * [including the GNU Public Licence.] */ + +#ifndef OPENSSL_HEADER_MEM_H +#define OPENSSL_HEADER_MEM_H + +#include + +#include +#include + +#if defined(__cplusplus) +extern "C" { +#endif + + +/* Memory and string functions, see also buf.h. + * + * OpenSSL has, historically, had a complex set of malloc debugging options. + * However, that was written in a time before Valgrind and ASAN. Since we now + * have those tools, the OpenSSL allocation functions are simply macros around + * the standard memory functions. */ + + +#define OPENSSL_malloc malloc +#define OPENSSL_realloc realloc +#define OPENSSL_free free + +/* OPENSSL_realloc_clean acts like |realloc|, but clears the previous memory + * buffer. Because this is implemented as a wrapper around |malloc|, it needs + * to be given the size of the buffer pointed to by |ptr|. */ +void *OPENSSL_realloc_clean(void *ptr, size_t old_size, size_t new_size); + +/* OPENSSL_cleanse zeros out |len| bytes of memory at |ptr|. This is similar to + * |memset_s| from C11. */ +OPENSSL_EXPORT void OPENSSL_cleanse(void *ptr, size_t len); + +/* CRYPTO_memcmp returns zero iff the |len| bytes at |a| and |b| are equal. It + * takes an amount of time dependent on |len|, but independent of the contents + * of |a| and |b|. Unlike memcmp, it cannot be used to put elements into a + * defined order as the return value when a != b is undefined, other than to be + * non-zero. */ +OPENSSL_EXPORT int CRYPTO_memcmp(const void *a, const void *b, size_t len); + +/* OPENSSL_hash32 implements the 32 bit, FNV-1a hash. */ +OPENSSL_EXPORT uint32_t OPENSSL_hash32(const void *ptr, size_t len); + +/* OPENSSL_strdup has the same behaviour as strdup(3). */ +OPENSSL_EXPORT char *OPENSSL_strdup(const char *s); + +/* OPENSSL_strnlen has the same behaviour as strnlen(3). */ +OPENSSL_EXPORT size_t OPENSSL_strnlen(const char *s, size_t len); + +/* OPENSSL_strcasecmp has the same behaviour as strcasecmp(3). */ +OPENSSL_EXPORT int OPENSSL_strcasecmp(const char *a, const char *b); + +/* OPENSSL_strncasecmp has the same behaviour as strncasecmp(3). */ +OPENSSL_EXPORT int OPENSSL_strncasecmp(const char *a, const char *b, size_t n); + +/* DECIMAL_SIZE returns an upper bound for the length of the decimal + * representation of the given type. */ +#define DECIMAL_SIZE(type) ((sizeof(type)*8+2)/3+1) + +/* Printf functions. + * + * These functions are either OpenSSL wrappers for standard functions (i.e. + * |BIO_snprintf| and |BIO_vsnprintf|) which don't exist in C89, or are + * versions of printf functions that output to a BIO rather than a FILE. */ +#ifdef __GNUC__ +#define __bio_h__attr__ __attribute__ +#else +#define __bio_h__attr__(x) +#endif +OPENSSL_EXPORT int BIO_snprintf(char *buf, size_t n, const char *format, ...) + __bio_h__attr__((__format__(__printf__, 3, 4))); + +OPENSSL_EXPORT int BIO_vsnprintf(char *buf, size_t n, const char *format, + va_list args) + __bio_h__attr__((__format__(__printf__, 3, 0))); +#undef __bio_h__attr__ + + +#if defined(__cplusplus) +} /* extern C */ +#endif + +#endif /* OPENSSL_HEADER_MEM_H */ diff --git a/phonelibs/boringssl/include/openssl/modes.h b/phonelibs/boringssl/include/openssl/modes.h new file mode 100644 index 00000000000000..220adec552d8be --- /dev/null +++ b/phonelibs/boringssl/include/openssl/modes.h @@ -0,0 +1,223 @@ +/* ==================================================================== + * Copyright (c) 2008 The OpenSSL Project. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * + * 3. All advertising materials mentioning features or use of this + * software must display the following acknowledgment: + * "This product includes software developed by the OpenSSL Project + * for use in the OpenSSL Toolkit. (http://www.openssl.org/)" + * + * 4. The names "OpenSSL Toolkit" and "OpenSSL Project" must not be used to + * endorse or promote products derived from this software without + * prior written permission. For written permission, please contact + * openssl-core@openssl.org. + * + * 5. Products derived from this software may not be called "OpenSSL" + * nor may "OpenSSL" appear in their names without prior written + * permission of the OpenSSL Project. + * + * 6. Redistributions of any form whatsoever must retain the following + * acknowledgment: + * "This product includes software developed by the OpenSSL Project + * for use in the OpenSSL Toolkit (http://www.openssl.org/)" + * + * THIS SOFTWARE IS PROVIDED BY THE OpenSSL PROJECT ``AS IS'' AND ANY + * EXPRESSED OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR + * PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE OpenSSL PROJECT OR + * ITS CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, + * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT + * NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + * STRICT LIABILITY, OR TORT (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 OPENSSL_HEADER_MODES_H +#define OPENSSL_HEADER_MODES_H + +#include + +#if defined(__cplusplus) +extern "C" { +#endif + + +/* modes.h contains functions that implement various block-cipher modes. */ + + +/* block128_f is the type of a 128-bit, block cipher. */ +typedef void (*block128_f)(const uint8_t in[16], uint8_t out[16], + const void *key); + + +/* CTR. */ + +/* ctr128_f is the type of a function that performs CTR-mode encryption. */ +typedef void (*ctr128_f)(const uint8_t *in, uint8_t *out, size_t blocks, + const void *key, const uint8_t ivec[16]); + +/* CRYPTO_ctr128_encrypt encrypts (or decrypts, it's the same in CTR mode) + * |len| bytes from |in| to |out| using |block| in counter mode. There's no + * requirement that |len| be a multiple of any value and any partial blocks are + * stored in |ecount_buf| and |*num|, which must be zeroed before the initial + * call. The counter is a 128-bit, big-endian value in |ivec| and is + * incremented by this function. */ +OPENSSL_EXPORT void CRYPTO_ctr128_encrypt(const uint8_t *in, uint8_t *out, + size_t len, const void *key, + uint8_t ivec[16], + uint8_t ecount_buf[16], + unsigned int *num, block128_f block); + +/* CRYPTO_ctr128_encrypt_ctr32 acts like |CRYPTO_ctr128_encrypt| but takes + * |ctr|, a function that performs CTR mode but only deals with the lower 32 + * bits of the counter. This is useful when |ctr| can be an optimised + * function. */ +OPENSSL_EXPORT void CRYPTO_ctr128_encrypt_ctr32( + const uint8_t *in, uint8_t *out, size_t len, const void *key, + uint8_t ivec[16], uint8_t ecount_buf[16], unsigned int *num, ctr128_f ctr); + + +/* GCM. */ + +typedef struct gcm128_context GCM128_CONTEXT; + +/* CRYPTO_gcm128_new allocates a fresh |GCM128_CONTEXT| and calls + * |CRYPTO_gcm128_init|. It returns the new context, or NULL on error. */ +OPENSSL_EXPORT GCM128_CONTEXT *CRYPTO_gcm128_new(void *key, block128_f block); + +/* CRYPTO_gcm128_init initialises |ctx| to use |block| (typically AES) with the + * given key. */ +OPENSSL_EXPORT void CRYPTO_gcm128_init(GCM128_CONTEXT *ctx, void *key, + block128_f block); + +/* CRYPTO_gcm128_setiv sets the IV (nonce) for |ctx|. */ +OPENSSL_EXPORT void CRYPTO_gcm128_setiv(GCM128_CONTEXT *ctx, const uint8_t *iv, + size_t len); + +/* CRYPTO_gcm128_aad sets the authenticated data for an instance of GCM. This + * must be called before and data is encrypted. It returns one on success and + * zero otherwise. */ +OPENSSL_EXPORT int CRYPTO_gcm128_aad(GCM128_CONTEXT *ctx, const uint8_t *aad, + size_t len); + +/* CRYPTO_gcm128_encrypt encrypts |len| bytes from |in| to |out|. It returns + * one on success and zero otherwise. */ +OPENSSL_EXPORT int CRYPTO_gcm128_encrypt(GCM128_CONTEXT *ctx, const uint8_t *in, + uint8_t *out, size_t len); + +/* CRYPTO_gcm128_decrypt decrypts |len| bytes from |in| to |out|. It returns + * one on success and zero otherwise. */ +OPENSSL_EXPORT int CRYPTO_gcm128_decrypt(GCM128_CONTEXT *ctx, const uint8_t *in, + uint8_t *out, size_t len); + +/* CRYPTO_gcm128_encrypt_ctr32 encrypts |len| bytes from |in| to |out| using a + * CTR function that only handles the bottom 32 bits of the nonce, like + * |CRYPTO_ctr128_encrypt_ctr32|. It returns one on success and zero + * otherwise. */ +OPENSSL_EXPORT int CRYPTO_gcm128_encrypt_ctr32(GCM128_CONTEXT *ctx, + const uint8_t *in, uint8_t *out, + size_t len, ctr128_f stream); + +/* CRYPTO_gcm128_decrypt_ctr32 decrypts |len| bytes from |in| to |out| using a + * CTR function that only handles the bottom 32 bits of the nonce, like + * |CRYPTO_ctr128_encrypt_ctr32|. It returns one on success and zero + * otherwise. */ +OPENSSL_EXPORT int CRYPTO_gcm128_decrypt_ctr32(GCM128_CONTEXT *ctx, + const uint8_t *in, uint8_t *out, + size_t len, ctr128_f stream); + +/* CRYPTO_gcm128_finish calculates the authenticator and compares it against + * |len| bytes of |tag|. It returns one on success and zero otherwise. */ +OPENSSL_EXPORT int CRYPTO_gcm128_finish(GCM128_CONTEXT *ctx, const uint8_t *tag, + size_t len); + +/* CRYPTO_gcm128_tag calculates the authenticator and copies it into |tag|. The + * minimum of |len| and 16 bytes are copied into |tag|. */ +OPENSSL_EXPORT void CRYPTO_gcm128_tag(GCM128_CONTEXT *ctx, uint8_t *tag, + size_t len); + +/* CRYPTO_gcm128_release clears and frees |ctx|. */ +OPENSSL_EXPORT void CRYPTO_gcm128_release(GCM128_CONTEXT *ctx); + + +/* CBC. */ + +/* cbc128_f is the type of a function that performs CBC-mode encryption. */ +typedef void (*cbc128_f)(const uint8_t *in, uint8_t *out, size_t len, + const void *key, uint8_t ivec[16], int enc); + +/* CRYPTO_cbc128_encrypt encrypts |len| bytes from |in| to |out| using the + * given IV and block cipher in CBC mode. The input need not be a multiple of + * 128 bits long, but the output will round up to the nearest 128 bit multiple, + * zero padding the input if needed. The IV will be updated on return. */ +void CRYPTO_cbc128_encrypt(const uint8_t *in, uint8_t *out, size_t len, + const void *key, uint8_t ivec[16], block128_f block); + +/* CRYPTO_cbc128_decrypt decrypts |len| bytes from |in| to |out| using the + * given IV and block cipher in CBC mode. If |len| is not a multiple of 128 + * bits then only that many bytes will be written, but a multiple of 128 bits + * is always read from |in|. The IV will be updated on return. */ +void CRYPTO_cbc128_decrypt(const uint8_t *in, uint8_t *out, size_t len, + const void *key, uint8_t ivec[16], block128_f block); + + +/* OFB. */ + +/* CRYPTO_ofb128_encrypt encrypts (or decrypts, it's the same with OFB mode) + * |len| bytes from |in| to |out| using |block| in OFB mode. There's no + * requirement that |len| be a multiple of any value and any partial blocks are + * stored in |ivec| and |*num|, the latter must be zero before the initial + * call. */ +void CRYPTO_ofb128_encrypt(const uint8_t *in, uint8_t *out, + size_t len, const void *key, uint8_t ivec[16], + int *num, block128_f block); + + +/* CFB. */ + +/* CRYPTO_cfb128_encrypt encrypts (or decrypts, if |enc| is zero) |len| bytes + * from |in| to |out| using |block| in CFB mode. There's no requirement that + * |len| be a multiple of any value and any partial blocks are stored in |ivec| + * and |*num|, the latter must be zero before the initial call. */ +void CRYPTO_cfb128_encrypt(const uint8_t *in, uint8_t *out, size_t len, + const void *key, uint8_t ivec[16], int *num, int enc, + block128_f block); + +/* CRYPTO_cfb128_8_encrypt encrypts (or decrypts, if |enc| is zero) |len| bytes + * from |in| to |out| using |block| in CFB-8 mode. Prior to the first call + * |num| should be set to zero. */ +void CRYPTO_cfb128_8_encrypt(const uint8_t *in, uint8_t *out, size_t len, + const void *key, uint8_t ivec[16], int *num, + int enc, block128_f block); + +/* CRYPTO_cfb128_1_encrypt encrypts (or decrypts, if |enc| is zero) |len| bytes + * from |in| to |out| using |block| in CFB-1 mode. Prior to the first call + * |num| should be set to zero. */ +void CRYPTO_cfb128_1_encrypt(const uint8_t *in, uint8_t *out, size_t bits, + const void *key, uint8_t ivec[16], int *num, + int enc, block128_f block); + +size_t CRYPTO_cts128_encrypt_block(const uint8_t *in, uint8_t *out, size_t len, + const void *key, uint8_t ivec[16], + block128_f block); + + +#if defined(__cplusplus) +} /* extern C */ +#endif + +#endif /* OPENSSL_HEADER_MODES_H */ diff --git a/phonelibs/boringssl/include/openssl/obj.h b/phonelibs/boringssl/include/openssl/obj.h new file mode 100644 index 00000000000000..f476617e18e427 --- /dev/null +++ b/phonelibs/boringssl/include/openssl/obj.h @@ -0,0 +1,202 @@ +/* Copyright (C) 1995-1998 Eric Young (eay@cryptsoft.com) + * All rights reserved. + * + * This package is an SSL implementation written + * by Eric Young (eay@cryptsoft.com). + * The implementation was written so as to conform with Netscapes SSL. + * + * This library is free for commercial and non-commercial use as long as + * the following conditions are aheared to. The following conditions + * apply to all code found in this distribution, be it the RC4, RSA, + * lhash, DES, etc., code; not just the SSL code. The SSL documentation + * included with this distribution is covered by the same copyright terms + * except that the holder is Tim Hudson (tjh@cryptsoft.com). + * + * Copyright remains Eric Young's, and as such any Copyright notices in + * the code are not to be removed. + * If this package is used in a product, Eric Young should be given attribution + * as the author of the parts of the library used. + * This can be in the form of a textual message at program startup or + * in documentation (online or textual) provided with the package. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must 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. All advertising materials mentioning features or use of this software + * must display the following acknowledgement: + * "This product includes cryptographic software written by + * Eric Young (eay@cryptsoft.com)" + * The word 'cryptographic' can be left out if the rouines from the library + * being used are not cryptographic related :-). + * 4. If you include any Windows specific code (or a derivative thereof) from + * the apps directory (application code) you must include an acknowledgement: + * "This product includes software written by Tim Hudson (tjh@cryptsoft.com)" + * + * THIS SOFTWARE IS PROVIDED BY ERIC YOUNG ``AS IS'' AND + * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHOR OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (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 licence and distribution terms for any publically available version or + * derivative of this code cannot be changed. i.e. this code cannot simply be + * copied and put under another distribution licence + * [including the GNU Public Licence.] */ + +#ifndef OPENSSL_HEADER_OBJECTS_H +#define OPENSSL_HEADER_OBJECTS_H + +#include + +#include +#include + +#if defined(__cplusplus) +extern "C" { +#endif + + +/* The objects library deals with the registration and indexing of ASN.1 object + * identifiers. These values are often written as a dotted sequence of numbers, + * e.g. 1.2.840.113549.1.9.16.3.9. + * + * Internally, OpenSSL likes to deal with these values by numbering them with + * numbers called "nids". OpenSSL has a large, built-in database of common + * object identifiers and also has both short and long names for them. + * + * This library provides functions for translating between object identifiers, + * nids, short names and long names. + * + * The nid values should not be used outside of a single process: they are not + * stable identifiers. */ + + +/* Basic operations. */ + +/* OBJ_dup returns a duplicate copy of |obj| or NULL on allocation failure. */ +OPENSSL_EXPORT ASN1_OBJECT *OBJ_dup(const ASN1_OBJECT *obj); + +/* OBJ_cmp returns a value less than, equal to or greater than zero if |a| is + * less than, equal to or greater than |b|, respectively. */ +OPENSSL_EXPORT int OBJ_cmp(const ASN1_OBJECT *a, const ASN1_OBJECT *b); + + +/* Looking up nids. */ + +/* OBJ_obj2nid returns the nid corresponding to |obj|, or |NID_undef| if no + * such object is known. */ +OPENSSL_EXPORT int OBJ_obj2nid(const ASN1_OBJECT *obj); + +/* OBJ_cbs2nid returns the nid corresponding to the DER data in |cbs|, or + * |NID_undef| if no such object is known. */ +OPENSSL_EXPORT int OBJ_cbs2nid(const CBS *cbs); + +/* OBJ_sn2nid returns the nid corresponding to |short_name|, or |NID_undef| if + * no such short name is known. */ +OPENSSL_EXPORT int OBJ_sn2nid(const char *short_name); + +/* OBJ_ln2nid returns the nid corresponding to |long_name|, or |NID_undef| if + * no such long name is known. */ +OPENSSL_EXPORT int OBJ_ln2nid(const char *long_name); + +/* OBJ_txt2nid returns the nid corresponding to |s|, which may be a short name, + * long name, or an ASCII string containing a dotted sequence of numbers. It + * returns the nid or NID_undef if unknown. */ +OPENSSL_EXPORT int OBJ_txt2nid(const char *s); + + +/* Getting information about nids. */ + +/* OBJ_nid2obj returns the ASN1_OBJECT corresponding to |nid|, or NULL if |nid| + * is unknown. */ +OPENSSL_EXPORT const ASN1_OBJECT *OBJ_nid2obj(int nid); + +/* OBJ_nid2sn returns the short name for |nid|, or NULL if |nid| is unknown. */ +OPENSSL_EXPORT const char *OBJ_nid2sn(int nid); + +/* OBJ_nid2sn returns the long name for |nid|, or NULL if |nid| is unknown. */ +OPENSSL_EXPORT const char *OBJ_nid2ln(int nid); + +/* OBJ_nid2cbs writes |nid| as an ASN.1 OBJECT IDENTIFIER to |out|. It returns + * one on success or zero otherwise. */ +OPENSSL_EXPORT int OBJ_nid2cbb(CBB *out, int nid); + + +/* Dealing with textual representations of object identifiers. */ + +/* OBJ_txt2obj returns an ASN1_OBJECT for the textual respresentation in |s|. + * If |dont_search_names| is zero, then |s| will be matched against the long + * and short names of a known objects to find a match. Otherwise |s| must + * contain an ASCII string with a dotted sequence of numbers. The resulting + * object need not be previously known. It returns a freshly allocated + * |ASN1_OBJECT| or NULL on error. */ +OPENSSL_EXPORT ASN1_OBJECT *OBJ_txt2obj(const char *s, int dont_search_names); + +/* OBJ_obj2txt converts |obj| to a textual representation. If + * |dont_return_name| is zero then |obj| will be matched against known objects + * and the long (preferably) or short name will be used if found. Otherwise + * |obj| will be converted into a dotted sequence of integers. If |out| is not + * NULL, then at most |out_len| bytes of the textual form will be written + * there. If |out_len| is at least one, then string written to |out| will + * always be NUL terminated. It returns the number of characters that could + * have been written, not including the final NUL, or -1 on error. */ +OPENSSL_EXPORT int OBJ_obj2txt(char *out, int out_len, const ASN1_OBJECT *obj, + int dont_return_name); + + +/* Adding objects at runtime. */ + +/* OBJ_create adds a known object and returns the nid of the new object, or + * NID_undef on error. */ +OPENSSL_EXPORT int OBJ_create(const char *oid, const char *short_name, + const char *long_name); + + +/* Handling signature algorithm identifiers. + * + * Some NIDs (e.g. sha256WithRSAEncryption) specify both a digest algorithm and + * a public key algorithm. The following functions map between pairs of digest + * and public-key algorithms and the NIDs that specify their combination. + * + * Sometimes the combination NID leaves the digest unspecified (e.g. + * rsassaPss). In these cases, the digest NID is |NID_undef|. */ + +/* OBJ_find_sigid_algs finds the digest and public-key NIDs that correspond to + * the signing algorithm |sign_nid|. If successful, it sets |*out_digest_nid| + * and |*out_pkey_nid| and returns one. Otherwise it returns zero. Any of + * |out_digest_nid| or |out_pkey_nid| can be NULL if the caller doesn't need + * that output value. */ +OPENSSL_EXPORT int OBJ_find_sigid_algs(int sign_nid, int *out_digest_nid, + int *out_pkey_nid); + +/* OBJ_find_sigid_by_algs finds the signature NID that corresponds to the + * combination of |digest_nid| and |pkey_nid|. If success, it sets + * |*out_sign_nid| and returns one. Otherwise it returns zero. The + * |out_sign_nid| argument can be NULL if the caller only wishes to learn + * whether the combination is valid. */ +OPENSSL_EXPORT int OBJ_find_sigid_by_algs(int *out_sign_nid, int digest_nid, + int pkey_nid); + + +#if defined(__cplusplus) +} /* extern C */ +#endif + +#define OBJ_F_OBJ_create 100 +#define OBJ_F_OBJ_dup 101 +#define OBJ_F_OBJ_nid2obj 102 +#define OBJ_F_OBJ_txt2obj 103 +#define OBJ_R_UNKNOWN_NID 100 + +#endif /* OPENSSL_HEADER_OBJECTS_H */ diff --git a/phonelibs/boringssl/include/openssl/obj_mac.h b/phonelibs/boringssl/include/openssl/obj_mac.h new file mode 100644 index 00000000000000..55e1cba2fee7bc --- /dev/null +++ b/phonelibs/boringssl/include/openssl/obj_mac.h @@ -0,0 +1,4140 @@ +/* THIS FILE IS GENERATED FROM objects.txt by objects.pl via the + * following command: + * perl objects.pl objects.txt obj_mac.num ../../include/openssl/obj_mac.h */ + +/* Copyright (C) 1995-1997 Eric Young (eay@cryptsoft.com) + * All rights reserved. + * + * This package is an SSL implementation written + * by Eric Young (eay@cryptsoft.com). + * The implementation was written so as to conform with Netscapes SSL. + * + * This library is free for commercial and non-commercial use as long as + * the following conditions are aheared to. The following conditions + * apply to all code found in this distribution, be it the RC4, RSA, + * lhash, DES, etc., code; not just the SSL code. The SSL documentation + * included with this distribution is covered by the same copyright terms + * except that the holder is Tim Hudson (tjh@cryptsoft.com). + * + * Copyright remains Eric Young's, and as such any Copyright notices in + * the code are not to be removed. + * If this package is used in a product, Eric Young should be given attribution + * as the author of the parts of the library used. + * This can be in the form of a textual message at program startup or + * in documentation (online or textual) provided with the package. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must 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. All advertising materials mentioning features or use of this software + * must display the following acknowledgement: + * "This product includes cryptographic software written by + * Eric Young (eay@cryptsoft.com)" + * The word 'cryptographic' can be left out if the rouines from the library + * being used are not cryptographic related :-). + * 4. If you include any Windows specific code (or a derivative thereof) from + * the apps directory (application code) you must include an acknowledgement: + * "This product includes software written by Tim Hudson (tjh@cryptsoft.com)" + * + * THIS SOFTWARE IS PROVIDED BY ERIC YOUNG ``AS IS'' AND + * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHOR OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (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 licence and distribution terms for any publically available version or + * derivative of this code cannot be changed. i.e. this code cannot simply be + * copied and put under another distribution licence + * [including the GNU Public Licence.] + */ + +#define SN_undef "UNDEF" +#define LN_undef "undefined" +#define NID_undef 0 +#define OBJ_undef 0L + +#define SN_itu_t "ITU-T" +#define LN_itu_t "itu-t" +#define NID_itu_t 645 +#define OBJ_itu_t 0L + +#define NID_ccitt 404 +#define OBJ_ccitt OBJ_itu_t + +#define SN_iso "ISO" +#define LN_iso "iso" +#define NID_iso 181 +#define OBJ_iso 1L + +#define SN_joint_iso_itu_t "JOINT-ISO-ITU-T" +#define LN_joint_iso_itu_t "joint-iso-itu-t" +#define NID_joint_iso_itu_t 646 +#define OBJ_joint_iso_itu_t 2L + +#define NID_joint_iso_ccitt 393 +#define OBJ_joint_iso_ccitt OBJ_joint_iso_itu_t + +#define SN_member_body "member-body" +#define LN_member_body "ISO Member Body" +#define NID_member_body 182 +#define OBJ_member_body OBJ_iso,2L + +#define SN_identified_organization "identified-organization" +#define NID_identified_organization 676 +#define OBJ_identified_organization OBJ_iso,3L + +#define SN_hmac_md5 "HMAC-MD5" +#define LN_hmac_md5 "hmac-md5" +#define NID_hmac_md5 780 +#define OBJ_hmac_md5 OBJ_identified_organization,6L,1L,5L,5L,8L,1L,1L + +#define SN_hmac_sha1 "HMAC-SHA1" +#define LN_hmac_sha1 "hmac-sha1" +#define NID_hmac_sha1 781 +#define OBJ_hmac_sha1 OBJ_identified_organization,6L,1L,5L,5L,8L,1L,2L + +#define SN_certicom_arc "certicom-arc" +#define NID_certicom_arc 677 +#define OBJ_certicom_arc OBJ_identified_organization,132L + +#define SN_international_organizations "international-organizations" +#define LN_international_organizations "International Organizations" +#define NID_international_organizations 647 +#define OBJ_international_organizations OBJ_joint_iso_itu_t,23L + +#define SN_wap "wap" +#define NID_wap 678 +#define OBJ_wap OBJ_international_organizations,43L + +#define SN_wap_wsg "wap-wsg" +#define NID_wap_wsg 679 +#define OBJ_wap_wsg OBJ_wap,1L + +#define SN_selected_attribute_types "selected-attribute-types" +#define LN_selected_attribute_types "Selected Attribute Types" +#define NID_selected_attribute_types 394 +#define OBJ_selected_attribute_types OBJ_joint_iso_itu_t,5L,1L,5L + +#define SN_clearance "clearance" +#define NID_clearance 395 +#define OBJ_clearance OBJ_selected_attribute_types,55L + +#define SN_ISO_US "ISO-US" +#define LN_ISO_US "ISO US Member Body" +#define NID_ISO_US 183 +#define OBJ_ISO_US OBJ_member_body,840L + +#define SN_X9_57 "X9-57" +#define LN_X9_57 "X9.57" +#define NID_X9_57 184 +#define OBJ_X9_57 OBJ_ISO_US,10040L + +#define SN_X9cm "X9cm" +#define LN_X9cm "X9.57 CM ?" +#define NID_X9cm 185 +#define OBJ_X9cm OBJ_X9_57,4L + +#define SN_dsa "DSA" +#define LN_dsa "dsaEncryption" +#define NID_dsa 116 +#define OBJ_dsa OBJ_X9cm,1L + +#define SN_dsaWithSHA1 "DSA-SHA1" +#define LN_dsaWithSHA1 "dsaWithSHA1" +#define NID_dsaWithSHA1 113 +#define OBJ_dsaWithSHA1 OBJ_X9cm,3L + +#define SN_ansi_X9_62 "ansi-X9-62" +#define LN_ansi_X9_62 "ANSI X9.62" +#define NID_ansi_X9_62 405 +#define OBJ_ansi_X9_62 OBJ_ISO_US,10045L + +#define OBJ_X9_62_id_fieldType OBJ_ansi_X9_62,1L + +#define SN_X9_62_prime_field "prime-field" +#define NID_X9_62_prime_field 406 +#define OBJ_X9_62_prime_field OBJ_X9_62_id_fieldType,1L + +#define SN_X9_62_characteristic_two_field "characteristic-two-field" +#define NID_X9_62_characteristic_two_field 407 +#define OBJ_X9_62_characteristic_two_field OBJ_X9_62_id_fieldType,2L + +#define SN_X9_62_id_characteristic_two_basis "id-characteristic-two-basis" +#define NID_X9_62_id_characteristic_two_basis 680 +#define OBJ_X9_62_id_characteristic_two_basis OBJ_X9_62_characteristic_two_field,3L + +#define SN_X9_62_onBasis "onBasis" +#define NID_X9_62_onBasis 681 +#define OBJ_X9_62_onBasis OBJ_X9_62_id_characteristic_two_basis,1L + +#define SN_X9_62_tpBasis "tpBasis" +#define NID_X9_62_tpBasis 682 +#define OBJ_X9_62_tpBasis OBJ_X9_62_id_characteristic_two_basis,2L + +#define SN_X9_62_ppBasis "ppBasis" +#define NID_X9_62_ppBasis 683 +#define OBJ_X9_62_ppBasis OBJ_X9_62_id_characteristic_two_basis,3L + +#define OBJ_X9_62_id_publicKeyType OBJ_ansi_X9_62,2L + +#define SN_X9_62_id_ecPublicKey "id-ecPublicKey" +#define NID_X9_62_id_ecPublicKey 408 +#define OBJ_X9_62_id_ecPublicKey OBJ_X9_62_id_publicKeyType,1L + +#define OBJ_X9_62_ellipticCurve OBJ_ansi_X9_62,3L + +#define OBJ_X9_62_c_TwoCurve OBJ_X9_62_ellipticCurve,0L + +#define SN_X9_62_c2pnb163v1 "c2pnb163v1" +#define NID_X9_62_c2pnb163v1 684 +#define OBJ_X9_62_c2pnb163v1 OBJ_X9_62_c_TwoCurve,1L + +#define SN_X9_62_c2pnb163v2 "c2pnb163v2" +#define NID_X9_62_c2pnb163v2 685 +#define OBJ_X9_62_c2pnb163v2 OBJ_X9_62_c_TwoCurve,2L + +#define SN_X9_62_c2pnb163v3 "c2pnb163v3" +#define NID_X9_62_c2pnb163v3 686 +#define OBJ_X9_62_c2pnb163v3 OBJ_X9_62_c_TwoCurve,3L + +#define SN_X9_62_c2pnb176v1 "c2pnb176v1" +#define NID_X9_62_c2pnb176v1 687 +#define OBJ_X9_62_c2pnb176v1 OBJ_X9_62_c_TwoCurve,4L + +#define SN_X9_62_c2tnb191v1 "c2tnb191v1" +#define NID_X9_62_c2tnb191v1 688 +#define OBJ_X9_62_c2tnb191v1 OBJ_X9_62_c_TwoCurve,5L + +#define SN_X9_62_c2tnb191v2 "c2tnb191v2" +#define NID_X9_62_c2tnb191v2 689 +#define OBJ_X9_62_c2tnb191v2 OBJ_X9_62_c_TwoCurve,6L + +#define SN_X9_62_c2tnb191v3 "c2tnb191v3" +#define NID_X9_62_c2tnb191v3 690 +#define OBJ_X9_62_c2tnb191v3 OBJ_X9_62_c_TwoCurve,7L + +#define SN_X9_62_c2onb191v4 "c2onb191v4" +#define NID_X9_62_c2onb191v4 691 +#define OBJ_X9_62_c2onb191v4 OBJ_X9_62_c_TwoCurve,8L + +#define SN_X9_62_c2onb191v5 "c2onb191v5" +#define NID_X9_62_c2onb191v5 692 +#define OBJ_X9_62_c2onb191v5 OBJ_X9_62_c_TwoCurve,9L + +#define SN_X9_62_c2pnb208w1 "c2pnb208w1" +#define NID_X9_62_c2pnb208w1 693 +#define OBJ_X9_62_c2pnb208w1 OBJ_X9_62_c_TwoCurve,10L + +#define SN_X9_62_c2tnb239v1 "c2tnb239v1" +#define NID_X9_62_c2tnb239v1 694 +#define OBJ_X9_62_c2tnb239v1 OBJ_X9_62_c_TwoCurve,11L + +#define SN_X9_62_c2tnb239v2 "c2tnb239v2" +#define NID_X9_62_c2tnb239v2 695 +#define OBJ_X9_62_c2tnb239v2 OBJ_X9_62_c_TwoCurve,12L + +#define SN_X9_62_c2tnb239v3 "c2tnb239v3" +#define NID_X9_62_c2tnb239v3 696 +#define OBJ_X9_62_c2tnb239v3 OBJ_X9_62_c_TwoCurve,13L + +#define SN_X9_62_c2onb239v4 "c2onb239v4" +#define NID_X9_62_c2onb239v4 697 +#define OBJ_X9_62_c2onb239v4 OBJ_X9_62_c_TwoCurve,14L + +#define SN_X9_62_c2onb239v5 "c2onb239v5" +#define NID_X9_62_c2onb239v5 698 +#define OBJ_X9_62_c2onb239v5 OBJ_X9_62_c_TwoCurve,15L + +#define SN_X9_62_c2pnb272w1 "c2pnb272w1" +#define NID_X9_62_c2pnb272w1 699 +#define OBJ_X9_62_c2pnb272w1 OBJ_X9_62_c_TwoCurve,16L + +#define SN_X9_62_c2pnb304w1 "c2pnb304w1" +#define NID_X9_62_c2pnb304w1 700 +#define OBJ_X9_62_c2pnb304w1 OBJ_X9_62_c_TwoCurve,17L + +#define SN_X9_62_c2tnb359v1 "c2tnb359v1" +#define NID_X9_62_c2tnb359v1 701 +#define OBJ_X9_62_c2tnb359v1 OBJ_X9_62_c_TwoCurve,18L + +#define SN_X9_62_c2pnb368w1 "c2pnb368w1" +#define NID_X9_62_c2pnb368w1 702 +#define OBJ_X9_62_c2pnb368w1 OBJ_X9_62_c_TwoCurve,19L + +#define SN_X9_62_c2tnb431r1 "c2tnb431r1" +#define NID_X9_62_c2tnb431r1 703 +#define OBJ_X9_62_c2tnb431r1 OBJ_X9_62_c_TwoCurve,20L + +#define OBJ_X9_62_primeCurve OBJ_X9_62_ellipticCurve,1L + +#define SN_X9_62_prime192v1 "prime192v1" +#define NID_X9_62_prime192v1 409 +#define OBJ_X9_62_prime192v1 OBJ_X9_62_primeCurve,1L + +#define SN_X9_62_prime192v2 "prime192v2" +#define NID_X9_62_prime192v2 410 +#define OBJ_X9_62_prime192v2 OBJ_X9_62_primeCurve,2L + +#define SN_X9_62_prime192v3 "prime192v3" +#define NID_X9_62_prime192v3 411 +#define OBJ_X9_62_prime192v3 OBJ_X9_62_primeCurve,3L + +#define SN_X9_62_prime239v1 "prime239v1" +#define NID_X9_62_prime239v1 412 +#define OBJ_X9_62_prime239v1 OBJ_X9_62_primeCurve,4L + +#define SN_X9_62_prime239v2 "prime239v2" +#define NID_X9_62_prime239v2 413 +#define OBJ_X9_62_prime239v2 OBJ_X9_62_primeCurve,5L + +#define SN_X9_62_prime239v3 "prime239v3" +#define NID_X9_62_prime239v3 414 +#define OBJ_X9_62_prime239v3 OBJ_X9_62_primeCurve,6L + +#define SN_X9_62_prime256v1 "prime256v1" +#define NID_X9_62_prime256v1 415 +#define OBJ_X9_62_prime256v1 OBJ_X9_62_primeCurve,7L + +#define OBJ_X9_62_id_ecSigType OBJ_ansi_X9_62,4L + +#define SN_ecdsa_with_SHA1 "ecdsa-with-SHA1" +#define NID_ecdsa_with_SHA1 416 +#define OBJ_ecdsa_with_SHA1 OBJ_X9_62_id_ecSigType,1L + +#define SN_ecdsa_with_Recommended "ecdsa-with-Recommended" +#define NID_ecdsa_with_Recommended 791 +#define OBJ_ecdsa_with_Recommended OBJ_X9_62_id_ecSigType,2L + +#define SN_ecdsa_with_Specified "ecdsa-with-Specified" +#define NID_ecdsa_with_Specified 792 +#define OBJ_ecdsa_with_Specified OBJ_X9_62_id_ecSigType,3L + +#define SN_ecdsa_with_SHA224 "ecdsa-with-SHA224" +#define NID_ecdsa_with_SHA224 793 +#define OBJ_ecdsa_with_SHA224 OBJ_ecdsa_with_Specified,1L + +#define SN_ecdsa_with_SHA256 "ecdsa-with-SHA256" +#define NID_ecdsa_with_SHA256 794 +#define OBJ_ecdsa_with_SHA256 OBJ_ecdsa_with_Specified,2L + +#define SN_ecdsa_with_SHA384 "ecdsa-with-SHA384" +#define NID_ecdsa_with_SHA384 795 +#define OBJ_ecdsa_with_SHA384 OBJ_ecdsa_with_Specified,3L + +#define SN_ecdsa_with_SHA512 "ecdsa-with-SHA512" +#define NID_ecdsa_with_SHA512 796 +#define OBJ_ecdsa_with_SHA512 OBJ_ecdsa_with_Specified,4L + +#define OBJ_secg_ellipticCurve OBJ_certicom_arc,0L + +#define SN_secp112r1 "secp112r1" +#define NID_secp112r1 704 +#define OBJ_secp112r1 OBJ_secg_ellipticCurve,6L + +#define SN_secp112r2 "secp112r2" +#define NID_secp112r2 705 +#define OBJ_secp112r2 OBJ_secg_ellipticCurve,7L + +#define SN_secp128r1 "secp128r1" +#define NID_secp128r1 706 +#define OBJ_secp128r1 OBJ_secg_ellipticCurve,28L + +#define SN_secp128r2 "secp128r2" +#define NID_secp128r2 707 +#define OBJ_secp128r2 OBJ_secg_ellipticCurve,29L + +#define SN_secp160k1 "secp160k1" +#define NID_secp160k1 708 +#define OBJ_secp160k1 OBJ_secg_ellipticCurve,9L + +#define SN_secp160r1 "secp160r1" +#define NID_secp160r1 709 +#define OBJ_secp160r1 OBJ_secg_ellipticCurve,8L + +#define SN_secp160r2 "secp160r2" +#define NID_secp160r2 710 +#define OBJ_secp160r2 OBJ_secg_ellipticCurve,30L + +#define SN_secp192k1 "secp192k1" +#define NID_secp192k1 711 +#define OBJ_secp192k1 OBJ_secg_ellipticCurve,31L + +#define SN_secp224k1 "secp224k1" +#define NID_secp224k1 712 +#define OBJ_secp224k1 OBJ_secg_ellipticCurve,32L + +#define SN_secp224r1 "secp224r1" +#define NID_secp224r1 713 +#define OBJ_secp224r1 OBJ_secg_ellipticCurve,33L + +#define SN_secp256k1 "secp256k1" +#define NID_secp256k1 714 +#define OBJ_secp256k1 OBJ_secg_ellipticCurve,10L + +#define SN_secp384r1 "secp384r1" +#define NID_secp384r1 715 +#define OBJ_secp384r1 OBJ_secg_ellipticCurve,34L + +#define SN_secp521r1 "secp521r1" +#define NID_secp521r1 716 +#define OBJ_secp521r1 OBJ_secg_ellipticCurve,35L + +#define SN_sect113r1 "sect113r1" +#define NID_sect113r1 717 +#define OBJ_sect113r1 OBJ_secg_ellipticCurve,4L + +#define SN_sect113r2 "sect113r2" +#define NID_sect113r2 718 +#define OBJ_sect113r2 OBJ_secg_ellipticCurve,5L + +#define SN_sect131r1 "sect131r1" +#define NID_sect131r1 719 +#define OBJ_sect131r1 OBJ_secg_ellipticCurve,22L + +#define SN_sect131r2 "sect131r2" +#define NID_sect131r2 720 +#define OBJ_sect131r2 OBJ_secg_ellipticCurve,23L + +#define SN_sect163k1 "sect163k1" +#define NID_sect163k1 721 +#define OBJ_sect163k1 OBJ_secg_ellipticCurve,1L + +#define SN_sect163r1 "sect163r1" +#define NID_sect163r1 722 +#define OBJ_sect163r1 OBJ_secg_ellipticCurve,2L + +#define SN_sect163r2 "sect163r2" +#define NID_sect163r2 723 +#define OBJ_sect163r2 OBJ_secg_ellipticCurve,15L + +#define SN_sect193r1 "sect193r1" +#define NID_sect193r1 724 +#define OBJ_sect193r1 OBJ_secg_ellipticCurve,24L + +#define SN_sect193r2 "sect193r2" +#define NID_sect193r2 725 +#define OBJ_sect193r2 OBJ_secg_ellipticCurve,25L + +#define SN_sect233k1 "sect233k1" +#define NID_sect233k1 726 +#define OBJ_sect233k1 OBJ_secg_ellipticCurve,26L + +#define SN_sect233r1 "sect233r1" +#define NID_sect233r1 727 +#define OBJ_sect233r1 OBJ_secg_ellipticCurve,27L + +#define SN_sect239k1 "sect239k1" +#define NID_sect239k1 728 +#define OBJ_sect239k1 OBJ_secg_ellipticCurve,3L + +#define SN_sect283k1 "sect283k1" +#define NID_sect283k1 729 +#define OBJ_sect283k1 OBJ_secg_ellipticCurve,16L + +#define SN_sect283r1 "sect283r1" +#define NID_sect283r1 730 +#define OBJ_sect283r1 OBJ_secg_ellipticCurve,17L + +#define SN_sect409k1 "sect409k1" +#define NID_sect409k1 731 +#define OBJ_sect409k1 OBJ_secg_ellipticCurve,36L + +#define SN_sect409r1 "sect409r1" +#define NID_sect409r1 732 +#define OBJ_sect409r1 OBJ_secg_ellipticCurve,37L + +#define SN_sect571k1 "sect571k1" +#define NID_sect571k1 733 +#define OBJ_sect571k1 OBJ_secg_ellipticCurve,38L + +#define SN_sect571r1 "sect571r1" +#define NID_sect571r1 734 +#define OBJ_sect571r1 OBJ_secg_ellipticCurve,39L + +#define OBJ_wap_wsg_idm_ecid OBJ_wap_wsg,4L + +#define SN_wap_wsg_idm_ecid_wtls1 "wap-wsg-idm-ecid-wtls1" +#define NID_wap_wsg_idm_ecid_wtls1 735 +#define OBJ_wap_wsg_idm_ecid_wtls1 OBJ_wap_wsg_idm_ecid,1L + +#define SN_wap_wsg_idm_ecid_wtls3 "wap-wsg-idm-ecid-wtls3" +#define NID_wap_wsg_idm_ecid_wtls3 736 +#define OBJ_wap_wsg_idm_ecid_wtls3 OBJ_wap_wsg_idm_ecid,3L + +#define SN_wap_wsg_idm_ecid_wtls4 "wap-wsg-idm-ecid-wtls4" +#define NID_wap_wsg_idm_ecid_wtls4 737 +#define OBJ_wap_wsg_idm_ecid_wtls4 OBJ_wap_wsg_idm_ecid,4L + +#define SN_wap_wsg_idm_ecid_wtls5 "wap-wsg-idm-ecid-wtls5" +#define NID_wap_wsg_idm_ecid_wtls5 738 +#define OBJ_wap_wsg_idm_ecid_wtls5 OBJ_wap_wsg_idm_ecid,5L + +#define SN_wap_wsg_idm_ecid_wtls6 "wap-wsg-idm-ecid-wtls6" +#define NID_wap_wsg_idm_ecid_wtls6 739 +#define OBJ_wap_wsg_idm_ecid_wtls6 OBJ_wap_wsg_idm_ecid,6L + +#define SN_wap_wsg_idm_ecid_wtls7 "wap-wsg-idm-ecid-wtls7" +#define NID_wap_wsg_idm_ecid_wtls7 740 +#define OBJ_wap_wsg_idm_ecid_wtls7 OBJ_wap_wsg_idm_ecid,7L + +#define SN_wap_wsg_idm_ecid_wtls8 "wap-wsg-idm-ecid-wtls8" +#define NID_wap_wsg_idm_ecid_wtls8 741 +#define OBJ_wap_wsg_idm_ecid_wtls8 OBJ_wap_wsg_idm_ecid,8L + +#define SN_wap_wsg_idm_ecid_wtls9 "wap-wsg-idm-ecid-wtls9" +#define NID_wap_wsg_idm_ecid_wtls9 742 +#define OBJ_wap_wsg_idm_ecid_wtls9 OBJ_wap_wsg_idm_ecid,9L + +#define SN_wap_wsg_idm_ecid_wtls10 "wap-wsg-idm-ecid-wtls10" +#define NID_wap_wsg_idm_ecid_wtls10 743 +#define OBJ_wap_wsg_idm_ecid_wtls10 OBJ_wap_wsg_idm_ecid,10L + +#define SN_wap_wsg_idm_ecid_wtls11 "wap-wsg-idm-ecid-wtls11" +#define NID_wap_wsg_idm_ecid_wtls11 744 +#define OBJ_wap_wsg_idm_ecid_wtls11 OBJ_wap_wsg_idm_ecid,11L + +#define SN_wap_wsg_idm_ecid_wtls12 "wap-wsg-idm-ecid-wtls12" +#define NID_wap_wsg_idm_ecid_wtls12 745 +#define OBJ_wap_wsg_idm_ecid_wtls12 OBJ_wap_wsg_idm_ecid,12L + +#define SN_cast5_cbc "CAST5-CBC" +#define LN_cast5_cbc "cast5-cbc" +#define NID_cast5_cbc 108 +#define OBJ_cast5_cbc OBJ_ISO_US,113533L,7L,66L,10L + +#define SN_cast5_ecb "CAST5-ECB" +#define LN_cast5_ecb "cast5-ecb" +#define NID_cast5_ecb 109 + +#define SN_cast5_cfb64 "CAST5-CFB" +#define LN_cast5_cfb64 "cast5-cfb" +#define NID_cast5_cfb64 110 + +#define SN_cast5_ofb64 "CAST5-OFB" +#define LN_cast5_ofb64 "cast5-ofb" +#define NID_cast5_ofb64 111 + +#define LN_pbeWithMD5AndCast5_CBC "pbeWithMD5AndCast5CBC" +#define NID_pbeWithMD5AndCast5_CBC 112 +#define OBJ_pbeWithMD5AndCast5_CBC OBJ_ISO_US,113533L,7L,66L,12L + +#define SN_id_PasswordBasedMAC "id-PasswordBasedMAC" +#define LN_id_PasswordBasedMAC "password based MAC" +#define NID_id_PasswordBasedMAC 782 +#define OBJ_id_PasswordBasedMAC OBJ_ISO_US,113533L,7L,66L,13L + +#define SN_id_DHBasedMac "id-DHBasedMac" +#define LN_id_DHBasedMac "Diffie-Hellman based MAC" +#define NID_id_DHBasedMac 783 +#define OBJ_id_DHBasedMac OBJ_ISO_US,113533L,7L,66L,30L + +#define SN_rsadsi "rsadsi" +#define LN_rsadsi "RSA Data Security, Inc." +#define NID_rsadsi 1 +#define OBJ_rsadsi OBJ_ISO_US,113549L + +#define SN_pkcs "pkcs" +#define LN_pkcs "RSA Data Security, Inc. PKCS" +#define NID_pkcs 2 +#define OBJ_pkcs OBJ_rsadsi,1L + +#define SN_pkcs1 "pkcs1" +#define NID_pkcs1 186 +#define OBJ_pkcs1 OBJ_pkcs,1L + +#define LN_rsaEncryption "rsaEncryption" +#define NID_rsaEncryption 6 +#define OBJ_rsaEncryption OBJ_pkcs1,1L + +#define SN_md2WithRSAEncryption "RSA-MD2" +#define LN_md2WithRSAEncryption "md2WithRSAEncryption" +#define NID_md2WithRSAEncryption 7 +#define OBJ_md2WithRSAEncryption OBJ_pkcs1,2L + +#define SN_md4WithRSAEncryption "RSA-MD4" +#define LN_md4WithRSAEncryption "md4WithRSAEncryption" +#define NID_md4WithRSAEncryption 396 +#define OBJ_md4WithRSAEncryption OBJ_pkcs1,3L + +#define SN_md5WithRSAEncryption "RSA-MD5" +#define LN_md5WithRSAEncryption "md5WithRSAEncryption" +#define NID_md5WithRSAEncryption 8 +#define OBJ_md5WithRSAEncryption OBJ_pkcs1,4L + +#define SN_sha1WithRSAEncryption "RSA-SHA1" +#define LN_sha1WithRSAEncryption "sha1WithRSAEncryption" +#define NID_sha1WithRSAEncryption 65 +#define OBJ_sha1WithRSAEncryption OBJ_pkcs1,5L + +#define SN_rsaesOaep "RSAES-OAEP" +#define LN_rsaesOaep "rsaesOaep" +#define NID_rsaesOaep 919 +#define OBJ_rsaesOaep OBJ_pkcs1,7L + +#define SN_mgf1 "MGF1" +#define LN_mgf1 "mgf1" +#define NID_mgf1 911 +#define OBJ_mgf1 OBJ_pkcs1,8L + +#define SN_pSpecified "PSPECIFIED" +#define LN_pSpecified "pSpecified" +#define NID_pSpecified 935 +#define OBJ_pSpecified OBJ_pkcs1,9L + +#define SN_rsassaPss "RSASSA-PSS" +#define LN_rsassaPss "rsassaPss" +#define NID_rsassaPss 912 +#define OBJ_rsassaPss OBJ_pkcs1,10L + +#define SN_sha256WithRSAEncryption "RSA-SHA256" +#define LN_sha256WithRSAEncryption "sha256WithRSAEncryption" +#define NID_sha256WithRSAEncryption 668 +#define OBJ_sha256WithRSAEncryption OBJ_pkcs1,11L + +#define SN_sha384WithRSAEncryption "RSA-SHA384" +#define LN_sha384WithRSAEncryption "sha384WithRSAEncryption" +#define NID_sha384WithRSAEncryption 669 +#define OBJ_sha384WithRSAEncryption OBJ_pkcs1,12L + +#define SN_sha512WithRSAEncryption "RSA-SHA512" +#define LN_sha512WithRSAEncryption "sha512WithRSAEncryption" +#define NID_sha512WithRSAEncryption 670 +#define OBJ_sha512WithRSAEncryption OBJ_pkcs1,13L + +#define SN_sha224WithRSAEncryption "RSA-SHA224" +#define LN_sha224WithRSAEncryption "sha224WithRSAEncryption" +#define NID_sha224WithRSAEncryption 671 +#define OBJ_sha224WithRSAEncryption OBJ_pkcs1,14L + +#define SN_pkcs3 "pkcs3" +#define NID_pkcs3 27 +#define OBJ_pkcs3 OBJ_pkcs,3L + +#define LN_dhKeyAgreement "dhKeyAgreement" +#define NID_dhKeyAgreement 28 +#define OBJ_dhKeyAgreement OBJ_pkcs3,1L + +#define SN_pkcs5 "pkcs5" +#define NID_pkcs5 187 +#define OBJ_pkcs5 OBJ_pkcs,5L + +#define SN_pbeWithMD2AndDES_CBC "PBE-MD2-DES" +#define LN_pbeWithMD2AndDES_CBC "pbeWithMD2AndDES-CBC" +#define NID_pbeWithMD2AndDES_CBC 9 +#define OBJ_pbeWithMD2AndDES_CBC OBJ_pkcs5,1L + +#define SN_pbeWithMD5AndDES_CBC "PBE-MD5-DES" +#define LN_pbeWithMD5AndDES_CBC "pbeWithMD5AndDES-CBC" +#define NID_pbeWithMD5AndDES_CBC 10 +#define OBJ_pbeWithMD5AndDES_CBC OBJ_pkcs5,3L + +#define SN_pbeWithMD2AndRC2_CBC "PBE-MD2-RC2-64" +#define LN_pbeWithMD2AndRC2_CBC "pbeWithMD2AndRC2-CBC" +#define NID_pbeWithMD2AndRC2_CBC 168 +#define OBJ_pbeWithMD2AndRC2_CBC OBJ_pkcs5,4L + +#define SN_pbeWithMD5AndRC2_CBC "PBE-MD5-RC2-64" +#define LN_pbeWithMD5AndRC2_CBC "pbeWithMD5AndRC2-CBC" +#define NID_pbeWithMD5AndRC2_CBC 169 +#define OBJ_pbeWithMD5AndRC2_CBC OBJ_pkcs5,6L + +#define SN_pbeWithSHA1AndDES_CBC "PBE-SHA1-DES" +#define LN_pbeWithSHA1AndDES_CBC "pbeWithSHA1AndDES-CBC" +#define NID_pbeWithSHA1AndDES_CBC 170 +#define OBJ_pbeWithSHA1AndDES_CBC OBJ_pkcs5,10L + +#define SN_pbeWithSHA1AndRC2_CBC "PBE-SHA1-RC2-64" +#define LN_pbeWithSHA1AndRC2_CBC "pbeWithSHA1AndRC2-CBC" +#define NID_pbeWithSHA1AndRC2_CBC 68 +#define OBJ_pbeWithSHA1AndRC2_CBC OBJ_pkcs5,11L + +#define LN_id_pbkdf2 "PBKDF2" +#define NID_id_pbkdf2 69 +#define OBJ_id_pbkdf2 OBJ_pkcs5,12L + +#define LN_pbes2 "PBES2" +#define NID_pbes2 161 +#define OBJ_pbes2 OBJ_pkcs5,13L + +#define LN_pbmac1 "PBMAC1" +#define NID_pbmac1 162 +#define OBJ_pbmac1 OBJ_pkcs5,14L + +#define SN_pkcs7 "pkcs7" +#define NID_pkcs7 20 +#define OBJ_pkcs7 OBJ_pkcs,7L + +#define LN_pkcs7_data "pkcs7-data" +#define NID_pkcs7_data 21 +#define OBJ_pkcs7_data OBJ_pkcs7,1L + +#define LN_pkcs7_signed "pkcs7-signedData" +#define NID_pkcs7_signed 22 +#define OBJ_pkcs7_signed OBJ_pkcs7,2L + +#define LN_pkcs7_enveloped "pkcs7-envelopedData" +#define NID_pkcs7_enveloped 23 +#define OBJ_pkcs7_enveloped OBJ_pkcs7,3L + +#define LN_pkcs7_signedAndEnveloped "pkcs7-signedAndEnvelopedData" +#define NID_pkcs7_signedAndEnveloped 24 +#define OBJ_pkcs7_signedAndEnveloped OBJ_pkcs7,4L + +#define LN_pkcs7_digest "pkcs7-digestData" +#define NID_pkcs7_digest 25 +#define OBJ_pkcs7_digest OBJ_pkcs7,5L + +#define LN_pkcs7_encrypted "pkcs7-encryptedData" +#define NID_pkcs7_encrypted 26 +#define OBJ_pkcs7_encrypted OBJ_pkcs7,6L + +#define SN_pkcs9 "pkcs9" +#define NID_pkcs9 47 +#define OBJ_pkcs9 OBJ_pkcs,9L + +#define LN_pkcs9_emailAddress "emailAddress" +#define NID_pkcs9_emailAddress 48 +#define OBJ_pkcs9_emailAddress OBJ_pkcs9,1L + +#define LN_pkcs9_unstructuredName "unstructuredName" +#define NID_pkcs9_unstructuredName 49 +#define OBJ_pkcs9_unstructuredName OBJ_pkcs9,2L + +#define LN_pkcs9_contentType "contentType" +#define NID_pkcs9_contentType 50 +#define OBJ_pkcs9_contentType OBJ_pkcs9,3L + +#define LN_pkcs9_messageDigest "messageDigest" +#define NID_pkcs9_messageDigest 51 +#define OBJ_pkcs9_messageDigest OBJ_pkcs9,4L + +#define LN_pkcs9_signingTime "signingTime" +#define NID_pkcs9_signingTime 52 +#define OBJ_pkcs9_signingTime OBJ_pkcs9,5L + +#define LN_pkcs9_countersignature "countersignature" +#define NID_pkcs9_countersignature 53 +#define OBJ_pkcs9_countersignature OBJ_pkcs9,6L + +#define LN_pkcs9_challengePassword "challengePassword" +#define NID_pkcs9_challengePassword 54 +#define OBJ_pkcs9_challengePassword OBJ_pkcs9,7L + +#define LN_pkcs9_unstructuredAddress "unstructuredAddress" +#define NID_pkcs9_unstructuredAddress 55 +#define OBJ_pkcs9_unstructuredAddress OBJ_pkcs9,8L + +#define LN_pkcs9_extCertAttributes "extendedCertificateAttributes" +#define NID_pkcs9_extCertAttributes 56 +#define OBJ_pkcs9_extCertAttributes OBJ_pkcs9,9L + +#define SN_ext_req "extReq" +#define LN_ext_req "Extension Request" +#define NID_ext_req 172 +#define OBJ_ext_req OBJ_pkcs9,14L + +#define SN_SMIMECapabilities "SMIME-CAPS" +#define LN_SMIMECapabilities "S/MIME Capabilities" +#define NID_SMIMECapabilities 167 +#define OBJ_SMIMECapabilities OBJ_pkcs9,15L + +#define SN_SMIME "SMIME" +#define LN_SMIME "S/MIME" +#define NID_SMIME 188 +#define OBJ_SMIME OBJ_pkcs9,16L + +#define SN_id_smime_mod "id-smime-mod" +#define NID_id_smime_mod 189 +#define OBJ_id_smime_mod OBJ_SMIME,0L + +#define SN_id_smime_ct "id-smime-ct" +#define NID_id_smime_ct 190 +#define OBJ_id_smime_ct OBJ_SMIME,1L + +#define SN_id_smime_aa "id-smime-aa" +#define NID_id_smime_aa 191 +#define OBJ_id_smime_aa OBJ_SMIME,2L + +#define SN_id_smime_alg "id-smime-alg" +#define NID_id_smime_alg 192 +#define OBJ_id_smime_alg OBJ_SMIME,3L + +#define SN_id_smime_cd "id-smime-cd" +#define NID_id_smime_cd 193 +#define OBJ_id_smime_cd OBJ_SMIME,4L + +#define SN_id_smime_spq "id-smime-spq" +#define NID_id_smime_spq 194 +#define OBJ_id_smime_spq OBJ_SMIME,5L + +#define SN_id_smime_cti "id-smime-cti" +#define NID_id_smime_cti 195 +#define OBJ_id_smime_cti OBJ_SMIME,6L + +#define SN_id_smime_mod_cms "id-smime-mod-cms" +#define NID_id_smime_mod_cms 196 +#define OBJ_id_smime_mod_cms OBJ_id_smime_mod,1L + +#define SN_id_smime_mod_ess "id-smime-mod-ess" +#define NID_id_smime_mod_ess 197 +#define OBJ_id_smime_mod_ess OBJ_id_smime_mod,2L + +#define SN_id_smime_mod_oid "id-smime-mod-oid" +#define NID_id_smime_mod_oid 198 +#define OBJ_id_smime_mod_oid OBJ_id_smime_mod,3L + +#define SN_id_smime_mod_msg_v3 "id-smime-mod-msg-v3" +#define NID_id_smime_mod_msg_v3 199 +#define OBJ_id_smime_mod_msg_v3 OBJ_id_smime_mod,4L + +#define SN_id_smime_mod_ets_eSignature_88 "id-smime-mod-ets-eSignature-88" +#define NID_id_smime_mod_ets_eSignature_88 200 +#define OBJ_id_smime_mod_ets_eSignature_88 OBJ_id_smime_mod,5L + +#define SN_id_smime_mod_ets_eSignature_97 "id-smime-mod-ets-eSignature-97" +#define NID_id_smime_mod_ets_eSignature_97 201 +#define OBJ_id_smime_mod_ets_eSignature_97 OBJ_id_smime_mod,6L + +#define SN_id_smime_mod_ets_eSigPolicy_88 "id-smime-mod-ets-eSigPolicy-88" +#define NID_id_smime_mod_ets_eSigPolicy_88 202 +#define OBJ_id_smime_mod_ets_eSigPolicy_88 OBJ_id_smime_mod,7L + +#define SN_id_smime_mod_ets_eSigPolicy_97 "id-smime-mod-ets-eSigPolicy-97" +#define NID_id_smime_mod_ets_eSigPolicy_97 203 +#define OBJ_id_smime_mod_ets_eSigPolicy_97 OBJ_id_smime_mod,8L + +#define SN_id_smime_ct_receipt "id-smime-ct-receipt" +#define NID_id_smime_ct_receipt 204 +#define OBJ_id_smime_ct_receipt OBJ_id_smime_ct,1L + +#define SN_id_smime_ct_authData "id-smime-ct-authData" +#define NID_id_smime_ct_authData 205 +#define OBJ_id_smime_ct_authData OBJ_id_smime_ct,2L + +#define SN_id_smime_ct_publishCert "id-smime-ct-publishCert" +#define NID_id_smime_ct_publishCert 206 +#define OBJ_id_smime_ct_publishCert OBJ_id_smime_ct,3L + +#define SN_id_smime_ct_TSTInfo "id-smime-ct-TSTInfo" +#define NID_id_smime_ct_TSTInfo 207 +#define OBJ_id_smime_ct_TSTInfo OBJ_id_smime_ct,4L + +#define SN_id_smime_ct_TDTInfo "id-smime-ct-TDTInfo" +#define NID_id_smime_ct_TDTInfo 208 +#define OBJ_id_smime_ct_TDTInfo OBJ_id_smime_ct,5L + +#define SN_id_smime_ct_contentInfo "id-smime-ct-contentInfo" +#define NID_id_smime_ct_contentInfo 209 +#define OBJ_id_smime_ct_contentInfo OBJ_id_smime_ct,6L + +#define SN_id_smime_ct_DVCSRequestData "id-smime-ct-DVCSRequestData" +#define NID_id_smime_ct_DVCSRequestData 210 +#define OBJ_id_smime_ct_DVCSRequestData OBJ_id_smime_ct,7L + +#define SN_id_smime_ct_DVCSResponseData "id-smime-ct-DVCSResponseData" +#define NID_id_smime_ct_DVCSResponseData 211 +#define OBJ_id_smime_ct_DVCSResponseData OBJ_id_smime_ct,8L + +#define SN_id_smime_ct_compressedData "id-smime-ct-compressedData" +#define NID_id_smime_ct_compressedData 786 +#define OBJ_id_smime_ct_compressedData OBJ_id_smime_ct,9L + +#define SN_id_ct_asciiTextWithCRLF "id-ct-asciiTextWithCRLF" +#define NID_id_ct_asciiTextWithCRLF 787 +#define OBJ_id_ct_asciiTextWithCRLF OBJ_id_smime_ct,27L + +#define SN_id_smime_aa_receiptRequest "id-smime-aa-receiptRequest" +#define NID_id_smime_aa_receiptRequest 212 +#define OBJ_id_smime_aa_receiptRequest OBJ_id_smime_aa,1L + +#define SN_id_smime_aa_securityLabel "id-smime-aa-securityLabel" +#define NID_id_smime_aa_securityLabel 213 +#define OBJ_id_smime_aa_securityLabel OBJ_id_smime_aa,2L + +#define SN_id_smime_aa_mlExpandHistory "id-smime-aa-mlExpandHistory" +#define NID_id_smime_aa_mlExpandHistory 214 +#define OBJ_id_smime_aa_mlExpandHistory OBJ_id_smime_aa,3L + +#define SN_id_smime_aa_contentHint "id-smime-aa-contentHint" +#define NID_id_smime_aa_contentHint 215 +#define OBJ_id_smime_aa_contentHint OBJ_id_smime_aa,4L + +#define SN_id_smime_aa_msgSigDigest "id-smime-aa-msgSigDigest" +#define NID_id_smime_aa_msgSigDigest 216 +#define OBJ_id_smime_aa_msgSigDigest OBJ_id_smime_aa,5L + +#define SN_id_smime_aa_encapContentType "id-smime-aa-encapContentType" +#define NID_id_smime_aa_encapContentType 217 +#define OBJ_id_smime_aa_encapContentType OBJ_id_smime_aa,6L + +#define SN_id_smime_aa_contentIdentifier "id-smime-aa-contentIdentifier" +#define NID_id_smime_aa_contentIdentifier 218 +#define OBJ_id_smime_aa_contentIdentifier OBJ_id_smime_aa,7L + +#define SN_id_smime_aa_macValue "id-smime-aa-macValue" +#define NID_id_smime_aa_macValue 219 +#define OBJ_id_smime_aa_macValue OBJ_id_smime_aa,8L + +#define SN_id_smime_aa_equivalentLabels "id-smime-aa-equivalentLabels" +#define NID_id_smime_aa_equivalentLabels 220 +#define OBJ_id_smime_aa_equivalentLabels OBJ_id_smime_aa,9L + +#define SN_id_smime_aa_contentReference "id-smime-aa-contentReference" +#define NID_id_smime_aa_contentReference 221 +#define OBJ_id_smime_aa_contentReference OBJ_id_smime_aa,10L + +#define SN_id_smime_aa_encrypKeyPref "id-smime-aa-encrypKeyPref" +#define NID_id_smime_aa_encrypKeyPref 222 +#define OBJ_id_smime_aa_encrypKeyPref OBJ_id_smime_aa,11L + +#define SN_id_smime_aa_signingCertificate "id-smime-aa-signingCertificate" +#define NID_id_smime_aa_signingCertificate 223 +#define OBJ_id_smime_aa_signingCertificate OBJ_id_smime_aa,12L + +#define SN_id_smime_aa_smimeEncryptCerts "id-smime-aa-smimeEncryptCerts" +#define NID_id_smime_aa_smimeEncryptCerts 224 +#define OBJ_id_smime_aa_smimeEncryptCerts OBJ_id_smime_aa,13L + +#define SN_id_smime_aa_timeStampToken "id-smime-aa-timeStampToken" +#define NID_id_smime_aa_timeStampToken 225 +#define OBJ_id_smime_aa_timeStampToken OBJ_id_smime_aa,14L + +#define SN_id_smime_aa_ets_sigPolicyId "id-smime-aa-ets-sigPolicyId" +#define NID_id_smime_aa_ets_sigPolicyId 226 +#define OBJ_id_smime_aa_ets_sigPolicyId OBJ_id_smime_aa,15L + +#define SN_id_smime_aa_ets_commitmentType "id-smime-aa-ets-commitmentType" +#define NID_id_smime_aa_ets_commitmentType 227 +#define OBJ_id_smime_aa_ets_commitmentType OBJ_id_smime_aa,16L + +#define SN_id_smime_aa_ets_signerLocation "id-smime-aa-ets-signerLocation" +#define NID_id_smime_aa_ets_signerLocation 228 +#define OBJ_id_smime_aa_ets_signerLocation OBJ_id_smime_aa,17L + +#define SN_id_smime_aa_ets_signerAttr "id-smime-aa-ets-signerAttr" +#define NID_id_smime_aa_ets_signerAttr 229 +#define OBJ_id_smime_aa_ets_signerAttr OBJ_id_smime_aa,18L + +#define SN_id_smime_aa_ets_otherSigCert "id-smime-aa-ets-otherSigCert" +#define NID_id_smime_aa_ets_otherSigCert 230 +#define OBJ_id_smime_aa_ets_otherSigCert OBJ_id_smime_aa,19L + +#define SN_id_smime_aa_ets_contentTimestamp "id-smime-aa-ets-contentTimestamp" +#define NID_id_smime_aa_ets_contentTimestamp 231 +#define OBJ_id_smime_aa_ets_contentTimestamp OBJ_id_smime_aa,20L + +#define SN_id_smime_aa_ets_CertificateRefs "id-smime-aa-ets-CertificateRefs" +#define NID_id_smime_aa_ets_CertificateRefs 232 +#define OBJ_id_smime_aa_ets_CertificateRefs OBJ_id_smime_aa,21L + +#define SN_id_smime_aa_ets_RevocationRefs "id-smime-aa-ets-RevocationRefs" +#define NID_id_smime_aa_ets_RevocationRefs 233 +#define OBJ_id_smime_aa_ets_RevocationRefs OBJ_id_smime_aa,22L + +#define SN_id_smime_aa_ets_certValues "id-smime-aa-ets-certValues" +#define NID_id_smime_aa_ets_certValues 234 +#define OBJ_id_smime_aa_ets_certValues OBJ_id_smime_aa,23L + +#define SN_id_smime_aa_ets_revocationValues "id-smime-aa-ets-revocationValues" +#define NID_id_smime_aa_ets_revocationValues 235 +#define OBJ_id_smime_aa_ets_revocationValues OBJ_id_smime_aa,24L + +#define SN_id_smime_aa_ets_escTimeStamp "id-smime-aa-ets-escTimeStamp" +#define NID_id_smime_aa_ets_escTimeStamp 236 +#define OBJ_id_smime_aa_ets_escTimeStamp OBJ_id_smime_aa,25L + +#define SN_id_smime_aa_ets_certCRLTimestamp "id-smime-aa-ets-certCRLTimestamp" +#define NID_id_smime_aa_ets_certCRLTimestamp 237 +#define OBJ_id_smime_aa_ets_certCRLTimestamp OBJ_id_smime_aa,26L + +#define SN_id_smime_aa_ets_archiveTimeStamp "id-smime-aa-ets-archiveTimeStamp" +#define NID_id_smime_aa_ets_archiveTimeStamp 238 +#define OBJ_id_smime_aa_ets_archiveTimeStamp OBJ_id_smime_aa,27L + +#define SN_id_smime_aa_signatureType "id-smime-aa-signatureType" +#define NID_id_smime_aa_signatureType 239 +#define OBJ_id_smime_aa_signatureType OBJ_id_smime_aa,28L + +#define SN_id_smime_aa_dvcs_dvc "id-smime-aa-dvcs-dvc" +#define NID_id_smime_aa_dvcs_dvc 240 +#define OBJ_id_smime_aa_dvcs_dvc OBJ_id_smime_aa,29L + +#define SN_id_smime_alg_ESDHwith3DES "id-smime-alg-ESDHwith3DES" +#define NID_id_smime_alg_ESDHwith3DES 241 +#define OBJ_id_smime_alg_ESDHwith3DES OBJ_id_smime_alg,1L + +#define SN_id_smime_alg_ESDHwithRC2 "id-smime-alg-ESDHwithRC2" +#define NID_id_smime_alg_ESDHwithRC2 242 +#define OBJ_id_smime_alg_ESDHwithRC2 OBJ_id_smime_alg,2L + +#define SN_id_smime_alg_3DESwrap "id-smime-alg-3DESwrap" +#define NID_id_smime_alg_3DESwrap 243 +#define OBJ_id_smime_alg_3DESwrap OBJ_id_smime_alg,3L + +#define SN_id_smime_alg_RC2wrap "id-smime-alg-RC2wrap" +#define NID_id_smime_alg_RC2wrap 244 +#define OBJ_id_smime_alg_RC2wrap OBJ_id_smime_alg,4L + +#define SN_id_smime_alg_ESDH "id-smime-alg-ESDH" +#define NID_id_smime_alg_ESDH 245 +#define OBJ_id_smime_alg_ESDH OBJ_id_smime_alg,5L + +#define SN_id_smime_alg_CMS3DESwrap "id-smime-alg-CMS3DESwrap" +#define NID_id_smime_alg_CMS3DESwrap 246 +#define OBJ_id_smime_alg_CMS3DESwrap OBJ_id_smime_alg,6L + +#define SN_id_smime_alg_CMSRC2wrap "id-smime-alg-CMSRC2wrap" +#define NID_id_smime_alg_CMSRC2wrap 247 +#define OBJ_id_smime_alg_CMSRC2wrap OBJ_id_smime_alg,7L + +#define SN_id_alg_PWRI_KEK "id-alg-PWRI-KEK" +#define NID_id_alg_PWRI_KEK 893 +#define OBJ_id_alg_PWRI_KEK OBJ_id_smime_alg,9L + +#define SN_id_smime_cd_ldap "id-smime-cd-ldap" +#define NID_id_smime_cd_ldap 248 +#define OBJ_id_smime_cd_ldap OBJ_id_smime_cd,1L + +#define SN_id_smime_spq_ets_sqt_uri "id-smime-spq-ets-sqt-uri" +#define NID_id_smime_spq_ets_sqt_uri 249 +#define OBJ_id_smime_spq_ets_sqt_uri OBJ_id_smime_spq,1L + +#define SN_id_smime_spq_ets_sqt_unotice "id-smime-spq-ets-sqt-unotice" +#define NID_id_smime_spq_ets_sqt_unotice 250 +#define OBJ_id_smime_spq_ets_sqt_unotice OBJ_id_smime_spq,2L + +#define SN_id_smime_cti_ets_proofOfOrigin "id-smime-cti-ets-proofOfOrigin" +#define NID_id_smime_cti_ets_proofOfOrigin 251 +#define OBJ_id_smime_cti_ets_proofOfOrigin OBJ_id_smime_cti,1L + +#define SN_id_smime_cti_ets_proofOfReceipt "id-smime-cti-ets-proofOfReceipt" +#define NID_id_smime_cti_ets_proofOfReceipt 252 +#define OBJ_id_smime_cti_ets_proofOfReceipt OBJ_id_smime_cti,2L + +#define SN_id_smime_cti_ets_proofOfDelivery "id-smime-cti-ets-proofOfDelivery" +#define NID_id_smime_cti_ets_proofOfDelivery 253 +#define OBJ_id_smime_cti_ets_proofOfDelivery OBJ_id_smime_cti,3L + +#define SN_id_smime_cti_ets_proofOfSender "id-smime-cti-ets-proofOfSender" +#define NID_id_smime_cti_ets_proofOfSender 254 +#define OBJ_id_smime_cti_ets_proofOfSender OBJ_id_smime_cti,4L + +#define SN_id_smime_cti_ets_proofOfApproval "id-smime-cti-ets-proofOfApproval" +#define NID_id_smime_cti_ets_proofOfApproval 255 +#define OBJ_id_smime_cti_ets_proofOfApproval OBJ_id_smime_cti,5L + +#define SN_id_smime_cti_ets_proofOfCreation "id-smime-cti-ets-proofOfCreation" +#define NID_id_smime_cti_ets_proofOfCreation 256 +#define OBJ_id_smime_cti_ets_proofOfCreation OBJ_id_smime_cti,6L + +#define LN_friendlyName "friendlyName" +#define NID_friendlyName 156 +#define OBJ_friendlyName OBJ_pkcs9,20L + +#define LN_localKeyID "localKeyID" +#define NID_localKeyID 157 +#define OBJ_localKeyID OBJ_pkcs9,21L + +#define SN_ms_csp_name "CSPName" +#define LN_ms_csp_name "Microsoft CSP Name" +#define NID_ms_csp_name 417 +#define OBJ_ms_csp_name 1L,3L,6L,1L,4L,1L,311L,17L,1L + +#define SN_LocalKeySet "LocalKeySet" +#define LN_LocalKeySet "Microsoft Local Key set" +#define NID_LocalKeySet 856 +#define OBJ_LocalKeySet 1L,3L,6L,1L,4L,1L,311L,17L,2L + +#define OBJ_certTypes OBJ_pkcs9,22L + +#define LN_x509Certificate "x509Certificate" +#define NID_x509Certificate 158 +#define OBJ_x509Certificate OBJ_certTypes,1L + +#define LN_sdsiCertificate "sdsiCertificate" +#define NID_sdsiCertificate 159 +#define OBJ_sdsiCertificate OBJ_certTypes,2L + +#define OBJ_crlTypes OBJ_pkcs9,23L + +#define LN_x509Crl "x509Crl" +#define NID_x509Crl 160 +#define OBJ_x509Crl OBJ_crlTypes,1L + +#define OBJ_pkcs12 OBJ_pkcs,12L + +#define OBJ_pkcs12_pbeids OBJ_pkcs12,1L + +#define SN_pbe_WithSHA1And128BitRC4 "PBE-SHA1-RC4-128" +#define LN_pbe_WithSHA1And128BitRC4 "pbeWithSHA1And128BitRC4" +#define NID_pbe_WithSHA1And128BitRC4 144 +#define OBJ_pbe_WithSHA1And128BitRC4 OBJ_pkcs12_pbeids,1L + +#define SN_pbe_WithSHA1And40BitRC4 "PBE-SHA1-RC4-40" +#define LN_pbe_WithSHA1And40BitRC4 "pbeWithSHA1And40BitRC4" +#define NID_pbe_WithSHA1And40BitRC4 145 +#define OBJ_pbe_WithSHA1And40BitRC4 OBJ_pkcs12_pbeids,2L + +#define SN_pbe_WithSHA1And3_Key_TripleDES_CBC "PBE-SHA1-3DES" +#define LN_pbe_WithSHA1And3_Key_TripleDES_CBC "pbeWithSHA1And3-KeyTripleDES-CBC" +#define NID_pbe_WithSHA1And3_Key_TripleDES_CBC 146 +#define OBJ_pbe_WithSHA1And3_Key_TripleDES_CBC OBJ_pkcs12_pbeids,3L + +#define SN_pbe_WithSHA1And2_Key_TripleDES_CBC "PBE-SHA1-2DES" +#define LN_pbe_WithSHA1And2_Key_TripleDES_CBC "pbeWithSHA1And2-KeyTripleDES-CBC" +#define NID_pbe_WithSHA1And2_Key_TripleDES_CBC 147 +#define OBJ_pbe_WithSHA1And2_Key_TripleDES_CBC OBJ_pkcs12_pbeids,4L + +#define SN_pbe_WithSHA1And128BitRC2_CBC "PBE-SHA1-RC2-128" +#define LN_pbe_WithSHA1And128BitRC2_CBC "pbeWithSHA1And128BitRC2-CBC" +#define NID_pbe_WithSHA1And128BitRC2_CBC 148 +#define OBJ_pbe_WithSHA1And128BitRC2_CBC OBJ_pkcs12_pbeids,5L + +#define SN_pbe_WithSHA1And40BitRC2_CBC "PBE-SHA1-RC2-40" +#define LN_pbe_WithSHA1And40BitRC2_CBC "pbeWithSHA1And40BitRC2-CBC" +#define NID_pbe_WithSHA1And40BitRC2_CBC 149 +#define OBJ_pbe_WithSHA1And40BitRC2_CBC OBJ_pkcs12_pbeids,6L + +#define OBJ_pkcs12_Version1 OBJ_pkcs12,10L + +#define OBJ_pkcs12_BagIds OBJ_pkcs12_Version1,1L + +#define LN_keyBag "keyBag" +#define NID_keyBag 150 +#define OBJ_keyBag OBJ_pkcs12_BagIds,1L + +#define LN_pkcs8ShroudedKeyBag "pkcs8ShroudedKeyBag" +#define NID_pkcs8ShroudedKeyBag 151 +#define OBJ_pkcs8ShroudedKeyBag OBJ_pkcs12_BagIds,2L + +#define LN_certBag "certBag" +#define NID_certBag 152 +#define OBJ_certBag OBJ_pkcs12_BagIds,3L + +#define LN_crlBag "crlBag" +#define NID_crlBag 153 +#define OBJ_crlBag OBJ_pkcs12_BagIds,4L + +#define LN_secretBag "secretBag" +#define NID_secretBag 154 +#define OBJ_secretBag OBJ_pkcs12_BagIds,5L + +#define LN_safeContentsBag "safeContentsBag" +#define NID_safeContentsBag 155 +#define OBJ_safeContentsBag OBJ_pkcs12_BagIds,6L + +#define SN_md2 "MD2" +#define LN_md2 "md2" +#define NID_md2 3 +#define OBJ_md2 OBJ_rsadsi,2L,2L + +#define SN_md4 "MD4" +#define LN_md4 "md4" +#define NID_md4 257 +#define OBJ_md4 OBJ_rsadsi,2L,4L + +#define SN_md5 "MD5" +#define LN_md5 "md5" +#define NID_md5 4 +#define OBJ_md5 OBJ_rsadsi,2L,5L + +#define SN_md5_sha1 "MD5-SHA1" +#define LN_md5_sha1 "md5-sha1" +#define NID_md5_sha1 114 + +#define LN_hmacWithMD5 "hmacWithMD5" +#define NID_hmacWithMD5 797 +#define OBJ_hmacWithMD5 OBJ_rsadsi,2L,6L + +#define LN_hmacWithSHA1 "hmacWithSHA1" +#define NID_hmacWithSHA1 163 +#define OBJ_hmacWithSHA1 OBJ_rsadsi,2L,7L + +#define LN_hmacWithSHA224 "hmacWithSHA224" +#define NID_hmacWithSHA224 798 +#define OBJ_hmacWithSHA224 OBJ_rsadsi,2L,8L + +#define LN_hmacWithSHA256 "hmacWithSHA256" +#define NID_hmacWithSHA256 799 +#define OBJ_hmacWithSHA256 OBJ_rsadsi,2L,9L + +#define LN_hmacWithSHA384 "hmacWithSHA384" +#define NID_hmacWithSHA384 800 +#define OBJ_hmacWithSHA384 OBJ_rsadsi,2L,10L + +#define LN_hmacWithSHA512 "hmacWithSHA512" +#define NID_hmacWithSHA512 801 +#define OBJ_hmacWithSHA512 OBJ_rsadsi,2L,11L + +#define SN_rc2_cbc "RC2-CBC" +#define LN_rc2_cbc "rc2-cbc" +#define NID_rc2_cbc 37 +#define OBJ_rc2_cbc OBJ_rsadsi,3L,2L + +#define SN_rc2_ecb "RC2-ECB" +#define LN_rc2_ecb "rc2-ecb" +#define NID_rc2_ecb 38 + +#define SN_rc2_cfb64 "RC2-CFB" +#define LN_rc2_cfb64 "rc2-cfb" +#define NID_rc2_cfb64 39 + +#define SN_rc2_ofb64 "RC2-OFB" +#define LN_rc2_ofb64 "rc2-ofb" +#define NID_rc2_ofb64 40 + +#define SN_rc2_40_cbc "RC2-40-CBC" +#define LN_rc2_40_cbc "rc2-40-cbc" +#define NID_rc2_40_cbc 98 + +#define SN_rc2_64_cbc "RC2-64-CBC" +#define LN_rc2_64_cbc "rc2-64-cbc" +#define NID_rc2_64_cbc 166 + +#define SN_rc4 "RC4" +#define LN_rc4 "rc4" +#define NID_rc4 5 +#define OBJ_rc4 OBJ_rsadsi,3L,4L + +#define SN_rc4_40 "RC4-40" +#define LN_rc4_40 "rc4-40" +#define NID_rc4_40 97 + +#define SN_des_ede3_cbc "DES-EDE3-CBC" +#define LN_des_ede3_cbc "des-ede3-cbc" +#define NID_des_ede3_cbc 44 +#define OBJ_des_ede3_cbc OBJ_rsadsi,3L,7L + +#define SN_rc5_cbc "RC5-CBC" +#define LN_rc5_cbc "rc5-cbc" +#define NID_rc5_cbc 120 +#define OBJ_rc5_cbc OBJ_rsadsi,3L,8L + +#define SN_rc5_ecb "RC5-ECB" +#define LN_rc5_ecb "rc5-ecb" +#define NID_rc5_ecb 121 + +#define SN_rc5_cfb64 "RC5-CFB" +#define LN_rc5_cfb64 "rc5-cfb" +#define NID_rc5_cfb64 122 + +#define SN_rc5_ofb64 "RC5-OFB" +#define LN_rc5_ofb64 "rc5-ofb" +#define NID_rc5_ofb64 123 + +#define SN_ms_ext_req "msExtReq" +#define LN_ms_ext_req "Microsoft Extension Request" +#define NID_ms_ext_req 171 +#define OBJ_ms_ext_req 1L,3L,6L,1L,4L,1L,311L,2L,1L,14L + +#define SN_ms_code_ind "msCodeInd" +#define LN_ms_code_ind "Microsoft Individual Code Signing" +#define NID_ms_code_ind 134 +#define OBJ_ms_code_ind 1L,3L,6L,1L,4L,1L,311L,2L,1L,21L + +#define SN_ms_code_com "msCodeCom" +#define LN_ms_code_com "Microsoft Commercial Code Signing" +#define NID_ms_code_com 135 +#define OBJ_ms_code_com 1L,3L,6L,1L,4L,1L,311L,2L,1L,22L + +#define SN_ms_ctl_sign "msCTLSign" +#define LN_ms_ctl_sign "Microsoft Trust List Signing" +#define NID_ms_ctl_sign 136 +#define OBJ_ms_ctl_sign 1L,3L,6L,1L,4L,1L,311L,10L,3L,1L + +#define SN_ms_sgc "msSGC" +#define LN_ms_sgc "Microsoft Server Gated Crypto" +#define NID_ms_sgc 137 +#define OBJ_ms_sgc 1L,3L,6L,1L,4L,1L,311L,10L,3L,3L + +#define SN_ms_efs "msEFS" +#define LN_ms_efs "Microsoft Encrypted File System" +#define NID_ms_efs 138 +#define OBJ_ms_efs 1L,3L,6L,1L,4L,1L,311L,10L,3L,4L + +#define SN_ms_smartcard_login "msSmartcardLogin" +#define LN_ms_smartcard_login "Microsoft Smartcardlogin" +#define NID_ms_smartcard_login 648 +#define OBJ_ms_smartcard_login 1L,3L,6L,1L,4L,1L,311L,20L,2L,2L + +#define SN_ms_upn "msUPN" +#define LN_ms_upn "Microsoft Universal Principal Name" +#define NID_ms_upn 649 +#define OBJ_ms_upn 1L,3L,6L,1L,4L,1L,311L,20L,2L,3L + +#define SN_idea_cbc "IDEA-CBC" +#define LN_idea_cbc "idea-cbc" +#define NID_idea_cbc 34 +#define OBJ_idea_cbc 1L,3L,6L,1L,4L,1L,188L,7L,1L,1L,2L + +#define SN_idea_ecb "IDEA-ECB" +#define LN_idea_ecb "idea-ecb" +#define NID_idea_ecb 36 + +#define SN_idea_cfb64 "IDEA-CFB" +#define LN_idea_cfb64 "idea-cfb" +#define NID_idea_cfb64 35 + +#define SN_idea_ofb64 "IDEA-OFB" +#define LN_idea_ofb64 "idea-ofb" +#define NID_idea_ofb64 46 + +#define SN_bf_cbc "BF-CBC" +#define LN_bf_cbc "bf-cbc" +#define NID_bf_cbc 91 +#define OBJ_bf_cbc 1L,3L,6L,1L,4L,1L,3029L,1L,2L + +#define SN_bf_ecb "BF-ECB" +#define LN_bf_ecb "bf-ecb" +#define NID_bf_ecb 92 + +#define SN_bf_cfb64 "BF-CFB" +#define LN_bf_cfb64 "bf-cfb" +#define NID_bf_cfb64 93 + +#define SN_bf_ofb64 "BF-OFB" +#define LN_bf_ofb64 "bf-ofb" +#define NID_bf_ofb64 94 + +#define SN_id_pkix "PKIX" +#define NID_id_pkix 127 +#define OBJ_id_pkix 1L,3L,6L,1L,5L,5L,7L + +#define SN_id_pkix_mod "id-pkix-mod" +#define NID_id_pkix_mod 258 +#define OBJ_id_pkix_mod OBJ_id_pkix,0L + +#define SN_id_pe "id-pe" +#define NID_id_pe 175 +#define OBJ_id_pe OBJ_id_pkix,1L + +#define SN_id_qt "id-qt" +#define NID_id_qt 259 +#define OBJ_id_qt OBJ_id_pkix,2L + +#define SN_id_kp "id-kp" +#define NID_id_kp 128 +#define OBJ_id_kp OBJ_id_pkix,3L + +#define SN_id_it "id-it" +#define NID_id_it 260 +#define OBJ_id_it OBJ_id_pkix,4L + +#define SN_id_pkip "id-pkip" +#define NID_id_pkip 261 +#define OBJ_id_pkip OBJ_id_pkix,5L + +#define SN_id_alg "id-alg" +#define NID_id_alg 262 +#define OBJ_id_alg OBJ_id_pkix,6L + +#define SN_id_cmc "id-cmc" +#define NID_id_cmc 263 +#define OBJ_id_cmc OBJ_id_pkix,7L + +#define SN_id_on "id-on" +#define NID_id_on 264 +#define OBJ_id_on OBJ_id_pkix,8L + +#define SN_id_pda "id-pda" +#define NID_id_pda 265 +#define OBJ_id_pda OBJ_id_pkix,9L + +#define SN_id_aca "id-aca" +#define NID_id_aca 266 +#define OBJ_id_aca OBJ_id_pkix,10L + +#define SN_id_qcs "id-qcs" +#define NID_id_qcs 267 +#define OBJ_id_qcs OBJ_id_pkix,11L + +#define SN_id_cct "id-cct" +#define NID_id_cct 268 +#define OBJ_id_cct OBJ_id_pkix,12L + +#define SN_id_ppl "id-ppl" +#define NID_id_ppl 662 +#define OBJ_id_ppl OBJ_id_pkix,21L + +#define SN_id_ad "id-ad" +#define NID_id_ad 176 +#define OBJ_id_ad OBJ_id_pkix,48L + +#define SN_id_pkix1_explicit_88 "id-pkix1-explicit-88" +#define NID_id_pkix1_explicit_88 269 +#define OBJ_id_pkix1_explicit_88 OBJ_id_pkix_mod,1L + +#define SN_id_pkix1_implicit_88 "id-pkix1-implicit-88" +#define NID_id_pkix1_implicit_88 270 +#define OBJ_id_pkix1_implicit_88 OBJ_id_pkix_mod,2L + +#define SN_id_pkix1_explicit_93 "id-pkix1-explicit-93" +#define NID_id_pkix1_explicit_93 271 +#define OBJ_id_pkix1_explicit_93 OBJ_id_pkix_mod,3L + +#define SN_id_pkix1_implicit_93 "id-pkix1-implicit-93" +#define NID_id_pkix1_implicit_93 272 +#define OBJ_id_pkix1_implicit_93 OBJ_id_pkix_mod,4L + +#define SN_id_mod_crmf "id-mod-crmf" +#define NID_id_mod_crmf 273 +#define OBJ_id_mod_crmf OBJ_id_pkix_mod,5L + +#define SN_id_mod_cmc "id-mod-cmc" +#define NID_id_mod_cmc 274 +#define OBJ_id_mod_cmc OBJ_id_pkix_mod,6L + +#define SN_id_mod_kea_profile_88 "id-mod-kea-profile-88" +#define NID_id_mod_kea_profile_88 275 +#define OBJ_id_mod_kea_profile_88 OBJ_id_pkix_mod,7L + +#define SN_id_mod_kea_profile_93 "id-mod-kea-profile-93" +#define NID_id_mod_kea_profile_93 276 +#define OBJ_id_mod_kea_profile_93 OBJ_id_pkix_mod,8L + +#define SN_id_mod_cmp "id-mod-cmp" +#define NID_id_mod_cmp 277 +#define OBJ_id_mod_cmp OBJ_id_pkix_mod,9L + +#define SN_id_mod_qualified_cert_88 "id-mod-qualified-cert-88" +#define NID_id_mod_qualified_cert_88 278 +#define OBJ_id_mod_qualified_cert_88 OBJ_id_pkix_mod,10L + +#define SN_id_mod_qualified_cert_93 "id-mod-qualified-cert-93" +#define NID_id_mod_qualified_cert_93 279 +#define OBJ_id_mod_qualified_cert_93 OBJ_id_pkix_mod,11L + +#define SN_id_mod_attribute_cert "id-mod-attribute-cert" +#define NID_id_mod_attribute_cert 280 +#define OBJ_id_mod_attribute_cert OBJ_id_pkix_mod,12L + +#define SN_id_mod_timestamp_protocol "id-mod-timestamp-protocol" +#define NID_id_mod_timestamp_protocol 281 +#define OBJ_id_mod_timestamp_protocol OBJ_id_pkix_mod,13L + +#define SN_id_mod_ocsp "id-mod-ocsp" +#define NID_id_mod_ocsp 282 +#define OBJ_id_mod_ocsp OBJ_id_pkix_mod,14L + +#define SN_id_mod_dvcs "id-mod-dvcs" +#define NID_id_mod_dvcs 283 +#define OBJ_id_mod_dvcs OBJ_id_pkix_mod,15L + +#define SN_id_mod_cmp2000 "id-mod-cmp2000" +#define NID_id_mod_cmp2000 284 +#define OBJ_id_mod_cmp2000 OBJ_id_pkix_mod,16L + +#define SN_info_access "authorityInfoAccess" +#define LN_info_access "Authority Information Access" +#define NID_info_access 177 +#define OBJ_info_access OBJ_id_pe,1L + +#define SN_biometricInfo "biometricInfo" +#define LN_biometricInfo "Biometric Info" +#define NID_biometricInfo 285 +#define OBJ_biometricInfo OBJ_id_pe,2L + +#define SN_qcStatements "qcStatements" +#define NID_qcStatements 286 +#define OBJ_qcStatements OBJ_id_pe,3L + +#define SN_ac_auditEntity "ac-auditEntity" +#define NID_ac_auditEntity 287 +#define OBJ_ac_auditEntity OBJ_id_pe,4L + +#define SN_ac_targeting "ac-targeting" +#define NID_ac_targeting 288 +#define OBJ_ac_targeting OBJ_id_pe,5L + +#define SN_aaControls "aaControls" +#define NID_aaControls 289 +#define OBJ_aaControls OBJ_id_pe,6L + +#define SN_sbgp_ipAddrBlock "sbgp-ipAddrBlock" +#define NID_sbgp_ipAddrBlock 290 +#define OBJ_sbgp_ipAddrBlock OBJ_id_pe,7L + +#define SN_sbgp_autonomousSysNum "sbgp-autonomousSysNum" +#define NID_sbgp_autonomousSysNum 291 +#define OBJ_sbgp_autonomousSysNum OBJ_id_pe,8L + +#define SN_sbgp_routerIdentifier "sbgp-routerIdentifier" +#define NID_sbgp_routerIdentifier 292 +#define OBJ_sbgp_routerIdentifier OBJ_id_pe,9L + +#define SN_ac_proxying "ac-proxying" +#define NID_ac_proxying 397 +#define OBJ_ac_proxying OBJ_id_pe,10L + +#define SN_sinfo_access "subjectInfoAccess" +#define LN_sinfo_access "Subject Information Access" +#define NID_sinfo_access 398 +#define OBJ_sinfo_access OBJ_id_pe,11L + +#define SN_proxyCertInfo "proxyCertInfo" +#define LN_proxyCertInfo "Proxy Certificate Information" +#define NID_proxyCertInfo 663 +#define OBJ_proxyCertInfo OBJ_id_pe,14L + +#define SN_id_qt_cps "id-qt-cps" +#define LN_id_qt_cps "Policy Qualifier CPS" +#define NID_id_qt_cps 164 +#define OBJ_id_qt_cps OBJ_id_qt,1L + +#define SN_id_qt_unotice "id-qt-unotice" +#define LN_id_qt_unotice "Policy Qualifier User Notice" +#define NID_id_qt_unotice 165 +#define OBJ_id_qt_unotice OBJ_id_qt,2L + +#define SN_textNotice "textNotice" +#define NID_textNotice 293 +#define OBJ_textNotice OBJ_id_qt,3L + +#define SN_server_auth "serverAuth" +#define LN_server_auth "TLS Web Server Authentication" +#define NID_server_auth 129 +#define OBJ_server_auth OBJ_id_kp,1L + +#define SN_client_auth "clientAuth" +#define LN_client_auth "TLS Web Client Authentication" +#define NID_client_auth 130 +#define OBJ_client_auth OBJ_id_kp,2L + +#define SN_code_sign "codeSigning" +#define LN_code_sign "Code Signing" +#define NID_code_sign 131 +#define OBJ_code_sign OBJ_id_kp,3L + +#define SN_email_protect "emailProtection" +#define LN_email_protect "E-mail Protection" +#define NID_email_protect 132 +#define OBJ_email_protect OBJ_id_kp,4L + +#define SN_ipsecEndSystem "ipsecEndSystem" +#define LN_ipsecEndSystem "IPSec End System" +#define NID_ipsecEndSystem 294 +#define OBJ_ipsecEndSystem OBJ_id_kp,5L + +#define SN_ipsecTunnel "ipsecTunnel" +#define LN_ipsecTunnel "IPSec Tunnel" +#define NID_ipsecTunnel 295 +#define OBJ_ipsecTunnel OBJ_id_kp,6L + +#define SN_ipsecUser "ipsecUser" +#define LN_ipsecUser "IPSec User" +#define NID_ipsecUser 296 +#define OBJ_ipsecUser OBJ_id_kp,7L + +#define SN_time_stamp "timeStamping" +#define LN_time_stamp "Time Stamping" +#define NID_time_stamp 133 +#define OBJ_time_stamp OBJ_id_kp,8L + +#define SN_OCSP_sign "OCSPSigning" +#define LN_OCSP_sign "OCSP Signing" +#define NID_OCSP_sign 180 +#define OBJ_OCSP_sign OBJ_id_kp,9L + +#define SN_dvcs "DVCS" +#define LN_dvcs "dvcs" +#define NID_dvcs 297 +#define OBJ_dvcs OBJ_id_kp,10L + +#define SN_id_it_caProtEncCert "id-it-caProtEncCert" +#define NID_id_it_caProtEncCert 298 +#define OBJ_id_it_caProtEncCert OBJ_id_it,1L + +#define SN_id_it_signKeyPairTypes "id-it-signKeyPairTypes" +#define NID_id_it_signKeyPairTypes 299 +#define OBJ_id_it_signKeyPairTypes OBJ_id_it,2L + +#define SN_id_it_encKeyPairTypes "id-it-encKeyPairTypes" +#define NID_id_it_encKeyPairTypes 300 +#define OBJ_id_it_encKeyPairTypes OBJ_id_it,3L + +#define SN_id_it_preferredSymmAlg "id-it-preferredSymmAlg" +#define NID_id_it_preferredSymmAlg 301 +#define OBJ_id_it_preferredSymmAlg OBJ_id_it,4L + +#define SN_id_it_caKeyUpdateInfo "id-it-caKeyUpdateInfo" +#define NID_id_it_caKeyUpdateInfo 302 +#define OBJ_id_it_caKeyUpdateInfo OBJ_id_it,5L + +#define SN_id_it_currentCRL "id-it-currentCRL" +#define NID_id_it_currentCRL 303 +#define OBJ_id_it_currentCRL OBJ_id_it,6L + +#define SN_id_it_unsupportedOIDs "id-it-unsupportedOIDs" +#define NID_id_it_unsupportedOIDs 304 +#define OBJ_id_it_unsupportedOIDs OBJ_id_it,7L + +#define SN_id_it_subscriptionRequest "id-it-subscriptionRequest" +#define NID_id_it_subscriptionRequest 305 +#define OBJ_id_it_subscriptionRequest OBJ_id_it,8L + +#define SN_id_it_subscriptionResponse "id-it-subscriptionResponse" +#define NID_id_it_subscriptionResponse 306 +#define OBJ_id_it_subscriptionResponse OBJ_id_it,9L + +#define SN_id_it_keyPairParamReq "id-it-keyPairParamReq" +#define NID_id_it_keyPairParamReq 307 +#define OBJ_id_it_keyPairParamReq OBJ_id_it,10L + +#define SN_id_it_keyPairParamRep "id-it-keyPairParamRep" +#define NID_id_it_keyPairParamRep 308 +#define OBJ_id_it_keyPairParamRep OBJ_id_it,11L + +#define SN_id_it_revPassphrase "id-it-revPassphrase" +#define NID_id_it_revPassphrase 309 +#define OBJ_id_it_revPassphrase OBJ_id_it,12L + +#define SN_id_it_implicitConfirm "id-it-implicitConfirm" +#define NID_id_it_implicitConfirm 310 +#define OBJ_id_it_implicitConfirm OBJ_id_it,13L + +#define SN_id_it_confirmWaitTime "id-it-confirmWaitTime" +#define NID_id_it_confirmWaitTime 311 +#define OBJ_id_it_confirmWaitTime OBJ_id_it,14L + +#define SN_id_it_origPKIMessage "id-it-origPKIMessage" +#define NID_id_it_origPKIMessage 312 +#define OBJ_id_it_origPKIMessage OBJ_id_it,15L + +#define SN_id_it_suppLangTags "id-it-suppLangTags" +#define NID_id_it_suppLangTags 784 +#define OBJ_id_it_suppLangTags OBJ_id_it,16L + +#define SN_id_regCtrl "id-regCtrl" +#define NID_id_regCtrl 313 +#define OBJ_id_regCtrl OBJ_id_pkip,1L + +#define SN_id_regInfo "id-regInfo" +#define NID_id_regInfo 314 +#define OBJ_id_regInfo OBJ_id_pkip,2L + +#define SN_id_regCtrl_regToken "id-regCtrl-regToken" +#define NID_id_regCtrl_regToken 315 +#define OBJ_id_regCtrl_regToken OBJ_id_regCtrl,1L + +#define SN_id_regCtrl_authenticator "id-regCtrl-authenticator" +#define NID_id_regCtrl_authenticator 316 +#define OBJ_id_regCtrl_authenticator OBJ_id_regCtrl,2L + +#define SN_id_regCtrl_pkiPublicationInfo "id-regCtrl-pkiPublicationInfo" +#define NID_id_regCtrl_pkiPublicationInfo 317 +#define OBJ_id_regCtrl_pkiPublicationInfo OBJ_id_regCtrl,3L + +#define SN_id_regCtrl_pkiArchiveOptions "id-regCtrl-pkiArchiveOptions" +#define NID_id_regCtrl_pkiArchiveOptions 318 +#define OBJ_id_regCtrl_pkiArchiveOptions OBJ_id_regCtrl,4L + +#define SN_id_regCtrl_oldCertID "id-regCtrl-oldCertID" +#define NID_id_regCtrl_oldCertID 319 +#define OBJ_id_regCtrl_oldCertID OBJ_id_regCtrl,5L + +#define SN_id_regCtrl_protocolEncrKey "id-regCtrl-protocolEncrKey" +#define NID_id_regCtrl_protocolEncrKey 320 +#define OBJ_id_regCtrl_protocolEncrKey OBJ_id_regCtrl,6L + +#define SN_id_regInfo_utf8Pairs "id-regInfo-utf8Pairs" +#define NID_id_regInfo_utf8Pairs 321 +#define OBJ_id_regInfo_utf8Pairs OBJ_id_regInfo,1L + +#define SN_id_regInfo_certReq "id-regInfo-certReq" +#define NID_id_regInfo_certReq 322 +#define OBJ_id_regInfo_certReq OBJ_id_regInfo,2L + +#define SN_id_alg_des40 "id-alg-des40" +#define NID_id_alg_des40 323 +#define OBJ_id_alg_des40 OBJ_id_alg,1L + +#define SN_id_alg_noSignature "id-alg-noSignature" +#define NID_id_alg_noSignature 324 +#define OBJ_id_alg_noSignature OBJ_id_alg,2L + +#define SN_id_alg_dh_sig_hmac_sha1 "id-alg-dh-sig-hmac-sha1" +#define NID_id_alg_dh_sig_hmac_sha1 325 +#define OBJ_id_alg_dh_sig_hmac_sha1 OBJ_id_alg,3L + +#define SN_id_alg_dh_pop "id-alg-dh-pop" +#define NID_id_alg_dh_pop 326 +#define OBJ_id_alg_dh_pop OBJ_id_alg,4L + +#define SN_id_cmc_statusInfo "id-cmc-statusInfo" +#define NID_id_cmc_statusInfo 327 +#define OBJ_id_cmc_statusInfo OBJ_id_cmc,1L + +#define SN_id_cmc_identification "id-cmc-identification" +#define NID_id_cmc_identification 328 +#define OBJ_id_cmc_identification OBJ_id_cmc,2L + +#define SN_id_cmc_identityProof "id-cmc-identityProof" +#define NID_id_cmc_identityProof 329 +#define OBJ_id_cmc_identityProof OBJ_id_cmc,3L + +#define SN_id_cmc_dataReturn "id-cmc-dataReturn" +#define NID_id_cmc_dataReturn 330 +#define OBJ_id_cmc_dataReturn OBJ_id_cmc,4L + +#define SN_id_cmc_transactionId "id-cmc-transactionId" +#define NID_id_cmc_transactionId 331 +#define OBJ_id_cmc_transactionId OBJ_id_cmc,5L + +#define SN_id_cmc_senderNonce "id-cmc-senderNonce" +#define NID_id_cmc_senderNonce 332 +#define OBJ_id_cmc_senderNonce OBJ_id_cmc,6L + +#define SN_id_cmc_recipientNonce "id-cmc-recipientNonce" +#define NID_id_cmc_recipientNonce 333 +#define OBJ_id_cmc_recipientNonce OBJ_id_cmc,7L + +#define SN_id_cmc_addExtensions "id-cmc-addExtensions" +#define NID_id_cmc_addExtensions 334 +#define OBJ_id_cmc_addExtensions OBJ_id_cmc,8L + +#define SN_id_cmc_encryptedPOP "id-cmc-encryptedPOP" +#define NID_id_cmc_encryptedPOP 335 +#define OBJ_id_cmc_encryptedPOP OBJ_id_cmc,9L + +#define SN_id_cmc_decryptedPOP "id-cmc-decryptedPOP" +#define NID_id_cmc_decryptedPOP 336 +#define OBJ_id_cmc_decryptedPOP OBJ_id_cmc,10L + +#define SN_id_cmc_lraPOPWitness "id-cmc-lraPOPWitness" +#define NID_id_cmc_lraPOPWitness 337 +#define OBJ_id_cmc_lraPOPWitness OBJ_id_cmc,11L + +#define SN_id_cmc_getCert "id-cmc-getCert" +#define NID_id_cmc_getCert 338 +#define OBJ_id_cmc_getCert OBJ_id_cmc,15L + +#define SN_id_cmc_getCRL "id-cmc-getCRL" +#define NID_id_cmc_getCRL 339 +#define OBJ_id_cmc_getCRL OBJ_id_cmc,16L + +#define SN_id_cmc_revokeRequest "id-cmc-revokeRequest" +#define NID_id_cmc_revokeRequest 340 +#define OBJ_id_cmc_revokeRequest OBJ_id_cmc,17L + +#define SN_id_cmc_regInfo "id-cmc-regInfo" +#define NID_id_cmc_regInfo 341 +#define OBJ_id_cmc_regInfo OBJ_id_cmc,18L + +#define SN_id_cmc_responseInfo "id-cmc-responseInfo" +#define NID_id_cmc_responseInfo 342 +#define OBJ_id_cmc_responseInfo OBJ_id_cmc,19L + +#define SN_id_cmc_queryPending "id-cmc-queryPending" +#define NID_id_cmc_queryPending 343 +#define OBJ_id_cmc_queryPending OBJ_id_cmc,21L + +#define SN_id_cmc_popLinkRandom "id-cmc-popLinkRandom" +#define NID_id_cmc_popLinkRandom 344 +#define OBJ_id_cmc_popLinkRandom OBJ_id_cmc,22L + +#define SN_id_cmc_popLinkWitness "id-cmc-popLinkWitness" +#define NID_id_cmc_popLinkWitness 345 +#define OBJ_id_cmc_popLinkWitness OBJ_id_cmc,23L + +#define SN_id_cmc_confirmCertAcceptance "id-cmc-confirmCertAcceptance" +#define NID_id_cmc_confirmCertAcceptance 346 +#define OBJ_id_cmc_confirmCertAcceptance OBJ_id_cmc,24L + +#define SN_id_on_personalData "id-on-personalData" +#define NID_id_on_personalData 347 +#define OBJ_id_on_personalData OBJ_id_on,1L + +#define SN_id_on_permanentIdentifier "id-on-permanentIdentifier" +#define LN_id_on_permanentIdentifier "Permanent Identifier" +#define NID_id_on_permanentIdentifier 858 +#define OBJ_id_on_permanentIdentifier OBJ_id_on,3L + +#define SN_id_pda_dateOfBirth "id-pda-dateOfBirth" +#define NID_id_pda_dateOfBirth 348 +#define OBJ_id_pda_dateOfBirth OBJ_id_pda,1L + +#define SN_id_pda_placeOfBirth "id-pda-placeOfBirth" +#define NID_id_pda_placeOfBirth 349 +#define OBJ_id_pda_placeOfBirth OBJ_id_pda,2L + +#define SN_id_pda_gender "id-pda-gender" +#define NID_id_pda_gender 351 +#define OBJ_id_pda_gender OBJ_id_pda,3L + +#define SN_id_pda_countryOfCitizenship "id-pda-countryOfCitizenship" +#define NID_id_pda_countryOfCitizenship 352 +#define OBJ_id_pda_countryOfCitizenship OBJ_id_pda,4L + +#define SN_id_pda_countryOfResidence "id-pda-countryOfResidence" +#define NID_id_pda_countryOfResidence 353 +#define OBJ_id_pda_countryOfResidence OBJ_id_pda,5L + +#define SN_id_aca_authenticationInfo "id-aca-authenticationInfo" +#define NID_id_aca_authenticationInfo 354 +#define OBJ_id_aca_authenticationInfo OBJ_id_aca,1L + +#define SN_id_aca_accessIdentity "id-aca-accessIdentity" +#define NID_id_aca_accessIdentity 355 +#define OBJ_id_aca_accessIdentity OBJ_id_aca,2L + +#define SN_id_aca_chargingIdentity "id-aca-chargingIdentity" +#define NID_id_aca_chargingIdentity 356 +#define OBJ_id_aca_chargingIdentity OBJ_id_aca,3L + +#define SN_id_aca_group "id-aca-group" +#define NID_id_aca_group 357 +#define OBJ_id_aca_group OBJ_id_aca,4L + +#define SN_id_aca_role "id-aca-role" +#define NID_id_aca_role 358 +#define OBJ_id_aca_role OBJ_id_aca,5L + +#define SN_id_aca_encAttrs "id-aca-encAttrs" +#define NID_id_aca_encAttrs 399 +#define OBJ_id_aca_encAttrs OBJ_id_aca,6L + +#define SN_id_qcs_pkixQCSyntax_v1 "id-qcs-pkixQCSyntax-v1" +#define NID_id_qcs_pkixQCSyntax_v1 359 +#define OBJ_id_qcs_pkixQCSyntax_v1 OBJ_id_qcs,1L + +#define SN_id_cct_crs "id-cct-crs" +#define NID_id_cct_crs 360 +#define OBJ_id_cct_crs OBJ_id_cct,1L + +#define SN_id_cct_PKIData "id-cct-PKIData" +#define NID_id_cct_PKIData 361 +#define OBJ_id_cct_PKIData OBJ_id_cct,2L + +#define SN_id_cct_PKIResponse "id-cct-PKIResponse" +#define NID_id_cct_PKIResponse 362 +#define OBJ_id_cct_PKIResponse OBJ_id_cct,3L + +#define SN_id_ppl_anyLanguage "id-ppl-anyLanguage" +#define LN_id_ppl_anyLanguage "Any language" +#define NID_id_ppl_anyLanguage 664 +#define OBJ_id_ppl_anyLanguage OBJ_id_ppl,0L + +#define SN_id_ppl_inheritAll "id-ppl-inheritAll" +#define LN_id_ppl_inheritAll "Inherit all" +#define NID_id_ppl_inheritAll 665 +#define OBJ_id_ppl_inheritAll OBJ_id_ppl,1L + +#define SN_Independent "id-ppl-independent" +#define LN_Independent "Independent" +#define NID_Independent 667 +#define OBJ_Independent OBJ_id_ppl,2L + +#define SN_ad_OCSP "OCSP" +#define LN_ad_OCSP "OCSP" +#define NID_ad_OCSP 178 +#define OBJ_ad_OCSP OBJ_id_ad,1L + +#define SN_ad_ca_issuers "caIssuers" +#define LN_ad_ca_issuers "CA Issuers" +#define NID_ad_ca_issuers 179 +#define OBJ_ad_ca_issuers OBJ_id_ad,2L + +#define SN_ad_timeStamping "ad_timestamping" +#define LN_ad_timeStamping "AD Time Stamping" +#define NID_ad_timeStamping 363 +#define OBJ_ad_timeStamping OBJ_id_ad,3L + +#define SN_ad_dvcs "AD_DVCS" +#define LN_ad_dvcs "ad dvcs" +#define NID_ad_dvcs 364 +#define OBJ_ad_dvcs OBJ_id_ad,4L + +#define SN_caRepository "caRepository" +#define LN_caRepository "CA Repository" +#define NID_caRepository 785 +#define OBJ_caRepository OBJ_id_ad,5L + +#define OBJ_id_pkix_OCSP OBJ_ad_OCSP + +#define SN_id_pkix_OCSP_basic "basicOCSPResponse" +#define LN_id_pkix_OCSP_basic "Basic OCSP Response" +#define NID_id_pkix_OCSP_basic 365 +#define OBJ_id_pkix_OCSP_basic OBJ_id_pkix_OCSP,1L + +#define SN_id_pkix_OCSP_Nonce "Nonce" +#define LN_id_pkix_OCSP_Nonce "OCSP Nonce" +#define NID_id_pkix_OCSP_Nonce 366 +#define OBJ_id_pkix_OCSP_Nonce OBJ_id_pkix_OCSP,2L + +#define SN_id_pkix_OCSP_CrlID "CrlID" +#define LN_id_pkix_OCSP_CrlID "OCSP CRL ID" +#define NID_id_pkix_OCSP_CrlID 367 +#define OBJ_id_pkix_OCSP_CrlID OBJ_id_pkix_OCSP,3L + +#define SN_id_pkix_OCSP_acceptableResponses "acceptableResponses" +#define LN_id_pkix_OCSP_acceptableResponses "Acceptable OCSP Responses" +#define NID_id_pkix_OCSP_acceptableResponses 368 +#define OBJ_id_pkix_OCSP_acceptableResponses OBJ_id_pkix_OCSP,4L + +#define SN_id_pkix_OCSP_noCheck "noCheck" +#define LN_id_pkix_OCSP_noCheck "OCSP No Check" +#define NID_id_pkix_OCSP_noCheck 369 +#define OBJ_id_pkix_OCSP_noCheck OBJ_id_pkix_OCSP,5L + +#define SN_id_pkix_OCSP_archiveCutoff "archiveCutoff" +#define LN_id_pkix_OCSP_archiveCutoff "OCSP Archive Cutoff" +#define NID_id_pkix_OCSP_archiveCutoff 370 +#define OBJ_id_pkix_OCSP_archiveCutoff OBJ_id_pkix_OCSP,6L + +#define SN_id_pkix_OCSP_serviceLocator "serviceLocator" +#define LN_id_pkix_OCSP_serviceLocator "OCSP Service Locator" +#define NID_id_pkix_OCSP_serviceLocator 371 +#define OBJ_id_pkix_OCSP_serviceLocator OBJ_id_pkix_OCSP,7L + +#define SN_id_pkix_OCSP_extendedStatus "extendedStatus" +#define LN_id_pkix_OCSP_extendedStatus "Extended OCSP Status" +#define NID_id_pkix_OCSP_extendedStatus 372 +#define OBJ_id_pkix_OCSP_extendedStatus OBJ_id_pkix_OCSP,8L + +#define SN_id_pkix_OCSP_valid "valid" +#define NID_id_pkix_OCSP_valid 373 +#define OBJ_id_pkix_OCSP_valid OBJ_id_pkix_OCSP,9L + +#define SN_id_pkix_OCSP_path "path" +#define NID_id_pkix_OCSP_path 374 +#define OBJ_id_pkix_OCSP_path OBJ_id_pkix_OCSP,10L + +#define SN_id_pkix_OCSP_trustRoot "trustRoot" +#define LN_id_pkix_OCSP_trustRoot "Trust Root" +#define NID_id_pkix_OCSP_trustRoot 375 +#define OBJ_id_pkix_OCSP_trustRoot OBJ_id_pkix_OCSP,11L + +#define SN_algorithm "algorithm" +#define LN_algorithm "algorithm" +#define NID_algorithm 376 +#define OBJ_algorithm 1L,3L,14L,3L,2L + +#define SN_md5WithRSA "RSA-NP-MD5" +#define LN_md5WithRSA "md5WithRSA" +#define NID_md5WithRSA 104 +#define OBJ_md5WithRSA OBJ_algorithm,3L + +#define SN_des_ecb "DES-ECB" +#define LN_des_ecb "des-ecb" +#define NID_des_ecb 29 +#define OBJ_des_ecb OBJ_algorithm,6L + +#define SN_des_cbc "DES-CBC" +#define LN_des_cbc "des-cbc" +#define NID_des_cbc 31 +#define OBJ_des_cbc OBJ_algorithm,7L + +#define SN_des_ofb64 "DES-OFB" +#define LN_des_ofb64 "des-ofb" +#define NID_des_ofb64 45 +#define OBJ_des_ofb64 OBJ_algorithm,8L + +#define SN_des_cfb64 "DES-CFB" +#define LN_des_cfb64 "des-cfb" +#define NID_des_cfb64 30 +#define OBJ_des_cfb64 OBJ_algorithm,9L + +#define SN_rsaSignature "rsaSignature" +#define NID_rsaSignature 377 +#define OBJ_rsaSignature OBJ_algorithm,11L + +#define SN_dsa_2 "DSA-old" +#define LN_dsa_2 "dsaEncryption-old" +#define NID_dsa_2 67 +#define OBJ_dsa_2 OBJ_algorithm,12L + +#define SN_dsaWithSHA "DSA-SHA" +#define LN_dsaWithSHA "dsaWithSHA" +#define NID_dsaWithSHA 66 +#define OBJ_dsaWithSHA OBJ_algorithm,13L + +#define SN_shaWithRSAEncryption "RSA-SHA" +#define LN_shaWithRSAEncryption "shaWithRSAEncryption" +#define NID_shaWithRSAEncryption 42 +#define OBJ_shaWithRSAEncryption OBJ_algorithm,15L + +#define SN_des_ede_ecb "DES-EDE" +#define LN_des_ede_ecb "des-ede" +#define NID_des_ede_ecb 32 +#define OBJ_des_ede_ecb OBJ_algorithm,17L + +#define SN_des_ede3_ecb "DES-EDE3" +#define LN_des_ede3_ecb "des-ede3" +#define NID_des_ede3_ecb 33 + +#define SN_des_ede_cbc "DES-EDE-CBC" +#define LN_des_ede_cbc "des-ede-cbc" +#define NID_des_ede_cbc 43 + +#define SN_des_ede_cfb64 "DES-EDE-CFB" +#define LN_des_ede_cfb64 "des-ede-cfb" +#define NID_des_ede_cfb64 60 + +#define SN_des_ede3_cfb64 "DES-EDE3-CFB" +#define LN_des_ede3_cfb64 "des-ede3-cfb" +#define NID_des_ede3_cfb64 61 + +#define SN_des_ede_ofb64 "DES-EDE-OFB" +#define LN_des_ede_ofb64 "des-ede-ofb" +#define NID_des_ede_ofb64 62 + +#define SN_des_ede3_ofb64 "DES-EDE3-OFB" +#define LN_des_ede3_ofb64 "des-ede3-ofb" +#define NID_des_ede3_ofb64 63 + +#define SN_desx_cbc "DESX-CBC" +#define LN_desx_cbc "desx-cbc" +#define NID_desx_cbc 80 + +#define SN_sha "SHA" +#define LN_sha "sha" +#define NID_sha 41 +#define OBJ_sha OBJ_algorithm,18L + +#define SN_sha1 "SHA1" +#define LN_sha1 "sha1" +#define NID_sha1 64 +#define OBJ_sha1 OBJ_algorithm,26L + +#define SN_dsaWithSHA1_2 "DSA-SHA1-old" +#define LN_dsaWithSHA1_2 "dsaWithSHA1-old" +#define NID_dsaWithSHA1_2 70 +#define OBJ_dsaWithSHA1_2 OBJ_algorithm,27L + +#define SN_sha1WithRSA "RSA-SHA1-2" +#define LN_sha1WithRSA "sha1WithRSA" +#define NID_sha1WithRSA 115 +#define OBJ_sha1WithRSA OBJ_algorithm,29L + +#define SN_ripemd160 "RIPEMD160" +#define LN_ripemd160 "ripemd160" +#define NID_ripemd160 117 +#define OBJ_ripemd160 1L,3L,36L,3L,2L,1L + +#define SN_ripemd160WithRSA "RSA-RIPEMD160" +#define LN_ripemd160WithRSA "ripemd160WithRSA" +#define NID_ripemd160WithRSA 119 +#define OBJ_ripemd160WithRSA 1L,3L,36L,3L,3L,1L,2L + +#define SN_sxnet "SXNetID" +#define LN_sxnet "Strong Extranet ID" +#define NID_sxnet 143 +#define OBJ_sxnet 1L,3L,101L,1L,4L,1L + +#define SN_X500 "X500" +#define LN_X500 "directory services (X.500)" +#define NID_X500 11 +#define OBJ_X500 2L,5L + +#define SN_X509 "X509" +#define NID_X509 12 +#define OBJ_X509 OBJ_X500,4L + +#define SN_commonName "CN" +#define LN_commonName "commonName" +#define NID_commonName 13 +#define OBJ_commonName OBJ_X509,3L + +#define SN_surname "SN" +#define LN_surname "surname" +#define NID_surname 100 +#define OBJ_surname OBJ_X509,4L + +#define LN_serialNumber "serialNumber" +#define NID_serialNumber 105 +#define OBJ_serialNumber OBJ_X509,5L + +#define SN_countryName "C" +#define LN_countryName "countryName" +#define NID_countryName 14 +#define OBJ_countryName OBJ_X509,6L + +#define SN_localityName "L" +#define LN_localityName "localityName" +#define NID_localityName 15 +#define OBJ_localityName OBJ_X509,7L + +#define SN_stateOrProvinceName "ST" +#define LN_stateOrProvinceName "stateOrProvinceName" +#define NID_stateOrProvinceName 16 +#define OBJ_stateOrProvinceName OBJ_X509,8L + +#define SN_streetAddress "street" +#define LN_streetAddress "streetAddress" +#define NID_streetAddress 660 +#define OBJ_streetAddress OBJ_X509,9L + +#define SN_organizationName "O" +#define LN_organizationName "organizationName" +#define NID_organizationName 17 +#define OBJ_organizationName OBJ_X509,10L + +#define SN_organizationalUnitName "OU" +#define LN_organizationalUnitName "organizationalUnitName" +#define NID_organizationalUnitName 18 +#define OBJ_organizationalUnitName OBJ_X509,11L + +#define SN_title "title" +#define LN_title "title" +#define NID_title 106 +#define OBJ_title OBJ_X509,12L + +#define LN_description "description" +#define NID_description 107 +#define OBJ_description OBJ_X509,13L + +#define LN_searchGuide "searchGuide" +#define NID_searchGuide 859 +#define OBJ_searchGuide OBJ_X509,14L + +#define LN_businessCategory "businessCategory" +#define NID_businessCategory 860 +#define OBJ_businessCategory OBJ_X509,15L + +#define LN_postalAddress "postalAddress" +#define NID_postalAddress 861 +#define OBJ_postalAddress OBJ_X509,16L + +#define LN_postalCode "postalCode" +#define NID_postalCode 661 +#define OBJ_postalCode OBJ_X509,17L + +#define LN_postOfficeBox "postOfficeBox" +#define NID_postOfficeBox 862 +#define OBJ_postOfficeBox OBJ_X509,18L + +#define LN_physicalDeliveryOfficeName "physicalDeliveryOfficeName" +#define NID_physicalDeliveryOfficeName 863 +#define OBJ_physicalDeliveryOfficeName OBJ_X509,19L + +#define LN_telephoneNumber "telephoneNumber" +#define NID_telephoneNumber 864 +#define OBJ_telephoneNumber OBJ_X509,20L + +#define LN_telexNumber "telexNumber" +#define NID_telexNumber 865 +#define OBJ_telexNumber OBJ_X509,21L + +#define LN_teletexTerminalIdentifier "teletexTerminalIdentifier" +#define NID_teletexTerminalIdentifier 866 +#define OBJ_teletexTerminalIdentifier OBJ_X509,22L + +#define LN_facsimileTelephoneNumber "facsimileTelephoneNumber" +#define NID_facsimileTelephoneNumber 867 +#define OBJ_facsimileTelephoneNumber OBJ_X509,23L + +#define LN_x121Address "x121Address" +#define NID_x121Address 868 +#define OBJ_x121Address OBJ_X509,24L + +#define LN_internationaliSDNNumber "internationaliSDNNumber" +#define NID_internationaliSDNNumber 869 +#define OBJ_internationaliSDNNumber OBJ_X509,25L + +#define LN_registeredAddress "registeredAddress" +#define NID_registeredAddress 870 +#define OBJ_registeredAddress OBJ_X509,26L + +#define LN_destinationIndicator "destinationIndicator" +#define NID_destinationIndicator 871 +#define OBJ_destinationIndicator OBJ_X509,27L + +#define LN_preferredDeliveryMethod "preferredDeliveryMethod" +#define NID_preferredDeliveryMethod 872 +#define OBJ_preferredDeliveryMethod OBJ_X509,28L + +#define LN_presentationAddress "presentationAddress" +#define NID_presentationAddress 873 +#define OBJ_presentationAddress OBJ_X509,29L + +#define LN_supportedApplicationContext "supportedApplicationContext" +#define NID_supportedApplicationContext 874 +#define OBJ_supportedApplicationContext OBJ_X509,30L + +#define SN_member "member" +#define NID_member 875 +#define OBJ_member OBJ_X509,31L + +#define SN_owner "owner" +#define NID_owner 876 +#define OBJ_owner OBJ_X509,32L + +#define LN_roleOccupant "roleOccupant" +#define NID_roleOccupant 877 +#define OBJ_roleOccupant OBJ_X509,33L + +#define SN_seeAlso "seeAlso" +#define NID_seeAlso 878 +#define OBJ_seeAlso OBJ_X509,34L + +#define LN_userPassword "userPassword" +#define NID_userPassword 879 +#define OBJ_userPassword OBJ_X509,35L + +#define LN_userCertificate "userCertificate" +#define NID_userCertificate 880 +#define OBJ_userCertificate OBJ_X509,36L + +#define LN_cACertificate "cACertificate" +#define NID_cACertificate 881 +#define OBJ_cACertificate OBJ_X509,37L + +#define LN_authorityRevocationList "authorityRevocationList" +#define NID_authorityRevocationList 882 +#define OBJ_authorityRevocationList OBJ_X509,38L + +#define LN_certificateRevocationList "certificateRevocationList" +#define NID_certificateRevocationList 883 +#define OBJ_certificateRevocationList OBJ_X509,39L + +#define LN_crossCertificatePair "crossCertificatePair" +#define NID_crossCertificatePair 884 +#define OBJ_crossCertificatePair OBJ_X509,40L + +#define SN_name "name" +#define LN_name "name" +#define NID_name 173 +#define OBJ_name OBJ_X509,41L + +#define SN_givenName "GN" +#define LN_givenName "givenName" +#define NID_givenName 99 +#define OBJ_givenName OBJ_X509,42L + +#define SN_initials "initials" +#define LN_initials "initials" +#define NID_initials 101 +#define OBJ_initials OBJ_X509,43L + +#define LN_generationQualifier "generationQualifier" +#define NID_generationQualifier 509 +#define OBJ_generationQualifier OBJ_X509,44L + +#define LN_x500UniqueIdentifier "x500UniqueIdentifier" +#define NID_x500UniqueIdentifier 503 +#define OBJ_x500UniqueIdentifier OBJ_X509,45L + +#define SN_dnQualifier "dnQualifier" +#define LN_dnQualifier "dnQualifier" +#define NID_dnQualifier 174 +#define OBJ_dnQualifier OBJ_X509,46L + +#define LN_enhancedSearchGuide "enhancedSearchGuide" +#define NID_enhancedSearchGuide 885 +#define OBJ_enhancedSearchGuide OBJ_X509,47L + +#define LN_protocolInformation "protocolInformation" +#define NID_protocolInformation 886 +#define OBJ_protocolInformation OBJ_X509,48L + +#define LN_distinguishedName "distinguishedName" +#define NID_distinguishedName 887 +#define OBJ_distinguishedName OBJ_X509,49L + +#define LN_uniqueMember "uniqueMember" +#define NID_uniqueMember 888 +#define OBJ_uniqueMember OBJ_X509,50L + +#define LN_houseIdentifier "houseIdentifier" +#define NID_houseIdentifier 889 +#define OBJ_houseIdentifier OBJ_X509,51L + +#define LN_supportedAlgorithms "supportedAlgorithms" +#define NID_supportedAlgorithms 890 +#define OBJ_supportedAlgorithms OBJ_X509,52L + +#define LN_deltaRevocationList "deltaRevocationList" +#define NID_deltaRevocationList 891 +#define OBJ_deltaRevocationList OBJ_X509,53L + +#define SN_dmdName "dmdName" +#define NID_dmdName 892 +#define OBJ_dmdName OBJ_X509,54L + +#define LN_pseudonym "pseudonym" +#define NID_pseudonym 510 +#define OBJ_pseudonym OBJ_X509,65L + +#define SN_role "role" +#define LN_role "role" +#define NID_role 400 +#define OBJ_role OBJ_X509,72L + +#define SN_X500algorithms "X500algorithms" +#define LN_X500algorithms "directory services - algorithms" +#define NID_X500algorithms 378 +#define OBJ_X500algorithms OBJ_X500,8L + +#define SN_rsa "RSA" +#define LN_rsa "rsa" +#define NID_rsa 19 +#define OBJ_rsa OBJ_X500algorithms,1L,1L + +#define SN_mdc2WithRSA "RSA-MDC2" +#define LN_mdc2WithRSA "mdc2WithRSA" +#define NID_mdc2WithRSA 96 +#define OBJ_mdc2WithRSA OBJ_X500algorithms,3L,100L + +#define SN_mdc2 "MDC2" +#define LN_mdc2 "mdc2" +#define NID_mdc2 95 +#define OBJ_mdc2 OBJ_X500algorithms,3L,101L + +#define SN_id_ce "id-ce" +#define NID_id_ce 81 +#define OBJ_id_ce OBJ_X500,29L + +#define SN_subject_directory_attributes "subjectDirectoryAttributes" +#define LN_subject_directory_attributes "X509v3 Subject Directory Attributes" +#define NID_subject_directory_attributes 769 +#define OBJ_subject_directory_attributes OBJ_id_ce,9L + +#define SN_subject_key_identifier "subjectKeyIdentifier" +#define LN_subject_key_identifier "X509v3 Subject Key Identifier" +#define NID_subject_key_identifier 82 +#define OBJ_subject_key_identifier OBJ_id_ce,14L + +#define SN_key_usage "keyUsage" +#define LN_key_usage "X509v3 Key Usage" +#define NID_key_usage 83 +#define OBJ_key_usage OBJ_id_ce,15L + +#define SN_private_key_usage_period "privateKeyUsagePeriod" +#define LN_private_key_usage_period "X509v3 Private Key Usage Period" +#define NID_private_key_usage_period 84 +#define OBJ_private_key_usage_period OBJ_id_ce,16L + +#define SN_subject_alt_name "subjectAltName" +#define LN_subject_alt_name "X509v3 Subject Alternative Name" +#define NID_subject_alt_name 85 +#define OBJ_subject_alt_name OBJ_id_ce,17L + +#define SN_issuer_alt_name "issuerAltName" +#define LN_issuer_alt_name "X509v3 Issuer Alternative Name" +#define NID_issuer_alt_name 86 +#define OBJ_issuer_alt_name OBJ_id_ce,18L + +#define SN_basic_constraints "basicConstraints" +#define LN_basic_constraints "X509v3 Basic Constraints" +#define NID_basic_constraints 87 +#define OBJ_basic_constraints OBJ_id_ce,19L + +#define SN_crl_number "crlNumber" +#define LN_crl_number "X509v3 CRL Number" +#define NID_crl_number 88 +#define OBJ_crl_number OBJ_id_ce,20L + +#define SN_crl_reason "CRLReason" +#define LN_crl_reason "X509v3 CRL Reason Code" +#define NID_crl_reason 141 +#define OBJ_crl_reason OBJ_id_ce,21L + +#define SN_invalidity_date "invalidityDate" +#define LN_invalidity_date "Invalidity Date" +#define NID_invalidity_date 142 +#define OBJ_invalidity_date OBJ_id_ce,24L + +#define SN_delta_crl "deltaCRL" +#define LN_delta_crl "X509v3 Delta CRL Indicator" +#define NID_delta_crl 140 +#define OBJ_delta_crl OBJ_id_ce,27L + +#define SN_issuing_distribution_point "issuingDistributionPoint" +#define LN_issuing_distribution_point "X509v3 Issuing Distribution Point" +#define NID_issuing_distribution_point 770 +#define OBJ_issuing_distribution_point OBJ_id_ce,28L + +#define SN_certificate_issuer "certificateIssuer" +#define LN_certificate_issuer "X509v3 Certificate Issuer" +#define NID_certificate_issuer 771 +#define OBJ_certificate_issuer OBJ_id_ce,29L + +#define SN_name_constraints "nameConstraints" +#define LN_name_constraints "X509v3 Name Constraints" +#define NID_name_constraints 666 +#define OBJ_name_constraints OBJ_id_ce,30L + +#define SN_crl_distribution_points "crlDistributionPoints" +#define LN_crl_distribution_points "X509v3 CRL Distribution Points" +#define NID_crl_distribution_points 103 +#define OBJ_crl_distribution_points OBJ_id_ce,31L + +#define SN_certificate_policies "certificatePolicies" +#define LN_certificate_policies "X509v3 Certificate Policies" +#define NID_certificate_policies 89 +#define OBJ_certificate_policies OBJ_id_ce,32L + +#define SN_any_policy "anyPolicy" +#define LN_any_policy "X509v3 Any Policy" +#define NID_any_policy 746 +#define OBJ_any_policy OBJ_certificate_policies,0L + +#define SN_policy_mappings "policyMappings" +#define LN_policy_mappings "X509v3 Policy Mappings" +#define NID_policy_mappings 747 +#define OBJ_policy_mappings OBJ_id_ce,33L + +#define SN_authority_key_identifier "authorityKeyIdentifier" +#define LN_authority_key_identifier "X509v3 Authority Key Identifier" +#define NID_authority_key_identifier 90 +#define OBJ_authority_key_identifier OBJ_id_ce,35L + +#define SN_policy_constraints "policyConstraints" +#define LN_policy_constraints "X509v3 Policy Constraints" +#define NID_policy_constraints 401 +#define OBJ_policy_constraints OBJ_id_ce,36L + +#define SN_ext_key_usage "extendedKeyUsage" +#define LN_ext_key_usage "X509v3 Extended Key Usage" +#define NID_ext_key_usage 126 +#define OBJ_ext_key_usage OBJ_id_ce,37L + +#define SN_freshest_crl "freshestCRL" +#define LN_freshest_crl "X509v3 Freshest CRL" +#define NID_freshest_crl 857 +#define OBJ_freshest_crl OBJ_id_ce,46L + +#define SN_inhibit_any_policy "inhibitAnyPolicy" +#define LN_inhibit_any_policy "X509v3 Inhibit Any Policy" +#define NID_inhibit_any_policy 748 +#define OBJ_inhibit_any_policy OBJ_id_ce,54L + +#define SN_target_information "targetInformation" +#define LN_target_information "X509v3 AC Targeting" +#define NID_target_information 402 +#define OBJ_target_information OBJ_id_ce,55L + +#define SN_no_rev_avail "noRevAvail" +#define LN_no_rev_avail "X509v3 No Revocation Available" +#define NID_no_rev_avail 403 +#define OBJ_no_rev_avail OBJ_id_ce,56L + +#define SN_anyExtendedKeyUsage "anyExtendedKeyUsage" +#define LN_anyExtendedKeyUsage "Any Extended Key Usage" +#define NID_anyExtendedKeyUsage 910 +#define OBJ_anyExtendedKeyUsage OBJ_ext_key_usage,0L + +#define SN_netscape "Netscape" +#define LN_netscape "Netscape Communications Corp." +#define NID_netscape 57 +#define OBJ_netscape 2L,16L,840L,1L,113730L + +#define SN_netscape_cert_extension "nsCertExt" +#define LN_netscape_cert_extension "Netscape Certificate Extension" +#define NID_netscape_cert_extension 58 +#define OBJ_netscape_cert_extension OBJ_netscape,1L + +#define SN_netscape_data_type "nsDataType" +#define LN_netscape_data_type "Netscape Data Type" +#define NID_netscape_data_type 59 +#define OBJ_netscape_data_type OBJ_netscape,2L + +#define SN_netscape_cert_type "nsCertType" +#define LN_netscape_cert_type "Netscape Cert Type" +#define NID_netscape_cert_type 71 +#define OBJ_netscape_cert_type OBJ_netscape_cert_extension,1L + +#define SN_netscape_base_url "nsBaseUrl" +#define LN_netscape_base_url "Netscape Base Url" +#define NID_netscape_base_url 72 +#define OBJ_netscape_base_url OBJ_netscape_cert_extension,2L + +#define SN_netscape_revocation_url "nsRevocationUrl" +#define LN_netscape_revocation_url "Netscape Revocation Url" +#define NID_netscape_revocation_url 73 +#define OBJ_netscape_revocation_url OBJ_netscape_cert_extension,3L + +#define SN_netscape_ca_revocation_url "nsCaRevocationUrl" +#define LN_netscape_ca_revocation_url "Netscape CA Revocation Url" +#define NID_netscape_ca_revocation_url 74 +#define OBJ_netscape_ca_revocation_url OBJ_netscape_cert_extension,4L + +#define SN_netscape_renewal_url "nsRenewalUrl" +#define LN_netscape_renewal_url "Netscape Renewal Url" +#define NID_netscape_renewal_url 75 +#define OBJ_netscape_renewal_url OBJ_netscape_cert_extension,7L + +#define SN_netscape_ca_policy_url "nsCaPolicyUrl" +#define LN_netscape_ca_policy_url "Netscape CA Policy Url" +#define NID_netscape_ca_policy_url 76 +#define OBJ_netscape_ca_policy_url OBJ_netscape_cert_extension,8L + +#define SN_netscape_ssl_server_name "nsSslServerName" +#define LN_netscape_ssl_server_name "Netscape SSL Server Name" +#define NID_netscape_ssl_server_name 77 +#define OBJ_netscape_ssl_server_name OBJ_netscape_cert_extension,12L + +#define SN_netscape_comment "nsComment" +#define LN_netscape_comment "Netscape Comment" +#define NID_netscape_comment 78 +#define OBJ_netscape_comment OBJ_netscape_cert_extension,13L + +#define SN_netscape_cert_sequence "nsCertSequence" +#define LN_netscape_cert_sequence "Netscape Certificate Sequence" +#define NID_netscape_cert_sequence 79 +#define OBJ_netscape_cert_sequence OBJ_netscape_data_type,5L + +#define SN_ns_sgc "nsSGC" +#define LN_ns_sgc "Netscape Server Gated Crypto" +#define NID_ns_sgc 139 +#define OBJ_ns_sgc OBJ_netscape,4L,1L + +#define SN_org "ORG" +#define LN_org "org" +#define NID_org 379 +#define OBJ_org OBJ_iso,3L + +#define SN_dod "DOD" +#define LN_dod "dod" +#define NID_dod 380 +#define OBJ_dod OBJ_org,6L + +#define SN_iana "IANA" +#define LN_iana "iana" +#define NID_iana 381 +#define OBJ_iana OBJ_dod,1L + +#define OBJ_internet OBJ_iana + +#define SN_Directory "directory" +#define LN_Directory "Directory" +#define NID_Directory 382 +#define OBJ_Directory OBJ_internet,1L + +#define SN_Management "mgmt" +#define LN_Management "Management" +#define NID_Management 383 +#define OBJ_Management OBJ_internet,2L + +#define SN_Experimental "experimental" +#define LN_Experimental "Experimental" +#define NID_Experimental 384 +#define OBJ_Experimental OBJ_internet,3L + +#define SN_Private "private" +#define LN_Private "Private" +#define NID_Private 385 +#define OBJ_Private OBJ_internet,4L + +#define SN_Security "security" +#define LN_Security "Security" +#define NID_Security 386 +#define OBJ_Security OBJ_internet,5L + +#define SN_SNMPv2 "snmpv2" +#define LN_SNMPv2 "SNMPv2" +#define NID_SNMPv2 387 +#define OBJ_SNMPv2 OBJ_internet,6L + +#define LN_Mail "Mail" +#define NID_Mail 388 +#define OBJ_Mail OBJ_internet,7L + +#define SN_Enterprises "enterprises" +#define LN_Enterprises "Enterprises" +#define NID_Enterprises 389 +#define OBJ_Enterprises OBJ_Private,1L + +#define SN_dcObject "dcobject" +#define LN_dcObject "dcObject" +#define NID_dcObject 390 +#define OBJ_dcObject OBJ_Enterprises,1466L,344L + +#define SN_mime_mhs "mime-mhs" +#define LN_mime_mhs "MIME MHS" +#define NID_mime_mhs 504 +#define OBJ_mime_mhs OBJ_Mail,1L + +#define SN_mime_mhs_headings "mime-mhs-headings" +#define LN_mime_mhs_headings "mime-mhs-headings" +#define NID_mime_mhs_headings 505 +#define OBJ_mime_mhs_headings OBJ_mime_mhs,1L + +#define SN_mime_mhs_bodies "mime-mhs-bodies" +#define LN_mime_mhs_bodies "mime-mhs-bodies" +#define NID_mime_mhs_bodies 506 +#define OBJ_mime_mhs_bodies OBJ_mime_mhs,2L + +#define SN_id_hex_partial_message "id-hex-partial-message" +#define LN_id_hex_partial_message "id-hex-partial-message" +#define NID_id_hex_partial_message 507 +#define OBJ_id_hex_partial_message OBJ_mime_mhs_headings,1L + +#define SN_id_hex_multipart_message "id-hex-multipart-message" +#define LN_id_hex_multipart_message "id-hex-multipart-message" +#define NID_id_hex_multipart_message 508 +#define OBJ_id_hex_multipart_message OBJ_mime_mhs_headings,2L + +#define SN_zlib_compression "ZLIB" +#define LN_zlib_compression "zlib compression" +#define NID_zlib_compression 125 +#define OBJ_zlib_compression OBJ_id_smime_alg,8L + +#define OBJ_csor 2L,16L,840L,1L,101L,3L + +#define OBJ_nistAlgorithms OBJ_csor,4L + +#define OBJ_aes OBJ_nistAlgorithms,1L + +#define SN_aes_128_ecb "AES-128-ECB" +#define LN_aes_128_ecb "aes-128-ecb" +#define NID_aes_128_ecb 418 +#define OBJ_aes_128_ecb OBJ_aes,1L + +#define SN_aes_128_cbc "AES-128-CBC" +#define LN_aes_128_cbc "aes-128-cbc" +#define NID_aes_128_cbc 419 +#define OBJ_aes_128_cbc OBJ_aes,2L + +#define SN_aes_128_ofb128 "AES-128-OFB" +#define LN_aes_128_ofb128 "aes-128-ofb" +#define NID_aes_128_ofb128 420 +#define OBJ_aes_128_ofb128 OBJ_aes,3L + +#define SN_aes_128_cfb128 "AES-128-CFB" +#define LN_aes_128_cfb128 "aes-128-cfb" +#define NID_aes_128_cfb128 421 +#define OBJ_aes_128_cfb128 OBJ_aes,4L + +#define SN_id_aes128_wrap "id-aes128-wrap" +#define NID_id_aes128_wrap 788 +#define OBJ_id_aes128_wrap OBJ_aes,5L + +#define SN_aes_128_gcm "id-aes128-GCM" +#define LN_aes_128_gcm "aes-128-gcm" +#define NID_aes_128_gcm 895 +#define OBJ_aes_128_gcm OBJ_aes,6L + +#define SN_aes_128_ccm "id-aes128-CCM" +#define LN_aes_128_ccm "aes-128-ccm" +#define NID_aes_128_ccm 896 +#define OBJ_aes_128_ccm OBJ_aes,7L + +#define SN_id_aes128_wrap_pad "id-aes128-wrap-pad" +#define NID_id_aes128_wrap_pad 897 +#define OBJ_id_aes128_wrap_pad OBJ_aes,8L + +#define SN_aes_192_ecb "AES-192-ECB" +#define LN_aes_192_ecb "aes-192-ecb" +#define NID_aes_192_ecb 422 +#define OBJ_aes_192_ecb OBJ_aes,21L + +#define SN_aes_192_cbc "AES-192-CBC" +#define LN_aes_192_cbc "aes-192-cbc" +#define NID_aes_192_cbc 423 +#define OBJ_aes_192_cbc OBJ_aes,22L + +#define SN_aes_192_ofb128 "AES-192-OFB" +#define LN_aes_192_ofb128 "aes-192-ofb" +#define NID_aes_192_ofb128 424 +#define OBJ_aes_192_ofb128 OBJ_aes,23L + +#define SN_aes_192_cfb128 "AES-192-CFB" +#define LN_aes_192_cfb128 "aes-192-cfb" +#define NID_aes_192_cfb128 425 +#define OBJ_aes_192_cfb128 OBJ_aes,24L + +#define SN_id_aes192_wrap "id-aes192-wrap" +#define NID_id_aes192_wrap 789 +#define OBJ_id_aes192_wrap OBJ_aes,25L + +#define SN_aes_192_gcm "id-aes192-GCM" +#define LN_aes_192_gcm "aes-192-gcm" +#define NID_aes_192_gcm 898 +#define OBJ_aes_192_gcm OBJ_aes,26L + +#define SN_aes_192_ccm "id-aes192-CCM" +#define LN_aes_192_ccm "aes-192-ccm" +#define NID_aes_192_ccm 899 +#define OBJ_aes_192_ccm OBJ_aes,27L + +#define SN_id_aes192_wrap_pad "id-aes192-wrap-pad" +#define NID_id_aes192_wrap_pad 900 +#define OBJ_id_aes192_wrap_pad OBJ_aes,28L + +#define SN_aes_256_ecb "AES-256-ECB" +#define LN_aes_256_ecb "aes-256-ecb" +#define NID_aes_256_ecb 426 +#define OBJ_aes_256_ecb OBJ_aes,41L + +#define SN_aes_256_cbc "AES-256-CBC" +#define LN_aes_256_cbc "aes-256-cbc" +#define NID_aes_256_cbc 427 +#define OBJ_aes_256_cbc OBJ_aes,42L + +#define SN_aes_256_ofb128 "AES-256-OFB" +#define LN_aes_256_ofb128 "aes-256-ofb" +#define NID_aes_256_ofb128 428 +#define OBJ_aes_256_ofb128 OBJ_aes,43L + +#define SN_aes_256_cfb128 "AES-256-CFB" +#define LN_aes_256_cfb128 "aes-256-cfb" +#define NID_aes_256_cfb128 429 +#define OBJ_aes_256_cfb128 OBJ_aes,44L + +#define SN_id_aes256_wrap "id-aes256-wrap" +#define NID_id_aes256_wrap 790 +#define OBJ_id_aes256_wrap OBJ_aes,45L + +#define SN_aes_256_gcm "id-aes256-GCM" +#define LN_aes_256_gcm "aes-256-gcm" +#define NID_aes_256_gcm 901 +#define OBJ_aes_256_gcm OBJ_aes,46L + +#define SN_aes_256_ccm "id-aes256-CCM" +#define LN_aes_256_ccm "aes-256-ccm" +#define NID_aes_256_ccm 902 +#define OBJ_aes_256_ccm OBJ_aes,47L + +#define SN_id_aes256_wrap_pad "id-aes256-wrap-pad" +#define NID_id_aes256_wrap_pad 903 +#define OBJ_id_aes256_wrap_pad OBJ_aes,48L + +#define SN_aes_128_cfb1 "AES-128-CFB1" +#define LN_aes_128_cfb1 "aes-128-cfb1" +#define NID_aes_128_cfb1 650 + +#define SN_aes_192_cfb1 "AES-192-CFB1" +#define LN_aes_192_cfb1 "aes-192-cfb1" +#define NID_aes_192_cfb1 651 + +#define SN_aes_256_cfb1 "AES-256-CFB1" +#define LN_aes_256_cfb1 "aes-256-cfb1" +#define NID_aes_256_cfb1 652 + +#define SN_aes_128_cfb8 "AES-128-CFB8" +#define LN_aes_128_cfb8 "aes-128-cfb8" +#define NID_aes_128_cfb8 653 + +#define SN_aes_192_cfb8 "AES-192-CFB8" +#define LN_aes_192_cfb8 "aes-192-cfb8" +#define NID_aes_192_cfb8 654 + +#define SN_aes_256_cfb8 "AES-256-CFB8" +#define LN_aes_256_cfb8 "aes-256-cfb8" +#define NID_aes_256_cfb8 655 + +#define SN_aes_128_ctr "AES-128-CTR" +#define LN_aes_128_ctr "aes-128-ctr" +#define NID_aes_128_ctr 904 + +#define SN_aes_192_ctr "AES-192-CTR" +#define LN_aes_192_ctr "aes-192-ctr" +#define NID_aes_192_ctr 905 + +#define SN_aes_256_ctr "AES-256-CTR" +#define LN_aes_256_ctr "aes-256-ctr" +#define NID_aes_256_ctr 906 + +#define SN_aes_128_xts "AES-128-XTS" +#define LN_aes_128_xts "aes-128-xts" +#define NID_aes_128_xts 913 + +#define SN_aes_256_xts "AES-256-XTS" +#define LN_aes_256_xts "aes-256-xts" +#define NID_aes_256_xts 914 + +#define SN_des_cfb1 "DES-CFB1" +#define LN_des_cfb1 "des-cfb1" +#define NID_des_cfb1 656 + +#define SN_des_cfb8 "DES-CFB8" +#define LN_des_cfb8 "des-cfb8" +#define NID_des_cfb8 657 + +#define SN_des_ede3_cfb1 "DES-EDE3-CFB1" +#define LN_des_ede3_cfb1 "des-ede3-cfb1" +#define NID_des_ede3_cfb1 658 + +#define SN_des_ede3_cfb8 "DES-EDE3-CFB8" +#define LN_des_ede3_cfb8 "des-ede3-cfb8" +#define NID_des_ede3_cfb8 659 + +#define OBJ_nist_hashalgs OBJ_nistAlgorithms,2L + +#define SN_sha256 "SHA256" +#define LN_sha256 "sha256" +#define NID_sha256 672 +#define OBJ_sha256 OBJ_nist_hashalgs,1L + +#define SN_sha384 "SHA384" +#define LN_sha384 "sha384" +#define NID_sha384 673 +#define OBJ_sha384 OBJ_nist_hashalgs,2L + +#define SN_sha512 "SHA512" +#define LN_sha512 "sha512" +#define NID_sha512 674 +#define OBJ_sha512 OBJ_nist_hashalgs,3L + +#define SN_sha224 "SHA224" +#define LN_sha224 "sha224" +#define NID_sha224 675 +#define OBJ_sha224 OBJ_nist_hashalgs,4L + +#define OBJ_dsa_with_sha2 OBJ_nistAlgorithms,3L + +#define SN_dsa_with_SHA224 "dsa_with_SHA224" +#define NID_dsa_with_SHA224 802 +#define OBJ_dsa_with_SHA224 OBJ_dsa_with_sha2,1L + +#define SN_dsa_with_SHA256 "dsa_with_SHA256" +#define NID_dsa_with_SHA256 803 +#define OBJ_dsa_with_SHA256 OBJ_dsa_with_sha2,2L + +#define SN_hold_instruction_code "holdInstructionCode" +#define LN_hold_instruction_code "Hold Instruction Code" +#define NID_hold_instruction_code 430 +#define OBJ_hold_instruction_code OBJ_id_ce,23L + +#define OBJ_holdInstruction OBJ_X9_57,2L + +#define SN_hold_instruction_none "holdInstructionNone" +#define LN_hold_instruction_none "Hold Instruction None" +#define NID_hold_instruction_none 431 +#define OBJ_hold_instruction_none OBJ_holdInstruction,1L + +#define SN_hold_instruction_call_issuer "holdInstructionCallIssuer" +#define LN_hold_instruction_call_issuer "Hold Instruction Call Issuer" +#define NID_hold_instruction_call_issuer 432 +#define OBJ_hold_instruction_call_issuer OBJ_holdInstruction,2L + +#define SN_hold_instruction_reject "holdInstructionReject" +#define LN_hold_instruction_reject "Hold Instruction Reject" +#define NID_hold_instruction_reject 433 +#define OBJ_hold_instruction_reject OBJ_holdInstruction,3L + +#define SN_data "data" +#define NID_data 434 +#define OBJ_data OBJ_itu_t,9L + +#define SN_pss "pss" +#define NID_pss 435 +#define OBJ_pss OBJ_data,2342L + +#define SN_ucl "ucl" +#define NID_ucl 436 +#define OBJ_ucl OBJ_pss,19200300L + +#define SN_pilot "pilot" +#define NID_pilot 437 +#define OBJ_pilot OBJ_ucl,100L + +#define LN_pilotAttributeType "pilotAttributeType" +#define NID_pilotAttributeType 438 +#define OBJ_pilotAttributeType OBJ_pilot,1L + +#define LN_pilotAttributeSyntax "pilotAttributeSyntax" +#define NID_pilotAttributeSyntax 439 +#define OBJ_pilotAttributeSyntax OBJ_pilot,3L + +#define LN_pilotObjectClass "pilotObjectClass" +#define NID_pilotObjectClass 440 +#define OBJ_pilotObjectClass OBJ_pilot,4L + +#define LN_pilotGroups "pilotGroups" +#define NID_pilotGroups 441 +#define OBJ_pilotGroups OBJ_pilot,10L + +#define LN_iA5StringSyntax "iA5StringSyntax" +#define NID_iA5StringSyntax 442 +#define OBJ_iA5StringSyntax OBJ_pilotAttributeSyntax,4L + +#define LN_caseIgnoreIA5StringSyntax "caseIgnoreIA5StringSyntax" +#define NID_caseIgnoreIA5StringSyntax 443 +#define OBJ_caseIgnoreIA5StringSyntax OBJ_pilotAttributeSyntax,5L + +#define LN_pilotObject "pilotObject" +#define NID_pilotObject 444 +#define OBJ_pilotObject OBJ_pilotObjectClass,3L + +#define LN_pilotPerson "pilotPerson" +#define NID_pilotPerson 445 +#define OBJ_pilotPerson OBJ_pilotObjectClass,4L + +#define SN_account "account" +#define NID_account 446 +#define OBJ_account OBJ_pilotObjectClass,5L + +#define SN_document "document" +#define NID_document 447 +#define OBJ_document OBJ_pilotObjectClass,6L + +#define SN_room "room" +#define NID_room 448 +#define OBJ_room OBJ_pilotObjectClass,7L + +#define LN_documentSeries "documentSeries" +#define NID_documentSeries 449 +#define OBJ_documentSeries OBJ_pilotObjectClass,9L + +#define SN_Domain "domain" +#define LN_Domain "Domain" +#define NID_Domain 392 +#define OBJ_Domain OBJ_pilotObjectClass,13L + +#define LN_rFC822localPart "rFC822localPart" +#define NID_rFC822localPart 450 +#define OBJ_rFC822localPart OBJ_pilotObjectClass,14L + +#define LN_dNSDomain "dNSDomain" +#define NID_dNSDomain 451 +#define OBJ_dNSDomain OBJ_pilotObjectClass,15L + +#define LN_domainRelatedObject "domainRelatedObject" +#define NID_domainRelatedObject 452 +#define OBJ_domainRelatedObject OBJ_pilotObjectClass,17L + +#define LN_friendlyCountry "friendlyCountry" +#define NID_friendlyCountry 453 +#define OBJ_friendlyCountry OBJ_pilotObjectClass,18L + +#define LN_simpleSecurityObject "simpleSecurityObject" +#define NID_simpleSecurityObject 454 +#define OBJ_simpleSecurityObject OBJ_pilotObjectClass,19L + +#define LN_pilotOrganization "pilotOrganization" +#define NID_pilotOrganization 455 +#define OBJ_pilotOrganization OBJ_pilotObjectClass,20L + +#define LN_pilotDSA "pilotDSA" +#define NID_pilotDSA 456 +#define OBJ_pilotDSA OBJ_pilotObjectClass,21L + +#define LN_qualityLabelledData "qualityLabelledData" +#define NID_qualityLabelledData 457 +#define OBJ_qualityLabelledData OBJ_pilotObjectClass,22L + +#define SN_userId "UID" +#define LN_userId "userId" +#define NID_userId 458 +#define OBJ_userId OBJ_pilotAttributeType,1L + +#define LN_textEncodedORAddress "textEncodedORAddress" +#define NID_textEncodedORAddress 459 +#define OBJ_textEncodedORAddress OBJ_pilotAttributeType,2L + +#define SN_rfc822Mailbox "mail" +#define LN_rfc822Mailbox "rfc822Mailbox" +#define NID_rfc822Mailbox 460 +#define OBJ_rfc822Mailbox OBJ_pilotAttributeType,3L + +#define SN_info "info" +#define NID_info 461 +#define OBJ_info OBJ_pilotAttributeType,4L + +#define LN_favouriteDrink "favouriteDrink" +#define NID_favouriteDrink 462 +#define OBJ_favouriteDrink OBJ_pilotAttributeType,5L + +#define LN_roomNumber "roomNumber" +#define NID_roomNumber 463 +#define OBJ_roomNumber OBJ_pilotAttributeType,6L + +#define SN_photo "photo" +#define NID_photo 464 +#define OBJ_photo OBJ_pilotAttributeType,7L + +#define LN_userClass "userClass" +#define NID_userClass 465 +#define OBJ_userClass OBJ_pilotAttributeType,8L + +#define SN_host "host" +#define NID_host 466 +#define OBJ_host OBJ_pilotAttributeType,9L + +#define SN_manager "manager" +#define NID_manager 467 +#define OBJ_manager OBJ_pilotAttributeType,10L + +#define LN_documentIdentifier "documentIdentifier" +#define NID_documentIdentifier 468 +#define OBJ_documentIdentifier OBJ_pilotAttributeType,11L + +#define LN_documentTitle "documentTitle" +#define NID_documentTitle 469 +#define OBJ_documentTitle OBJ_pilotAttributeType,12L + +#define LN_documentVersion "documentVersion" +#define NID_documentVersion 470 +#define OBJ_documentVersion OBJ_pilotAttributeType,13L + +#define LN_documentAuthor "documentAuthor" +#define NID_documentAuthor 471 +#define OBJ_documentAuthor OBJ_pilotAttributeType,14L + +#define LN_documentLocation "documentLocation" +#define NID_documentLocation 472 +#define OBJ_documentLocation OBJ_pilotAttributeType,15L + +#define LN_homeTelephoneNumber "homeTelephoneNumber" +#define NID_homeTelephoneNumber 473 +#define OBJ_homeTelephoneNumber OBJ_pilotAttributeType,20L + +#define SN_secretary "secretary" +#define NID_secretary 474 +#define OBJ_secretary OBJ_pilotAttributeType,21L + +#define LN_otherMailbox "otherMailbox" +#define NID_otherMailbox 475 +#define OBJ_otherMailbox OBJ_pilotAttributeType,22L + +#define LN_lastModifiedTime "lastModifiedTime" +#define NID_lastModifiedTime 476 +#define OBJ_lastModifiedTime OBJ_pilotAttributeType,23L + +#define LN_lastModifiedBy "lastModifiedBy" +#define NID_lastModifiedBy 477 +#define OBJ_lastModifiedBy OBJ_pilotAttributeType,24L + +#define SN_domainComponent "DC" +#define LN_domainComponent "domainComponent" +#define NID_domainComponent 391 +#define OBJ_domainComponent OBJ_pilotAttributeType,25L + +#define LN_aRecord "aRecord" +#define NID_aRecord 478 +#define OBJ_aRecord OBJ_pilotAttributeType,26L + +#define LN_pilotAttributeType27 "pilotAttributeType27" +#define NID_pilotAttributeType27 479 +#define OBJ_pilotAttributeType27 OBJ_pilotAttributeType,27L + +#define LN_mXRecord "mXRecord" +#define NID_mXRecord 480 +#define OBJ_mXRecord OBJ_pilotAttributeType,28L + +#define LN_nSRecord "nSRecord" +#define NID_nSRecord 481 +#define OBJ_nSRecord OBJ_pilotAttributeType,29L + +#define LN_sOARecord "sOARecord" +#define NID_sOARecord 482 +#define OBJ_sOARecord OBJ_pilotAttributeType,30L + +#define LN_cNAMERecord "cNAMERecord" +#define NID_cNAMERecord 483 +#define OBJ_cNAMERecord OBJ_pilotAttributeType,31L + +#define LN_associatedDomain "associatedDomain" +#define NID_associatedDomain 484 +#define OBJ_associatedDomain OBJ_pilotAttributeType,37L + +#define LN_associatedName "associatedName" +#define NID_associatedName 485 +#define OBJ_associatedName OBJ_pilotAttributeType,38L + +#define LN_homePostalAddress "homePostalAddress" +#define NID_homePostalAddress 486 +#define OBJ_homePostalAddress OBJ_pilotAttributeType,39L + +#define LN_personalTitle "personalTitle" +#define NID_personalTitle 487 +#define OBJ_personalTitle OBJ_pilotAttributeType,40L + +#define LN_mobileTelephoneNumber "mobileTelephoneNumber" +#define NID_mobileTelephoneNumber 488 +#define OBJ_mobileTelephoneNumber OBJ_pilotAttributeType,41L + +#define LN_pagerTelephoneNumber "pagerTelephoneNumber" +#define NID_pagerTelephoneNumber 489 +#define OBJ_pagerTelephoneNumber OBJ_pilotAttributeType,42L + +#define LN_friendlyCountryName "friendlyCountryName" +#define NID_friendlyCountryName 490 +#define OBJ_friendlyCountryName OBJ_pilotAttributeType,43L + +#define LN_organizationalStatus "organizationalStatus" +#define NID_organizationalStatus 491 +#define OBJ_organizationalStatus OBJ_pilotAttributeType,45L + +#define LN_janetMailbox "janetMailbox" +#define NID_janetMailbox 492 +#define OBJ_janetMailbox OBJ_pilotAttributeType,46L + +#define LN_mailPreferenceOption "mailPreferenceOption" +#define NID_mailPreferenceOption 493 +#define OBJ_mailPreferenceOption OBJ_pilotAttributeType,47L + +#define LN_buildingName "buildingName" +#define NID_buildingName 494 +#define OBJ_buildingName OBJ_pilotAttributeType,48L + +#define LN_dSAQuality "dSAQuality" +#define NID_dSAQuality 495 +#define OBJ_dSAQuality OBJ_pilotAttributeType,49L + +#define LN_singleLevelQuality "singleLevelQuality" +#define NID_singleLevelQuality 496 +#define OBJ_singleLevelQuality OBJ_pilotAttributeType,50L + +#define LN_subtreeMinimumQuality "subtreeMinimumQuality" +#define NID_subtreeMinimumQuality 497 +#define OBJ_subtreeMinimumQuality OBJ_pilotAttributeType,51L + +#define LN_subtreeMaximumQuality "subtreeMaximumQuality" +#define NID_subtreeMaximumQuality 498 +#define OBJ_subtreeMaximumQuality OBJ_pilotAttributeType,52L + +#define LN_personalSignature "personalSignature" +#define NID_personalSignature 499 +#define OBJ_personalSignature OBJ_pilotAttributeType,53L + +#define LN_dITRedirect "dITRedirect" +#define NID_dITRedirect 500 +#define OBJ_dITRedirect OBJ_pilotAttributeType,54L + +#define SN_audio "audio" +#define NID_audio 501 +#define OBJ_audio OBJ_pilotAttributeType,55L + +#define LN_documentPublisher "documentPublisher" +#define NID_documentPublisher 502 +#define OBJ_documentPublisher OBJ_pilotAttributeType,56L + +#define SN_id_set "id-set" +#define LN_id_set "Secure Electronic Transactions" +#define NID_id_set 512 +#define OBJ_id_set OBJ_international_organizations,42L + +#define SN_set_ctype "set-ctype" +#define LN_set_ctype "content types" +#define NID_set_ctype 513 +#define OBJ_set_ctype OBJ_id_set,0L + +#define SN_set_msgExt "set-msgExt" +#define LN_set_msgExt "message extensions" +#define NID_set_msgExt 514 +#define OBJ_set_msgExt OBJ_id_set,1L + +#define SN_set_attr "set-attr" +#define NID_set_attr 515 +#define OBJ_set_attr OBJ_id_set,3L + +#define SN_set_policy "set-policy" +#define NID_set_policy 516 +#define OBJ_set_policy OBJ_id_set,5L + +#define SN_set_certExt "set-certExt" +#define LN_set_certExt "certificate extensions" +#define NID_set_certExt 517 +#define OBJ_set_certExt OBJ_id_set,7L + +#define SN_set_brand "set-brand" +#define NID_set_brand 518 +#define OBJ_set_brand OBJ_id_set,8L + +#define SN_setct_PANData "setct-PANData" +#define NID_setct_PANData 519 +#define OBJ_setct_PANData OBJ_set_ctype,0L + +#define SN_setct_PANToken "setct-PANToken" +#define NID_setct_PANToken 520 +#define OBJ_setct_PANToken OBJ_set_ctype,1L + +#define SN_setct_PANOnly "setct-PANOnly" +#define NID_setct_PANOnly 521 +#define OBJ_setct_PANOnly OBJ_set_ctype,2L + +#define SN_setct_OIData "setct-OIData" +#define NID_setct_OIData 522 +#define OBJ_setct_OIData OBJ_set_ctype,3L + +#define SN_setct_PI "setct-PI" +#define NID_setct_PI 523 +#define OBJ_setct_PI OBJ_set_ctype,4L + +#define SN_setct_PIData "setct-PIData" +#define NID_setct_PIData 524 +#define OBJ_setct_PIData OBJ_set_ctype,5L + +#define SN_setct_PIDataUnsigned "setct-PIDataUnsigned" +#define NID_setct_PIDataUnsigned 525 +#define OBJ_setct_PIDataUnsigned OBJ_set_ctype,6L + +#define SN_setct_HODInput "setct-HODInput" +#define NID_setct_HODInput 526 +#define OBJ_setct_HODInput OBJ_set_ctype,7L + +#define SN_setct_AuthResBaggage "setct-AuthResBaggage" +#define NID_setct_AuthResBaggage 527 +#define OBJ_setct_AuthResBaggage OBJ_set_ctype,8L + +#define SN_setct_AuthRevReqBaggage "setct-AuthRevReqBaggage" +#define NID_setct_AuthRevReqBaggage 528 +#define OBJ_setct_AuthRevReqBaggage OBJ_set_ctype,9L + +#define SN_setct_AuthRevResBaggage "setct-AuthRevResBaggage" +#define NID_setct_AuthRevResBaggage 529 +#define OBJ_setct_AuthRevResBaggage OBJ_set_ctype,10L + +#define SN_setct_CapTokenSeq "setct-CapTokenSeq" +#define NID_setct_CapTokenSeq 530 +#define OBJ_setct_CapTokenSeq OBJ_set_ctype,11L + +#define SN_setct_PInitResData "setct-PInitResData" +#define NID_setct_PInitResData 531 +#define OBJ_setct_PInitResData OBJ_set_ctype,12L + +#define SN_setct_PI_TBS "setct-PI-TBS" +#define NID_setct_PI_TBS 532 +#define OBJ_setct_PI_TBS OBJ_set_ctype,13L + +#define SN_setct_PResData "setct-PResData" +#define NID_setct_PResData 533 +#define OBJ_setct_PResData OBJ_set_ctype,14L + +#define SN_setct_AuthReqTBS "setct-AuthReqTBS" +#define NID_setct_AuthReqTBS 534 +#define OBJ_setct_AuthReqTBS OBJ_set_ctype,16L + +#define SN_setct_AuthResTBS "setct-AuthResTBS" +#define NID_setct_AuthResTBS 535 +#define OBJ_setct_AuthResTBS OBJ_set_ctype,17L + +#define SN_setct_AuthResTBSX "setct-AuthResTBSX" +#define NID_setct_AuthResTBSX 536 +#define OBJ_setct_AuthResTBSX OBJ_set_ctype,18L + +#define SN_setct_AuthTokenTBS "setct-AuthTokenTBS" +#define NID_setct_AuthTokenTBS 537 +#define OBJ_setct_AuthTokenTBS OBJ_set_ctype,19L + +#define SN_setct_CapTokenData "setct-CapTokenData" +#define NID_setct_CapTokenData 538 +#define OBJ_setct_CapTokenData OBJ_set_ctype,20L + +#define SN_setct_CapTokenTBS "setct-CapTokenTBS" +#define NID_setct_CapTokenTBS 539 +#define OBJ_setct_CapTokenTBS OBJ_set_ctype,21L + +#define SN_setct_AcqCardCodeMsg "setct-AcqCardCodeMsg" +#define NID_setct_AcqCardCodeMsg 540 +#define OBJ_setct_AcqCardCodeMsg OBJ_set_ctype,22L + +#define SN_setct_AuthRevReqTBS "setct-AuthRevReqTBS" +#define NID_setct_AuthRevReqTBS 541 +#define OBJ_setct_AuthRevReqTBS OBJ_set_ctype,23L + +#define SN_setct_AuthRevResData "setct-AuthRevResData" +#define NID_setct_AuthRevResData 542 +#define OBJ_setct_AuthRevResData OBJ_set_ctype,24L + +#define SN_setct_AuthRevResTBS "setct-AuthRevResTBS" +#define NID_setct_AuthRevResTBS 543 +#define OBJ_setct_AuthRevResTBS OBJ_set_ctype,25L + +#define SN_setct_CapReqTBS "setct-CapReqTBS" +#define NID_setct_CapReqTBS 544 +#define OBJ_setct_CapReqTBS OBJ_set_ctype,26L + +#define SN_setct_CapReqTBSX "setct-CapReqTBSX" +#define NID_setct_CapReqTBSX 545 +#define OBJ_setct_CapReqTBSX OBJ_set_ctype,27L + +#define SN_setct_CapResData "setct-CapResData" +#define NID_setct_CapResData 546 +#define OBJ_setct_CapResData OBJ_set_ctype,28L + +#define SN_setct_CapRevReqTBS "setct-CapRevReqTBS" +#define NID_setct_CapRevReqTBS 547 +#define OBJ_setct_CapRevReqTBS OBJ_set_ctype,29L + +#define SN_setct_CapRevReqTBSX "setct-CapRevReqTBSX" +#define NID_setct_CapRevReqTBSX 548 +#define OBJ_setct_CapRevReqTBSX OBJ_set_ctype,30L + +#define SN_setct_CapRevResData "setct-CapRevResData" +#define NID_setct_CapRevResData 549 +#define OBJ_setct_CapRevResData OBJ_set_ctype,31L + +#define SN_setct_CredReqTBS "setct-CredReqTBS" +#define NID_setct_CredReqTBS 550 +#define OBJ_setct_CredReqTBS OBJ_set_ctype,32L + +#define SN_setct_CredReqTBSX "setct-CredReqTBSX" +#define NID_setct_CredReqTBSX 551 +#define OBJ_setct_CredReqTBSX OBJ_set_ctype,33L + +#define SN_setct_CredResData "setct-CredResData" +#define NID_setct_CredResData 552 +#define OBJ_setct_CredResData OBJ_set_ctype,34L + +#define SN_setct_CredRevReqTBS "setct-CredRevReqTBS" +#define NID_setct_CredRevReqTBS 553 +#define OBJ_setct_CredRevReqTBS OBJ_set_ctype,35L + +#define SN_setct_CredRevReqTBSX "setct-CredRevReqTBSX" +#define NID_setct_CredRevReqTBSX 554 +#define OBJ_setct_CredRevReqTBSX OBJ_set_ctype,36L + +#define SN_setct_CredRevResData "setct-CredRevResData" +#define NID_setct_CredRevResData 555 +#define OBJ_setct_CredRevResData OBJ_set_ctype,37L + +#define SN_setct_PCertReqData "setct-PCertReqData" +#define NID_setct_PCertReqData 556 +#define OBJ_setct_PCertReqData OBJ_set_ctype,38L + +#define SN_setct_PCertResTBS "setct-PCertResTBS" +#define NID_setct_PCertResTBS 557 +#define OBJ_setct_PCertResTBS OBJ_set_ctype,39L + +#define SN_setct_BatchAdminReqData "setct-BatchAdminReqData" +#define NID_setct_BatchAdminReqData 558 +#define OBJ_setct_BatchAdminReqData OBJ_set_ctype,40L + +#define SN_setct_BatchAdminResData "setct-BatchAdminResData" +#define NID_setct_BatchAdminResData 559 +#define OBJ_setct_BatchAdminResData OBJ_set_ctype,41L + +#define SN_setct_CardCInitResTBS "setct-CardCInitResTBS" +#define NID_setct_CardCInitResTBS 560 +#define OBJ_setct_CardCInitResTBS OBJ_set_ctype,42L + +#define SN_setct_MeAqCInitResTBS "setct-MeAqCInitResTBS" +#define NID_setct_MeAqCInitResTBS 561 +#define OBJ_setct_MeAqCInitResTBS OBJ_set_ctype,43L + +#define SN_setct_RegFormResTBS "setct-RegFormResTBS" +#define NID_setct_RegFormResTBS 562 +#define OBJ_setct_RegFormResTBS OBJ_set_ctype,44L + +#define SN_setct_CertReqData "setct-CertReqData" +#define NID_setct_CertReqData 563 +#define OBJ_setct_CertReqData OBJ_set_ctype,45L + +#define SN_setct_CertReqTBS "setct-CertReqTBS" +#define NID_setct_CertReqTBS 564 +#define OBJ_setct_CertReqTBS OBJ_set_ctype,46L + +#define SN_setct_CertResData "setct-CertResData" +#define NID_setct_CertResData 565 +#define OBJ_setct_CertResData OBJ_set_ctype,47L + +#define SN_setct_CertInqReqTBS "setct-CertInqReqTBS" +#define NID_setct_CertInqReqTBS 566 +#define OBJ_setct_CertInqReqTBS OBJ_set_ctype,48L + +#define SN_setct_ErrorTBS "setct-ErrorTBS" +#define NID_setct_ErrorTBS 567 +#define OBJ_setct_ErrorTBS OBJ_set_ctype,49L + +#define SN_setct_PIDualSignedTBE "setct-PIDualSignedTBE" +#define NID_setct_PIDualSignedTBE 568 +#define OBJ_setct_PIDualSignedTBE OBJ_set_ctype,50L + +#define SN_setct_PIUnsignedTBE "setct-PIUnsignedTBE" +#define NID_setct_PIUnsignedTBE 569 +#define OBJ_setct_PIUnsignedTBE OBJ_set_ctype,51L + +#define SN_setct_AuthReqTBE "setct-AuthReqTBE" +#define NID_setct_AuthReqTBE 570 +#define OBJ_setct_AuthReqTBE OBJ_set_ctype,52L + +#define SN_setct_AuthResTBE "setct-AuthResTBE" +#define NID_setct_AuthResTBE 571 +#define OBJ_setct_AuthResTBE OBJ_set_ctype,53L + +#define SN_setct_AuthResTBEX "setct-AuthResTBEX" +#define NID_setct_AuthResTBEX 572 +#define OBJ_setct_AuthResTBEX OBJ_set_ctype,54L + +#define SN_setct_AuthTokenTBE "setct-AuthTokenTBE" +#define NID_setct_AuthTokenTBE 573 +#define OBJ_setct_AuthTokenTBE OBJ_set_ctype,55L + +#define SN_setct_CapTokenTBE "setct-CapTokenTBE" +#define NID_setct_CapTokenTBE 574 +#define OBJ_setct_CapTokenTBE OBJ_set_ctype,56L + +#define SN_setct_CapTokenTBEX "setct-CapTokenTBEX" +#define NID_setct_CapTokenTBEX 575 +#define OBJ_setct_CapTokenTBEX OBJ_set_ctype,57L + +#define SN_setct_AcqCardCodeMsgTBE "setct-AcqCardCodeMsgTBE" +#define NID_setct_AcqCardCodeMsgTBE 576 +#define OBJ_setct_AcqCardCodeMsgTBE OBJ_set_ctype,58L + +#define SN_setct_AuthRevReqTBE "setct-AuthRevReqTBE" +#define NID_setct_AuthRevReqTBE 577 +#define OBJ_setct_AuthRevReqTBE OBJ_set_ctype,59L + +#define SN_setct_AuthRevResTBE "setct-AuthRevResTBE" +#define NID_setct_AuthRevResTBE 578 +#define OBJ_setct_AuthRevResTBE OBJ_set_ctype,60L + +#define SN_setct_AuthRevResTBEB "setct-AuthRevResTBEB" +#define NID_setct_AuthRevResTBEB 579 +#define OBJ_setct_AuthRevResTBEB OBJ_set_ctype,61L + +#define SN_setct_CapReqTBE "setct-CapReqTBE" +#define NID_setct_CapReqTBE 580 +#define OBJ_setct_CapReqTBE OBJ_set_ctype,62L + +#define SN_setct_CapReqTBEX "setct-CapReqTBEX" +#define NID_setct_CapReqTBEX 581 +#define OBJ_setct_CapReqTBEX OBJ_set_ctype,63L + +#define SN_setct_CapResTBE "setct-CapResTBE" +#define NID_setct_CapResTBE 582 +#define OBJ_setct_CapResTBE OBJ_set_ctype,64L + +#define SN_setct_CapRevReqTBE "setct-CapRevReqTBE" +#define NID_setct_CapRevReqTBE 583 +#define OBJ_setct_CapRevReqTBE OBJ_set_ctype,65L + +#define SN_setct_CapRevReqTBEX "setct-CapRevReqTBEX" +#define NID_setct_CapRevReqTBEX 584 +#define OBJ_setct_CapRevReqTBEX OBJ_set_ctype,66L + +#define SN_setct_CapRevResTBE "setct-CapRevResTBE" +#define NID_setct_CapRevResTBE 585 +#define OBJ_setct_CapRevResTBE OBJ_set_ctype,67L + +#define SN_setct_CredReqTBE "setct-CredReqTBE" +#define NID_setct_CredReqTBE 586 +#define OBJ_setct_CredReqTBE OBJ_set_ctype,68L + +#define SN_setct_CredReqTBEX "setct-CredReqTBEX" +#define NID_setct_CredReqTBEX 587 +#define OBJ_setct_CredReqTBEX OBJ_set_ctype,69L + +#define SN_setct_CredResTBE "setct-CredResTBE" +#define NID_setct_CredResTBE 588 +#define OBJ_setct_CredResTBE OBJ_set_ctype,70L + +#define SN_setct_CredRevReqTBE "setct-CredRevReqTBE" +#define NID_setct_CredRevReqTBE 589 +#define OBJ_setct_CredRevReqTBE OBJ_set_ctype,71L + +#define SN_setct_CredRevReqTBEX "setct-CredRevReqTBEX" +#define NID_setct_CredRevReqTBEX 590 +#define OBJ_setct_CredRevReqTBEX OBJ_set_ctype,72L + +#define SN_setct_CredRevResTBE "setct-CredRevResTBE" +#define NID_setct_CredRevResTBE 591 +#define OBJ_setct_CredRevResTBE OBJ_set_ctype,73L + +#define SN_setct_BatchAdminReqTBE "setct-BatchAdminReqTBE" +#define NID_setct_BatchAdminReqTBE 592 +#define OBJ_setct_BatchAdminReqTBE OBJ_set_ctype,74L + +#define SN_setct_BatchAdminResTBE "setct-BatchAdminResTBE" +#define NID_setct_BatchAdminResTBE 593 +#define OBJ_setct_BatchAdminResTBE OBJ_set_ctype,75L + +#define SN_setct_RegFormReqTBE "setct-RegFormReqTBE" +#define NID_setct_RegFormReqTBE 594 +#define OBJ_setct_RegFormReqTBE OBJ_set_ctype,76L + +#define SN_setct_CertReqTBE "setct-CertReqTBE" +#define NID_setct_CertReqTBE 595 +#define OBJ_setct_CertReqTBE OBJ_set_ctype,77L + +#define SN_setct_CertReqTBEX "setct-CertReqTBEX" +#define NID_setct_CertReqTBEX 596 +#define OBJ_setct_CertReqTBEX OBJ_set_ctype,78L + +#define SN_setct_CertResTBE "setct-CertResTBE" +#define NID_setct_CertResTBE 597 +#define OBJ_setct_CertResTBE OBJ_set_ctype,79L + +#define SN_setct_CRLNotificationTBS "setct-CRLNotificationTBS" +#define NID_setct_CRLNotificationTBS 598 +#define OBJ_setct_CRLNotificationTBS OBJ_set_ctype,80L + +#define SN_setct_CRLNotificationResTBS "setct-CRLNotificationResTBS" +#define NID_setct_CRLNotificationResTBS 599 +#define OBJ_setct_CRLNotificationResTBS OBJ_set_ctype,81L + +#define SN_setct_BCIDistributionTBS "setct-BCIDistributionTBS" +#define NID_setct_BCIDistributionTBS 600 +#define OBJ_setct_BCIDistributionTBS OBJ_set_ctype,82L + +#define SN_setext_genCrypt "setext-genCrypt" +#define LN_setext_genCrypt "generic cryptogram" +#define NID_setext_genCrypt 601 +#define OBJ_setext_genCrypt OBJ_set_msgExt,1L + +#define SN_setext_miAuth "setext-miAuth" +#define LN_setext_miAuth "merchant initiated auth" +#define NID_setext_miAuth 602 +#define OBJ_setext_miAuth OBJ_set_msgExt,3L + +#define SN_setext_pinSecure "setext-pinSecure" +#define NID_setext_pinSecure 603 +#define OBJ_setext_pinSecure OBJ_set_msgExt,4L + +#define SN_setext_pinAny "setext-pinAny" +#define NID_setext_pinAny 604 +#define OBJ_setext_pinAny OBJ_set_msgExt,5L + +#define SN_setext_track2 "setext-track2" +#define NID_setext_track2 605 +#define OBJ_setext_track2 OBJ_set_msgExt,7L + +#define SN_setext_cv "setext-cv" +#define LN_setext_cv "additional verification" +#define NID_setext_cv 606 +#define OBJ_setext_cv OBJ_set_msgExt,8L + +#define SN_set_policy_root "set-policy-root" +#define NID_set_policy_root 607 +#define OBJ_set_policy_root OBJ_set_policy,0L + +#define SN_setCext_hashedRoot "setCext-hashedRoot" +#define NID_setCext_hashedRoot 608 +#define OBJ_setCext_hashedRoot OBJ_set_certExt,0L + +#define SN_setCext_certType "setCext-certType" +#define NID_setCext_certType 609 +#define OBJ_setCext_certType OBJ_set_certExt,1L + +#define SN_setCext_merchData "setCext-merchData" +#define NID_setCext_merchData 610 +#define OBJ_setCext_merchData OBJ_set_certExt,2L + +#define SN_setCext_cCertRequired "setCext-cCertRequired" +#define NID_setCext_cCertRequired 611 +#define OBJ_setCext_cCertRequired OBJ_set_certExt,3L + +#define SN_setCext_tunneling "setCext-tunneling" +#define NID_setCext_tunneling 612 +#define OBJ_setCext_tunneling OBJ_set_certExt,4L + +#define SN_setCext_setExt "setCext-setExt" +#define NID_setCext_setExt 613 +#define OBJ_setCext_setExt OBJ_set_certExt,5L + +#define SN_setCext_setQualf "setCext-setQualf" +#define NID_setCext_setQualf 614 +#define OBJ_setCext_setQualf OBJ_set_certExt,6L + +#define SN_setCext_PGWYcapabilities "setCext-PGWYcapabilities" +#define NID_setCext_PGWYcapabilities 615 +#define OBJ_setCext_PGWYcapabilities OBJ_set_certExt,7L + +#define SN_setCext_TokenIdentifier "setCext-TokenIdentifier" +#define NID_setCext_TokenIdentifier 616 +#define OBJ_setCext_TokenIdentifier OBJ_set_certExt,8L + +#define SN_setCext_Track2Data "setCext-Track2Data" +#define NID_setCext_Track2Data 617 +#define OBJ_setCext_Track2Data OBJ_set_certExt,9L + +#define SN_setCext_TokenType "setCext-TokenType" +#define NID_setCext_TokenType 618 +#define OBJ_setCext_TokenType OBJ_set_certExt,10L + +#define SN_setCext_IssuerCapabilities "setCext-IssuerCapabilities" +#define NID_setCext_IssuerCapabilities 619 +#define OBJ_setCext_IssuerCapabilities OBJ_set_certExt,11L + +#define SN_setAttr_Cert "setAttr-Cert" +#define NID_setAttr_Cert 620 +#define OBJ_setAttr_Cert OBJ_set_attr,0L + +#define SN_setAttr_PGWYcap "setAttr-PGWYcap" +#define LN_setAttr_PGWYcap "payment gateway capabilities" +#define NID_setAttr_PGWYcap 621 +#define OBJ_setAttr_PGWYcap OBJ_set_attr,1L + +#define SN_setAttr_TokenType "setAttr-TokenType" +#define NID_setAttr_TokenType 622 +#define OBJ_setAttr_TokenType OBJ_set_attr,2L + +#define SN_setAttr_IssCap "setAttr-IssCap" +#define LN_setAttr_IssCap "issuer capabilities" +#define NID_setAttr_IssCap 623 +#define OBJ_setAttr_IssCap OBJ_set_attr,3L + +#define SN_set_rootKeyThumb "set-rootKeyThumb" +#define NID_set_rootKeyThumb 624 +#define OBJ_set_rootKeyThumb OBJ_setAttr_Cert,0L + +#define SN_set_addPolicy "set-addPolicy" +#define NID_set_addPolicy 625 +#define OBJ_set_addPolicy OBJ_setAttr_Cert,1L + +#define SN_setAttr_Token_EMV "setAttr-Token-EMV" +#define NID_setAttr_Token_EMV 626 +#define OBJ_setAttr_Token_EMV OBJ_setAttr_TokenType,1L + +#define SN_setAttr_Token_B0Prime "setAttr-Token-B0Prime" +#define NID_setAttr_Token_B0Prime 627 +#define OBJ_setAttr_Token_B0Prime OBJ_setAttr_TokenType,2L + +#define SN_setAttr_IssCap_CVM "setAttr-IssCap-CVM" +#define NID_setAttr_IssCap_CVM 628 +#define OBJ_setAttr_IssCap_CVM OBJ_setAttr_IssCap,3L + +#define SN_setAttr_IssCap_T2 "setAttr-IssCap-T2" +#define NID_setAttr_IssCap_T2 629 +#define OBJ_setAttr_IssCap_T2 OBJ_setAttr_IssCap,4L + +#define SN_setAttr_IssCap_Sig "setAttr-IssCap-Sig" +#define NID_setAttr_IssCap_Sig 630 +#define OBJ_setAttr_IssCap_Sig OBJ_setAttr_IssCap,5L + +#define SN_setAttr_GenCryptgrm "setAttr-GenCryptgrm" +#define LN_setAttr_GenCryptgrm "generate cryptogram" +#define NID_setAttr_GenCryptgrm 631 +#define OBJ_setAttr_GenCryptgrm OBJ_setAttr_IssCap_CVM,1L + +#define SN_setAttr_T2Enc "setAttr-T2Enc" +#define LN_setAttr_T2Enc "encrypted track 2" +#define NID_setAttr_T2Enc 632 +#define OBJ_setAttr_T2Enc OBJ_setAttr_IssCap_T2,1L + +#define SN_setAttr_T2cleartxt "setAttr-T2cleartxt" +#define LN_setAttr_T2cleartxt "cleartext track 2" +#define NID_setAttr_T2cleartxt 633 +#define OBJ_setAttr_T2cleartxt OBJ_setAttr_IssCap_T2,2L + +#define SN_setAttr_TokICCsig "setAttr-TokICCsig" +#define LN_setAttr_TokICCsig "ICC or token signature" +#define NID_setAttr_TokICCsig 634 +#define OBJ_setAttr_TokICCsig OBJ_setAttr_IssCap_Sig,1L + +#define SN_setAttr_SecDevSig "setAttr-SecDevSig" +#define LN_setAttr_SecDevSig "secure device signature" +#define NID_setAttr_SecDevSig 635 +#define OBJ_setAttr_SecDevSig OBJ_setAttr_IssCap_Sig,2L + +#define SN_set_brand_IATA_ATA "set-brand-IATA-ATA" +#define NID_set_brand_IATA_ATA 636 +#define OBJ_set_brand_IATA_ATA OBJ_set_brand,1L + +#define SN_set_brand_Diners "set-brand-Diners" +#define NID_set_brand_Diners 637 +#define OBJ_set_brand_Diners OBJ_set_brand,30L + +#define SN_set_brand_AmericanExpress "set-brand-AmericanExpress" +#define NID_set_brand_AmericanExpress 638 +#define OBJ_set_brand_AmericanExpress OBJ_set_brand,34L + +#define SN_set_brand_JCB "set-brand-JCB" +#define NID_set_brand_JCB 639 +#define OBJ_set_brand_JCB OBJ_set_brand,35L + +#define SN_set_brand_Visa "set-brand-Visa" +#define NID_set_brand_Visa 640 +#define OBJ_set_brand_Visa OBJ_set_brand,4L + +#define SN_set_brand_MasterCard "set-brand-MasterCard" +#define NID_set_brand_MasterCard 641 +#define OBJ_set_brand_MasterCard OBJ_set_brand,5L + +#define SN_set_brand_Novus "set-brand-Novus" +#define NID_set_brand_Novus 642 +#define OBJ_set_brand_Novus OBJ_set_brand,6011L + +#define SN_des_cdmf "DES-CDMF" +#define LN_des_cdmf "des-cdmf" +#define NID_des_cdmf 643 +#define OBJ_des_cdmf OBJ_rsadsi,3L,10L + +#define SN_rsaOAEPEncryptionSET "rsaOAEPEncryptionSET" +#define NID_rsaOAEPEncryptionSET 644 +#define OBJ_rsaOAEPEncryptionSET OBJ_rsadsi,1L,1L,6L + +#define SN_ipsec3 "Oakley-EC2N-3" +#define LN_ipsec3 "ipsec3" +#define NID_ipsec3 749 + +#define SN_ipsec4 "Oakley-EC2N-4" +#define LN_ipsec4 "ipsec4" +#define NID_ipsec4 750 + +#define SN_whirlpool "whirlpool" +#define NID_whirlpool 804 +#define OBJ_whirlpool OBJ_iso,0L,10118L,3L,0L,55L + +#define SN_cryptopro "cryptopro" +#define NID_cryptopro 805 +#define OBJ_cryptopro OBJ_member_body,643L,2L,2L + +#define SN_cryptocom "cryptocom" +#define NID_cryptocom 806 +#define OBJ_cryptocom OBJ_member_body,643L,2L,9L + +#define SN_id_GostR3411_94_with_GostR3410_2001 "id-GostR3411-94-with-GostR3410-2001" +#define LN_id_GostR3411_94_with_GostR3410_2001 "GOST R 34.11-94 with GOST R 34.10-2001" +#define NID_id_GostR3411_94_with_GostR3410_2001 807 +#define OBJ_id_GostR3411_94_with_GostR3410_2001 OBJ_cryptopro,3L + +#define SN_id_GostR3411_94_with_GostR3410_94 "id-GostR3411-94-with-GostR3410-94" +#define LN_id_GostR3411_94_with_GostR3410_94 "GOST R 34.11-94 with GOST R 34.10-94" +#define NID_id_GostR3411_94_with_GostR3410_94 808 +#define OBJ_id_GostR3411_94_with_GostR3410_94 OBJ_cryptopro,4L + +#define SN_id_GostR3411_94 "md_gost94" +#define LN_id_GostR3411_94 "GOST R 34.11-94" +#define NID_id_GostR3411_94 809 +#define OBJ_id_GostR3411_94 OBJ_cryptopro,9L + +#define SN_id_HMACGostR3411_94 "id-HMACGostR3411-94" +#define LN_id_HMACGostR3411_94 "HMAC GOST 34.11-94" +#define NID_id_HMACGostR3411_94 810 +#define OBJ_id_HMACGostR3411_94 OBJ_cryptopro,10L + +#define SN_id_GostR3410_2001 "gost2001" +#define LN_id_GostR3410_2001 "GOST R 34.10-2001" +#define NID_id_GostR3410_2001 811 +#define OBJ_id_GostR3410_2001 OBJ_cryptopro,19L + +#define SN_id_GostR3410_94 "gost94" +#define LN_id_GostR3410_94 "GOST R 34.10-94" +#define NID_id_GostR3410_94 812 +#define OBJ_id_GostR3410_94 OBJ_cryptopro,20L + +#define SN_id_Gost28147_89 "gost89" +#define LN_id_Gost28147_89 "GOST 28147-89" +#define NID_id_Gost28147_89 813 +#define OBJ_id_Gost28147_89 OBJ_cryptopro,21L + +#define SN_gost89_cnt "gost89-cnt" +#define NID_gost89_cnt 814 + +#define SN_id_Gost28147_89_MAC "gost-mac" +#define LN_id_Gost28147_89_MAC "GOST 28147-89 MAC" +#define NID_id_Gost28147_89_MAC 815 +#define OBJ_id_Gost28147_89_MAC OBJ_cryptopro,22L + +#define SN_id_GostR3411_94_prf "prf-gostr3411-94" +#define LN_id_GostR3411_94_prf "GOST R 34.11-94 PRF" +#define NID_id_GostR3411_94_prf 816 +#define OBJ_id_GostR3411_94_prf OBJ_cryptopro,23L + +#define SN_id_GostR3410_2001DH "id-GostR3410-2001DH" +#define LN_id_GostR3410_2001DH "GOST R 34.10-2001 DH" +#define NID_id_GostR3410_2001DH 817 +#define OBJ_id_GostR3410_2001DH OBJ_cryptopro,98L + +#define SN_id_GostR3410_94DH "id-GostR3410-94DH" +#define LN_id_GostR3410_94DH "GOST R 34.10-94 DH" +#define NID_id_GostR3410_94DH 818 +#define OBJ_id_GostR3410_94DH OBJ_cryptopro,99L + +#define SN_id_Gost28147_89_CryptoPro_KeyMeshing "id-Gost28147-89-CryptoPro-KeyMeshing" +#define NID_id_Gost28147_89_CryptoPro_KeyMeshing 819 +#define OBJ_id_Gost28147_89_CryptoPro_KeyMeshing OBJ_cryptopro,14L,1L + +#define SN_id_Gost28147_89_None_KeyMeshing "id-Gost28147-89-None-KeyMeshing" +#define NID_id_Gost28147_89_None_KeyMeshing 820 +#define OBJ_id_Gost28147_89_None_KeyMeshing OBJ_cryptopro,14L,0L + +#define SN_id_GostR3411_94_TestParamSet "id-GostR3411-94-TestParamSet" +#define NID_id_GostR3411_94_TestParamSet 821 +#define OBJ_id_GostR3411_94_TestParamSet OBJ_cryptopro,30L,0L + +#define SN_id_GostR3411_94_CryptoProParamSet "id-GostR3411-94-CryptoProParamSet" +#define NID_id_GostR3411_94_CryptoProParamSet 822 +#define OBJ_id_GostR3411_94_CryptoProParamSet OBJ_cryptopro,30L,1L + +#define SN_id_Gost28147_89_TestParamSet "id-Gost28147-89-TestParamSet" +#define NID_id_Gost28147_89_TestParamSet 823 +#define OBJ_id_Gost28147_89_TestParamSet OBJ_cryptopro,31L,0L + +#define SN_id_Gost28147_89_CryptoPro_A_ParamSet "id-Gost28147-89-CryptoPro-A-ParamSet" +#define NID_id_Gost28147_89_CryptoPro_A_ParamSet 824 +#define OBJ_id_Gost28147_89_CryptoPro_A_ParamSet OBJ_cryptopro,31L,1L + +#define SN_id_Gost28147_89_CryptoPro_B_ParamSet "id-Gost28147-89-CryptoPro-B-ParamSet" +#define NID_id_Gost28147_89_CryptoPro_B_ParamSet 825 +#define OBJ_id_Gost28147_89_CryptoPro_B_ParamSet OBJ_cryptopro,31L,2L + +#define SN_id_Gost28147_89_CryptoPro_C_ParamSet "id-Gost28147-89-CryptoPro-C-ParamSet" +#define NID_id_Gost28147_89_CryptoPro_C_ParamSet 826 +#define OBJ_id_Gost28147_89_CryptoPro_C_ParamSet OBJ_cryptopro,31L,3L + +#define SN_id_Gost28147_89_CryptoPro_D_ParamSet "id-Gost28147-89-CryptoPro-D-ParamSet" +#define NID_id_Gost28147_89_CryptoPro_D_ParamSet 827 +#define OBJ_id_Gost28147_89_CryptoPro_D_ParamSet OBJ_cryptopro,31L,4L + +#define SN_id_Gost28147_89_CryptoPro_Oscar_1_1_ParamSet "id-Gost28147-89-CryptoPro-Oscar-1-1-ParamSet" +#define NID_id_Gost28147_89_CryptoPro_Oscar_1_1_ParamSet 828 +#define OBJ_id_Gost28147_89_CryptoPro_Oscar_1_1_ParamSet OBJ_cryptopro,31L,5L + +#define SN_id_Gost28147_89_CryptoPro_Oscar_1_0_ParamSet "id-Gost28147-89-CryptoPro-Oscar-1-0-ParamSet" +#define NID_id_Gost28147_89_CryptoPro_Oscar_1_0_ParamSet 829 +#define OBJ_id_Gost28147_89_CryptoPro_Oscar_1_0_ParamSet OBJ_cryptopro,31L,6L + +#define SN_id_Gost28147_89_CryptoPro_RIC_1_ParamSet "id-Gost28147-89-CryptoPro-RIC-1-ParamSet" +#define NID_id_Gost28147_89_CryptoPro_RIC_1_ParamSet 830 +#define OBJ_id_Gost28147_89_CryptoPro_RIC_1_ParamSet OBJ_cryptopro,31L,7L + +#define SN_id_GostR3410_94_TestParamSet "id-GostR3410-94-TestParamSet" +#define NID_id_GostR3410_94_TestParamSet 831 +#define OBJ_id_GostR3410_94_TestParamSet OBJ_cryptopro,32L,0L + +#define SN_id_GostR3410_94_CryptoPro_A_ParamSet "id-GostR3410-94-CryptoPro-A-ParamSet" +#define NID_id_GostR3410_94_CryptoPro_A_ParamSet 832 +#define OBJ_id_GostR3410_94_CryptoPro_A_ParamSet OBJ_cryptopro,32L,2L + +#define SN_id_GostR3410_94_CryptoPro_B_ParamSet "id-GostR3410-94-CryptoPro-B-ParamSet" +#define NID_id_GostR3410_94_CryptoPro_B_ParamSet 833 +#define OBJ_id_GostR3410_94_CryptoPro_B_ParamSet OBJ_cryptopro,32L,3L + +#define SN_id_GostR3410_94_CryptoPro_C_ParamSet "id-GostR3410-94-CryptoPro-C-ParamSet" +#define NID_id_GostR3410_94_CryptoPro_C_ParamSet 834 +#define OBJ_id_GostR3410_94_CryptoPro_C_ParamSet OBJ_cryptopro,32L,4L + +#define SN_id_GostR3410_94_CryptoPro_D_ParamSet "id-GostR3410-94-CryptoPro-D-ParamSet" +#define NID_id_GostR3410_94_CryptoPro_D_ParamSet 835 +#define OBJ_id_GostR3410_94_CryptoPro_D_ParamSet OBJ_cryptopro,32L,5L + +#define SN_id_GostR3410_94_CryptoPro_XchA_ParamSet "id-GostR3410-94-CryptoPro-XchA-ParamSet" +#define NID_id_GostR3410_94_CryptoPro_XchA_ParamSet 836 +#define OBJ_id_GostR3410_94_CryptoPro_XchA_ParamSet OBJ_cryptopro,33L,1L + +#define SN_id_GostR3410_94_CryptoPro_XchB_ParamSet "id-GostR3410-94-CryptoPro-XchB-ParamSet" +#define NID_id_GostR3410_94_CryptoPro_XchB_ParamSet 837 +#define OBJ_id_GostR3410_94_CryptoPro_XchB_ParamSet OBJ_cryptopro,33L,2L + +#define SN_id_GostR3410_94_CryptoPro_XchC_ParamSet "id-GostR3410-94-CryptoPro-XchC-ParamSet" +#define NID_id_GostR3410_94_CryptoPro_XchC_ParamSet 838 +#define OBJ_id_GostR3410_94_CryptoPro_XchC_ParamSet OBJ_cryptopro,33L,3L + +#define SN_id_GostR3410_2001_TestParamSet "id-GostR3410-2001-TestParamSet" +#define NID_id_GostR3410_2001_TestParamSet 839 +#define OBJ_id_GostR3410_2001_TestParamSet OBJ_cryptopro,35L,0L + +#define SN_id_GostR3410_2001_CryptoPro_A_ParamSet "id-GostR3410-2001-CryptoPro-A-ParamSet" +#define NID_id_GostR3410_2001_CryptoPro_A_ParamSet 840 +#define OBJ_id_GostR3410_2001_CryptoPro_A_ParamSet OBJ_cryptopro,35L,1L + +#define SN_id_GostR3410_2001_CryptoPro_B_ParamSet "id-GostR3410-2001-CryptoPro-B-ParamSet" +#define NID_id_GostR3410_2001_CryptoPro_B_ParamSet 841 +#define OBJ_id_GostR3410_2001_CryptoPro_B_ParamSet OBJ_cryptopro,35L,2L + +#define SN_id_GostR3410_2001_CryptoPro_C_ParamSet "id-GostR3410-2001-CryptoPro-C-ParamSet" +#define NID_id_GostR3410_2001_CryptoPro_C_ParamSet 842 +#define OBJ_id_GostR3410_2001_CryptoPro_C_ParamSet OBJ_cryptopro,35L,3L + +#define SN_id_GostR3410_2001_CryptoPro_XchA_ParamSet "id-GostR3410-2001-CryptoPro-XchA-ParamSet" +#define NID_id_GostR3410_2001_CryptoPro_XchA_ParamSet 843 +#define OBJ_id_GostR3410_2001_CryptoPro_XchA_ParamSet OBJ_cryptopro,36L,0L + +#define SN_id_GostR3410_2001_CryptoPro_XchB_ParamSet "id-GostR3410-2001-CryptoPro-XchB-ParamSet" +#define NID_id_GostR3410_2001_CryptoPro_XchB_ParamSet 844 +#define OBJ_id_GostR3410_2001_CryptoPro_XchB_ParamSet OBJ_cryptopro,36L,1L + +#define SN_id_GostR3410_94_a "id-GostR3410-94-a" +#define NID_id_GostR3410_94_a 845 +#define OBJ_id_GostR3410_94_a OBJ_id_GostR3410_94,1L + +#define SN_id_GostR3410_94_aBis "id-GostR3410-94-aBis" +#define NID_id_GostR3410_94_aBis 846 +#define OBJ_id_GostR3410_94_aBis OBJ_id_GostR3410_94,2L + +#define SN_id_GostR3410_94_b "id-GostR3410-94-b" +#define NID_id_GostR3410_94_b 847 +#define OBJ_id_GostR3410_94_b OBJ_id_GostR3410_94,3L + +#define SN_id_GostR3410_94_bBis "id-GostR3410-94-bBis" +#define NID_id_GostR3410_94_bBis 848 +#define OBJ_id_GostR3410_94_bBis OBJ_id_GostR3410_94,4L + +#define SN_id_Gost28147_89_cc "id-Gost28147-89-cc" +#define LN_id_Gost28147_89_cc "GOST 28147-89 Cryptocom ParamSet" +#define NID_id_Gost28147_89_cc 849 +#define OBJ_id_Gost28147_89_cc OBJ_cryptocom,1L,6L,1L + +#define SN_id_GostR3410_94_cc "gost94cc" +#define LN_id_GostR3410_94_cc "GOST 34.10-94 Cryptocom" +#define NID_id_GostR3410_94_cc 850 +#define OBJ_id_GostR3410_94_cc OBJ_cryptocom,1L,5L,3L + +#define SN_id_GostR3410_2001_cc "gost2001cc" +#define LN_id_GostR3410_2001_cc "GOST 34.10-2001 Cryptocom" +#define NID_id_GostR3410_2001_cc 851 +#define OBJ_id_GostR3410_2001_cc OBJ_cryptocom,1L,5L,4L + +#define SN_id_GostR3411_94_with_GostR3410_94_cc "id-GostR3411-94-with-GostR3410-94-cc" +#define LN_id_GostR3411_94_with_GostR3410_94_cc "GOST R 34.11-94 with GOST R 34.10-94 Cryptocom" +#define NID_id_GostR3411_94_with_GostR3410_94_cc 852 +#define OBJ_id_GostR3411_94_with_GostR3410_94_cc OBJ_cryptocom,1L,3L,3L + +#define SN_id_GostR3411_94_with_GostR3410_2001_cc "id-GostR3411-94-with-GostR3410-2001-cc" +#define LN_id_GostR3411_94_with_GostR3410_2001_cc "GOST R 34.11-94 with GOST R 34.10-2001 Cryptocom" +#define NID_id_GostR3411_94_with_GostR3410_2001_cc 853 +#define OBJ_id_GostR3411_94_with_GostR3410_2001_cc OBJ_cryptocom,1L,3L,4L + +#define SN_id_GostR3410_2001_ParamSet_cc "id-GostR3410-2001-ParamSet-cc" +#define LN_id_GostR3410_2001_ParamSet_cc "GOST R 3410-2001 Parameter Set Cryptocom" +#define NID_id_GostR3410_2001_ParamSet_cc 854 +#define OBJ_id_GostR3410_2001_ParamSet_cc OBJ_cryptocom,1L,8L,1L + +#define SN_camellia_128_cbc "CAMELLIA-128-CBC" +#define LN_camellia_128_cbc "camellia-128-cbc" +#define NID_camellia_128_cbc 751 +#define OBJ_camellia_128_cbc 1L,2L,392L,200011L,61L,1L,1L,1L,2L + +#define SN_camellia_192_cbc "CAMELLIA-192-CBC" +#define LN_camellia_192_cbc "camellia-192-cbc" +#define NID_camellia_192_cbc 752 +#define OBJ_camellia_192_cbc 1L,2L,392L,200011L,61L,1L,1L,1L,3L + +#define SN_camellia_256_cbc "CAMELLIA-256-CBC" +#define LN_camellia_256_cbc "camellia-256-cbc" +#define NID_camellia_256_cbc 753 +#define OBJ_camellia_256_cbc 1L,2L,392L,200011L,61L,1L,1L,1L,4L + +#define SN_id_camellia128_wrap "id-camellia128-wrap" +#define NID_id_camellia128_wrap 907 +#define OBJ_id_camellia128_wrap 1L,2L,392L,200011L,61L,1L,1L,3L,2L + +#define SN_id_camellia192_wrap "id-camellia192-wrap" +#define NID_id_camellia192_wrap 908 +#define OBJ_id_camellia192_wrap 1L,2L,392L,200011L,61L,1L,1L,3L,3L + +#define SN_id_camellia256_wrap "id-camellia256-wrap" +#define NID_id_camellia256_wrap 909 +#define OBJ_id_camellia256_wrap 1L,2L,392L,200011L,61L,1L,1L,3L,4L + +#define OBJ_ntt_ds 0L,3L,4401L,5L + +#define OBJ_camellia OBJ_ntt_ds,3L,1L,9L + +#define SN_camellia_128_ecb "CAMELLIA-128-ECB" +#define LN_camellia_128_ecb "camellia-128-ecb" +#define NID_camellia_128_ecb 754 +#define OBJ_camellia_128_ecb OBJ_camellia,1L + +#define SN_camellia_128_ofb128 "CAMELLIA-128-OFB" +#define LN_camellia_128_ofb128 "camellia-128-ofb" +#define NID_camellia_128_ofb128 766 +#define OBJ_camellia_128_ofb128 OBJ_camellia,3L + +#define SN_camellia_128_cfb128 "CAMELLIA-128-CFB" +#define LN_camellia_128_cfb128 "camellia-128-cfb" +#define NID_camellia_128_cfb128 757 +#define OBJ_camellia_128_cfb128 OBJ_camellia,4L + +#define SN_camellia_192_ecb "CAMELLIA-192-ECB" +#define LN_camellia_192_ecb "camellia-192-ecb" +#define NID_camellia_192_ecb 755 +#define OBJ_camellia_192_ecb OBJ_camellia,21L + +#define SN_camellia_192_ofb128 "CAMELLIA-192-OFB" +#define LN_camellia_192_ofb128 "camellia-192-ofb" +#define NID_camellia_192_ofb128 767 +#define OBJ_camellia_192_ofb128 OBJ_camellia,23L + +#define SN_camellia_192_cfb128 "CAMELLIA-192-CFB" +#define LN_camellia_192_cfb128 "camellia-192-cfb" +#define NID_camellia_192_cfb128 758 +#define OBJ_camellia_192_cfb128 OBJ_camellia,24L + +#define SN_camellia_256_ecb "CAMELLIA-256-ECB" +#define LN_camellia_256_ecb "camellia-256-ecb" +#define NID_camellia_256_ecb 756 +#define OBJ_camellia_256_ecb OBJ_camellia,41L + +#define SN_camellia_256_ofb128 "CAMELLIA-256-OFB" +#define LN_camellia_256_ofb128 "camellia-256-ofb" +#define NID_camellia_256_ofb128 768 +#define OBJ_camellia_256_ofb128 OBJ_camellia,43L + +#define SN_camellia_256_cfb128 "CAMELLIA-256-CFB" +#define LN_camellia_256_cfb128 "camellia-256-cfb" +#define NID_camellia_256_cfb128 759 +#define OBJ_camellia_256_cfb128 OBJ_camellia,44L + +#define SN_camellia_128_cfb1 "CAMELLIA-128-CFB1" +#define LN_camellia_128_cfb1 "camellia-128-cfb1" +#define NID_camellia_128_cfb1 760 + +#define SN_camellia_192_cfb1 "CAMELLIA-192-CFB1" +#define LN_camellia_192_cfb1 "camellia-192-cfb1" +#define NID_camellia_192_cfb1 761 + +#define SN_camellia_256_cfb1 "CAMELLIA-256-CFB1" +#define LN_camellia_256_cfb1 "camellia-256-cfb1" +#define NID_camellia_256_cfb1 762 + +#define SN_camellia_128_cfb8 "CAMELLIA-128-CFB8" +#define LN_camellia_128_cfb8 "camellia-128-cfb8" +#define NID_camellia_128_cfb8 763 + +#define SN_camellia_192_cfb8 "CAMELLIA-192-CFB8" +#define LN_camellia_192_cfb8 "camellia-192-cfb8" +#define NID_camellia_192_cfb8 764 + +#define SN_camellia_256_cfb8 "CAMELLIA-256-CFB8" +#define LN_camellia_256_cfb8 "camellia-256-cfb8" +#define NID_camellia_256_cfb8 765 + +#define SN_kisa "KISA" +#define LN_kisa "kisa" +#define NID_kisa 773 +#define OBJ_kisa OBJ_member_body,410L,200004L + +#define SN_seed_ecb "SEED-ECB" +#define LN_seed_ecb "seed-ecb" +#define NID_seed_ecb 776 +#define OBJ_seed_ecb OBJ_kisa,1L,3L + +#define SN_seed_cbc "SEED-CBC" +#define LN_seed_cbc "seed-cbc" +#define NID_seed_cbc 777 +#define OBJ_seed_cbc OBJ_kisa,1L,4L + +#define SN_seed_cfb128 "SEED-CFB" +#define LN_seed_cfb128 "seed-cfb" +#define NID_seed_cfb128 779 +#define OBJ_seed_cfb128 OBJ_kisa,1L,5L + +#define SN_seed_ofb128 "SEED-OFB" +#define LN_seed_ofb128 "seed-ofb" +#define NID_seed_ofb128 778 +#define OBJ_seed_ofb128 OBJ_kisa,1L,6L + +#define SN_hmac "HMAC" +#define LN_hmac "hmac" +#define NID_hmac 855 + +#define SN_cmac "CMAC" +#define LN_cmac "cmac" +#define NID_cmac 894 + +#define SN_rc4_hmac_md5 "RC4-HMAC-MD5" +#define LN_rc4_hmac_md5 "rc4-hmac-md5" +#define NID_rc4_hmac_md5 915 + +#define SN_aes_128_cbc_hmac_sha1 "AES-128-CBC-HMAC-SHA1" +#define LN_aes_128_cbc_hmac_sha1 "aes-128-cbc-hmac-sha1" +#define NID_aes_128_cbc_hmac_sha1 916 + +#define SN_aes_192_cbc_hmac_sha1 "AES-192-CBC-HMAC-SHA1" +#define LN_aes_192_cbc_hmac_sha1 "aes-192-cbc-hmac-sha1" +#define NID_aes_192_cbc_hmac_sha1 917 + +#define SN_aes_256_cbc_hmac_sha1 "AES-256-CBC-HMAC-SHA1" +#define LN_aes_256_cbc_hmac_sha1 "aes-256-cbc-hmac-sha1" +#define NID_aes_256_cbc_hmac_sha1 918 + +#define SN_dhpublicnumber "dhpublicnumber" +#define LN_dhpublicnumber "X9.42 DH" +#define NID_dhpublicnumber 920 +#define OBJ_dhpublicnumber OBJ_ISO_US,10046L,2L,1L + +#define SN_brainpoolP160r1 "brainpoolP160r1" +#define NID_brainpoolP160r1 921 +#define OBJ_brainpoolP160r1 1L,3L,36L,3L,3L,2L,8L,1L,1L,1L + +#define SN_brainpoolP160t1 "brainpoolP160t1" +#define NID_brainpoolP160t1 922 +#define OBJ_brainpoolP160t1 1L,3L,36L,3L,3L,2L,8L,1L,1L,2L + +#define SN_brainpoolP192r1 "brainpoolP192r1" +#define NID_brainpoolP192r1 923 +#define OBJ_brainpoolP192r1 1L,3L,36L,3L,3L,2L,8L,1L,1L,3L + +#define SN_brainpoolP192t1 "brainpoolP192t1" +#define NID_brainpoolP192t1 924 +#define OBJ_brainpoolP192t1 1L,3L,36L,3L,3L,2L,8L,1L,1L,4L + +#define SN_brainpoolP224r1 "brainpoolP224r1" +#define NID_brainpoolP224r1 925 +#define OBJ_brainpoolP224r1 1L,3L,36L,3L,3L,2L,8L,1L,1L,5L + +#define SN_brainpoolP224t1 "brainpoolP224t1" +#define NID_brainpoolP224t1 926 +#define OBJ_brainpoolP224t1 1L,3L,36L,3L,3L,2L,8L,1L,1L,6L + +#define SN_brainpoolP256r1 "brainpoolP256r1" +#define NID_brainpoolP256r1 927 +#define OBJ_brainpoolP256r1 1L,3L,36L,3L,3L,2L,8L,1L,1L,7L + +#define SN_brainpoolP256t1 "brainpoolP256t1" +#define NID_brainpoolP256t1 928 +#define OBJ_brainpoolP256t1 1L,3L,36L,3L,3L,2L,8L,1L,1L,8L + +#define SN_brainpoolP320r1 "brainpoolP320r1" +#define NID_brainpoolP320r1 929 +#define OBJ_brainpoolP320r1 1L,3L,36L,3L,3L,2L,8L,1L,1L,9L + +#define SN_brainpoolP320t1 "brainpoolP320t1" +#define NID_brainpoolP320t1 930 +#define OBJ_brainpoolP320t1 1L,3L,36L,3L,3L,2L,8L,1L,1L,10L + +#define SN_brainpoolP384r1 "brainpoolP384r1" +#define NID_brainpoolP384r1 931 +#define OBJ_brainpoolP384r1 1L,3L,36L,3L,3L,2L,8L,1L,1L,11L + +#define SN_brainpoolP384t1 "brainpoolP384t1" +#define NID_brainpoolP384t1 932 +#define OBJ_brainpoolP384t1 1L,3L,36L,3L,3L,2L,8L,1L,1L,12L + +#define SN_brainpoolP512r1 "brainpoolP512r1" +#define NID_brainpoolP512r1 933 +#define OBJ_brainpoolP512r1 1L,3L,36L,3L,3L,2L,8L,1L,1L,13L + +#define SN_brainpoolP512t1 "brainpoolP512t1" +#define NID_brainpoolP512t1 934 +#define OBJ_brainpoolP512t1 1L,3L,36L,3L,3L,2L,8L,1L,1L,14L + +#define OBJ_x9_63_scheme 1L,3L,133L,16L,840L,63L,0L + +#define OBJ_secg_scheme OBJ_certicom_arc,1L + +#define SN_dhSinglePass_stdDH_sha1kdf_scheme "dhSinglePass-stdDH-sha1kdf-scheme" +#define NID_dhSinglePass_stdDH_sha1kdf_scheme 936 +#define OBJ_dhSinglePass_stdDH_sha1kdf_scheme OBJ_x9_63_scheme,2L + +#define SN_dhSinglePass_stdDH_sha224kdf_scheme "dhSinglePass-stdDH-sha224kdf-scheme" +#define NID_dhSinglePass_stdDH_sha224kdf_scheme 937 +#define OBJ_dhSinglePass_stdDH_sha224kdf_scheme OBJ_secg_scheme,11L,0L + +#define SN_dhSinglePass_stdDH_sha256kdf_scheme "dhSinglePass-stdDH-sha256kdf-scheme" +#define NID_dhSinglePass_stdDH_sha256kdf_scheme 938 +#define OBJ_dhSinglePass_stdDH_sha256kdf_scheme OBJ_secg_scheme,11L,1L + +#define SN_dhSinglePass_stdDH_sha384kdf_scheme "dhSinglePass-stdDH-sha384kdf-scheme" +#define NID_dhSinglePass_stdDH_sha384kdf_scheme 939 +#define OBJ_dhSinglePass_stdDH_sha384kdf_scheme OBJ_secg_scheme,11L,2L + +#define SN_dhSinglePass_stdDH_sha512kdf_scheme "dhSinglePass-stdDH-sha512kdf-scheme" +#define NID_dhSinglePass_stdDH_sha512kdf_scheme 940 +#define OBJ_dhSinglePass_stdDH_sha512kdf_scheme OBJ_secg_scheme,11L,3L + +#define SN_dhSinglePass_cofactorDH_sha1kdf_scheme "dhSinglePass-cofactorDH-sha1kdf-scheme" +#define NID_dhSinglePass_cofactorDH_sha1kdf_scheme 941 +#define OBJ_dhSinglePass_cofactorDH_sha1kdf_scheme OBJ_x9_63_scheme,3L + +#define SN_dhSinglePass_cofactorDH_sha224kdf_scheme "dhSinglePass-cofactorDH-sha224kdf-scheme" +#define NID_dhSinglePass_cofactorDH_sha224kdf_scheme 942 +#define OBJ_dhSinglePass_cofactorDH_sha224kdf_scheme OBJ_secg_scheme,14L,0L + +#define SN_dhSinglePass_cofactorDH_sha256kdf_scheme "dhSinglePass-cofactorDH-sha256kdf-scheme" +#define NID_dhSinglePass_cofactorDH_sha256kdf_scheme 943 +#define OBJ_dhSinglePass_cofactorDH_sha256kdf_scheme OBJ_secg_scheme,14L,1L + +#define SN_dhSinglePass_cofactorDH_sha384kdf_scheme "dhSinglePass-cofactorDH-sha384kdf-scheme" +#define NID_dhSinglePass_cofactorDH_sha384kdf_scheme 944 +#define OBJ_dhSinglePass_cofactorDH_sha384kdf_scheme OBJ_secg_scheme,14L,2L + +#define SN_dhSinglePass_cofactorDH_sha512kdf_scheme "dhSinglePass-cofactorDH-sha512kdf-scheme" +#define NID_dhSinglePass_cofactorDH_sha512kdf_scheme 945 +#define OBJ_dhSinglePass_cofactorDH_sha512kdf_scheme OBJ_secg_scheme,14L,3L + +#define SN_dh_std_kdf "dh-std-kdf" +#define NID_dh_std_kdf 946 + +#define SN_dh_cofactor_kdf "dh-cofactor-kdf" +#define NID_dh_cofactor_kdf 947 + diff --git a/phonelibs/boringssl/include/openssl/objects.h b/phonelibs/boringssl/include/openssl/objects.h new file mode 100644 index 00000000000000..dd6556f26489c5 --- /dev/null +++ b/phonelibs/boringssl/include/openssl/objects.h @@ -0,0 +1,18 @@ +/* Copyright (c) 2014, Google Inc. + * + * Permission to use, copy, modify, and/or distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY + * SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN ACTION + * OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF OR IN + * CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. */ + +/* This header is provided in order to make compiling against code that expects + OpenSSL easier. */ + +#include "obj.h" diff --git a/phonelibs/boringssl/include/openssl/opensslfeatures.h b/phonelibs/boringssl/include/openssl/opensslfeatures.h new file mode 100644 index 00000000000000..c3f97d5a48e620 --- /dev/null +++ b/phonelibs/boringssl/include/openssl/opensslfeatures.h @@ -0,0 +1,60 @@ +/* Copyright (c) 2014, Google Inc. + * + * Permission to use, copy, modify, and/or distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY + * SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN ACTION + * OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF OR IN + * CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. */ + +/* This header is provided in order to make compiling against code that expects + OpenSSL easier. */ + +#ifndef OPENSSL_HEADER_OPENSSLFEATURES_H +#define OPENSSL_HEADER_OPENSSLFEATURES_H + + +#define OPENSSL_NO_BF +#define OPENSSL_NO_BUF_FREELISTS +#define OPENSSL_NO_CAMELLIA +#define OPENSSL_NO_CAPIENG +#define OPENSSL_NO_CAST +#define OPENSSL_NO_CMS +#define OPENSSL_NO_COMP +#define OPENSSL_NO_DANE +#define OPENSSL_NO_DEPRECATED +#define OPENSSL_NO_DYNAMIC_ENGINE +#define OPENSSL_NO_EC_NISTP_64_GCC_128 +#define OPENSSL_NO_EC2M +#define OPENSSL_NO_ENGINE +#define OPENSSL_NO_GMP +#define OPENSSL_NO_GOST +#define OPENSSL_NO_HEARTBEATS +#define OPENSSL_NO_HW +#define OPENSSL_NO_IDEA +#define OPENSSL_NO_JPAKE +#define OPENSSL_NO_KRB5 +#define OPENSSL_NO_MD2 +#define OPENSSL_NO_MDC2 +#define OPENSSL_NO_OCB +#define OPENSSL_NO_OCSP +#define OPENSSL_NO_RC2 +#define OPENSSL_NO_RC5 +#define OPENSSL_NO_RFC3779 +#define OPENSSL_NO_RIPEMD +#define OPENSSL_NO_RMD160 +#define OPENSSL_NO_SCTP +#define OPENSSL_NO_SEED +#define OPENSSL_NO_SRP +#define OPENSSL_NO_SSL2 +#define OPENSSL_NO_STATIC_ENGINE +#define OPENSSL_NO_STORE +#define OPENSSL_NO_WHIRLPOOL + + +#endif /* OPENSSL_HEADER_OPENSSLFEATURES_H */ diff --git a/phonelibs/boringssl/include/openssl/opensslv.h b/phonelibs/boringssl/include/openssl/opensslv.h new file mode 100644 index 00000000000000..a3555d4f8b0027 --- /dev/null +++ b/phonelibs/boringssl/include/openssl/opensslv.h @@ -0,0 +1,18 @@ +/* Copyright (c) 2014, Google Inc. + * + * Permission to use, copy, modify, and/or distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY + * SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN ACTION + * OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF OR IN + * CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. */ + +/* This header is provided in order to make compiling against code that expects + OpenSSL easier. */ + +#include "crypto.h" diff --git a/phonelibs/boringssl/include/openssl/ossl_typ.h b/phonelibs/boringssl/include/openssl/ossl_typ.h new file mode 100644 index 00000000000000..c2b3fe7c500965 --- /dev/null +++ b/phonelibs/boringssl/include/openssl/ossl_typ.h @@ -0,0 +1,18 @@ +/* Copyright (c) 2014, Google Inc. + * + * Permission to use, copy, modify, and/or distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY + * SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN ACTION + * OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF OR IN + * CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. */ + +/* This header is provided in order to make compiling against code that expects + OpenSSL easier. */ + +#include "base.h" diff --git a/phonelibs/boringssl/include/openssl/pem.h b/phonelibs/boringssl/include/openssl/pem.h new file mode 100644 index 00000000000000..7756e45ed3e73c --- /dev/null +++ b/phonelibs/boringssl/include/openssl/pem.h @@ -0,0 +1,545 @@ +/* Copyright (C) 1995-1997 Eric Young (eay@cryptsoft.com) + * All rights reserved. + * + * This package is an SSL implementation written + * by Eric Young (eay@cryptsoft.com). + * The implementation was written so as to conform with Netscapes SSL. + * + * This library is free for commercial and non-commercial use as long as + * the following conditions are aheared to. The following conditions + * apply to all code found in this distribution, be it the RC4, RSA, + * lhash, DES, etc., code; not just the SSL code. The SSL documentation + * included with this distribution is covered by the same copyright terms + * except that the holder is Tim Hudson (tjh@cryptsoft.com). + * + * Copyright remains Eric Young's, and as such any Copyright notices in + * the code are not to be removed. + * If this package is used in a product, Eric Young should be given attribution + * as the author of the parts of the library used. + * This can be in the form of a textual message at program startup or + * in documentation (online or textual) provided with the package. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must 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. All advertising materials mentioning features or use of this software + * must display the following acknowledgement: + * "This product includes cryptographic software written by + * Eric Young (eay@cryptsoft.com)" + * The word 'cryptographic' can be left out if the rouines from the library + * being used are not cryptographic related :-). + * 4. If you include any Windows specific code (or a derivative thereof) from + * the apps directory (application code) you must include an acknowledgement: + * "This product includes software written by Tim Hudson (tjh@cryptsoft.com)" + * + * THIS SOFTWARE IS PROVIDED BY ERIC YOUNG ``AS IS'' AND + * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHOR OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (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 licence and distribution terms for any publically available version or + * derivative of this code cannot be changed. i.e. this code cannot simply be + * copied and put under another distribution licence + * [including the GNU Public Licence.] */ + +#ifndef OPENSSL_HEADER_PEM_H +#define OPENSSL_HEADER_PEM_H + +#include +#include +#include +#include +#include +#include +#include + +#ifdef __cplusplus +extern "C" { +#endif + + +#define PEM_BUFSIZE 1024 + +#define PEM_OBJ_UNDEF 0 +#define PEM_OBJ_X509 1 +#define PEM_OBJ_X509_REQ 2 +#define PEM_OBJ_CRL 3 +#define PEM_OBJ_SSL_SESSION 4 +#define PEM_OBJ_PRIV_KEY 10 +#define PEM_OBJ_PRIV_RSA 11 +#define PEM_OBJ_PRIV_DSA 12 +#define PEM_OBJ_PRIV_DH 13 +#define PEM_OBJ_PUB_RSA 14 +#define PEM_OBJ_PUB_DSA 15 +#define PEM_OBJ_PUB_DH 16 +#define PEM_OBJ_DHPARAMS 17 +#define PEM_OBJ_DSAPARAMS 18 +#define PEM_OBJ_PRIV_RSA_PUBLIC 19 +#define PEM_OBJ_PRIV_ECDSA 20 +#define PEM_OBJ_PUB_ECDSA 21 +#define PEM_OBJ_ECPARAMETERS 22 + +#define PEM_ERROR 30 +#define PEM_DEK_DES_CBC 40 +#define PEM_DEK_IDEA_CBC 45 +#define PEM_DEK_DES_EDE 50 +#define PEM_DEK_DES_ECB 60 +#define PEM_DEK_RSA 70 +#define PEM_DEK_RSA_MD2 80 +#define PEM_DEK_RSA_MD5 90 + +#define PEM_MD_MD2 NID_md2 +#define PEM_MD_MD5 NID_md5 +#define PEM_MD_SHA NID_sha +#define PEM_MD_MD2_RSA NID_md2WithRSAEncryption +#define PEM_MD_MD5_RSA NID_md5WithRSAEncryption +#define PEM_MD_SHA_RSA NID_sha1WithRSAEncryption + +#define PEM_STRING_X509_OLD "X509 CERTIFICATE" +#define PEM_STRING_X509 "CERTIFICATE" +#define PEM_STRING_X509_PAIR "CERTIFICATE PAIR" +#define PEM_STRING_X509_TRUSTED "TRUSTED CERTIFICATE" +#define PEM_STRING_X509_REQ_OLD "NEW CERTIFICATE REQUEST" +#define PEM_STRING_X509_REQ "CERTIFICATE REQUEST" +#define PEM_STRING_X509_CRL "X509 CRL" +#define PEM_STRING_EVP_PKEY "ANY PRIVATE KEY" +#define PEM_STRING_PUBLIC "PUBLIC KEY" +#define PEM_STRING_RSA "RSA PRIVATE KEY" +#define PEM_STRING_RSA_PUBLIC "RSA PUBLIC KEY" +#define PEM_STRING_DSA "DSA PRIVATE KEY" +#define PEM_STRING_DSA_PUBLIC "DSA PUBLIC KEY" +#define PEM_STRING_PKCS7 "PKCS7" +#define PEM_STRING_PKCS7_SIGNED "PKCS #7 SIGNED DATA" +#define PEM_STRING_PKCS8 "ENCRYPTED PRIVATE KEY" +#define PEM_STRING_PKCS8INF "PRIVATE KEY" +#define PEM_STRING_DHPARAMS "DH PARAMETERS" +#define PEM_STRING_DHXPARAMS "X9.42 DH PARAMETERS" +#define PEM_STRING_SSL_SESSION "SSL SESSION PARAMETERS" +#define PEM_STRING_DSAPARAMS "DSA PARAMETERS" +#define PEM_STRING_ECDSA_PUBLIC "ECDSA PUBLIC KEY" +#define PEM_STRING_ECPARAMETERS "EC PARAMETERS" +#define PEM_STRING_ECPRIVATEKEY "EC PRIVATE KEY" +#define PEM_STRING_PARAMETERS "PARAMETERS" +#define PEM_STRING_CMS "CMS" + + /* Note that this structure is initialised by PEM_SealInit and cleaned up + by PEM_SealFinal (at least for now) */ +typedef struct PEM_Encode_Seal_st + { + EVP_ENCODE_CTX encode; + EVP_MD_CTX md; + EVP_CIPHER_CTX cipher; + } PEM_ENCODE_SEAL_CTX; + +/* enc_type is one off */ +#define PEM_TYPE_ENCRYPTED 10 +#define PEM_TYPE_MIC_ONLY 20 +#define PEM_TYPE_MIC_CLEAR 30 +#define PEM_TYPE_CLEAR 40 + +typedef struct pem_recip_st + { + char *name; + X509_NAME *dn; + + int cipher; + int key_enc; + /* char iv[8]; unused and wrong size */ + } PEM_USER; + +typedef struct pem_ctx_st + { + int type; /* what type of object */ + + struct { + int version; + int mode; + } proc_type; + + char *domain; + + struct { + int cipher; + /* unused, and wrong size + unsigned char iv[8]; */ + } DEK_info; + + PEM_USER *originator; + + int num_recipient; + PEM_USER **recipient; + + EVP_MD *md; /* signature type */ + + int md_enc; /* is the md encrypted or not? */ + int md_len; /* length of md_data */ + char *md_data; /* message digest, could be pkey encrypted */ + + EVP_CIPHER *dec; /* date encryption cipher */ + int key_len; /* key length */ + unsigned char *key; /* key */ + /* unused, and wrong size + unsigned char iv[8]; */ + + + int data_enc; /* is the data encrypted */ + int data_len; + unsigned char *data; + } PEM_CTX; + +/* These macros make the PEM_read/PEM_write functions easier to maintain and + * write. Now they are all implemented with either: + * IMPLEMENT_PEM_rw(...) or IMPLEMENT_PEM_rw_cb(...) + */ + +#ifdef OPENSSL_NO_FP_API + +#define IMPLEMENT_PEM_read_fp(name, type, str, asn1) /**/ +#define IMPLEMENT_PEM_write_fp(name, type, str, asn1) /**/ +#define IMPLEMENT_PEM_write_fp_const(name, type, str, asn1) /**/ +#define IMPLEMENT_PEM_write_cb_fp(name, type, str, asn1) /**/ +#define IMPLEMENT_PEM_write_cb_fp_const(name, type, str, asn1) /**/ + +#else + +#define IMPLEMENT_PEM_read_fp(name, type, str, asn1) \ +OPENSSL_EXPORT type *PEM_read_##name(FILE *fp, type **x, pem_password_cb *cb, void *u)\ +{ \ +return PEM_ASN1_read((d2i_of_void *)d2i_##asn1, str,fp,(void **)x,cb,u); \ +} + +#define IMPLEMENT_PEM_write_fp(name, type, str, asn1) \ +OPENSSL_EXPORT int PEM_write_##name(FILE *fp, type *x) \ +{ \ +return PEM_ASN1_write((i2d_of_void *)i2d_##asn1,str,fp,x,NULL,NULL,0,NULL,NULL); \ +} + +#define IMPLEMENT_PEM_write_fp_const(name, type, str, asn1) \ +OPENSSL_EXPORT int PEM_write_##name(FILE *fp, const type *x) \ +{ \ +return PEM_ASN1_write((i2d_of_void *)i2d_##asn1,str,fp,(void *)x,NULL,NULL,0,NULL,NULL); \ +} + +#define IMPLEMENT_PEM_write_cb_fp(name, type, str, asn1) \ +OPENSSL_EXPORT int PEM_write_##name(FILE *fp, type *x, const EVP_CIPHER *enc, \ + unsigned char *kstr, int klen, pem_password_cb *cb, \ + void *u) \ + { \ + return PEM_ASN1_write((i2d_of_void *)i2d_##asn1,str,fp,x,enc,kstr,klen,cb,u); \ + } + +#define IMPLEMENT_PEM_write_cb_fp_const(name, type, str, asn1) \ +OPENSSL_EXPORT int PEM_write_##name(FILE *fp, type *x, const EVP_CIPHER *enc, \ + unsigned char *kstr, int klen, pem_password_cb *cb, \ + void *u) \ + { \ + return PEM_ASN1_write((i2d_of_void *)i2d_##asn1,str,fp,x,enc,kstr,klen,cb,u); \ + } + +#endif + +#define IMPLEMENT_PEM_read_bio(name, type, str, asn1) \ +OPENSSL_EXPORT type *PEM_read_bio_##name(BIO *bp, type **x, pem_password_cb *cb, void *u)\ +{ \ +return PEM_ASN1_read_bio((d2i_of_void *)d2i_##asn1, str,bp,(void **)x,cb,u); \ +} + +#define IMPLEMENT_PEM_write_bio(name, type, str, asn1) \ +OPENSSL_EXPORT int PEM_write_bio_##name(BIO *bp, type *x) \ +{ \ +return PEM_ASN1_write_bio((i2d_of_void *)i2d_##asn1,str,bp,x,NULL,NULL,0,NULL,NULL); \ +} + +#define IMPLEMENT_PEM_write_bio_const(name, type, str, asn1) \ +OPENSSL_EXPORT int PEM_write_bio_##name(BIO *bp, const type *x) \ +{ \ +return PEM_ASN1_write_bio((i2d_of_void *)i2d_##asn1,str,bp,(void *)x,NULL,NULL,0,NULL,NULL); \ +} + +#define IMPLEMENT_PEM_write_cb_bio(name, type, str, asn1) \ +OPENSSL_EXPORT int PEM_write_bio_##name(BIO *bp, type *x, const EVP_CIPHER *enc, \ + unsigned char *kstr, int klen, pem_password_cb *cb, void *u) \ + { \ + return PEM_ASN1_write_bio((i2d_of_void *)i2d_##asn1,str,bp,x,enc,kstr,klen,cb,u); \ + } + +#define IMPLEMENT_PEM_write_cb_bio_const(name, type, str, asn1) \ +OPENSSL_EXPORT int PEM_write_bio_##name(BIO *bp, type *x, const EVP_CIPHER *enc, \ + unsigned char *kstr, int klen, pem_password_cb *cb, void *u) \ + { \ + return PEM_ASN1_write_bio((i2d_of_void *)i2d_##asn1,str,bp,(void *)x,enc,kstr,klen,cb,u); \ + } + +#define IMPLEMENT_PEM_write(name, type, str, asn1) \ + IMPLEMENT_PEM_write_bio(name, type, str, asn1) \ + IMPLEMENT_PEM_write_fp(name, type, str, asn1) + +#define IMPLEMENT_PEM_write_const(name, type, str, asn1) \ + IMPLEMENT_PEM_write_bio_const(name, type, str, asn1) \ + IMPLEMENT_PEM_write_fp_const(name, type, str, asn1) + +#define IMPLEMENT_PEM_write_cb(name, type, str, asn1) \ + IMPLEMENT_PEM_write_cb_bio(name, type, str, asn1) \ + IMPLEMENT_PEM_write_cb_fp(name, type, str, asn1) + +#define IMPLEMENT_PEM_write_cb_const(name, type, str, asn1) \ + IMPLEMENT_PEM_write_cb_bio_const(name, type, str, asn1) \ + IMPLEMENT_PEM_write_cb_fp_const(name, type, str, asn1) + +#define IMPLEMENT_PEM_read(name, type, str, asn1) \ + IMPLEMENT_PEM_read_bio(name, type, str, asn1) \ + IMPLEMENT_PEM_read_fp(name, type, str, asn1) + +#define IMPLEMENT_PEM_rw(name, type, str, asn1) \ + IMPLEMENT_PEM_read(name, type, str, asn1) \ + IMPLEMENT_PEM_write(name, type, str, asn1) + +#define IMPLEMENT_PEM_rw_const(name, type, str, asn1) \ + IMPLEMENT_PEM_read(name, type, str, asn1) \ + IMPLEMENT_PEM_write_const(name, type, str, asn1) + +#define IMPLEMENT_PEM_rw_cb(name, type, str, asn1) \ + IMPLEMENT_PEM_read(name, type, str, asn1) \ + IMPLEMENT_PEM_write_cb(name, type, str, asn1) + +/* These are the same except they are for the declarations */ + +#if defined(OPENSSL_NO_FP_API) + +#define DECLARE_PEM_read_fp(name, type) /**/ +#define DECLARE_PEM_write_fp(name, type) /**/ +#define DECLARE_PEM_write_cb_fp(name, type) /**/ + +#else + +#define DECLARE_PEM_read_fp(name, type) \ + OPENSSL_EXPORT type *PEM_read_##name(FILE *fp, type **x, pem_password_cb *cb, void *u); + +#define DECLARE_PEM_write_fp(name, type) \ + OPENSSL_EXPORT int PEM_write_##name(FILE *fp, type *x); + +#define DECLARE_PEM_write_fp_const(name, type) \ + OPENSSL_EXPORT int PEM_write_##name(FILE *fp, const type *x); + +#define DECLARE_PEM_write_cb_fp(name, type) \ + OPENSSL_EXPORT int PEM_write_##name(FILE *fp, type *x, const EVP_CIPHER *enc, \ + unsigned char *kstr, int klen, pem_password_cb *cb, void *u); + +#endif + +#define DECLARE_PEM_read_bio(name, type) \ + OPENSSL_EXPORT type *PEM_read_bio_##name(BIO *bp, type **x, pem_password_cb *cb, void *u); + +#define DECLARE_PEM_write_bio(name, type) \ + OPENSSL_EXPORT int PEM_write_bio_##name(BIO *bp, type *x); + +#define DECLARE_PEM_write_bio_const(name, type) \ + OPENSSL_EXPORT int PEM_write_bio_##name(BIO *bp, const type *x); + +#define DECLARE_PEM_write_cb_bio(name, type) \ + OPENSSL_EXPORT int PEM_write_bio_##name(BIO *bp, type *x, const EVP_CIPHER *enc, \ + unsigned char *kstr, int klen, pem_password_cb *cb, void *u); + + +#define DECLARE_PEM_write(name, type) \ + DECLARE_PEM_write_bio(name, type) \ + DECLARE_PEM_write_fp(name, type) + +#define DECLARE_PEM_write_const(name, type) \ + DECLARE_PEM_write_bio_const(name, type) \ + DECLARE_PEM_write_fp_const(name, type) + +#define DECLARE_PEM_write_cb(name, type) \ + DECLARE_PEM_write_cb_bio(name, type) \ + DECLARE_PEM_write_cb_fp(name, type) + +#define DECLARE_PEM_read(name, type) \ + DECLARE_PEM_read_bio(name, type) \ + DECLARE_PEM_read_fp(name, type) + +#define DECLARE_PEM_rw(name, type) \ + DECLARE_PEM_read(name, type) \ + DECLARE_PEM_write(name, type) + +#define DECLARE_PEM_rw_const(name, type) \ + DECLARE_PEM_read(name, type) \ + DECLARE_PEM_write_const(name, type) + +#define DECLARE_PEM_rw_cb(name, type) \ + DECLARE_PEM_read(name, type) \ + DECLARE_PEM_write_cb(name, type) + +/* "userdata": new with OpenSSL 0.9.4 */ +typedef int pem_password_cb(char *buf, int size, int rwflag, void *userdata); + +OPENSSL_EXPORT int PEM_get_EVP_CIPHER_INFO(char *header, EVP_CIPHER_INFO *cipher); +OPENSSL_EXPORT int PEM_do_header (EVP_CIPHER_INFO *cipher, unsigned char *data,long *len, pem_password_cb *callback,void *u); + +OPENSSL_EXPORT int PEM_read_bio(BIO *bp, char **name, char **header, unsigned char **data,long *len); +OPENSSL_EXPORT int PEM_write_bio(BIO *bp,const char *name, const char *hdr, const unsigned char *data, long len); +OPENSSL_EXPORT int PEM_bytes_read_bio(unsigned char **pdata, long *plen, char **pnm, const char *name, BIO *bp, pem_password_cb *cb, void *u); +OPENSSL_EXPORT void * PEM_ASN1_read_bio(d2i_of_void *d2i, const char *name, BIO *bp, void **x, pem_password_cb *cb, void *u); +OPENSSL_EXPORT int PEM_ASN1_write_bio(i2d_of_void *i2d,const char *name,BIO *bp, void *x, const EVP_CIPHER *enc,unsigned char *kstr,int klen, pem_password_cb *cb, void *u); + +OPENSSL_EXPORT STACK_OF(X509_INFO) * PEM_X509_INFO_read_bio(BIO *bp, STACK_OF(X509_INFO) *sk, pem_password_cb *cb, void *u); +OPENSSL_EXPORT int PEM_X509_INFO_write_bio(BIO *bp,X509_INFO *xi, EVP_CIPHER *enc, unsigned char *kstr, int klen, pem_password_cb *cd, void *u); + +OPENSSL_EXPORT int PEM_read(FILE *fp, char **name, char **header, unsigned char **data,long *len); +OPENSSL_EXPORT int PEM_write(FILE *fp, const char *name, const char *hdr, const unsigned char *data, long len); +OPENSSL_EXPORT void * PEM_ASN1_read(d2i_of_void *d2i, const char *name, FILE *fp, void **x, pem_password_cb *cb, void *u); +OPENSSL_EXPORT int PEM_ASN1_write(i2d_of_void *i2d,const char *name,FILE *fp, void *x,const EVP_CIPHER *enc,unsigned char *kstr, int klen,pem_password_cb *callback, void *u); +OPENSSL_EXPORT STACK_OF(X509_INFO) * PEM_X509_INFO_read(FILE *fp, STACK_OF(X509_INFO) *sk, pem_password_cb *cb, void *u); + +OPENSSL_EXPORT int PEM_SealInit(PEM_ENCODE_SEAL_CTX *ctx, EVP_CIPHER *type, EVP_MD *md_type, unsigned char **ek, int *ekl, unsigned char *iv, EVP_PKEY **pubk, int npubk); +OPENSSL_EXPORT void PEM_SealUpdate(PEM_ENCODE_SEAL_CTX *ctx, unsigned char *out, int *outl, unsigned char *in, int inl); +OPENSSL_EXPORT int PEM_SealFinal(PEM_ENCODE_SEAL_CTX *ctx, unsigned char *sig,int *sigl, unsigned char *out, int *outl, EVP_PKEY *priv); + +OPENSSL_EXPORT void PEM_SignInit(EVP_MD_CTX *ctx, EVP_MD *type); +OPENSSL_EXPORT void PEM_SignUpdate(EVP_MD_CTX *ctx,unsigned char *d,unsigned int cnt); +OPENSSL_EXPORT int PEM_SignFinal(EVP_MD_CTX *ctx, unsigned char *sigret, unsigned int *siglen, EVP_PKEY *pkey); + +/* |PEM_def_callback| treats |userdata| as a string and copies it into |buf|, + * assuming its |size| is sufficient. Returns the length of the string, or 0 + * if there is not enough room. If either |buf| or |userdata| is NULL, 0 is + * returned. Note that this is different from OpenSSL, which prompts for a + * password. */ +OPENSSL_EXPORT int PEM_def_callback(char *buf, int size, int rwflag, void *userdata); +OPENSSL_EXPORT void PEM_proc_type(char *buf, int type); +OPENSSL_EXPORT void PEM_dek_info(char *buf, const char *type, int len, char *str); + + +DECLARE_PEM_rw(X509, X509) + +DECLARE_PEM_rw(X509_AUX, X509) + +DECLARE_PEM_rw(X509_CERT_PAIR, X509_CERT_PAIR) + +DECLARE_PEM_rw(X509_REQ, X509_REQ) +DECLARE_PEM_write(X509_REQ_NEW, X509_REQ) + +DECLARE_PEM_rw(X509_CRL, X509_CRL) + +/* DECLARE_PEM_rw(PKCS7, PKCS7) */ + +DECLARE_PEM_rw(NETSCAPE_CERT_SEQUENCE, NETSCAPE_CERT_SEQUENCE) + +DECLARE_PEM_rw(PKCS8, X509_SIG) + +DECLARE_PEM_rw(PKCS8_PRIV_KEY_INFO, PKCS8_PRIV_KEY_INFO) + +DECLARE_PEM_rw_cb(RSAPrivateKey, RSA) + +DECLARE_PEM_rw_const(RSAPublicKey, RSA) +DECLARE_PEM_rw(RSA_PUBKEY, RSA) + +#ifndef OPENSSL_NO_DSA + +DECLARE_PEM_rw_cb(DSAPrivateKey, DSA) + +DECLARE_PEM_rw(DSA_PUBKEY, DSA) + +DECLARE_PEM_rw_const(DSAparams, DSA) + +#endif + +DECLARE_PEM_rw_const(ECPKParameters, EC_GROUP) +DECLARE_PEM_rw_cb(ECPrivateKey, EC_KEY) +DECLARE_PEM_rw(EC_PUBKEY, EC_KEY) + + +DECLARE_PEM_rw_const(DHparams, DH) +DECLARE_PEM_write_const(DHxparams, DH) + + +DECLARE_PEM_rw_cb(PrivateKey, EVP_PKEY) + +DECLARE_PEM_rw(PUBKEY, EVP_PKEY) + +OPENSSL_EXPORT int PEM_write_bio_PKCS8PrivateKey_nid(BIO *bp, EVP_PKEY *x, int nid, char *kstr, int klen, pem_password_cb *cb, void *u); +OPENSSL_EXPORT int PEM_write_bio_PKCS8PrivateKey(BIO *, EVP_PKEY *, const EVP_CIPHER *, char *, int, pem_password_cb *, void *); +OPENSSL_EXPORT int i2d_PKCS8PrivateKey_bio(BIO *bp, EVP_PKEY *x, const EVP_CIPHER *enc, char *kstr, int klen, pem_password_cb *cb, void *u); +OPENSSL_EXPORT int i2d_PKCS8PrivateKey_nid_bio(BIO *bp, EVP_PKEY *x, int nid, char *kstr, int klen, pem_password_cb *cb, void *u); +OPENSSL_EXPORT EVP_PKEY *d2i_PKCS8PrivateKey_bio(BIO *bp, EVP_PKEY **x, pem_password_cb *cb, void *u); + +OPENSSL_EXPORT int i2d_PKCS8PrivateKey_fp(FILE *fp, EVP_PKEY *x, const EVP_CIPHER *enc, char *kstr, int klen, pem_password_cb *cb, void *u); +OPENSSL_EXPORT int i2d_PKCS8PrivateKey_nid_fp(FILE *fp, EVP_PKEY *x, int nid, char *kstr, int klen, pem_password_cb *cb, void *u); +OPENSSL_EXPORT int PEM_write_PKCS8PrivateKey_nid(FILE *fp, EVP_PKEY *x, int nid, char *kstr, int klen, pem_password_cb *cb, void *u); + +OPENSSL_EXPORT EVP_PKEY *d2i_PKCS8PrivateKey_fp(FILE *fp, EVP_PKEY **x, pem_password_cb *cb, void *u); + +OPENSSL_EXPORT int PEM_write_PKCS8PrivateKey(FILE *fp,EVP_PKEY *x,const EVP_CIPHER *enc, char *kstr,int klen, pem_password_cb *cd, void *u); + +OPENSSL_EXPORT EVP_PKEY *PEM_read_bio_Parameters(BIO *bp, EVP_PKEY **x); +OPENSSL_EXPORT int PEM_write_bio_Parameters(BIO *bp, EVP_PKEY *x); + + +OPENSSL_EXPORT EVP_PKEY *b2i_PrivateKey(const unsigned char **in, long length); +OPENSSL_EXPORT EVP_PKEY *b2i_PublicKey(const unsigned char **in, long length); +OPENSSL_EXPORT EVP_PKEY *b2i_PrivateKey_bio(BIO *in); +OPENSSL_EXPORT EVP_PKEY *b2i_PublicKey_bio(BIO *in); +OPENSSL_EXPORT int i2b_PrivateKey_bio(BIO *out, EVP_PKEY *pk); +OPENSSL_EXPORT int i2b_PublicKey_bio(BIO *out, EVP_PKEY *pk); +OPENSSL_EXPORT EVP_PKEY *b2i_PVK_bio(BIO *in, pem_password_cb *cb, void *u); +OPENSSL_EXPORT int i2b_PVK_bio(BIO *out, EVP_PKEY *pk, int enclevel, pem_password_cb *cb, void *u); + + +void ERR_load_PEM_strings(void); + + +#ifdef __cplusplus +} +#endif + +#define PEM_F_PEM_ASN1_read 100 +#define PEM_F_PEM_ASN1_read_bio 101 +#define PEM_F_PEM_ASN1_write 102 +#define PEM_F_PEM_ASN1_write_bio 103 +#define PEM_F_PEM_X509_INFO_read 104 +#define PEM_F_PEM_X509_INFO_read_bio 105 +#define PEM_F_PEM_X509_INFO_write_bio 106 +#define PEM_F_PEM_do_header 107 +#define PEM_F_PEM_get_EVP_CIPHER_INFO 108 +#define PEM_F_PEM_read 109 +#define PEM_F_PEM_read_DHparams 110 +#define PEM_F_PEM_read_PrivateKey 111 +#define PEM_F_PEM_read_bio 112 +#define PEM_F_PEM_read_bio_DHparams 113 +#define PEM_F_PEM_read_bio_Parameters 114 +#define PEM_F_PEM_read_bio_PrivateKey 115 +#define PEM_F_PEM_write 116 +#define PEM_F_PEM_write_PrivateKey 117 +#define PEM_F_PEM_write_bio 118 +#define PEM_F_d2i_PKCS8PrivateKey_bio 119 +#define PEM_F_d2i_PKCS8PrivateKey_fp 120 +#define PEM_F_do_pk8pkey 121 +#define PEM_F_do_pk8pkey_fp 122 +#define PEM_F_load_iv 123 +#define PEM_R_BAD_BASE64_DECODE 100 +#define PEM_R_BAD_DECRYPT 101 +#define PEM_R_BAD_END_LINE 102 +#define PEM_R_BAD_IV_CHARS 103 +#define PEM_R_BAD_PASSWORD_READ 104 +#define PEM_R_CIPHER_IS_NULL 105 +#define PEM_R_ERROR_CONVERTING_PRIVATE_KEY 106 +#define PEM_R_NOT_DEK_INFO 107 +#define PEM_R_NOT_ENCRYPTED 108 +#define PEM_R_NOT_PROC_TYPE 109 +#define PEM_R_NO_START_LINE 110 +#define PEM_R_READ_KEY 111 +#define PEM_R_SHORT_HEADER 112 +#define PEM_R_UNSUPPORTED_CIPHER 113 +#define PEM_R_UNSUPPORTED_ENCRYPTION 114 + +#endif /* OPENSSL_HEADER_PEM_H */ diff --git a/phonelibs/boringssl/include/openssl/pkcs12.h b/phonelibs/boringssl/include/openssl/pkcs12.h new file mode 100644 index 00000000000000..b5e951638275f8 --- /dev/null +++ b/phonelibs/boringssl/include/openssl/pkcs12.h @@ -0,0 +1,18 @@ +/* Copyright (c) 2014, Google Inc. + * + * Permission to use, copy, modify, and/or distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY + * SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN ACTION + * OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF OR IN + * CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. */ + +/* This header is provided in order to make compiling against code that expects + OpenSSL easier. */ + +#include "pkcs8.h" diff --git a/phonelibs/boringssl/include/openssl/pkcs7.h b/phonelibs/boringssl/include/openssl/pkcs7.h new file mode 100644 index 00000000000000..6e5e433074f867 --- /dev/null +++ b/phonelibs/boringssl/include/openssl/pkcs7.h @@ -0,0 +1,16 @@ +/* Copyright (c) 2014, Google Inc. + * + * Permission to use, copy, modify, and/or distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY + * SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN ACTION + * OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF OR IN + * CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. */ + +/* This header is provided in order to make compiling against code that expects + OpenSSL easier. */ diff --git a/phonelibs/boringssl/include/openssl/pkcs8.h b/phonelibs/boringssl/include/openssl/pkcs8.h new file mode 100644 index 00000000000000..8dc7731bf5f349 --- /dev/null +++ b/phonelibs/boringssl/include/openssl/pkcs8.h @@ -0,0 +1,217 @@ +/* Written by Dr Stephen N Henson (steve@openssl.org) for the OpenSSL + * project 1999. + */ +/* ==================================================================== + * Copyright (c) 1999 The OpenSSL Project. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * + * 3. All advertising materials mentioning features or use of this + * software must display the following acknowledgment: + * "This product includes software developed by the OpenSSL Project + * for use in the OpenSSL Toolkit. (http://www.OpenSSL.org/)" + * + * 4. The names "OpenSSL Toolkit" and "OpenSSL Project" must not be used to + * endorse or promote products derived from this software without + * prior written permission. For written permission, please contact + * licensing@OpenSSL.org. + * + * 5. Products derived from this software may not be called "OpenSSL" + * nor may "OpenSSL" appear in their names without prior written + * permission of the OpenSSL Project. + * + * 6. Redistributions of any form whatsoever must retain the following + * acknowledgment: + * "This product includes software developed by the OpenSSL Project + * for use in the OpenSSL Toolkit (http://www.OpenSSL.org/)" + * + * THIS SOFTWARE IS PROVIDED BY THE OpenSSL PROJECT ``AS IS'' AND ANY + * EXPRESSED OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR + * PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE OpenSSL PROJECT OR + * ITS CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, + * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT + * NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + * STRICT LIABILITY, OR TORT (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 product includes cryptographic software written by Eric Young + * (eay@cryptsoft.com). This product includes software written by Tim + * Hudson (tjh@cryptsoft.com). */ + + +#ifndef OPENSSL_HEADER_PKCS8_H +#define OPENSSL_HEADER_PKCS8_H + +#include +#include + + +#if defined(__cplusplus) +extern "C" { +#endif + + +/* PKCS8_encrypt_pbe serializes and encrypts a PKCS8_PRIV_KEY_INFO with PBES1 as + * defined in PKCS #5. Only pbeWithSHAAnd128BitRC4, + * pbeWithSHAAnd3-KeyTripleDES-CBC and pbeWithSHA1And40BitRC2, defined in PKCS + * #12, are supported. The |pass_raw_len| bytes pointed to by |pass_raw| are + * used as the password. Note that any conversions from the password as + * supplied in a text string (such as those specified in B.1 of PKCS #12) must + * be performed by the caller. + * + * If |salt| is NULL, a random salt of |salt_len| bytes is generated. If + * |salt_len| is zero, a default salt length is used instead. + * + * The resulting structure is stored in an X509_SIG which must be freed by the + * caller. + * + * TODO(davidben): Really? An X509_SIG? OpenSSL probably did that because it has + * the same structure as EncryptedPrivateKeyInfo. */ +OPENSSL_EXPORT X509_SIG *PKCS8_encrypt_pbe(int pbe_nid, + const uint8_t *pass_raw, + size_t pass_raw_len, + uint8_t *salt, size_t salt_len, + int iterations, + PKCS8_PRIV_KEY_INFO *p8inf); + +/* PKCS8_decrypt_pbe decrypts and decodes a PKCS8_PRIV_KEY_INFO with PBES1 as + * defined in PKCS #5. Only pbeWithSHAAnd128BitRC4, + * pbeWithSHAAnd3-KeyTripleDES-CBC and pbeWithSHA1And40BitRC2, defined in PKCS + * #12, are supported. The |pass_raw_len| bytes pointed to by |pass_raw| are + * used as the password. Note that any conversions from the password as + * supplied in a text string (such as those specified in B.1 of PKCS #12) must + * be performed by the caller. + * + * The resulting structure must be freed by the caller. */ +OPENSSL_EXPORT PKCS8_PRIV_KEY_INFO *PKCS8_decrypt_pbe(X509_SIG *pkcs8, + const uint8_t *pass_raw, + size_t pass_raw_len); + + +/* Deprecated functions. */ + +/* PKCS8_encrypt calls PKCS8_encrypt_pbe after treating |pass| as an ASCII + * string, appending U+0000, and converting to UCS-2. (So the empty password + * encodes as two NUL bytes.) The |cipher| argument is ignored. */ +OPENSSL_EXPORT X509_SIG *PKCS8_encrypt(int pbe_nid, const EVP_CIPHER *cipher, + const char *pass, int pass_len, + uint8_t *salt, size_t salt_len, + int iterations, + PKCS8_PRIV_KEY_INFO *p8inf); + +/* PKCS8_decrypt calls PKCS8_decrypt_pbe after treating |pass| as an ASCII + * string, appending U+0000, and converting to UCS-2. (So the empty password + * encodes as two NUL bytes.) */ +OPENSSL_EXPORT PKCS8_PRIV_KEY_INFO *PKCS8_decrypt(X509_SIG *pkcs8, + const char *pass, + int pass_len); + +/* PKCS12_get_key_and_certs parses a PKCS#12 structure from |in|, authenticates + * and decrypts it using |password|, sets |*out_key| to the included private + * key and appends the included certificates to |out_certs|. It returns one on + * success and zero on error. The caller takes ownership of the outputs. */ +OPENSSL_EXPORT int PKCS12_get_key_and_certs(EVP_PKEY **out_key, + STACK_OF(X509) *out_certs, + CBS *in, const char *password); + + +/* Deprecated functions. */ + +/* PKCS12_PBE_add does nothing. It exists for compatibility with OpenSSL. */ +OPENSSL_EXPORT void PKCS12_PBE_add(void); + +/* d2i_PKCS12 is a dummy function that copies |*ber_bytes| into a + * |PKCS12| structure. The |out_p12| argument must be NULL. On exit, + * |*ber_bytes| will be advanced by |ber_len|. It returns a fresh |PKCS12| + * structure or NULL on error. + * + * Note: unlike other d2i functions, |d2i_PKCS12| will always consume |ber_len| + * bytes.*/ +OPENSSL_EXPORT PKCS12 *d2i_PKCS12(PKCS12 **out_p12, const uint8_t **ber_bytes, + size_t ber_len); + +/* d2i_PKCS12_bio acts like |d2i_PKCS12| but reads from a |BIO|. */ +OPENSSL_EXPORT PKCS12* d2i_PKCS12_bio(BIO *bio, PKCS12 **out_p12); + +/* d2i_PKCS12_fp acts like |d2i_PKCS12| but reads from a |FILE|. */ +OPENSSL_EXPORT PKCS12* d2i_PKCS12_fp(FILE *fp, PKCS12 **out_p12); + +/* PKCS12_parse calls |PKCS12_get_key_and_certs| on the ASN.1 data stored in + * |p12|. The |out_pkey| and |out_cert| arguments must not be NULL and, on + * successful exit, the private key and first certificate will be stored in + * them. The |out_ca_certs| argument may be NULL but, if not, then any extra + * certificates will be appended to |*out_ca_certs|. If |*out_ca_certs| is NULL + * then it will be set to a freshly allocated stack containing the extra certs. + * + * It returns one on success and zero on error. */ +OPENSSL_EXPORT int PKCS12_parse(const PKCS12 *p12, const char *password, + EVP_PKEY **out_pkey, X509 **out_cert, + STACK_OF(X509) **out_ca_certs); + +/* PKCS12_free frees |p12| and its contents. */ +OPENSSL_EXPORT void PKCS12_free(PKCS12 *p12); + +#if defined(__cplusplus) +} /* extern C */ +#endif + +#define PKCS8_F_EVP_PKCS82PKEY 100 +#define PKCS8_F_EVP_PKEY2PKCS8 101 +#define PKCS8_F_PKCS12_get_key_and_certs 102 +#define PKCS8_F_PKCS12_handle_content_info 103 +#define PKCS8_F_PKCS12_handle_content_infos 104 +#define PKCS8_F_PKCS5_pbe2_set_iv 105 +#define PKCS8_F_PKCS5_pbe_set 106 +#define PKCS8_F_PKCS5_pbe_set0_algor 107 +#define PKCS8_F_PKCS5_pbkdf2_set 108 +#define PKCS8_F_PKCS8_decrypt 109 +#define PKCS8_F_PKCS8_encrypt 110 +#define PKCS8_F_PKCS8_encrypt_pbe 111 +#define PKCS8_F_pbe_cipher_init 112 +#define PKCS8_F_pbe_crypt 113 +#define PKCS8_F_pkcs12_item_decrypt_d2i 114 +#define PKCS8_F_pkcs12_item_i2d_encrypt 115 +#define PKCS8_F_pkcs12_key_gen_raw 116 +#define PKCS8_F_pkcs12_pbe_keyivgen 117 +#define PKCS8_R_BAD_PKCS12_DATA 100 +#define PKCS8_R_BAD_PKCS12_VERSION 101 +#define PKCS8_R_CIPHER_HAS_NO_OBJECT_IDENTIFIER 102 +#define PKCS8_R_CRYPT_ERROR 103 +#define PKCS8_R_DECODE_ERROR 104 +#define PKCS8_R_ENCODE_ERROR 105 +#define PKCS8_R_ENCRYPT_ERROR 106 +#define PKCS8_R_ERROR_SETTING_CIPHER_PARAMS 107 +#define PKCS8_R_INCORRECT_PASSWORD 108 +#define PKCS8_R_KEYGEN_FAILURE 109 +#define PKCS8_R_KEY_GEN_ERROR 110 +#define PKCS8_R_METHOD_NOT_SUPPORTED 111 +#define PKCS8_R_MISSING_MAC 112 +#define PKCS8_R_MULTIPLE_PRIVATE_KEYS_IN_PKCS12 113 +#define PKCS8_R_PKCS12_PUBLIC_KEY_INTEGRITY_NOT_SUPPORTED 114 +#define PKCS8_R_PKCS12_TOO_DEEPLY_NESTED 115 +#define PKCS8_R_PRIVATE_KEY_DECODE_ERROR 116 +#define PKCS8_R_PRIVATE_KEY_ENCODE_ERROR 117 +#define PKCS8_R_TOO_LONG 118 +#define PKCS8_R_UNKNOWN_ALGORITHM 119 +#define PKCS8_R_UNKNOWN_CIPHER 120 +#define PKCS8_R_UNKNOWN_CIPHER_ALGORITHM 121 +#define PKCS8_R_UNKNOWN_DIGEST 122 +#define PKCS8_R_UNKNOWN_HASH 123 +#define PKCS8_R_UNSUPPORTED_PRIVATE_KEY_ALGORITHM 124 + +#endif /* OPENSSL_HEADER_PKCS8_H */ diff --git a/phonelibs/boringssl/include/openssl/poly1305.h b/phonelibs/boringssl/include/openssl/poly1305.h new file mode 100644 index 00000000000000..aa904869ce5f17 --- /dev/null +++ b/phonelibs/boringssl/include/openssl/poly1305.h @@ -0,0 +1,47 @@ +/* Copyright (c) 2014, Google Inc. + * + * Permission to use, copy, modify, and/or distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY + * SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN ACTION + * OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF OR IN + * CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. */ + +#ifndef OPENSSL_HEADER_POLY1305_H +#define OPENSSL_HEADER_POLY1305_H + +#include + +#ifdef __cplusplus +extern "C" { +#endif + + +typedef unsigned char poly1305_state[512]; + +/* poly1305_init sets up |state| so that it can be used to calculate an + * authentication tag with the one-time key |key|. Note that |key| is a + * one-time key and therefore there is no `reset' method because that would + * enable several messages to be authenticated with the same key. */ +extern void CRYPTO_poly1305_init(poly1305_state* state, const uint8_t key[32]); + +/* poly1305_update processes |in_len| bytes from |in|. It can be called zero or + * more times after poly1305_init. */ +extern void CRYPTO_poly1305_update(poly1305_state* state, const uint8_t* in, + size_t in_len); + +/* poly1305_finish completes the poly1305 calculation and writes a 16 byte + * authentication tag to |mac|. The |mac| address must be 16-byte aligned. */ +extern void CRYPTO_poly1305_finish(poly1305_state* state, uint8_t mac[16]); + + +#if defined(__cplusplus) +} /* extern C */ +#endif + +#endif /* OPENSSL_HEADER_POLY1305_H */ diff --git a/phonelibs/boringssl/include/openssl/pqueue.h b/phonelibs/boringssl/include/openssl/pqueue.h new file mode 100644 index 00000000000000..ceb1fa2a749757 --- /dev/null +++ b/phonelibs/boringssl/include/openssl/pqueue.h @@ -0,0 +1,146 @@ +/* + * DTLS implementation written by Nagendra Modadugu + * (nagendra@cs.stanford.edu) for the OpenSSL project 2005. + */ +/* ==================================================================== + * Copyright (c) 1999-2005 The OpenSSL Project. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * + * 3. All advertising materials mentioning features or use of this + * software must display the following acknowledgment: + * "This product includes software developed by the OpenSSL Project + * for use in the OpenSSL Toolkit. (http://www.OpenSSL.org/)" + * + * 4. The names "OpenSSL Toolkit" and "OpenSSL Project" must not be used to + * endorse or promote products derived from this software without + * prior written permission. For written permission, please contact + * openssl-core@OpenSSL.org. + * + * 5. Products derived from this software may not be called "OpenSSL" + * nor may "OpenSSL" appear in their names without prior written + * permission of the OpenSSL Project. + * + * 6. Redistributions of any form whatsoever must retain the following + * acknowledgment: + * "This product includes software developed by the OpenSSL Project + * for use in the OpenSSL Toolkit (http://www.OpenSSL.org/)" + * + * THIS SOFTWARE IS PROVIDED BY THE OpenSSL PROJECT ``AS IS'' AND ANY + * EXPRESSED OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR + * PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE OpenSSL PROJECT OR + * ITS CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, + * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT + * NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + * STRICT LIABILITY, OR TORT (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 product includes cryptographic software written by Eric Young + * (eay@cryptsoft.com). This product includes software written by Tim + * Hudson (tjh@cryptsoft.com). */ + +#ifndef OPENSSL_HEADER_PQUEUE_H +#define OPENSSL_HEADER_PQUEUE_H + +#include + +#if defined(__cplusplus) +extern "C" { +#endif + + +/* Priority queue. + * + * The priority queue maintains a linked-list of nodes, each with a unique, + * 64-bit priority, in ascending priority order. */ + +typedef struct _pqueue *pqueue; + +typedef struct _pitem { + uint8_t priority[8]; /* 64-bit value in big-endian encoding */ + void *data; + struct _pitem *next; +} pitem; + +typedef struct _pitem *piterator; + + +/* Creating and freeing queues. */ + +/* pqueue_new allocates a fresh, empty priority queue object and returns it, or + * NULL on error. */ +OPENSSL_EXPORT pqueue pqueue_new(void); + +/* pqueue_free frees |pq| but not any of the items it points to. Thus |pq| must + * be empty or a memory leak will occur. */ +OPENSSL_EXPORT void pqueue_free(pqueue pq); + + +/* Creating and freeing items. */ + +/* pitem_new allocates a fresh priority queue item that points at |data| and + * has a priority given by |prio64be|, which is a 64-bit, unsigned number + * expressed in big-endian form. It returns the fresh item, or NULL on + * error. */ +OPENSSL_EXPORT pitem *pitem_new(uint8_t prio64be[8], void *data); + +/* pitem_free frees |item|, but not any data that it points to. */ +OPENSSL_EXPORT void pitem_free(pitem *item); + + +/* Queue accessor functions */ + +/* pqueue_peek returns the item with the smallest priority from |pq|, or NULL + * if empty. */ +OPENSSL_EXPORT pitem *pqueue_peek(pqueue pq); + +/* pqueue_find returns the item whose priority matches |prio64be| or NULL if no + * such item exists. */ +OPENSSL_EXPORT pitem *pqueue_find(pqueue pq, uint8_t *prio64be); + + +/* Queue mutation functions */ + +/* pqueue_insert inserts |item| into |pq| and returns item. */ +OPENSSL_EXPORT pitem *pqueue_insert(pqueue pq, pitem *item); + +/* pqueue_pop takes the item with the least priority from |pq| and returns it, + * or NULL if |pq| is empty. */ +OPENSSL_EXPORT pitem *pqueue_pop(pqueue pq); + +/* pqueue_size returns the number of items in |pq|. */ +OPENSSL_EXPORT size_t pqueue_size(pqueue pq); + + +/* Iterating */ + +/* pqueue_iterator returns an iterator that can be used to iterate over the + * contents of the queue. */ +OPENSSL_EXPORT piterator pqueue_iterator(pqueue pq); + +/* pqueue_next returns the current value of |iter| and advances it to the next + * position. If the iterator has advanced over all the elements, it returns + * NULL. */ +OPENSSL_EXPORT pitem *pqueue_next(piterator *iter); + + +#if defined(__cplusplus) +} /* extern C */ +#endif + +#endif /* OPENSSL_HEADER_PQUEUE_H */ diff --git a/phonelibs/boringssl/include/openssl/rand.h b/phonelibs/boringssl/include/openssl/rand.h new file mode 100644 index 00000000000000..300bf422877c6a --- /dev/null +++ b/phonelibs/boringssl/include/openssl/rand.h @@ -0,0 +1,61 @@ +/* Copyright (c) 2014, Google Inc. + * + * Permission to use, copy, modify, and/or distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY + * SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN ACTION + * OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF OR IN + * CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. */ + +#ifndef OPENSSL_HEADER_RAND_H +#define OPENSSL_HEADER_RAND_H + +#include + +#if defined(__cplusplus) +extern "C" { +#endif + + +/* Random number generation. */ + + +/* RAND_bytes writes |len| bytes of random data to |buf| and returns one. */ +OPENSSL_EXPORT int RAND_bytes(uint8_t *buf, size_t len); + +/* RAND_cleanup frees any resources used by the RNG. This is not safe if other + * threads might still be calling |RAND_bytes|. */ +OPENSSL_EXPORT void RAND_cleanup(void); + + +/* Deprecated functions */ + +/* RAND_pseudo_bytes is a wrapper around |RAND_bytes|. */ +OPENSSL_EXPORT int RAND_pseudo_bytes(uint8_t *buf, size_t len); + +/* RAND_seed does nothing. */ +OPENSSL_EXPORT void RAND_seed(const void *buf, int num); + +/* RAND_load_file returns a nonnegative number. */ +OPENSSL_EXPORT int RAND_load_file(const char *path, long num); + +/* RAND_add does nothing. */ +OPENSSL_EXPORT void RAND_add(const void *buf, int num, double entropy); + +/* RAND_poll returns one. */ +OPENSSL_EXPORT int RAND_poll(void); + +/* RAND_status returns one. */ +OPENSSL_EXPORT int RAND_status(void); + + +#if defined(__cplusplus) +} /* extern C */ +#endif + +#endif /* OPENSSL_HEADER_RAND_H */ diff --git a/phonelibs/boringssl/include/openssl/rc4.h b/phonelibs/boringssl/include/openssl/rc4.h new file mode 100644 index 00000000000000..0619cac35507fc --- /dev/null +++ b/phonelibs/boringssl/include/openssl/rc4.h @@ -0,0 +1,90 @@ +/* Copyright (C) 1995-1998 Eric Young (eay@cryptsoft.com) + * All rights reserved. + * + * This package is an SSL implementation written + * by Eric Young (eay@cryptsoft.com). + * The implementation was written so as to conform with Netscapes SSL. + * + * This library is free for commercial and non-commercial use as long as + * the following conditions are aheared to. The following conditions + * apply to all code found in this distribution, be it the RC4, RSA, + * lhash, DES, etc., code; not just the SSL code. The SSL documentation + * included with this distribution is covered by the same copyright terms + * except that the holder is Tim Hudson (tjh@cryptsoft.com). + * + * Copyright remains Eric Young's, and as such any Copyright notices in + * the code are not to be removed. + * If this package is used in a product, Eric Young should be given attribution + * as the author of the parts of the library used. + * This can be in the form of a textual message at program startup or + * in documentation (online or textual) provided with the package. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must 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. All advertising materials mentioning features or use of this software + * must display the following acknowledgement: + * "This product includes cryptographic software written by + * Eric Young (eay@cryptsoft.com)" + * The word 'cryptographic' can be left out if the rouines from the library + * being used are not cryptographic related :-). + * 4. If you include any Windows specific code (or a derivative thereof) from + * the apps directory (application code) you must include an acknowledgement: + * "This product includes software written by Tim Hudson (tjh@cryptsoft.com)" + * + * THIS SOFTWARE IS PROVIDED BY ERIC YOUNG ``AS IS'' AND + * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHOR OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (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 licence and distribution terms for any publically available version or + * derivative of this code cannot be changed. i.e. this code cannot simply be + * copied and put under another distribution licence + * [including the GNU Public Licence.] */ + +#ifndef OPENSSL_HEADER_RC4_H +#define OPENSSL_HEADER_RC4_H + +#include + +#if defined(__cplusplus) +extern "C" { +#endif + + +/* RC4. */ + + +struct rc4_key_st { + uint32_t x, y; + uint32_t data[256]; +} /* RC4_KEY */; + +/* RC4_set_key performs an RC4 key schedule and initialises |rc4key| with |len| + * bytes of key material from |key|. */ +OPENSSL_EXPORT void RC4_set_key(RC4_KEY *rc4key, unsigned len, + const uint8_t *key); + +/* RC4 encrypts (or decrypts, it's the same with RC4) |len| bytes from |in| to + * |out|. */ +OPENSSL_EXPORT void RC4(RC4_KEY *key, size_t len, const uint8_t *in, + uint8_t *out); + + +#if defined(__cplusplus) +} /* extern C */ +#endif + +#endif /* OPENSSL_HEADER_RC4_H */ diff --git a/phonelibs/boringssl/include/openssl/rsa.h b/phonelibs/boringssl/include/openssl/rsa.h new file mode 100644 index 00000000000000..9b415d75e1b141 --- /dev/null +++ b/phonelibs/boringssl/include/openssl/rsa.h @@ -0,0 +1,575 @@ +/* Copyright (C) 1995-1998 Eric Young (eay@cryptsoft.com) + * All rights reserved. + * + * This package is an SSL implementation written + * by Eric Young (eay@cryptsoft.com). + * The implementation was written so as to conform with Netscapes SSL. + * + * This library is free for commercial and non-commercial use as long as + * the following conditions are aheared to. The following conditions + * apply to all code found in this distribution, be it the RC4, RSA, + * lhash, DES, etc., code; not just the SSL code. The SSL documentation + * included with this distribution is covered by the same copyright terms + * except that the holder is Tim Hudson (tjh@cryptsoft.com). + * + * Copyright remains Eric Young's, and as such any Copyright notices in + * the code are not to be removed. + * If this package is used in a product, Eric Young should be given attribution + * as the author of the parts of the library used. + * This can be in the form of a textual message at program startup or + * in documentation (online or textual) provided with the package. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must 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. All advertising materials mentioning features or use of this software + * must display the following acknowledgement: + * "This product includes cryptographic software written by + * Eric Young (eay@cryptsoft.com)" + * The word 'cryptographic' can be left out if the rouines from the library + * being used are not cryptographic related :-). + * 4. If you include any Windows specific code (or a derivative thereof) from + * the apps directory (application code) you must include an acknowledgement: + * "This product includes software written by Tim Hudson (tjh@cryptsoft.com)" + * + * THIS SOFTWARE IS PROVIDED BY ERIC YOUNG ``AS IS'' AND + * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHOR OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (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 licence and distribution terms for any publically available version or + * derivative of this code cannot be changed. i.e. this code cannot simply be + * copied and put under another distribution licence + * [including the GNU Public Licence.] */ + +#ifndef OPENSSL_HEADER_RSA_H +#define OPENSSL_HEADER_RSA_H + +#include + +#include +#include +#include + +#if defined(__cplusplus) +extern "C" { +#endif + + +/* rsa.h contains functions for handling encryption and signature using RSA. */ + + +/* Allocation and destruction. */ + +/* RSA_new returns a new, empty RSA object or NULL on error. */ +OPENSSL_EXPORT RSA *RSA_new(void); + +/* RSA_new_method acts the same as |RSA_new| but takes an explicit |ENGINE|. */ +OPENSSL_EXPORT RSA *RSA_new_method(const ENGINE *engine); + +/* RSA_free decrements the reference count of |rsa| and frees it if the + * reference count drops to zero. */ +OPENSSL_EXPORT void RSA_free(RSA *rsa); + +/* RSA_up_ref increments the reference count of |rsa|. */ +OPENSSL_EXPORT int RSA_up_ref(RSA *rsa); + + +/* Key generation. */ + +/* RSA_generate_key_ex generates a new RSA key where the modulus has size + * |bits| and the public exponent is |e|. If unsure, |RSA_F4| is a good value + * for |e|. If |cb| is not NULL then it is called during the key generation + * process. In addition to the calls documented for |BN_generate_prime_ex|, it + * is called with event=2 when the n'th prime is rejected as unsuitable and + * with event=3 when a suitable value for |p| is found. + * + * It returns one on success or zero on error. */ +OPENSSL_EXPORT int RSA_generate_key_ex(RSA *rsa, int bits, BIGNUM *e, + BN_GENCB *cb); + + +/* Encryption / Decryption */ + +/* Padding types for encryption. */ +#define RSA_PKCS1_PADDING 1 +#define RSA_NO_PADDING 3 +#define RSA_PKCS1_OAEP_PADDING 4 +/* RSA_PKCS1_PSS_PADDING can only be used via the EVP interface. */ +#define RSA_PKCS1_PSS_PADDING 6 + +/* RSA_encrypt encrypts |in_len| bytes from |in| to the public key from |rsa| + * and writes, at most, |max_out| bytes of encrypted data to |out|. The + * |max_out| argument must be, at least, |RSA_size| in order to ensure success. + * + * It returns 1 on success or zero on error. + * + * The |padding| argument must be one of the |RSA_*_PADDING| values. If in + * doubt, |RSA_PKCS1_PADDING| is the most common but |RSA_PKCS1_OAEP_PADDING| + * is the most secure. */ +OPENSSL_EXPORT int RSA_encrypt(RSA *rsa, size_t *out_len, uint8_t *out, + size_t max_out, const uint8_t *in, size_t in_len, + int padding); + +/* RSA_decrypt decrypts |in_len| bytes from |in| with the private key from + * |rsa| and writes, at most, |max_out| bytes of plaintext to |out|. The + * |max_out| argument must be, at least, |RSA_size| in order to ensure success. + * + * It returns 1 on success or zero on error. + * + * The |padding| argument must be one of the |RSA_*_PADDING| values. If in + * doubt, |RSA_PKCS1_PADDING| is the most common but |RSA_PKCS1_OAEP_PADDING| + * is the most secure. */ +OPENSSL_EXPORT int RSA_decrypt(RSA *rsa, size_t *out_len, uint8_t *out, + size_t max_out, const uint8_t *in, size_t in_len, + int padding); + +/* RSA_public_encrypt encrypts |flen| bytes from |from| to the public key in + * |rsa| and writes the encrypted data to |to|. The |to| buffer must have at + * least |RSA_size| bytes of space. It returns the number of bytes written, or + * -1 on error. The |padding| argument must be one of the |RSA_*_PADDING| + * values. If in doubt, |RSA_PKCS1_PADDING| is the most common but + * |RSA_PKCS1_OAEP_PADDING| is the most secure. + * + * WARNING: this function is dangerous because it breaks the usual return value + * convention. Use |RSA_encrypt| instead. */ +OPENSSL_EXPORT int RSA_public_encrypt(int flen, const uint8_t *from, + uint8_t *to, RSA *rsa, int padding); + +/* RSA_private_decrypt decrypts |flen| bytes from |from| with the public key in + * |rsa| and writes the plaintext to |to|. The |to| buffer must have at + * least |RSA_size| bytes of space. It returns the number of bytes written, or + * -1 on error. The |padding| argument must be one of the |RSA_*_PADDING| + * values. If in doubt, |RSA_PKCS1_PADDING| is the most common but + * |RSA_PKCS1_OAEP_PADDING| is the most secure. + * + * WARNING: this function is dangerous because it breaks the usual return value + * convention. Use |RSA_decrypt| instead. */ +OPENSSL_EXPORT int RSA_private_decrypt(int flen, const uint8_t *from, + uint8_t *to, RSA *rsa, int padding); + +/* RSA_message_index_PKCS1_type_2 performs the first step of a PKCS #1 padding + * check for decryption. If the |from_len| bytes pointed to at |from| are a + * valid PKCS #1 message, it returns one and sets |*out_index| to the start of + * the unpadded message. The unpadded message is a suffix of the input and has + * length |from_len - *out_index|. Otherwise, it returns zero and sets + * |*out_index| to zero. This function runs in time independent of the input + * data and is intended to be used directly to avoid Bleichenbacher's attack. + * + * WARNING: This function behaves differently from the usual OpenSSL convention + * in that it does NOT put an error on the queue in the error case. */ +OPENSSL_EXPORT int RSA_message_index_PKCS1_type_2(const uint8_t *from, + size_t from_len, + size_t *out_index); + + +/* Signing / Verification */ + +/* RSA_sign signs |in_len| bytes of digest from |in| with |rsa| and writes, at + * most, |RSA_size(rsa)| bytes to |out|. On successful return, the actual + * number of bytes written is written to |*out_len|. + * + * The |hash_nid| argument identifies the hash function used to calculate |in| + * and is embedded in the resulting signature. For example, it might be + * |NID_sha256|. + * + * It returns 1 on success and zero on error. */ +OPENSSL_EXPORT int RSA_sign(int hash_nid, const uint8_t *in, + unsigned int in_len, uint8_t *out, + unsigned int *out_len, RSA *rsa); + +/* RSA_sign_raw signs |in_len| bytes from |in| with the public key from |rsa| + * and writes, at most, |max_out| bytes of signature data to |out|. The + * |max_out| argument must be, at least, |RSA_size| in order to ensure success. + * + * It returns 1 on success or zero on error. + * + * The |padding| argument must be one of the |RSA_*_PADDING| values. If in + * doubt, |RSA_PKCS1_PADDING| is the most common. */ +OPENSSL_EXPORT int RSA_sign_raw(RSA *rsa, size_t *out_len, uint8_t *out, + size_t max_out, const uint8_t *in, + size_t in_len, int padding); + +/* RSA_verify verifies that |sig_len| bytes from |sig| are a valid, PKCS#1 + * signature of |msg_len| bytes at |msg| by |rsa|. + * + * The |hash_nid| argument identifies the hash function used to calculate |in| + * and is embedded in the resulting signature in order to prevent hash + * confusion attacks. For example, it might be |NID_sha256|. + * + * It returns one if the signature is valid and zero otherwise. + * + * WARNING: this differs from the original, OpenSSL function which additionally + * returned -1 on error. */ +OPENSSL_EXPORT int RSA_verify(int hash_nid, const uint8_t *msg, size_t msg_len, + const uint8_t *sig, size_t sig_len, RSA *rsa); + +/* RSA_verify_raw verifies |in_len| bytes of signature from |in| using the + * public key from |rsa| and writes, at most, |max_out| bytes of plaintext to + * |out|. The |max_out| argument must be, at least, |RSA_size| in order to + * ensure success. + * + * It returns 1 on success or zero on error. + * + * The |padding| argument must be one of the |RSA_*_PADDING| values. If in + * doubt, |RSA_PKCS1_PADDING| is the most common. */ +OPENSSL_EXPORT int RSA_verify_raw(RSA *rsa, size_t *out_len, uint8_t *out, + size_t max_out, const uint8_t *in, + size_t in_len, int padding); + +/* RSA_private_encrypt encrypts |flen| bytes from |from| with the private key in + * |rsa| and writes the encrypted data to |to|. The |to| buffer must have at + * least |RSA_size| bytes of space. It returns the number of bytes written, or + * -1 on error. The |padding| argument must be one of the |RSA_*_PADDING| + * values. If in doubt, |RSA_PKCS1_PADDING| is the most common. + * + * WARNING: this function is dangerous because it breaks the usual return value + * convention. Use |RSA_sign_raw| instead. */ +OPENSSL_EXPORT int RSA_private_encrypt(int flen, const uint8_t *from, + uint8_t *to, RSA *rsa, int padding); + +/* RSA_private_encrypt verifies |flen| bytes of signature from |from| using the + * public key in |rsa| and writes the plaintext to |to|. The |to| buffer must + * have at least |RSA_size| bytes of space. It returns the number of bytes + * written, or -1 on error. The |padding| argument must be one of the + * |RSA_*_PADDING| values. If in doubt, |RSA_PKCS1_PADDING| is the most common. + * + * WARNING: this function is dangerous because it breaks the usual return value + * convention. Use |RSA_verify_raw| instead. */ +OPENSSL_EXPORT int RSA_public_decrypt(int flen, const uint8_t *from, + uint8_t *to, RSA *rsa, int padding); + + +/* Utility functions. */ + +/* RSA_size returns the number of bytes in the modulus, which is also the size + * of a signature or encrypted value using |rsa|. */ +OPENSSL_EXPORT unsigned RSA_size(const RSA *rsa); + +/* RSA_is_opaque returns one if |rsa| is opaque and doesn't expose its key + * material. Otherwise it returns zero. */ +OPENSSL_EXPORT int RSA_is_opaque(const RSA *rsa); + +/* RSA_supports_digest returns one if |rsa| supports signing digests + * of type |md|. Otherwise it returns zero. */ +OPENSSL_EXPORT int RSA_supports_digest(const RSA *rsa, const EVP_MD *md); + +/* RSAPublicKey_dup allocates a fresh |RSA| and copies the private key from + * |rsa| into it. It returns the fresh |RSA| object, or NULL on error. */ +OPENSSL_EXPORT RSA *RSAPublicKey_dup(const RSA *rsa); + +/* RSAPrivateKey_dup allocates a fresh |RSA| and copies the private key from + * |rsa| into it. It returns the fresh |RSA| object, or NULL on error. */ +OPENSSL_EXPORT RSA *RSAPrivateKey_dup(const RSA *rsa); + +/* RSA_check_key performs basic validatity tests on |rsa|. It returns one if + * they pass and zero otherwise. Opaque keys and public keys always pass. If it + * returns zero then a more detailed error is available on the error queue. */ +OPENSSL_EXPORT int RSA_check_key(const RSA *rsa); + +/* RSA_recover_crt_params uses |rsa->n|, |rsa->d| and |rsa->e| in order to + * calculate the two primes used and thus the precomputed, CRT values. These + * values are set in the |p|, |q|, |dmp1|, |dmq1| and |iqmp| members of |rsa|, + * which must be |NULL| on entry. It returns one on success and zero + * otherwise. */ +OPENSSL_EXPORT int RSA_recover_crt_params(RSA *rsa); + +/* RSA_verify_PKCS1_PSS_mgf1 verifies that |EM| is a correct PSS padding of + * |mHash|, where |mHash| is a digest produced by |Hash|. |EM| must point to + * exactly |RSA_size(rsa)| bytes of data. The |mgf1Hash| argument specifies the + * hash function for generating the mask. If NULL, |Hash| is used. The |sLen| + * argument specifies the expected salt length in bytes. If |sLen| is -1 then + * the salt length is the same as the hash length. If -2, then the salt length + * is maximal and is taken from the size of |EM|. + * + * It returns one on success or zero on error. */ +OPENSSL_EXPORT int RSA_verify_PKCS1_PSS_mgf1(RSA *rsa, const uint8_t *mHash, + const EVP_MD *Hash, + const EVP_MD *mgf1Hash, + const uint8_t *EM, int sLen); + +/* RSA_padding_add_PKCS1_PSS_mgf1 writes a PSS padding of |mHash| to |EM|, + * where |mHash| is a digest produced by |Hash|. |RSA_size(rsa)| bytes of + * output will be written to |EM|. The |mgf1Hash| argument specifies the hash + * function for generating the mask. If NULL, |Hash| is used. The |sLen| + * argument specifies the expected salt length in bytes. If |sLen| is -1 then + * the salt length is the same as the hash length. If -2, then the salt length + * is maximal given the space in |EM|. + * + * It returns one on success or zero on error. */ +OPENSSL_EXPORT int RSA_padding_add_PKCS1_PSS_mgf1(RSA *rsa, uint8_t *EM, + const uint8_t *mHash, + const EVP_MD *Hash, + const EVP_MD *mgf1Hash, + int sLen); + + +/* ASN.1 functions. */ + +/* d2i_RSAPublicKey parses an ASN.1, DER-encoded, RSA public key from |len| + * bytes at |*inp|. If |out| is not NULL then, on exit, a pointer to the result + * is in |*out|. If |*out| is already non-NULL on entry then the result is + * written directly into |*out|, otherwise a fresh |RSA| is allocated. On + * successful exit, |*inp| is advanced past the DER structure. It returns the + * result or NULL on error. */ +OPENSSL_EXPORT RSA *d2i_RSAPublicKey(RSA **out, const uint8_t **inp, long len); + +/* i2d_RSAPublicKey marshals |in| to an ASN.1, DER structure. If |outp| is not + * NULL then the result is written to |*outp| and |*outp| is advanced just past + * the output. It returns the number of bytes in the result, whether written or + * not, or a negative value on error. */ +OPENSSL_EXPORT int i2d_RSAPublicKey(const RSA *in, uint8_t **outp); + +/* d2i_RSAPrivateKey parses an ASN.1, DER-encoded, RSA private key from |len| + * bytes at |*inp|. If |out| is not NULL then, on exit, a pointer to the result + * is in |*out|. If |*out| is already non-NULL on entry then the result is + * written directly into |*out|, otherwise a fresh |RSA| is allocated. On + * successful exit, |*inp| is advanced past the DER structure. It returns the + * result or NULL on error. */ +OPENSSL_EXPORT RSA *d2i_RSAPrivateKey(RSA **out, const uint8_t **inp, long len); + +/* i2d_RSAPrivateKey marshals |in| to an ASN.1, DER structure. If |outp| is not + * NULL then the result is written to |*outp| and |*outp| is advanced just past + * the output. It returns the number of bytes in the result, whether written or + * not, or a negative value on error. */ +OPENSSL_EXPORT int i2d_RSAPrivateKey(const RSA *in, uint8_t **outp); + + +/* ex_data functions. + * + * See |ex_data.h| for details. */ + +OPENSSL_EXPORT int RSA_get_ex_new_index(long argl, void *argp, + CRYPTO_EX_new *new_func, + CRYPTO_EX_dup *dup_func, + CRYPTO_EX_free *free_func); +OPENSSL_EXPORT int RSA_set_ex_data(RSA *r, int idx, void *arg); +OPENSSL_EXPORT void *RSA_get_ex_data(const RSA *r, int idx); + +/* RSA_FLAG_OPAQUE specifies that this RSA_METHOD does not expose its key + * material. This may be set if, for instance, it is wrapping some other crypto + * API, like a platform key store. */ +#define RSA_FLAG_OPAQUE 1 + +/* RSA_FLAG_CACHE_PUBLIC causes a precomputed Montgomery context to be created, + * on demand, for the public key operations. */ +#define RSA_FLAG_CACHE_PUBLIC 2 + +/* RSA_FLAG_CACHE_PRIVATE causes a precomputed Montgomery context to be + * created, on demand, for the private key operations. */ +#define RSA_FLAG_CACHE_PRIVATE 4 + +/* RSA_FLAG_NO_BLINDING disables blinding of private operations. */ +#define RSA_FLAG_NO_BLINDING 8 + +/* RSA_FLAG_EXT_PKEY means that private key operations will be handled by + * |mod_exp| and that they do not depend on the private key components being + * present: for example a key stored in external hardware. */ +#define RSA_FLAG_EXT_PKEY 0x20 + +/* RSA_FLAG_SIGN_VER causes the |sign| and |verify| functions of |rsa_meth_st| + * to be called when set. */ +#define RSA_FLAG_SIGN_VER 0x40 + + +/* RSA public exponent values. */ + +#define RSA_3 0x3 +#define RSA_F4 0x10001 + + +/* Deprecated functions. */ + +/* RSA_blinding_on returns one. */ +OPENSSL_EXPORT int RSA_blinding_on(RSA *rsa, BN_CTX *ctx); + + +struct rsa_meth_st { + struct openssl_method_common_st common; + + void *app_data; + + int (*init)(RSA *rsa); + int (*finish)(RSA *rsa); + + /* size returns the size of the RSA modulus in bytes. */ + size_t (*size)(const RSA *rsa); + + int (*sign)(int type, const uint8_t *m, unsigned int m_length, + uint8_t *sigret, unsigned int *siglen, const RSA *rsa); + + int (*verify)(int dtype, const uint8_t *m, unsigned int m_length, + const uint8_t *sigbuf, unsigned int siglen, const RSA *rsa); + + + /* These functions mirror the |RSA_*| functions of the same name. */ + int (*encrypt)(RSA *rsa, size_t *out_len, uint8_t *out, size_t max_out, + const uint8_t *in, size_t in_len, int padding); + int (*sign_raw)(RSA *rsa, size_t *out_len, uint8_t *out, size_t max_out, + const uint8_t *in, size_t in_len, int padding); + + int (*decrypt)(RSA *rsa, size_t *out_len, uint8_t *out, size_t max_out, + const uint8_t *in, size_t in_len, int padding); + int (*verify_raw)(RSA *rsa, size_t *out_len, uint8_t *out, size_t max_out, + const uint8_t *in, size_t in_len, int padding); + + /* private_transform takes a big-endian integer from |in|, calculates the + * d'th power of it, modulo the RSA modulus and writes the result as a + * big-endian integer to |out|. Both |in| and |out| are |len| bytes long and + * |len| is always equal to |RSA_size(rsa)|. If the result of the transform + * can be represented in fewer than |len| bytes, then |out| must be zero + * padded on the left. + * + * It returns one on success and zero otherwise. + * + * RSA decrypt and sign operations will call this, thus an ENGINE might wish + * to override it in order to avoid having to implement the padding + * functionality demanded by those, higher level, operations. */ + int (*private_transform)(RSA *rsa, uint8_t *out, const uint8_t *in, + size_t len); + + int (*mod_exp)(BIGNUM *r0, const BIGNUM *I, RSA *rsa, + BN_CTX *ctx); /* Can be null */ + int (*bn_mod_exp)(BIGNUM *r, const BIGNUM *a, const BIGNUM *p, + const BIGNUM *m, BN_CTX *ctx, + BN_MONT_CTX *m_ctx); + + int flags; + + int (*keygen)(RSA *rsa, int bits, BIGNUM *e, BN_GENCB *cb); + + /* supports_digest returns one if |rsa| supports digests of type + * |md|. If null, it is assumed that all digests are supported. */ + int (*supports_digest)(const RSA *rsa, const EVP_MD *md); +}; + + +/* Private functions. */ + +typedef struct bn_blinding_st BN_BLINDING; + +struct rsa_st { + /* version is only used during ASN.1 (de)serialisation. */ + long version; + RSA_METHOD *meth; + + BIGNUM *n; + BIGNUM *e; + BIGNUM *d; + BIGNUM *p; + BIGNUM *q; + BIGNUM *dmp1; + BIGNUM *dmq1; + BIGNUM *iqmp; + /* be careful using this if the RSA structure is shared */ + CRYPTO_EX_DATA ex_data; + CRYPTO_refcount_t references; + int flags; + + CRYPTO_MUTEX lock; + + /* Used to cache montgomery values. The creation of these values is protected + * by |lock|. */ + BN_MONT_CTX *_method_mod_n; + BN_MONT_CTX *_method_mod_p; + BN_MONT_CTX *_method_mod_q; + + /* num_blindings contains the size of the |blindings| and |blindings_inuse| + * arrays. This member and the |blindings_inuse| array are protected by + * |lock|. */ + unsigned num_blindings; + /* blindings is an array of BN_BLINDING structures that can be reserved by a + * thread by locking |lock| and changing the corresponding element in + * |blindings_inuse| from 0 to 1. */ + BN_BLINDING **blindings; + unsigned char *blindings_inuse; +}; + + +#if defined(__cplusplus) +} /* extern C */ +#endif + +#define RSA_F_BN_BLINDING_convert_ex 100 +#define RSA_F_BN_BLINDING_create_param 101 +#define RSA_F_BN_BLINDING_invert_ex 102 +#define RSA_F_BN_BLINDING_new 103 +#define RSA_F_BN_BLINDING_update 104 +#define RSA_F_RSA_check_key 105 +#define RSA_F_RSA_new_method 106 +#define RSA_F_RSA_padding_add_PKCS1_OAEP_mgf1 107 +#define RSA_F_RSA_padding_add_PKCS1_PSS_mgf1 108 +#define RSA_F_RSA_padding_add_PKCS1_type_1 109 +#define RSA_F_RSA_padding_add_PKCS1_type_2 110 +#define RSA_F_RSA_padding_add_none 111 +#define RSA_F_RSA_padding_check_PKCS1_OAEP_mgf1 112 +#define RSA_F_RSA_padding_check_PKCS1_type_1 113 +#define RSA_F_RSA_padding_check_PKCS1_type_2 114 +#define RSA_F_RSA_padding_check_none 115 +#define RSA_F_RSA_recover_crt_params 116 +#define RSA_F_RSA_sign 117 +#define RSA_F_RSA_verify 118 +#define RSA_F_RSA_verify_PKCS1_PSS_mgf1 119 +#define RSA_F_decrypt 120 +#define RSA_F_encrypt 121 +#define RSA_F_keygen 122 +#define RSA_F_pkcs1_prefixed_msg 123 +#define RSA_F_private_transform 124 +#define RSA_F_rsa_setup_blinding 125 +#define RSA_F_sign_raw 126 +#define RSA_F_verify_raw 127 +#define RSA_R_BAD_E_VALUE 100 +#define RSA_R_BAD_FIXED_HEADER_DECRYPT 101 +#define RSA_R_BAD_PAD_BYTE_COUNT 102 +#define RSA_R_BAD_RSA_PARAMETERS 103 +#define RSA_R_BAD_SIGNATURE 104 +#define RSA_R_BLOCK_TYPE_IS_NOT_01 105 +#define RSA_R_BN_NOT_INITIALIZED 106 +#define RSA_R_CRT_PARAMS_ALREADY_GIVEN 107 +#define RSA_R_CRT_VALUES_INCORRECT 108 +#define RSA_R_DATA_LEN_NOT_EQUAL_TO_MOD_LEN 109 +#define RSA_R_DATA_TOO_LARGE 110 +#define RSA_R_DATA_TOO_LARGE_FOR_KEY_SIZE 111 +#define RSA_R_DATA_TOO_LARGE_FOR_MODULUS 112 +#define RSA_R_DATA_TOO_SMALL 113 +#define RSA_R_DATA_TOO_SMALL_FOR_KEY_SIZE 114 +#define RSA_R_DIGEST_TOO_BIG_FOR_RSA_KEY 115 +#define RSA_R_D_E_NOT_CONGRUENT_TO_1 116 +#define RSA_R_EMPTY_PUBLIC_KEY 117 +#define RSA_R_FIRST_OCTET_INVALID 118 +#define RSA_R_INCONSISTENT_SET_OF_CRT_VALUES 119 +#define RSA_R_INTERNAL_ERROR 120 +#define RSA_R_INVALID_MESSAGE_LENGTH 121 +#define RSA_R_KEY_SIZE_TOO_SMALL 122 +#define RSA_R_LAST_OCTET_INVALID 123 +#define RSA_R_MODULUS_TOO_LARGE 124 +#define RSA_R_NO_PUBLIC_EXPONENT 125 +#define RSA_R_NULL_BEFORE_BLOCK_MISSING 126 +#define RSA_R_N_NOT_EQUAL_P_Q 127 +#define RSA_R_OAEP_DECODING_ERROR 128 +#define RSA_R_ONLY_ONE_OF_P_Q_GIVEN 129 +#define RSA_R_OUTPUT_BUFFER_TOO_SMALL 130 +#define RSA_R_PADDING_CHECK_FAILED 131 +#define RSA_R_PKCS_DECODING_ERROR 132 +#define RSA_R_SLEN_CHECK_FAILED 133 +#define RSA_R_SLEN_RECOVERY_FAILED 134 +#define RSA_R_TOO_LONG 135 +#define RSA_R_TOO_MANY_ITERATIONS 136 +#define RSA_R_UNKNOWN_ALGORITHM_TYPE 137 +#define RSA_R_UNKNOWN_PADDING_TYPE 138 +#define RSA_R_VALUE_MISSING 139 +#define RSA_R_WRONG_SIGNATURE_LENGTH 140 + +#endif /* OPENSSL_HEADER_RSA_H */ diff --git a/phonelibs/boringssl/include/openssl/safestack.h b/phonelibs/boringssl/include/openssl/safestack.h new file mode 100644 index 00000000000000..6e5e433074f867 --- /dev/null +++ b/phonelibs/boringssl/include/openssl/safestack.h @@ -0,0 +1,16 @@ +/* Copyright (c) 2014, Google Inc. + * + * Permission to use, copy, modify, and/or distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY + * SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN ACTION + * OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF OR IN + * CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. */ + +/* This header is provided in order to make compiling against code that expects + OpenSSL easier. */ diff --git a/phonelibs/boringssl/include/openssl/sha.h b/phonelibs/boringssl/include/openssl/sha.h new file mode 100644 index 00000000000000..ac2ab758b41a85 --- /dev/null +++ b/phonelibs/boringssl/include/openssl/sha.h @@ -0,0 +1,241 @@ +/* Copyright (C) 1995-1998 Eric Young (eay@cryptsoft.com) + * All rights reserved. + * + * This package is an SSL implementation written + * by Eric Young (eay@cryptsoft.com). + * The implementation was written so as to conform with Netscapes SSL. + * + * This library is free for commercial and non-commercial use as long as + * the following conditions are aheared to. The following conditions + * apply to all code found in this distribution, be it the RC4, RSA, + * lhash, DES, etc., code; not just the SSL code. The SSL documentation + * included with this distribution is covered by the same copyright terms + * except that the holder is Tim Hudson (tjh@cryptsoft.com). + * + * Copyright remains Eric Young's, and as such any Copyright notices in + * the code are not to be removed. + * If this package is used in a product, Eric Young should be given attribution + * as the author of the parts of the library used. + * This can be in the form of a textual message at program startup or + * in documentation (online or textual) provided with the package. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must 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. All advertising materials mentioning features or use of this software + * must display the following acknowledgement: + * "This product includes cryptographic software written by + * Eric Young (eay@cryptsoft.com)" + * The word 'cryptographic' can be left out if the rouines from the library + * being used are not cryptographic related :-). + * 4. If you include any Windows specific code (or a derivative thereof) from + * the apps directory (application code) you must include an acknowledgement: + * "This product includes software written by Tim Hudson (tjh@cryptsoft.com)" + * + * THIS SOFTWARE IS PROVIDED BY ERIC YOUNG ``AS IS'' AND + * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHOR OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (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 licence and distribution terms for any publically available version or + * derivative of this code cannot be changed. i.e. this code cannot simply be + * copied and put under another distribution licence + * [including the GNU Public Licence.] */ + +#ifndef OPENSSL_HEADER_SHA_H +#define OPENSSL_HEADER_SHA_H + +#include + +#if defined(__cplusplus) +extern "C" { +#endif + + +/* The SHA family of hash functions (SHA-1 and SHA-2). */ + + +/* SHA_CBLOCK is the block size of SHA-1. */ +#define SHA_CBLOCK 64 + +/* SHA_DIGEST_LENGTH is the length of a SHA-1 digest. */ +#define SHA_DIGEST_LENGTH 20 + +/* TODO(fork): remove */ +#define SHA_LBLOCK 16 +#define SHA_LONG uint32_t + +/* SHA1_Init initialises |sha| and returns one. */ +OPENSSL_EXPORT int SHA1_Init(SHA_CTX *sha); + +/* SHA1_Update adds |len| bytes from |data| to |sha| and returns one. */ +OPENSSL_EXPORT int SHA1_Update(SHA_CTX *sha, const void *data, size_t len); + +/* SHA1_Final adds the final padding to |sha| and writes the resulting digest + * to |md|, which must have at least |SHA_DIGEST_LENGTH| bytes of space. It + * returns one. */ +OPENSSL_EXPORT int SHA1_Final(uint8_t *md, SHA_CTX *sha); + +/* SHA1 writes the digest of |len| bytes from |data| to |out| and returns + * |out|. There must be at least |SHA_DIGEST_LENGTH| bytes of space in + * |out|. */ +OPENSSL_EXPORT uint8_t *SHA1(const uint8_t *data, size_t len, uint8_t *out); + +/* SHA1_Transform is a low-level function that performs a single, SHA-1 block + * transformation using the state from |sha| and 64 bytes from |block|. */ +OPENSSL_EXPORT void SHA1_Transform(SHA_CTX *sha, const uint8_t *block); + +struct sha_state_st { + uint32_t h0, h1, h2, h3, h4; + uint32_t Nl, Nh; + uint32_t data[16]; + unsigned int num; +}; + + +/* SHA-224. */ + +/* SHA224_CBLOCK is the block size of SHA-224. */ +#define SHA224_CBLOCK 64 + +/* SHA224_DIGEST_LENGTH is the length of a SHA-224 digest. */ +#define SHA224_DIGEST_LENGTH 28 + +/* SHA224_Init initialises |sha| and returns 1. */ +OPENSSL_EXPORT int SHA224_Init(SHA256_CTX *sha); + +/* SHA224_Update adds |len| bytes from |data| to |sha| and returns 1. */ +OPENSSL_EXPORT int SHA224_Update(SHA256_CTX *sha, const void *data, size_t len); + +/* SHA224_Final adds the final padding to |sha| and writes the resulting digest + * to |md|, which must have at least |SHA224_DIGEST_LENGTH| bytes of space. It + * returns one on success and zero on programmer error. */ +OPENSSL_EXPORT int SHA224_Final(uint8_t *md, SHA256_CTX *sha); + +/* SHA224 writes the digest of |len| bytes from |data| to |out| and returns + * |out|. There must be at least |SHA224_DIGEST_LENGTH| bytes of space in + * |out|. */ +OPENSSL_EXPORT uint8_t *SHA224(const uint8_t *data, size_t len, uint8_t *out); + + +/* SHA-256. */ + +/* SHA256_CBLOCK is the block size of SHA-256. */ +#define SHA256_CBLOCK 64 + +/* SHA256_DIGEST_LENGTH is the length of a SHA-256 digest. */ +#define SHA256_DIGEST_LENGTH 32 + +/* SHA256_Init initialises |sha| and returns 1. */ +OPENSSL_EXPORT int SHA256_Init(SHA256_CTX *sha); + +/* SHA256_Update adds |len| bytes from |data| to |sha| and returns 1. */ +OPENSSL_EXPORT int SHA256_Update(SHA256_CTX *sha, const void *data, size_t len); + +/* SHA256_Final adds the final padding to |sha| and writes the resulting digest + * to |md|, which must have at least |SHA256_DIGEST_LENGTH| bytes of space. It + * returns one on success and zero on programmer error. */ +OPENSSL_EXPORT int SHA256_Final(uint8_t *md, SHA256_CTX *sha); + +/* SHA256 writes the digest of |len| bytes from |data| to |out| and returns + * |out|. There must be at least |SHA256_DIGEST_LENGTH| bytes of space in + * |out|. */ +OPENSSL_EXPORT uint8_t *SHA256(const uint8_t *data, size_t len, uint8_t *out); + +/* SHA256_Transform is a low-level function that performs a single, SHA-1 block + * transformation using the state from |sha| and 64 bytes from |block|. */ +OPENSSL_EXPORT void SHA256_Transform(SHA256_CTX *sha, const uint8_t *data); + +struct sha256_state_st { + uint32_t h[8]; + uint32_t Nl, Nh; + uint32_t data[16]; + unsigned int num, md_len; +}; + + +/* SHA-384. */ + +/* SHA384_CBLOCK is the block size of SHA-384. */ +#define SHA384_CBLOCK 128 + +/* SHA384_DIGEST_LENGTH is the length of a SHA-384 digest. */ +#define SHA384_DIGEST_LENGTH 48 + +/* SHA384_Init initialises |sha| and returns 1. */ +OPENSSL_EXPORT int SHA384_Init(SHA512_CTX *sha); + +/* SHA384_Update adds |len| bytes from |data| to |sha| and returns 1. */ +OPENSSL_EXPORT int SHA384_Update(SHA512_CTX *sha, const void *data, size_t len); + +/* SHA384_Final adds the final padding to |sha| and writes the resulting digest + * to |md|, which must have at least |SHA384_DIGEST_LENGTH| bytes of space. It + * returns one on success and zero on programmer error. */ +OPENSSL_EXPORT int SHA384_Final(uint8_t *md, SHA512_CTX *sha); + +/* SHA384 writes the digest of |len| bytes from |data| to |out| and returns + * |out|. There must be at least |SHA384_DIGEST_LENGTH| bytes of space in + * |out|. */ +OPENSSL_EXPORT uint8_t *SHA384(const uint8_t *data, size_t len, uint8_t *out); + +/* SHA384_Transform is a low-level function that performs a single, SHA-1 block + * transformation using the state from |sha| and 64 bytes from |block|. */ +OPENSSL_EXPORT void SHA384_Transform(SHA512_CTX *sha, const uint8_t *data); + + +/* SHA-512. */ + +/* SHA512_CBLOCK is the block size of SHA-512. */ +#define SHA512_CBLOCK 128 + +/* SHA512_DIGEST_LENGTH is the length of a SHA-512 digest. */ +#define SHA512_DIGEST_LENGTH 64 + +/* SHA512_Init initialises |sha| and returns 1. */ +OPENSSL_EXPORT int SHA512_Init(SHA512_CTX *sha); + +/* SHA512_Update adds |len| bytes from |data| to |sha| and returns 1. */ +OPENSSL_EXPORT int SHA512_Update(SHA512_CTX *sha, const void *data, size_t len); + +/* SHA512_Final adds the final padding to |sha| and writes the resulting digest + * to |md|, which must have at least |SHA512_DIGEST_LENGTH| bytes of space. It + * returns one on success and zero on programmer error. */ +OPENSSL_EXPORT int SHA512_Final(uint8_t *md, SHA512_CTX *sha); + +/* SHA512 writes the digest of |len| bytes from |data| to |out| and returns + * |out|. There must be at least |SHA512_DIGEST_LENGTH| bytes of space in + * |out|. */ +OPENSSL_EXPORT uint8_t *SHA512(const uint8_t *data, size_t len, uint8_t *out); + +/* SHA512_Transform is a low-level function that performs a single, SHA-1 block + * transformation using the state from |sha| and 64 bytes from |block|. */ +OPENSSL_EXPORT void SHA512_Transform(SHA512_CTX *sha, const uint8_t *data); + +struct sha512_state_st { + uint64_t h[8]; + uint64_t Nl, Nh; + union { + uint64_t d[16]; + uint8_t p[128]; + } u; + unsigned int num, md_len; +}; + + +#if defined(__cplusplus) +} /* extern C */ +#endif + +#endif /* OPENSSL_HEADER_SHA_H */ diff --git a/phonelibs/boringssl/include/openssl/srtp.h b/phonelibs/boringssl/include/openssl/srtp.h new file mode 100644 index 00000000000000..3f5a53e2c1e1de --- /dev/null +++ b/phonelibs/boringssl/include/openssl/srtp.h @@ -0,0 +1,178 @@ +/* ssl/tls1.h */ +/* Copyright (C) 1995-1998 Eric Young (eay@cryptsoft.com) + * All rights reserved. + * + * This package is an SSL implementation written + * by Eric Young (eay@cryptsoft.com). + * The implementation was written so as to conform with Netscapes SSL. + * + * This library is free for commercial and non-commercial use as long as + * the following conditions are aheared to. The following conditions + * apply to all code found in this distribution, be it the RC4, RSA, + * lhash, DES, etc., code; not just the SSL code. The SSL documentation + * included with this distribution is covered by the same copyright terms + * except that the holder is Tim Hudson (tjh@cryptsoft.com). + * + * Copyright remains Eric Young's, and as such any Copyright notices in + * the code are not to be removed. + * If this package is used in a product, Eric Young should be given attribution + * as the author of the parts of the library used. + * This can be in the form of a textual message at program startup or + * in documentation (online or textual) provided with the package. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must 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. All advertising materials mentioning features or use of this software + * must display the following acknowledgement: + * "This product includes cryptographic software written by + * Eric Young (eay@cryptsoft.com)" + * The word 'cryptographic' can be left out if the rouines from the library + * being used are not cryptographic related :-). + * 4. If you include any Windows specific code (or a derivative thereof) from + * the apps directory (application code) you must include an acknowledgement: + * "This product includes software written by Tim Hudson (tjh@cryptsoft.com)" + * + * THIS SOFTWARE IS PROVIDED BY ERIC YOUNG ``AS IS'' AND + * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHOR OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (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 licence and distribution terms for any publically available version or + * derivative of this code cannot be changed. i.e. this code cannot simply be + * copied and put under another distribution licence + * [including the GNU Public Licence.] + */ +/* ==================================================================== + * Copyright (c) 1998-2006 The OpenSSL Project. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * + * 3. All advertising materials mentioning features or use of this + * software must display the following acknowledgment: + * "This product includes software developed by the OpenSSL Project + * for use in the OpenSSL Toolkit. (http://www.openssl.org/)" + * + * 4. The names "OpenSSL Toolkit" and "OpenSSL Project" must not be used to + * endorse or promote products derived from this software without + * prior written permission. For written permission, please contact + * openssl-core@openssl.org. + * + * 5. Products derived from this software may not be called "OpenSSL" + * nor may "OpenSSL" appear in their names without prior written + * permission of the OpenSSL Project. + * + * 6. Redistributions of any form whatsoever must retain the following + * acknowledgment: + * "This product includes software developed by the OpenSSL Project + * for use in the OpenSSL Toolkit (http://www.openssl.org/)" + * + * THIS SOFTWARE IS PROVIDED BY THE OpenSSL PROJECT ``AS IS'' AND ANY + * EXPRESSED OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR + * PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE OpenSSL PROJECT OR + * ITS CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, + * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT + * NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + * STRICT LIABILITY, OR TORT (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 product includes cryptographic software written by Eric Young + * (eay@cryptsoft.com). This product includes software written by Tim + * Hudson (tjh@cryptsoft.com). + * + */ +/* + DTLS code by Eric Rescorla + + Copyright (C) 2006, Network Resonance, Inc. + Copyright (C) 2011, RTFM, Inc. +*/ + +#ifndef OPENSSL_HEADER_SRTP_H +#define OPENSSL_HEADER_SRTP_H + +#ifdef __cplusplus +extern "C" { +#endif + + +/* Constants for SRTP profiles */ +#define SRTP_AES128_CM_SHA1_80 0x0001 +#define SRTP_AES128_CM_SHA1_32 0x0002 +#define SRTP_AES128_F8_SHA1_80 0x0003 +#define SRTP_AES128_F8_SHA1_32 0x0004 +#define SRTP_NULL_SHA1_80 0x0005 +#define SRTP_NULL_SHA1_32 0x0006 + +/* SSL_CTX_set_srtp_profiles enables SRTP for all SSL objects created from + * |ctx|. |profile| contains a colon-separated list of profile names. It returns + * one on success and zero on failure. */ +OPENSSL_EXPORT int SSL_CTX_set_srtp_profiles(SSL_CTX *ctx, + const char *profiles); + +/* SSL_set_srtp_profiles enables SRTP for |ssl|. |profile| contains a + * colon-separated list of profile names. It returns one on success and zero on + * failure. */ +OPENSSL_EXPORT int SSL_set_srtp_profiles(SSL *ctx, const char *profiles); + +/* SSL_get_srtp_profiles returns the SRTP profiles supported by |ssl|. */ +OPENSSL_EXPORT STACK_OF(SRTP_PROTECTION_PROFILE) *SSL_get_srtp_profiles( + SSL *ssl); + +/* SSL_get_selected_srtp_profile returns the selected SRTP profile, or NULL if + * SRTP was not negotiated. */ +OPENSSL_EXPORT const SRTP_PROTECTION_PROFILE *SSL_get_selected_srtp_profile( + SSL *s); + + +/* Deprecated functions */ + +/* SSL_CTX_set_tlsext_use_srtp calls SSL_CTX_set_srtp_profiles. It returns zero + * on success and one on failure. + * + * WARNING: this function is dangerous because it breaks the usual return value + * convention. Use SSL_CTX_set_srtp_profiles instead. */ +OPENSSL_EXPORT int SSL_CTX_set_tlsext_use_srtp(SSL_CTX *ctx, + const char *profiles); + +/* SSL_set_tlsext_use_srtp calls SSL_set_srtp_profiles. It returns zero on + * success and one on failure. + * + * WARNING: this function is dangerous because it breaks the usual return value + * convention. Use SSL_set_srtp_profiles instead. */ +OPENSSL_EXPORT int SSL_set_tlsext_use_srtp(SSL *ctx, const char *profiles); + + +#ifdef __cplusplus +} /* extern C */ +#endif + +#endif /* OPENSSL_HEADER_SRTP_H */ + diff --git a/phonelibs/boringssl/include/openssl/ssl.h b/phonelibs/boringssl/include/openssl/ssl.h new file mode 100644 index 00000000000000..217dbaf2f45173 --- /dev/null +++ b/phonelibs/boringssl/include/openssl/ssl.h @@ -0,0 +1,2959 @@ +/* ssl/ssl.h */ +/* Copyright (C) 1995-1998 Eric Young (eay@cryptsoft.com) + * All rights reserved. + * + * This package is an SSL implementation written + * by Eric Young (eay@cryptsoft.com). + * The implementation was written so as to conform with Netscapes SSL. + * + * This library is free for commercial and non-commercial use as long as + * the following conditions are aheared to. The following conditions + * apply to all code found in this distribution, be it the RC4, RSA, + * lhash, DES, etc., code; not just the SSL code. The SSL documentation + * included with this distribution is covered by the same copyright terms + * except that the holder is Tim Hudson (tjh@cryptsoft.com). + * + * Copyright remains Eric Young's, and as such any Copyright notices in + * the code are not to be removed. + * If this package is used in a product, Eric Young should be given attribution + * as the author of the parts of the library used. + * This can be in the form of a textual message at program startup or + * in documentation (online or textual) provided with the package. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must 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. All advertising materials mentioning features or use of this software + * must display the following acknowledgement: + * "This product includes cryptographic software written by + * Eric Young (eay@cryptsoft.com)" + * The word 'cryptographic' can be left out if the rouines from the library + * being used are not cryptographic related :-). + * 4. If you include any Windows specific code (or a derivative thereof) from + * the apps directory (application code) you must include an acknowledgement: + * "This product includes software written by Tim Hudson (tjh@cryptsoft.com)" + * + * THIS SOFTWARE IS PROVIDED BY ERIC YOUNG ``AS IS'' AND + * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHOR OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (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 licence and distribution terms for any publically available version or + * derivative of this code cannot be changed. i.e. this code cannot simply be + * copied and put under another distribution licence + * [including the GNU Public Licence.] + */ +/* ==================================================================== + * Copyright (c) 1998-2007 The OpenSSL Project. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * + * 3. All advertising materials mentioning features or use of this + * software must display the following acknowledgment: + * "This product includes software developed by the OpenSSL Project + * for use in the OpenSSL Toolkit. (http://www.openssl.org/)" + * + * 4. The names "OpenSSL Toolkit" and "OpenSSL Project" must not be used to + * endorse or promote products derived from this software without + * prior written permission. For written permission, please contact + * openssl-core@openssl.org. + * + * 5. Products derived from this software may not be called "OpenSSL" + * nor may "OpenSSL" appear in their names without prior written + * permission of the OpenSSL Project. + * + * 6. Redistributions of any form whatsoever must retain the following + * acknowledgment: + * "This product includes software developed by the OpenSSL Project + * for use in the OpenSSL Toolkit (http://www.openssl.org/)" + * + * THIS SOFTWARE IS PROVIDED BY THE OpenSSL PROJECT ``AS IS'' AND ANY + * EXPRESSED OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR + * PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE OpenSSL PROJECT OR + * ITS CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, + * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT + * NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + * STRICT LIABILITY, OR TORT (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 product includes cryptographic software written by Eric Young + * (eay@cryptsoft.com). This product includes software written by Tim + * Hudson (tjh@cryptsoft.com). + * + */ +/* ==================================================================== + * Copyright 2002 Sun Microsystems, Inc. ALL RIGHTS RESERVED. + * ECC cipher suite support in OpenSSL originally developed by + * SUN MICROSYSTEMS, INC., and contributed to the OpenSSL project. + */ +/* ==================================================================== + * Copyright 2005 Nokia. All rights reserved. + * + * The portions of the attached software ("Contribution") is developed by + * Nokia Corporation and is licensed pursuant to the OpenSSL open source + * license. + * + * The Contribution, originally written by Mika Kousa and Pasi Eronen of + * Nokia Corporation, consists of the "PSK" (Pre-Shared Key) ciphersuites + * support (see RFC 4279) to OpenSSL. + * + * No patent licenses or other rights except those expressly stated in + * the OpenSSL open source license shall be deemed granted or received + * expressly, by implication, estoppel, or otherwise. + * + * No assurances are provided by Nokia that the Contribution does not + * infringe the patent or other intellectual property rights of any third + * party or that the license provides you with all the necessary rights + * to make use of the Contribution. + * + * THE SOFTWARE IS PROVIDED "AS IS" WITHOUT WARRANTY OF ANY KIND. IN + * ADDITION TO THE DISCLAIMERS INCLUDED IN THE LICENSE, NOKIA + * SPECIFICALLY DISCLAIMS ANY LIABILITY FOR CLAIMS BROUGHT BY YOU OR ANY + * OTHER ENTITY BASED ON INFRINGEMENT OF INTELLECTUAL PROPERTY RIGHTS OR + * OTHERWISE. + */ + +#ifndef OPENSSL_HEADER_SSL_H +#define OPENSSL_HEADER_SSL_H + +#include + +#include +#include +#include +#include +#include +#include +#include + +#if !defined(OPENSSL_WINDOWS) +#include +#endif + +/* wpa_supplicant expects to get the version functions from ssl.h */ +#include + +/* Forward-declare struct timeval. On Windows, it is defined in winsock2.h and + * Windows headers define too many macros to be included in public headers. + * However, only a forward declaration is needed. */ +struct timeval; + +#if defined(__cplusplus) +extern "C" { +#endif + + +/* SSL implementation. */ + + +/* Initialization. */ + +/* SSL_library_init initializes the crypto and SSL libraries and returns one. */ +OPENSSL_EXPORT int SSL_library_init(void); + + +/* Cipher suites. */ + +/* An SSL_CIPHER represents a cipher suite. */ +typedef struct ssl_cipher_st { + /* name is the OpenSSL name for the cipher. */ + const char *name; + /* id is the cipher suite value bitwise OR-d with 0x03000000. */ + uint32_t id; + + /* The following are internal fields. See ssl/internal.h for their values. */ + + uint32_t algorithm_mkey; + uint32_t algorithm_auth; + uint32_t algorithm_enc; + uint32_t algorithm_mac; + uint32_t algorithm_ssl; + uint32_t algo_strength; + + /* algorithm2 contains extra flags. See ssl/internal.h. */ + uint32_t algorithm2; + + /* strength_bits is the strength of the cipher in bits. */ + int strength_bits; + /* alg_bits is the number of bits of key material used by the algorithm. */ + int alg_bits; +} SSL_CIPHER; + +DECLARE_STACK_OF(SSL_CIPHER) + +/* SSL_get_cipher_by_value returns the structure representing a TLS cipher + * suite based on its assigned number, or NULL if unknown. See + * https://www.iana.org/assignments/tls-parameters/tls-parameters.xhtml#tls-parameters-4. */ +OPENSSL_EXPORT const SSL_CIPHER *SSL_get_cipher_by_value(uint16_t value); + +/* SSL_CIPHER_get_id returns |cipher|'s id. It may be cast to a |uint16_t| to + * get the cipher suite value. */ +OPENSSL_EXPORT uint32_t SSL_CIPHER_get_id(const SSL_CIPHER *cipher); + +/* SSL_CIPHER_is_AES returns one if |cipher| uses AES (either GCM or CBC + * mode). */ +OPENSSL_EXPORT int SSL_CIPHER_is_AES(const SSL_CIPHER *cipher); + +/* SSL_CIPHER_has_MD5_HMAC returns one if |cipher| uses HMAC-MD5. */ +OPENSSL_EXPORT int SSL_CIPHER_has_MD5_HMAC(const SSL_CIPHER *cipher); + +/* SSL_CIPHER_is_AESGCM returns one if |cipher| uses AES-GCM. */ +OPENSSL_EXPORT int SSL_CIPHER_is_AESGCM(const SSL_CIPHER *cipher); + +/* SSL_CIPHER_is_CHACHA20POLY1305 returns one if |cipher| uses + * CHACHA20_POLY1305. */ +OPENSSL_EXPORT int SSL_CIPHER_is_CHACHA20POLY1305(const SSL_CIPHER *cipher); + +/* SSL_CIPHER_get_name returns the OpenSSL name of |cipher|. */ +OPENSSL_EXPORT const char *SSL_CIPHER_get_name(const SSL_CIPHER *cipher); + +/* SSL_CIPHER_get_kx_name returns a string that describes the key-exchange + * method used by |cipher|. For example, "ECDHE_ECDSA". */ +OPENSSL_EXPORT const char *SSL_CIPHER_get_kx_name(const SSL_CIPHER *cipher); + +/* SSL_CIPHER_get_rfc_name returns a newly-allocated string with the standard + * name for |cipher| or NULL on error. For example, + * "TLS_ECDHE_RSA_WITH_AES_128_GCM_SHA256". The caller is responsible for + * calling |OPENSSL_free| on the result. */ +OPENSSL_EXPORT char *SSL_CIPHER_get_rfc_name(const SSL_CIPHER *cipher); + +/* SSL_CIPHER_get_bits returns the strength, in bits, of |cipher|. If + * |out_alg_bits| is not NULL, it writes the number of bits consumed by the + * symmetric algorithm to |*out_alg_bits|. */ +OPENSSL_EXPORT int SSL_CIPHER_get_bits(const SSL_CIPHER *cipher, + int *out_alg_bits); + + +/* SSL contexts. */ + +/* An SSL_METHOD selects whether to use TLS or DTLS. */ +typedef struct ssl_method_st SSL_METHOD; + +/* TLS_method is the |SSL_METHOD| used for TLS (and SSLv3) connections. */ +OPENSSL_EXPORT const SSL_METHOD *TLS_method(void); + +/* DTLS_method is the |SSL_METHOD| used for DTLS connections. */ +OPENSSL_EXPORT const SSL_METHOD *DTLS_method(void); + +/* SSL_CTX_new returns a newly-allocated |SSL_CTX| with default settings or NULL + * on error. An |SSL_CTX| manages shared state and configuration between + * multiple TLS or DTLS connections. */ +OPENSSL_EXPORT SSL_CTX *SSL_CTX_new(const SSL_METHOD *method); + +/* SSL_CTX_free releases memory associated with |ctx|. */ +OPENSSL_EXPORT void SSL_CTX_free(SSL_CTX *ctx); + + +/* SSL connections. */ + +/* SSL_new returns a newly-allocated |SSL| using |ctx| or NULL on error. An + * |SSL| object represents a single TLS or DTLS connection. It inherits settings + * from |ctx| at the time of creation. Settings may also be individually + * configured on the connection. + * + * On creation, an |SSL| is not configured to be either a client or server. Call + * |SSL_set_connect_state| or |SSL_set_accept_state| to set this. */ +OPENSSL_EXPORT SSL *SSL_new(SSL_CTX *ctx); + +/* SSL_free releases memory associated with |ssl|. */ +OPENSSL_EXPORT void SSL_free(SSL *ssl); + +/* SSL_set_connect_state configures |ssl| to be a client. */ +OPENSSL_EXPORT void SSL_set_connect_state(SSL *ssl); + +/* SSL_set_accept_state configures |ssl| to be a server. */ +OPENSSL_EXPORT void SSL_set_accept_state(SSL *ssl); + + +/* Protocol versions. */ + +#define SSL3_VERSION_MAJOR 0x03 + +#define SSL3_VERSION 0x0300 +#define TLS1_VERSION 0x0301 +#define TLS1_1_VERSION 0x0302 +#define TLS1_2_VERSION 0x0303 + +#define DTLS1_VERSION 0xfeff +#define DTLS1_2_VERSION 0xfefd + +/* SSL_CTX_set_min_version sets the minimum protocol version for |ctx| to + * |version|. */ +OPENSSL_EXPORT void SSL_CTX_set_min_version(SSL_CTX *ctx, uint16_t version); + +/* SSL_CTX_set_max_version sets the maximum protocol version for |ctx| to + * |version|. */ +OPENSSL_EXPORT void SSL_CTX_set_max_version(SSL_CTX *ctx, uint16_t version); + +/* SSL_set_min_version sets the minimum protocol version for |ssl| to + * |version|. */ +OPENSSL_EXPORT void SSL_set_min_version(SSL *ssl, uint16_t version); + +/* SSL_set_max_version sets the maximum protocol version for |ssl| to + * |version|. */ +OPENSSL_EXPORT void SSL_set_max_version(SSL *ssl, uint16_t version); + + +/* Options. + * + * Options configure protocol behavior. */ + +/* SSL_OP_LEGACY_SERVER_CONNECT allows initial connections to servers that don't + * support the renegotiation_info extension (RFC 5746). It is on by default. */ +#define SSL_OP_LEGACY_SERVER_CONNECT 0x00000004L + +/* SSL_OP_MICROSOFT_BIG_SSLV3_BUFFER allows for record sizes |SSL3_RT_MAX_EXTRA| + * bytes above the maximum record size. */ +#define SSL_OP_MICROSOFT_BIG_SSLV3_BUFFER 0x00000020L + +/* SSL_OP_TLS_D5_BUG accepts an RSAClientKeyExchange in TLS encoded as in SSL3 + * (i.e. without a length prefix). */ +#define SSL_OP_TLS_D5_BUG 0x00000100L + +/* SSL_OP_ALL enables the above bug workarounds that are enabled by many + * consumers. + * TODO(davidben): Determine which of the remaining may be removed now. */ +#define SSL_OP_ALL 0x00000BFFL + +/* SSL_OP_NO_QUERY_MTU, in DTLS, disables querying the MTU from the underlying + * |BIO|. Instead, the MTU is configured with |SSL_set_mtu|. */ +#define SSL_OP_NO_QUERY_MTU 0x00001000L + +/* SSL_OP_NO_TICKET disables session ticket support (RFC 4507). */ +#define SSL_OP_NO_TICKET 0x00004000L + +/* SSL_OP_ALLOW_UNSAFE_LEGACY_RENEGOTIATION permits unsafe legacy renegotiation + * without renegotiation_info (RFC 5746) support. */ +#define SSL_OP_ALLOW_UNSAFE_LEGACY_RENEGOTIATION 0x00040000L + +/* SSL_OP_CIPHER_SERVER_PREFERENCE configures servers to select ciphers and + * ECDHE curves according to the server's preferences instead of the + * client's. */ +#define SSL_OP_CIPHER_SERVER_PREFERENCE 0x00400000L + +/* The following flags toggle individual protocol versions. This is deprecated. + * Use |SSL_CTX_set_min_version| and |SSL_CTX_set_max_version| instead. */ +#define SSL_OP_NO_SSLv3 0x02000000L +#define SSL_OP_NO_TLSv1 0x04000000L +#define SSL_OP_NO_TLSv1_2 0x08000000L +#define SSL_OP_NO_TLSv1_1 0x10000000L +#define SSL_OP_NO_DTLSv1 SSL_OP_NO_TLSv1 +#define SSL_OP_NO_DTLSv1_2 SSL_OP_NO_TLSv1_2 + +/* The following flags do nothing and are included only to make it easier to + * compile code with BoringSSL. */ +#define SSL_OP_DONT_INSERT_EMPTY_FRAGMENTS 0 +#define SSL_OP_MICROSOFT_SESS_ID_BUG 0 +#define SSL_OP_NETSCAPE_CHALLENGE_BUG 0 +#define SSL_OP_NO_COMPRESSION 0 +#define SSL_OP_NO_SESSION_RESUMPTION_ON_RENEGOTIATION 0 +#define SSL_OP_NO_SSLv2 0 +#define SSL_OP_SINGLE_DH_USE 0 +#define SSL_OP_SINGLE_ECDH_USE 0 +#define SSL_OP_SSLREF2_REUSE_CERT_TYPE_BUG 0 +#define SSL_OP_TLS_BLOCK_PADDING_BUG 0 +#define SSL_OP_TLS_ROLLBACK_BUG 0 + +/* SSL_CTX_set_options enables all options set in |options| (which should be one + * or more of the |SSL_OP_*| values, ORed together) in |ctx|. It returns a + * bitmask representing the resulting enabled options. */ +OPENSSL_EXPORT uint32_t SSL_CTX_set_options(SSL_CTX *ctx, uint32_t options); + +/* SSL_CTX_clear_options disables all options set in |options| (which should be + * one or more of the |SSL_OP_*| values, ORed together) in |ctx|. It returns a + * bitmask representing the resulting enabled options. */ +OPENSSL_EXPORT uint32_t SSL_CTX_clear_options(SSL_CTX *ctx, uint32_t options); + +/* SSL_CTX_get_options returns a bitmask of |SSL_OP_*| values that represent all + * the options enabled for |ctx|. */ +OPENSSL_EXPORT uint32_t SSL_CTX_get_options(const SSL_CTX *ctx); + +/* SSL_set_options enables all options set in |options| (which should be one or + * more of the |SSL_OP_*| values, ORed together) in |ssl|. It returns a bitmask + * representing the resulting enabled options. */ +OPENSSL_EXPORT uint32_t SSL_set_options(SSL *ssl, uint32_t options); + +/* SSL_clear_options disables all options set in |options| (which should be one + * or more of the |SSL_OP_*| values, ORed together) in |ssl|. It returns a + * bitmask representing the resulting enabled options. */ +OPENSSL_EXPORT uint32_t SSL_clear_options(SSL *ssl, uint32_t options); + +/* SSL_get_options returns a bitmask of |SSL_OP_*| values that represent all the + * options enabled for |ssl|. */ +OPENSSL_EXPORT uint32_t SSL_get_options(const SSL *ssl); + + +/* Modes. + * + * Modes configure API behavior. */ + +/* SSL_MODE_ENABLE_PARTIAL_WRITE allows |SSL_write| to complete with a partial + * result when the only part of the input was written in a single record. */ +#define SSL_MODE_ENABLE_PARTIAL_WRITE 0x00000001L + +/* SSL_MODE_ACCEPT_MOVING_WRITE_BUFFER allows retrying an incomplete |SSL_write| + * with a different buffer. However, |SSL_write| still assumes the buffer + * contents are unchanged. This is not the default to avoid the misconception + * that non-blocking |SSL_write| behaves like non-blocking |write|. */ +#define SSL_MODE_ACCEPT_MOVING_WRITE_BUFFER 0x00000002L + +/* SSL_MODE_NO_AUTO_CHAIN disables automatically building a certificate chain + * before sending certificates to the peer. + * TODO(davidben): Remove this behavior. https://crbug.com/486295. */ +#define SSL_MODE_NO_AUTO_CHAIN 0x00000008L + +/* SSL_MODE_ENABLE_FALSE_START allows clients to send application data before + * receipt of CCS and Finished. This mode enables full-handshakes to 'complete' + * in one RTT. See draft-bmoeller-tls-falsestart-01. */ +#define SSL_MODE_ENABLE_FALSE_START 0x00000080L + +/* Deprecated: SSL_MODE_HANDSHAKE_CUTTHROUGH is the same as + * SSL_MODE_ENABLE_FALSE_START. */ +#define SSL_MODE_HANDSHAKE_CUTTHROUGH SSL_MODE_ENABLE_FALSE_START + +/* SSL_MODE_CBC_RECORD_SPLITTING causes multi-byte CBC records in SSL 3.0 and + * TLS 1.0 to be split in two: the first record will contain a single byte and + * the second will contain the remainder. This effectively randomises the IV and + * prevents BEAST attacks. */ +#define SSL_MODE_CBC_RECORD_SPLITTING 0x00000100L + +/* SSL_MODE_NO_SESSION_CREATION will cause any attempts to create a session to + * fail with SSL_R_SESSION_MAY_NOT_BE_CREATED. This can be used to enforce that + * session resumption is used for a given SSL*. */ +#define SSL_MODE_NO_SESSION_CREATION 0x00000200L + +/* SSL_MODE_SEND_FALLBACK_SCSV sends TLS_FALLBACK_SCSV in the ClientHello. + * To be set only by applications that reconnect with a downgraded protocol + * version; see https://tools.ietf.org/html/draft-ietf-tls-downgrade-scsv-05 + * for details. + * + * DO NOT ENABLE THIS if your application attempts a normal handshake. Only use + * this in explicit fallback retries, following the guidance in + * draft-ietf-tls-downgrade-scsv-05. */ +#define SSL_MODE_SEND_FALLBACK_SCSV 0x00000400L + +/* The following flags do nothing and are included only to make it easier to + * compile code with BoringSSL. */ +#define SSL_MODE_AUTO_RETRY 0 +#define SSL_MODE_RELEASE_BUFFERS 0 +#define SSL_MODE_SEND_CLIENTHELLO_TIME 0 +#define SSL_MODE_SEND_SERVERHELLO_TIME 0 + +/* SSL_CTX_set_mode enables all modes set in |mode| (which should be one or more + * of the |SSL_MODE_*| values, ORed together) in |ctx|. It returns a bitmask + * representing the resulting enabled modes. */ +OPENSSL_EXPORT uint32_t SSL_CTX_set_mode(SSL_CTX *ctx, uint32_t mode); + +/* SSL_CTX_clear_mode disables all modes set in |mode| (which should be one or + * more of the |SSL_MODE_*| values, ORed together) in |ctx|. It returns a + * bitmask representing the resulting enabled modes. */ +OPENSSL_EXPORT uint32_t SSL_CTX_clear_mode(SSL_CTX *ctx, uint32_t mode); + +/* SSL_CTX_get_mode returns a bitmask of |SSL_MODE_*| values that represent all + * the modes enabled for |ssl|. */ +OPENSSL_EXPORT uint32_t SSL_CTX_get_mode(const SSL_CTX *ctx); + +/* SSL_set_mode enables all modes set in |mode| (which should be one or more of + * the |SSL_MODE_*| values, ORed together) in |ssl|. It returns a bitmask + * representing the resulting enabled modes. */ +OPENSSL_EXPORT uint32_t SSL_set_mode(SSL *ssl, uint32_t mode); + +/* SSL_clear_mode disables all modes set in |mode| (which should be one or more + * of the |SSL_MODE_*| values, ORed together) in |ssl|. It returns a bitmask + * representing the resulting enabled modes. */ +OPENSSL_EXPORT uint32_t SSL_clear_mode(SSL *ssl, uint32_t mode); + +/* SSL_get_mode returns a bitmask of |SSL_MODE_*| values that represent all the + * modes enabled for |ssl|. */ +OPENSSL_EXPORT uint32_t SSL_get_mode(const SSL *ssl); + + +/* Connection information. */ + +/* SSL_get_tls_unique writes at most |max_out| bytes of the tls-unique value + * for |ssl| to |out| and sets |*out_len| to the number of bytes written. It + * returns one on success or zero on error. In general |max_out| should be at + * least 12. + * + * This function will always fail if the initial handshake has not completed. + * The tls-unique value will change after a renegotiation but, since + * renegotiations can be initiated by the server at any point, the higher-level + * protocol must either leave them disabled or define states in which the + * tls-unique value can be read. + * + * The tls-unique value is defined by + * https://tools.ietf.org/html/rfc5929#section-3.1. Due to a weakness in the + * TLS protocol, tls-unique is broken for resumed connections unless the + * Extended Master Secret extension is negotiated. Thus this function will + * return zero if |ssl| performed session resumption unless EMS was used when + * negotiating the original session. */ +OPENSSL_EXPORT int SSL_get_tls_unique(const SSL *ssl, uint8_t *out, + size_t *out_len, size_t max_out); + + +/* Underdocumented functions. + * + * Functions below here haven't been touched up and may be underdocumented. */ + +/* SSLeay version number for ASN.1 encoding of the session information */ +/* Version 0 - initial version + * Version 1 - added the optional peer certificate. */ +#define SSL_SESSION_ASN1_VERSION 0x0001 + +#define SSL_MAX_SSL_SESSION_ID_LENGTH 32 +#define SSL_MAX_SID_CTX_LENGTH 32 +#define SSL_MAX_MASTER_KEY_LENGTH 48 + +/* These are used to specify which ciphers to use and not to use */ + +#define SSL_TXT_MEDIUM "MEDIUM" +#define SSL_TXT_HIGH "HIGH" +#define SSL_TXT_FIPS "FIPS" + +#define SSL_TXT_kRSA "kRSA" +#define SSL_TXT_kDHE "kDHE" +#define SSL_TXT_kEDH "kEDH" /* same as "kDHE" */ +#define SSL_TXT_kECDHE "kECDHE" +#define SSL_TXT_kEECDH "kEECDH" /* same as "kECDHE" */ +#define SSL_TXT_kPSK "kPSK" + +#define SSL_TXT_aRSA "aRSA" +#define SSL_TXT_aECDSA "aECDSA" +#define SSL_TXT_aPSK "aPSK" + +#define SSL_TXT_DH "DH" +#define SSL_TXT_DHE "DHE" /* same as "kDHE" */ +#define SSL_TXT_EDH "EDH" /* same as "DHE" */ +#define SSL_TXT_RSA "RSA" +#define SSL_TXT_ECDH "ECDH" +#define SSL_TXT_ECDHE "ECDHE" /* same as "kECDHE" */ +#define SSL_TXT_EECDH "EECDH" /* same as "ECDHE" */ +#define SSL_TXT_ECDSA "ECDSA" +#define SSL_TXT_PSK "PSK" + +#define SSL_TXT_3DES "3DES" +#define SSL_TXT_RC4 "RC4" +#define SSL_TXT_AES128 "AES128" +#define SSL_TXT_AES256 "AES256" +#define SSL_TXT_AES "AES" +#define SSL_TXT_AES_GCM "AESGCM" +#define SSL_TXT_CHACHA20 "CHACHA20" + +#define SSL_TXT_MD5 "MD5" +#define SSL_TXT_SHA1 "SHA1" +#define SSL_TXT_SHA "SHA" /* same as "SHA1" */ +#define SSL_TXT_SHA256 "SHA256" +#define SSL_TXT_SHA384 "SHA384" + +#define SSL_TXT_SSLV3 "SSLv3" +#define SSL_TXT_TLSV1 "TLSv1" +#define SSL_TXT_TLSV1_1 "TLSv1.1" +#define SSL_TXT_TLSV1_2 "TLSv1.2" + +#define SSL_TXT_ALL "ALL" + +/* COMPLEMENTOF* definitions. These identifiers are used to (de-select) ciphers + * normally not being used. + * + * Example: "RC4" will activate all ciphers using RC4 including ciphers without + * authentication, which would normally disabled by DEFAULT (due the "!ADH" + * being part of default). Therefore "RC4:!COMPLEMENTOFDEFAULT" will make sure + * that it is also disabled in the specific selection. COMPLEMENTOF* + * identifiers are portable between version, as adjustments to the default + * cipher setup will also be included here. + * + * COMPLEMENTOFDEFAULT does not experience the same special treatment that + * DEFAULT gets, as only selection is being done and no sorting as needed for + * DEFAULT. */ +#define SSL_TXT_CMPDEF "COMPLEMENTOFDEFAULT" + +/* The following cipher list is used by default. It also is substituted when an + * application-defined cipher list string starts with 'DEFAULT'. */ +#define SSL_DEFAULT_CIPHER_LIST "ALL" + +/* As of OpenSSL 1.0.0, ssl_create_cipher_list() in ssl/ssl_ciph.c always + * starts with a reasonable order, and all we have to do for DEFAULT is + * throwing out anonymous and unencrypted ciphersuites! (The latter are not + * actually enabled by ALL, but "ALL:RSA" would enable some of them.) */ + +/* Used in SSL_set_shutdown()/SSL_get_shutdown(); */ +#define SSL_SENT_SHUTDOWN 1 +#define SSL_RECEIVED_SHUTDOWN 2 + +#define SSL_FILETYPE_ASN1 X509_FILETYPE_ASN1 +#define SSL_FILETYPE_PEM X509_FILETYPE_PEM + +typedef struct ssl_protocol_method_st SSL_PROTOCOL_METHOD; +typedef struct ssl_session_st SSL_SESSION; +typedef struct tls_sigalgs_st TLS_SIGALGS; +typedef struct ssl_conf_ctx_st SSL_CONF_CTX; +typedef struct ssl3_enc_method SSL3_ENC_METHOD; + +/* SRTP protection profiles for use with the use_srtp extension (RFC 5764). */ +typedef struct srtp_protection_profile_st { + const char *name; + unsigned long id; +} SRTP_PROTECTION_PROFILE; + +DECLARE_STACK_OF(SRTP_PROTECTION_PROFILE) + +/* An SSL_SESSION represents an SSL session that may be resumed in an + * abbreviated handshake. */ +struct ssl_session_st { + int ssl_version; /* what ssl version session info is being kept in here? */ + + int master_key_length; + uint8_t master_key[SSL_MAX_MASTER_KEY_LENGTH]; + /* session_id - valid? */ + unsigned int session_id_length; + uint8_t session_id[SSL_MAX_SSL_SESSION_ID_LENGTH]; + /* this is used to determine whether the session is being reused in + * the appropriate context. It is up to the application to set this, + * via SSL_new */ + unsigned int sid_ctx_length; + uint8_t sid_ctx[SSL_MAX_SID_CTX_LENGTH]; + + char *psk_identity; + /* Used to indicate that session resumption is not allowed. Applications can + * also set this bit for a new session via not_resumable_session_cb to + * disable session caching and tickets. */ + int not_resumable; + + /* The cert is the certificate used to establish this connection */ + struct sess_cert_st /* SESS_CERT */ *sess_cert; + + /* This is the cert for the other end. On clients, it will be the same as + * sess_cert->peer_key->x509 (the latter is not enough as sess_cert is not + * retained in the external representation of sessions, see ssl_asn1.c). */ + X509 *peer; + /* when app_verify_callback accepts a session where the peer's certificate is + * not ok, we must remember the error for session reuse: */ + long verify_result; /* only for servers */ + + CRYPTO_refcount_t references; + long timeout; + long time; + + const SSL_CIPHER *cipher; + + CRYPTO_EX_DATA ex_data; /* application specific data */ + + /* These are used to make removal of session-ids more efficient and to + * implement a maximum cache size. */ + SSL_SESSION *prev, *next; + char *tlsext_hostname; + /* RFC4507 info */ + uint8_t *tlsext_tick; /* Session ticket */ + size_t tlsext_ticklen; /* Session ticket length */ + uint32_t tlsext_tick_lifetime_hint; /* Session lifetime hint in seconds */ + + size_t tlsext_signed_cert_timestamp_list_length; + uint8_t *tlsext_signed_cert_timestamp_list; /* Server's list. */ + + /* The OCSP response that came with the session. */ + size_t ocsp_response_length; + uint8_t *ocsp_response; + + char peer_sha256_valid; /* Non-zero if peer_sha256 is valid */ + uint8_t + peer_sha256[SHA256_DIGEST_LENGTH]; /* SHA256 of peer certificate */ + + /* original_handshake_hash contains the handshake hash (either SHA-1+MD5 or + * SHA-2, depending on TLS version) for the original, full handshake that + * created a session. This is used by Channel IDs during resumption. */ + uint8_t original_handshake_hash[EVP_MAX_MD_SIZE]; + unsigned int original_handshake_hash_len; + + /* extended_master_secret is true if the master secret in this session was + * generated using EMS and thus isn't vulnerable to the Triple Handshake + * attack. */ + char extended_master_secret; +}; + + +/* Cert related flags */ +/* Many implementations ignore some aspects of the TLS standards such as + * enforcing certifcate chain algorithms. When this is set we enforce them. */ +#define SSL_CERT_FLAG_TLS_STRICT 0x00000001L + +/* Flags for building certificate chains */ +/* Treat any existing certificates as untrusted CAs */ +#define SSL_BUILD_CHAIN_FLAG_UNTRUSTED 0x1 +/* Don't include root CA in chain */ +#define SSL_BUILD_CHAIN_FLAG_NO_ROOT 0x2 +/* Just check certificates already there */ +#define SSL_BUILD_CHAIN_FLAG_CHECK 0x4 +/* Ignore verification errors */ +#define SSL_BUILD_CHAIN_FLAG_IGNORE_ERROR 0x8 +/* Clear verification errors from queue */ +#define SSL_BUILD_CHAIN_FLAG_CLEAR_ERROR 0x10 + +/* SSL_set_mtu sets the |ssl|'s MTU in DTLS to |mtu|. It returns one on success + * and zero on failure. */ +OPENSSL_EXPORT int SSL_set_mtu(SSL *ssl, unsigned mtu); + +/* SSL_get_secure_renegotiation_support returns one if the peer supports secure + * renegotiation (RFC 5746) and zero otherwise. */ +OPENSSL_EXPORT int SSL_get_secure_renegotiation_support(const SSL *ssl); + +/* SSL_CTX_set_msg_callback installs |cb| as the message callback for |ctx|. + * This callback will be called when sending or receiving low-level record + * headers, complete handshake messages, ChangeCipherSpec, and alerts. + * |write_p| is one for outgoing messages and zero for incoming messages. + * + * For each record header, |cb| is called with |version| = 0 and |content_type| + * = |SSL3_RT_HEADER|. The |len| bytes from |buf| contain the header. Note that + * this does not include the record body. If the record is sealed, the length + * in the header is the length of the ciphertext. + * + * For each handshake message, ChangeCipherSpec, and alert, |version| is the + * protocol version and |content_type| is the corresponding record type. The + * |len| bytes from |buf| contain the handshake message, one-byte + * ChangeCipherSpec body, and two-byte alert, respectively. */ +OPENSSL_EXPORT void SSL_CTX_set_msg_callback( + SSL_CTX *ctx, void (*cb)(int write_p, int version, int content_type, + const void *buf, size_t len, SSL *ssl, void *arg)); + +/* SSL_CTX_set_msg_callback_arg sets the |arg| parameter of the message + * callback. */ +OPENSSL_EXPORT void SSL_CTX_set_msg_callback_arg(SSL_CTX *ctx, void *arg); + +/* SSL_set_msg_callback installs |cb| as the message callback of |ssl|. See + * |SSL_CTX_set_msg_callback| for when this callback is called. */ +OPENSSL_EXPORT void SSL_set_msg_callback( + SSL *ssl, void (*cb)(int write_p, int version, int content_type, + const void *buf, size_t len, SSL *ssl, void *arg)); + +/* SSL_set_msg_callback_arg sets the |arg| parameter of the message callback. */ +OPENSSL_EXPORT void SSL_set_msg_callback_arg(SSL *ssl, void *arg); + +/* SSL_CTX_set_keylog_bio sets configures all SSL objects attached to |ctx| to + * log session material to |keylog_bio|. This is intended for debugging use + * with tools like Wireshark. |ctx| takes ownership of |keylog_bio|. + * + * The format is described in + * https://developer.mozilla.org/en-US/docs/Mozilla/Projects/NSS/Key_Log_Format. */ +OPENSSL_EXPORT void SSL_CTX_set_keylog_bio(SSL_CTX *ctx, BIO *keylog_bio); + + +struct ssl_aead_ctx_st; +typedef struct ssl_aead_ctx_st SSL_AEAD_CTX; + +#define SSL_MAX_CERT_LIST_DEFAULT 1024 * 100 /* 100k max cert list */ + +#define SSL_SESSION_CACHE_MAX_SIZE_DEFAULT (1024 * 20) + +#define SSL_DEFAULT_SESSION_TIMEOUT (2 * 60 * 60) + +/* This callback type is used inside SSL_CTX, SSL, and in the functions that + * set them. It is used to override the generation of SSL/TLS session IDs in a + * server. Return value should be zero on an error, non-zero to proceed. Also, + * callbacks should themselves check if the id they generate is unique + * otherwise the SSL handshake will fail with an error - callbacks can do this + * using the 'ssl' value they're passed by; + * SSL_has_matching_session_id(ssl, id, *id_len) + * The length value passed in is set at the maximum size the session ID can be. + * In SSLv2 this is 16 bytes, whereas SSLv3/TLSv1 it is 32 bytes. The callback + * can alter this length to be less if desired, but under SSLv2 session IDs are + * supposed to be fixed at 16 bytes so the id will be padded after the callback + * returns in this case. It is also an error for the callback to set the size + * to zero. */ +typedef int (*GEN_SESSION_CB)(const SSL *ssl, uint8_t *id, + unsigned int *id_len); + +/* ssl_early_callback_ctx is passed to certain callbacks that are called very + * early on during the server handshake. At this point, much of the SSL* hasn't + * been filled out and only the ClientHello can be depended on. */ +struct ssl_early_callback_ctx { + SSL *ssl; + const uint8_t *client_hello; + size_t client_hello_len; + const uint8_t *session_id; + size_t session_id_len; + const uint8_t *cipher_suites; + size_t cipher_suites_len; + const uint8_t *compression_methods; + size_t compression_methods_len; + const uint8_t *extensions; + size_t extensions_len; +}; + +/* SSL_early_callback_ctx_extension_get searches the extensions in |ctx| for an + * extension of the given type. If not found, it returns zero. Otherwise it + * sets |out_data| to point to the extension contents (not including the type + * and length bytes), sets |out_len| to the length of the extension contents + * and returns one. */ +OPENSSL_EXPORT char SSL_early_callback_ctx_extension_get( + const struct ssl_early_callback_ctx *ctx, uint16_t extension_type, + const uint8_t **out_data, size_t *out_len); + +typedef struct ssl_comp_st SSL_COMP; + +struct ssl_comp_st { + int id; + const char *name; + char *method; +}; + +DECLARE_STACK_OF(SSL_COMP) +DECLARE_LHASH_OF(SSL_SESSION) + +/* ssl_cipher_preference_list_st contains a list of SSL_CIPHERs with + * equal-preference groups. For TLS clients, the groups are moot because the + * server picks the cipher and groups cannot be expressed on the wire. However, + * for servers, the equal-preference groups allow the client's preferences to + * be partially respected. (This only has an effect with + * SSL_OP_CIPHER_SERVER_PREFERENCE). + * + * The equal-preference groups are expressed by grouping SSL_CIPHERs together. + * All elements of a group have the same priority: no ordering is expressed + * within a group. + * + * The values in |ciphers| are in one-to-one correspondence with + * |in_group_flags|. (That is, sk_SSL_CIPHER_num(ciphers) is the number of + * bytes in |in_group_flags|.) The bytes in |in_group_flags| are either 1, to + * indicate that the corresponding SSL_CIPHER is not the last element of a + * group, or 0 to indicate that it is. + * + * For example, if |in_group_flags| contains all zeros then that indicates a + * traditional, fully-ordered preference. Every SSL_CIPHER is the last element + * of the group (i.e. they are all in a one-element group). + * + * For a more complex example, consider: + * ciphers: A B C D E F + * in_group_flags: 1 1 0 0 1 0 + * + * That would express the following, order: + * + * A E + * B -> D -> F + * C + */ +struct ssl_cipher_preference_list_st { + STACK_OF(SSL_CIPHER) *ciphers; + uint8_t *in_group_flags; +}; + +struct ssl_ctx_st { + const SSL_PROTOCOL_METHOD *method; + + /* lock is used to protect various operations on this object. */ + CRYPTO_MUTEX lock; + + /* max_version is the maximum acceptable protocol version. If zero, the + * maximum supported version, currently (D)TLS 1.2, is used. */ + uint16_t max_version; + + /* min_version is the minimum acceptable protocl version. If zero, the + * minimum supported version, currently SSL 3.0 and DTLS 1.0, is used */ + uint16_t min_version; + + struct ssl_cipher_preference_list_st *cipher_list; + /* same as above but sorted for lookup */ + STACK_OF(SSL_CIPHER) *cipher_list_by_id; + /* cipher_list_tls11 is the list of ciphers when TLS 1.1 or greater is in + * use. This only applies to server connections as, for clients, the version + * number is known at connect time and so the cipher list can be set then. */ + struct ssl_cipher_preference_list_st *cipher_list_tls11; + + X509_STORE *cert_store; + LHASH_OF(SSL_SESSION) *sessions; + /* Most session-ids that will be cached, default is + * SSL_SESSION_CACHE_MAX_SIZE_DEFAULT. 0 is unlimited. */ + unsigned long session_cache_size; + SSL_SESSION *session_cache_head; + SSL_SESSION *session_cache_tail; + + /* handshakes_since_cache_flush is the number of successful handshakes since + * the last cache flush. */ + int handshakes_since_cache_flush; + + /* This can have one of 2 values, ored together, + * SSL_SESS_CACHE_CLIENT, + * SSL_SESS_CACHE_SERVER, + * Default is SSL_SESSION_CACHE_SERVER, which means only + * SSL_accept which cache SSL_SESSIONS. */ + int session_cache_mode; + + /* If timeout is not 0, it is the default timeout value set when SSL_new() is + * called. This has been put in to make life easier to set things up */ + long session_timeout; + + /* If this callback is not null, it will be called each time a session id is + * added to the cache. If this function returns 1, it means that the + * callback will do a SSL_SESSION_free() when it has finished using it. + * Otherwise, on 0, it means the callback has finished with it. If + * remove_session_cb is not null, it will be called when a session-id is + * removed from the cache. After the call, OpenSSL will SSL_SESSION_free() + * it. */ + int (*new_session_cb)(SSL *ssl, SSL_SESSION *sess); + void (*remove_session_cb)(SSL_CTX *ctx, SSL_SESSION *sess); + SSL_SESSION *(*get_session_cb)(SSL *ssl, uint8_t *data, int len, + int *copy); + + CRYPTO_refcount_t references; + + /* if defined, these override the X509_verify_cert() calls */ + int (*app_verify_callback)(X509_STORE_CTX *, void *); + void *app_verify_arg; + /* before OpenSSL 0.9.7, 'app_verify_arg' was ignored ('app_verify_callback' + * was called with just one argument) */ + + /* Default password callback. */ + pem_password_cb *default_passwd_callback; + + /* Default password callback user data. */ + void *default_passwd_callback_userdata; + + /* get client cert callback */ + int (*client_cert_cb)(SSL *ssl, X509 **x509, EVP_PKEY **pkey); + + /* get channel id callback */ + void (*channel_id_cb)(SSL *ssl, EVP_PKEY **pkey); + + CRYPTO_EX_DATA ex_data; + + STACK_OF(X509) *extra_certs; + + + /* Default values used when no per-SSL value is defined follow */ + + void (*info_callback)(const SSL *ssl, int type, + int val); /* used if SSL's info_callback is NULL */ + + /* what we put in client cert requests */ + STACK_OF(X509_NAME) *client_CA; + + + /* Default values to use in SSL structures follow (these are copied by + * SSL_new) */ + + uint32_t options; + uint32_t mode; + uint32_t max_cert_list; + + struct cert_st /* CERT */ *cert; + + /* callback that allows applications to peek at protocol messages */ + void (*msg_callback)(int write_p, int version, int content_type, + const void *buf, size_t len, SSL *ssl, void *arg); + void *msg_callback_arg; + + int verify_mode; + unsigned int sid_ctx_length; + uint8_t sid_ctx[SSL_MAX_SID_CTX_LENGTH]; + int (*default_verify_callback)( + int ok, X509_STORE_CTX *ctx); /* called 'verify_callback' in the SSL */ + + /* Default generate session ID callback. */ + GEN_SESSION_CB generate_session_id; + + X509_VERIFY_PARAM *param; + + /* select_certificate_cb is called before most ClientHello processing and + * before the decision whether to resume a session is made. It may return one + * to continue the handshake or zero to cause the handshake loop to return + * with an error and cause SSL_get_error to return + * SSL_ERROR_PENDING_CERTIFICATE. Note: when the handshake loop is resumed, it + * will not call the callback a second time. */ + int (*select_certificate_cb)(const struct ssl_early_callback_ctx *); + + /* dos_protection_cb is called once the resumption decision for a ClientHello + * has been made. It returns one to continue the handshake or zero to + * abort. */ + int (*dos_protection_cb) (const struct ssl_early_callback_ctx *); + + /* quiet_shutdown is true if the connection should not send a close_notify on + * shutdown. */ + int quiet_shutdown; + + /* Maximum amount of data to send in one fragment. actual record size can be + * more than this due to padding and MAC overheads. */ + uint16_t max_send_fragment; + + /* TLS extensions servername callback */ + int (*tlsext_servername_callback)(SSL *, int *, void *); + void *tlsext_servername_arg; + /* RFC 4507 session ticket keys */ + uint8_t tlsext_tick_key_name[16]; + uint8_t tlsext_tick_hmac_key[16]; + uint8_t tlsext_tick_aes_key[16]; + /* Callback to support customisation of ticket key setting */ + int (*tlsext_ticket_key_cb)(SSL *ssl, uint8_t *name, uint8_t *iv, + EVP_CIPHER_CTX *ectx, HMAC_CTX *hctx, int enc); + + /* Server-only: psk_identity_hint is the default identity hint to send in + * PSK-based key exchanges. */ + char *psk_identity_hint; + + unsigned int (*psk_client_callback)(SSL *ssl, const char *hint, + char *identity, + unsigned int max_identity_len, + uint8_t *psk, unsigned int max_psk_len); + unsigned int (*psk_server_callback)(SSL *ssl, const char *identity, + uint8_t *psk, unsigned int max_psk_len); + + + /* retain_only_sha256_of_client_certs is true if we should compute the SHA256 + * hash of the peer's certifiate and then discard it to save memory and + * session space. Only effective on the server side. */ + char retain_only_sha256_of_client_certs; + + /* Next protocol negotiation information */ + /* (for experimental NPN extension). */ + + /* For a server, this contains a callback function by which the set of + * advertised protocols can be provided. */ + int (*next_protos_advertised_cb)(SSL *s, const uint8_t **buf, + unsigned int *len, void *arg); + void *next_protos_advertised_cb_arg; + /* For a client, this contains a callback function that selects the + * next protocol from the list provided by the server. */ + int (*next_proto_select_cb)(SSL *s, uint8_t **out, uint8_t *outlen, + const uint8_t *in, unsigned int inlen, void *arg); + void *next_proto_select_cb_arg; + + /* ALPN information + * (we are in the process of transitioning from NPN to ALPN.) */ + + /* For a server, this contains a callback function that allows the + * server to select the protocol for the connection. + * out: on successful return, this must point to the raw protocol + * name (without the length prefix). + * outlen: on successful return, this contains the length of |*out|. + * in: points to the client's list of supported protocols in + * wire-format. + * inlen: the length of |in|. */ + int (*alpn_select_cb)(SSL *s, const uint8_t **out, uint8_t *outlen, + const uint8_t *in, unsigned int inlen, void *arg); + void *alpn_select_cb_arg; + + /* For a client, this contains the list of supported protocols in wire + * format. */ + uint8_t *alpn_client_proto_list; + unsigned alpn_client_proto_list_len; + + /* SRTP profiles we are willing to do from RFC 5764 */ + STACK_OF(SRTP_PROTECTION_PROFILE) *srtp_profiles; + + /* EC extension values inherited by SSL structure */ + size_t tlsext_ecpointformatlist_length; + uint8_t *tlsext_ecpointformatlist; + size_t tlsext_ellipticcurvelist_length; + uint16_t *tlsext_ellipticcurvelist; + + /* If true, a client will advertise the Channel ID extension and a server + * will echo it. */ + char tlsext_channel_id_enabled; + /* tlsext_channel_id_enabled_new is a hack to support both old and new + * ChannelID signatures. It indicates that a client should advertise the new + * ChannelID extension number. */ + char tlsext_channel_id_enabled_new; + /* The client's Channel ID private key. */ + EVP_PKEY *tlsext_channel_id_private; + + /* If true, a client will request certificate timestamps. */ + char signed_cert_timestamps_enabled; + + /* If true, a client will request a stapled OCSP response. */ + char ocsp_stapling_enabled; + + /* If not NULL, session key material will be logged to this BIO for debugging + * purposes. The format matches NSS's and is readable by Wireshark. */ + BIO *keylog_bio; + + /* current_time_cb, if not NULL, is the function to use to get the current + * time. It sets |*out_clock| to the current time. */ + void (*current_time_cb)(const SSL *ssl, struct timeval *out_clock); +}; + +OPENSSL_EXPORT LHASH_OF(SSL_SESSION) *SSL_CTX_sessions(SSL_CTX *ctx); + +/* SSL_CTX_sess_number returns the number of sessions in |ctx|'s internal + * session cache. */ +OPENSSL_EXPORT size_t SSL_CTX_sess_number(const SSL_CTX *ctx); + +OPENSSL_EXPORT void SSL_CTX_sess_set_new_cb( + SSL_CTX *ctx, int (*new_session_cb)(SSL *ssl, SSL_SESSION *sess)); +OPENSSL_EXPORT int (*SSL_CTX_sess_get_new_cb(SSL_CTX *ctx))(SSL *ssl, + SSL_SESSION *sess); +OPENSSL_EXPORT void SSL_CTX_sess_set_remove_cb( + SSL_CTX *ctx, + void (*remove_session_cb)(SSL_CTX *ctx, SSL_SESSION *sess)); +OPENSSL_EXPORT void (*SSL_CTX_sess_get_remove_cb(SSL_CTX *ctx))( + SSL_CTX *ctx, SSL_SESSION *sess); +OPENSSL_EXPORT void SSL_CTX_sess_set_get_cb( + SSL_CTX *ctx, + SSL_SESSION *(*get_session_cb)(SSL *ssl, uint8_t *data, int len, + int *copy)); +OPENSSL_EXPORT SSL_SESSION *(*SSL_CTX_sess_get_get_cb(SSL_CTX *ctx))( + SSL *ssl, uint8_t *data, int len, int *copy); +/* SSL_magic_pending_session_ptr returns a magic SSL_SESSION* which indicates + * that the session isn't currently unavailable. SSL_get_error will then return + * SSL_ERROR_PENDING_SESSION and the handshake can be retried later when the + * lookup has completed. */ +OPENSSL_EXPORT SSL_SESSION *SSL_magic_pending_session_ptr(void); +OPENSSL_EXPORT void SSL_CTX_set_info_callback(SSL_CTX *ctx, + void (*cb)(const SSL *ssl, + int type, int val)); +OPENSSL_EXPORT void (*SSL_CTX_get_info_callback(SSL_CTX *ctx))(const SSL *ssl, + int type, + int val); +OPENSSL_EXPORT void SSL_CTX_set_client_cert_cb( + SSL_CTX *ctx, + int (*client_cert_cb)(SSL *ssl, X509 **x509, EVP_PKEY **pkey)); +OPENSSL_EXPORT int (*SSL_CTX_get_client_cert_cb(SSL_CTX *ctx))(SSL *ssl, + X509 **x509, + EVP_PKEY **pkey); +OPENSSL_EXPORT void SSL_CTX_set_channel_id_cb( + SSL_CTX *ctx, void (*channel_id_cb)(SSL *ssl, EVP_PKEY **pkey)); +OPENSSL_EXPORT void (*SSL_CTX_get_channel_id_cb(SSL_CTX *ctx))(SSL *ssl, + EVP_PKEY **pkey); + +/* SSL_enable_signed_cert_timestamps causes |ssl| (which must be the client end + * of a connection) to request SCTs from the server. See + * https://tools.ietf.org/html/rfc6962. It returns one. */ +OPENSSL_EXPORT int SSL_enable_signed_cert_timestamps(SSL *ssl); + +/* SSL_CTX_enable_signed_cert_timestamps enables SCT requests on all client SSL + * objects created from |ctx|. */ +OPENSSL_EXPORT void SSL_CTX_enable_signed_cert_timestamps(SSL_CTX *ctx); + +/* SSL_enable_ocsp_stapling causes |ssl| (which must be the client end of a + * connection) to request a stapled OCSP response from the server. It returns + * one. */ +OPENSSL_EXPORT int SSL_enable_ocsp_stapling(SSL *ssl); + +/* SSL_CTX_enable_ocsp_stapling enables OCSP stapling on all client SSL objects + * created from |ctx|. */ +OPENSSL_EXPORT void SSL_CTX_enable_ocsp_stapling(SSL_CTX *ctx); + +/* SSL_get0_signed_cert_timestamp_list sets |*out| and |*out_len| to point to + * |*out_len| bytes of SCT information from the server. This is only valid if + * |ssl| is a client. The SCT information is a SignedCertificateTimestampList + * (including the two leading length bytes). + * See https://tools.ietf.org/html/rfc6962#section-3.3 + * If no SCT was received then |*out_len| will be zero on return. + * + * WARNING: the returned data is not guaranteed to be well formed. */ +OPENSSL_EXPORT void SSL_get0_signed_cert_timestamp_list(const SSL *ssl, + const uint8_t **out, + size_t *out_len); + +/* SSL_get0_ocsp_response sets |*out| and |*out_len| to point to |*out_len| + * bytes of an OCSP response from the server. This is the DER encoding of an + * OCSPResponse type as defined in RFC 2560. + * + * WARNING: the returned data is not guaranteed to be well formed. */ +OPENSSL_EXPORT void SSL_get0_ocsp_response(const SSL *ssl, const uint8_t **out, + size_t *out_len); + +OPENSSL_EXPORT void SSL_CTX_set_next_protos_advertised_cb( + SSL_CTX *s, + int (*cb)(SSL *ssl, const uint8_t **out, unsigned int *outlen, void *arg), + void *arg); +OPENSSL_EXPORT void SSL_CTX_set_next_proto_select_cb( + SSL_CTX *s, int (*cb)(SSL *ssl, uint8_t **out, uint8_t *outlen, + const uint8_t *in, unsigned int inlen, void *arg), + void *arg); +OPENSSL_EXPORT void SSL_get0_next_proto_negotiated(const SSL *s, + const uint8_t **data, + unsigned *len); + +OPENSSL_EXPORT int SSL_select_next_proto(uint8_t **out, uint8_t *outlen, + const uint8_t *in, unsigned int inlen, + const uint8_t *client, + unsigned int client_len); + +#define OPENSSL_NPN_UNSUPPORTED 0 +#define OPENSSL_NPN_NEGOTIATED 1 +#define OPENSSL_NPN_NO_OVERLAP 2 + +/* SSL_CTX_set_alpn_protos sets the ALPN protocol list on |ctx| to |protos|. + * |protos| must be in wire-format (i.e. a series of non-empty, 8-bit + * length-prefixed strings). It returns zero on success and one on failure. + * + * WARNING: this function is dangerous because it breaks the usual return value + * convention. */ +OPENSSL_EXPORT int SSL_CTX_set_alpn_protos(SSL_CTX *ctx, const uint8_t *protos, + unsigned protos_len); + +/* SSL_set_alpn_protos sets the ALPN protocol list on |ssl| to |protos|. + * |protos| must be in wire-format (i.e. a series of non-empty, 8-bit + * length-prefixed strings). It returns zero on success and one on failure. + * + * WARNING: this function is dangerous because it breaks the usual return value + * convention. */ +OPENSSL_EXPORT int SSL_set_alpn_protos(SSL *ssl, const uint8_t *protos, + unsigned protos_len); + +OPENSSL_EXPORT void SSL_CTX_set_alpn_select_cb( + SSL_CTX *ctx, int (*cb)(SSL *ssl, const uint8_t **out, uint8_t *outlen, + const uint8_t *in, unsigned int inlen, void *arg), + void *arg); +OPENSSL_EXPORT void SSL_get0_alpn_selected(const SSL *ssl, const uint8_t **data, + unsigned *len); + +/* SSL_enable_fastradio_padding controls whether fastradio padding is enabled + * on |ssl|. If it is, ClientHello messages are padded to 1024 bytes. This + * causes 3G radios to switch to DCH mode (high data rate). */ +OPENSSL_EXPORT void SSL_enable_fastradio_padding(SSL *ssl, char on_off); + +/* SSL_set_reject_peer_renegotiations controls whether renegotiation attempts by + * the peer are rejected. It may be set at any point in a connection's lifetime + * to control future renegotiations programmatically. By default, renegotiations + * are rejected. (Renegotiations requested by a client are always rejected.) */ +OPENSSL_EXPORT void SSL_set_reject_peer_renegotiations(SSL *ssl, int reject); + +/* the maximum length of the buffer given to callbacks containing the resulting + * identity/psk */ +#define PSK_MAX_IDENTITY_LEN 128 +#define PSK_MAX_PSK_LEN 256 +OPENSSL_EXPORT void SSL_CTX_set_psk_client_callback( + SSL_CTX *ctx, + unsigned int (*psk_client_callback)( + SSL *ssl, const char *hint, char *identity, + unsigned int max_identity_len, uint8_t *psk, unsigned int max_psk_len)); +OPENSSL_EXPORT void SSL_set_psk_client_callback( + SSL *ssl, unsigned int (*psk_client_callback)(SSL *ssl, const char *hint, + char *identity, + unsigned int max_identity_len, + uint8_t *psk, + unsigned int max_psk_len)); +OPENSSL_EXPORT void SSL_CTX_set_psk_server_callback( + SSL_CTX *ctx, + unsigned int (*psk_server_callback)(SSL *ssl, const char *identity, + uint8_t *psk, + unsigned int max_psk_len)); +OPENSSL_EXPORT void SSL_set_psk_server_callback( + SSL *ssl, + unsigned int (*psk_server_callback)(SSL *ssl, const char *identity, + uint8_t *psk, + unsigned int max_psk_len)); +OPENSSL_EXPORT int SSL_CTX_use_psk_identity_hint(SSL_CTX *ctx, + const char *identity_hint); +OPENSSL_EXPORT int SSL_use_psk_identity_hint(SSL *s, const char *identity_hint); +OPENSSL_EXPORT const char *SSL_get_psk_identity_hint(const SSL *s); +OPENSSL_EXPORT const char *SSL_get_psk_identity(const SSL *s); + +#define SSL_NOTHING 1 +#define SSL_WRITING 2 +#define SSL_READING 3 +#define SSL_X509_LOOKUP 4 +#define SSL_CHANNEL_ID_LOOKUP 5 +#define SSL_PENDING_SESSION 7 +#define SSL_CERTIFICATE_SELECTION_PENDING 8 + +/* These will only be used when doing non-blocking IO */ +#define SSL_want_nothing(s) (SSL_want(s) == SSL_NOTHING) +#define SSL_want_read(s) (SSL_want(s) == SSL_READING) +#define SSL_want_write(s) (SSL_want(s) == SSL_WRITING) +#define SSL_want_x509_lookup(s) (SSL_want(s) == SSL_X509_LOOKUP) +#define SSL_want_channel_id_lookup(s) (SSL_want(s) == SSL_CHANNEL_ID_LOOKUP) +#define SSL_want_session(s) (SSL_want(s) == SSL_PENDING_SESSION) +#define SSL_want_certificate(s) \ + (SSL_want(s) == SSL_CERTIFICATE_SELECTION_PENDING) + +struct ssl_st { + /* version is the protocol version. */ + int version; + + /* method is the method table corresponding to the current protocol (DTLS or + * TLS). */ + const SSL_PROTOCOL_METHOD *method; + + /* enc_method is the method table corresponding to the current protocol + * version. */ + const SSL3_ENC_METHOD *enc_method; + + /* max_version is the maximum acceptable protocol version. If zero, the + * maximum supported version, currently (D)TLS 1.2, is used. */ + uint16_t max_version; + + /* min_version is the minimum acceptable protocl version. If zero, the + * minimum supported version, currently SSL 3.0 and DTLS 1.0, is used */ + uint16_t min_version; + + /* There are 2 BIO's even though they are normally both the same. This is so + * data can be read and written to different handlers */ + + BIO *rbio; /* used by SSL_read */ + BIO *wbio; /* used by SSL_write */ + BIO *bbio; /* used during session-id reuse to concatenate + * messages */ + + /* This holds a variable that indicates what we were doing when a 0 or -1 is + * returned. This is needed for non-blocking IO so we know what request + * needs re-doing when in SSL_accept or SSL_connect */ + int rwstate; + + /* true when we are actually in SSL_accept() or SSL_connect() */ + int in_handshake; + int (*handshake_func)(SSL *); + + /* Imagine that here's a boolean member "init" that is switched as soon as + * SSL_set_{accept/connect}_state is called for the first time, so that + * "state" and "handshake_func" are properly initialized. But as + * handshake_func is == 0 until then, we use this test instead of an "init" + * member. */ + + /* server is true iff the this SSL* is the server half. Note: before the SSL* + * is initialized by either SSL_set_accept_state or SSL_set_connect_state, + * the side is not determined. In this state, server is always false. */ + int server; + + /* quiet_shutdown is true if the connection should not send a close_notify on + * shutdown. */ + int quiet_shutdown; + + int shutdown; /* we have shut things down, 0x01 sent, 0x02 + * for received */ + int state; /* where we are */ + int rstate; /* where we are when reading */ + + BUF_MEM *init_buf; /* buffer used during init */ + uint8_t *init_msg; /* pointer to handshake message body, set by + ssl3_get_message() */ + int init_num; /* amount read/written */ + int init_off; /* amount read/written */ + + /* used internally to point at a raw packet */ + uint8_t *packet; + unsigned int packet_length; + + struct ssl3_state_st *s3; /* SSLv3 variables */ + struct dtls1_state_st *d1; /* DTLSv1 variables */ + + /* callback that allows applications to peek at protocol messages */ + void (*msg_callback)(int write_p, int version, int content_type, + const void *buf, size_t len, SSL *ssl, void *arg); + void *msg_callback_arg; + + int hit; /* reusing a previous session */ + + X509_VERIFY_PARAM *param; + + /* crypto */ + struct ssl_cipher_preference_list_st *cipher_list; + STACK_OF(SSL_CIPHER) *cipher_list_by_id; + + SSL_AEAD_CTX *aead_read_ctx; + SSL_AEAD_CTX *aead_write_ctx; + + /* session info */ + + /* client cert? */ + /* This is used to hold the server certificate used */ + struct cert_st /* CERT */ *cert; + + /* the session_id_context is used to ensure sessions are only reused + * in the appropriate context */ + unsigned int sid_ctx_length; + uint8_t sid_ctx[SSL_MAX_SID_CTX_LENGTH]; + + /* This can also be in the session once a session is established */ + SSL_SESSION *session; + + /* Default generate session ID callback. */ + GEN_SESSION_CB generate_session_id; + + /* Used in SSL2 and SSL3 */ + int verify_mode; /* 0 don't care about verify failure. + * 1 fail if verify fails */ + int (*verify_callback)(int ok, + X509_STORE_CTX *ctx); /* fail if callback returns 0 */ + + void (*info_callback)(const SSL *ssl, int type, + int val); /* optional informational callback */ + + /* Server-only: psk_identity_hint is the identity hint to send in + * PSK-based key exchanges. */ + char *psk_identity_hint; + + unsigned int (*psk_client_callback)(SSL *ssl, const char *hint, + char *identity, + unsigned int max_identity_len, + uint8_t *psk, unsigned int max_psk_len); + unsigned int (*psk_server_callback)(SSL *ssl, const char *identity, + uint8_t *psk, unsigned int max_psk_len); + + SSL_CTX *ctx; + + /* extra application data */ + long verify_result; + CRYPTO_EX_DATA ex_data; + + /* for server side, keep the list of CA_dn we can use */ + STACK_OF(X509_NAME) *client_CA; + + uint32_t options; /* protocol behaviour */ + uint32_t mode; /* API behaviour */ + uint32_t max_cert_list; + int client_version; /* what was passed, used for + * SSLv3/TLS rollback check */ + uint16_t max_send_fragment; + char *tlsext_hostname; + /* should_ack_sni is true if the SNI extension should be acked. This is + * only used by a server. */ + char should_ack_sni; + /* RFC4507 session ticket expected to be received or sent */ + int tlsext_ticket_expected; + size_t tlsext_ecpointformatlist_length; + uint8_t *tlsext_ecpointformatlist; /* our list */ + size_t tlsext_ellipticcurvelist_length; + uint16_t *tlsext_ellipticcurvelist; /* our list */ + + SSL_CTX *initial_ctx; /* initial ctx, used to store sessions */ + + /* Next protocol negotiation. For the client, this is the protocol that we + * sent in NextProtocol and is set when handling ServerHello extensions. + * + * For a server, this is the client's selected_protocol from NextProtocol and + * is set when handling the NextProtocol message, before the Finished + * message. */ + uint8_t *next_proto_negotiated; + size_t next_proto_negotiated_len; + + /* srtp_profiles is the list of configured SRTP protection profiles for + * DTLS-SRTP. */ + STACK_OF(SRTP_PROTECTION_PROFILE) *srtp_profiles; + + /* srtp_profile is the selected SRTP protection profile for + * DTLS-SRTP. */ + const SRTP_PROTECTION_PROFILE *srtp_profile; + + /* Copied from the SSL_CTX. For a server, means that we'll accept Channel IDs + * from clients. For a client, means that we'll advertise support. */ + char tlsext_channel_id_enabled; + /* The client's Channel ID private key. */ + EVP_PKEY *tlsext_channel_id_private; + + /* Enable signed certificate time stamps. Currently client only. */ + char signed_cert_timestamps_enabled; + + /* Enable OCSP stapling. Currently client only. + * TODO(davidben): Add a server-side implementation when it becomes + * necesary. */ + char ocsp_stapling_enabled; + + /* For a client, this contains the list of supported protocols in wire + * format. */ + uint8_t *alpn_client_proto_list; + unsigned alpn_client_proto_list_len; + + /* fastradio_padding, if true, causes ClientHellos to be padded to 1024 + * bytes. This ensures that the cellular radio is fast forwarded to DCH (high + * data rate) state in 3G networks. */ + char fastradio_padding; + + /* accept_peer_renegotiations, if one, accepts renegotiation attempts from the + * peer. Otherwise, they will be rejected with a fatal error. */ + char accept_peer_renegotiations; + + /* These fields are always NULL and exist only to keep wpa_supplicant happy + * about the change to EVP_AEAD. They are only needed for EAP-FAST, which we + * don't support. */ + EVP_CIPHER_CTX *enc_read_ctx; + EVP_MD_CTX *read_hash; +}; + +/* compatibility */ +#define SSL_set_app_data(s, arg) (SSL_set_ex_data(s, 0, (char *)arg)) +#define SSL_get_app_data(s) (SSL_get_ex_data(s, 0)) +#define SSL_SESSION_set_app_data(s, a) \ + (SSL_SESSION_set_ex_data(s, 0, (char *)a)) +#define SSL_SESSION_get_app_data(s) (SSL_SESSION_get_ex_data(s, 0)) +#define SSL_CTX_get_app_data(ctx) (SSL_CTX_get_ex_data(ctx, 0)) +#define SSL_CTX_set_app_data(ctx, arg) \ + (SSL_CTX_set_ex_data(ctx, 0, (char *)arg)) + +/* The following are the possible values for ssl->state are are used to + * indicate where we are up to in the SSL connection establishment. The macros + * that follow are about the only things you should need to use and even then, + * only when using non-blocking IO. It can also be useful to work out where you + * were when the connection failed */ + +#define SSL_ST_CONNECT 0x1000 +#define SSL_ST_ACCEPT 0x2000 +#define SSL_ST_MASK 0x0FFF +#define SSL_ST_INIT (SSL_ST_CONNECT | SSL_ST_ACCEPT) +#define SSL_ST_OK 0x03 +#define SSL_ST_RENEGOTIATE (0x04 | SSL_ST_INIT) + +#define SSL_CB_LOOP 0x01 +#define SSL_CB_EXIT 0x02 +#define SSL_CB_READ 0x04 +#define SSL_CB_WRITE 0x08 +#define SSL_CB_ALERT 0x4000 /* used in callback */ +#define SSL_CB_READ_ALERT (SSL_CB_ALERT | SSL_CB_READ) +#define SSL_CB_WRITE_ALERT (SSL_CB_ALERT | SSL_CB_WRITE) +#define SSL_CB_ACCEPT_LOOP (SSL_ST_ACCEPT | SSL_CB_LOOP) +#define SSL_CB_ACCEPT_EXIT (SSL_ST_ACCEPT | SSL_CB_EXIT) +#define SSL_CB_CONNECT_LOOP (SSL_ST_CONNECT | SSL_CB_LOOP) +#define SSL_CB_CONNECT_EXIT (SSL_ST_CONNECT | SSL_CB_EXIT) +#define SSL_CB_HANDSHAKE_START 0x10 +#define SSL_CB_HANDSHAKE_DONE 0x20 + +/* Is the SSL_connection established? */ +#define SSL_get_state(a) SSL_state(a) +#define SSL_is_init_finished(a) (SSL_state(a) == SSL_ST_OK) +#define SSL_in_init(a) (SSL_state(a) & SSL_ST_INIT) +#define SSL_in_connect_init(a) (SSL_state(a) & SSL_ST_CONNECT) +#define SSL_in_accept_init(a) (SSL_state(a) & SSL_ST_ACCEPT) + +/* SSL_in_false_start returns one if |s| has a pending unfinished handshake that + * is in False Start. |SSL_write| may be called at this point without waiting + * for the peer, but |SSL_read| will require the handshake to be completed. */ +OPENSSL_EXPORT int SSL_in_false_start(const SSL *s); + +/* The following 2 states are kept in ssl->rstate when reads fail, + * you should not need these */ +#define SSL_ST_READ_HEADER 0xF0 +#define SSL_ST_READ_BODY 0xF1 +#define SSL_ST_READ_DONE 0xF2 + +/* Obtain latest Finished message + * -- that we sent (SSL_get_finished) + * -- that we expected from peer (SSL_get_peer_finished). + * Returns length (0 == no Finished so far), copies up to 'count' bytes. */ +OPENSSL_EXPORT size_t SSL_get_finished(const SSL *s, void *buf, size_t count); +OPENSSL_EXPORT size_t SSL_get_peer_finished(const SSL *s, void *buf, size_t count); + +/* use either SSL_VERIFY_NONE or SSL_VERIFY_PEER, the last 3 options + * are 'ored' with SSL_VERIFY_PEER if they are desired */ +#define SSL_VERIFY_NONE 0x00 +#define SSL_VERIFY_PEER 0x01 +#define SSL_VERIFY_FAIL_IF_NO_PEER_CERT 0x02 +/* SSL_VERIFY_CLIENT_ONCE does nothing. */ +#define SSL_VERIFY_CLIENT_ONCE 0x04 +#define SSL_VERIFY_PEER_IF_NO_OBC 0x08 + +#define OpenSSL_add_ssl_algorithms() SSL_library_init() +#define SSLeay_add_ssl_algorithms() SSL_library_init() + +/* For backward compatibility */ +#define SSL_get_cipher(s) SSL_CIPHER_get_name(SSL_get_current_cipher(s)) +#define SSL_get_cipher_bits(s, np) \ + SSL_CIPHER_get_bits(SSL_get_current_cipher(s), np) +#define SSL_get_cipher_version(s) \ + SSL_CIPHER_get_version(SSL_get_current_cipher(s)) +#define SSL_get_cipher_name(s) SSL_CIPHER_get_name(SSL_get_current_cipher(s)) +#define SSL_get_time(a) SSL_SESSION_get_time(a) +#define SSL_set_time(a, b) SSL_SESSION_set_time((a), (b)) +#define SSL_get_timeout(a) SSL_SESSION_get_timeout(a) +#define SSL_set_timeout(a, b) SSL_SESSION_set_timeout((a), (b)) + +#define d2i_SSL_SESSION_bio(bp, s_id) \ + ASN1_d2i_bio_of(SSL_SESSION, SSL_SESSION_new, d2i_SSL_SESSION, bp, s_id) +#define i2d_SSL_SESSION_bio(bp, s_id) \ + ASN1_i2d_bio_of(SSL_SESSION, i2d_SSL_SESSION, bp, s_id) + +DECLARE_PEM_rw(SSL_SESSION, SSL_SESSION) + +/* make_errors.go reserves error codes above 1000 for manually-assigned errors. + * This value must be kept in sync with reservedReasonCode in make_errors.h */ +#define SSL_AD_REASON_OFFSET \ + 1000 /* offset to get SSL_R_... value from SSL_AD_... */ + +/* These alert types are for SSLv3 and TLSv1 */ +#define SSL_AD_CLOSE_NOTIFY SSL3_AD_CLOSE_NOTIFY +#define SSL_AD_UNEXPECTED_MESSAGE SSL3_AD_UNEXPECTED_MESSAGE /* fatal */ +#define SSL_AD_BAD_RECORD_MAC SSL3_AD_BAD_RECORD_MAC /* fatal */ +#define SSL_AD_DECRYPTION_FAILED TLS1_AD_DECRYPTION_FAILED +#define SSL_AD_RECORD_OVERFLOW TLS1_AD_RECORD_OVERFLOW +#define SSL_AD_DECOMPRESSION_FAILURE SSL3_AD_DECOMPRESSION_FAILURE /* fatal */ +#define SSL_AD_HANDSHAKE_FAILURE SSL3_AD_HANDSHAKE_FAILURE /* fatal */ +#define SSL_AD_NO_CERTIFICATE SSL3_AD_NO_CERTIFICATE /* Not for TLS */ +#define SSL_AD_BAD_CERTIFICATE SSL3_AD_BAD_CERTIFICATE +#define SSL_AD_UNSUPPORTED_CERTIFICATE SSL3_AD_UNSUPPORTED_CERTIFICATE +#define SSL_AD_CERTIFICATE_REVOKED SSL3_AD_CERTIFICATE_REVOKED +#define SSL_AD_CERTIFICATE_EXPIRED SSL3_AD_CERTIFICATE_EXPIRED +#define SSL_AD_CERTIFICATE_UNKNOWN SSL3_AD_CERTIFICATE_UNKNOWN +#define SSL_AD_ILLEGAL_PARAMETER SSL3_AD_ILLEGAL_PARAMETER /* fatal */ +#define SSL_AD_UNKNOWN_CA TLS1_AD_UNKNOWN_CA /* fatal */ +#define SSL_AD_ACCESS_DENIED TLS1_AD_ACCESS_DENIED /* fatal */ +#define SSL_AD_DECODE_ERROR TLS1_AD_DECODE_ERROR /* fatal */ +#define SSL_AD_DECRYPT_ERROR TLS1_AD_DECRYPT_ERROR +#define SSL_AD_EXPORT_RESTRICTION TLS1_AD_EXPORT_RESTRICTION /* fatal */ +#define SSL_AD_PROTOCOL_VERSION TLS1_AD_PROTOCOL_VERSION /* fatal */ +#define SSL_AD_INSUFFICIENT_SECURITY TLS1_AD_INSUFFICIENT_SECURITY /* fatal */ +#define SSL_AD_INTERNAL_ERROR TLS1_AD_INTERNAL_ERROR /* fatal */ +#define SSL_AD_USER_CANCELLED TLS1_AD_USER_CANCELLED +#define SSL_AD_NO_RENEGOTIATION TLS1_AD_NO_RENEGOTIATION +#define SSL_AD_UNSUPPORTED_EXTENSION TLS1_AD_UNSUPPORTED_EXTENSION +#define SSL_AD_CERTIFICATE_UNOBTAINABLE TLS1_AD_CERTIFICATE_UNOBTAINABLE +#define SSL_AD_UNRECOGNIZED_NAME TLS1_AD_UNRECOGNIZED_NAME +#define SSL_AD_BAD_CERTIFICATE_STATUS_RESPONSE \ + TLS1_AD_BAD_CERTIFICATE_STATUS_RESPONSE +#define SSL_AD_BAD_CERTIFICATE_HASH_VALUE TLS1_AD_BAD_CERTIFICATE_HASH_VALUE +#define SSL_AD_UNKNOWN_PSK_IDENTITY TLS1_AD_UNKNOWN_PSK_IDENTITY /* fatal */ +#define SSL_AD_INAPPROPRIATE_FALLBACK SSL3_AD_INAPPROPRIATE_FALLBACK /* fatal */ + +#define SSL_ERROR_NONE 0 +#define SSL_ERROR_SSL 1 +#define SSL_ERROR_WANT_READ 2 +#define SSL_ERROR_WANT_WRITE 3 +#define SSL_ERROR_WANT_X509_LOOKUP 4 +#define SSL_ERROR_SYSCALL 5 /* look at error stack/return value/errno */ +#define SSL_ERROR_ZERO_RETURN 6 +#define SSL_ERROR_WANT_CONNECT 7 +#define SSL_ERROR_WANT_ACCEPT 8 +#define SSL_ERROR_WANT_CHANNEL_ID_LOOKUP 9 +#define SSL_ERROR_PENDING_SESSION 11 +#define SSL_ERROR_PENDING_CERTIFICATE 12 + +#define SSL_CTRL_EXTRA_CHAIN_CERT 14 + +/* see tls1.h for macros based on these */ +#define SSL_CTRL_GET_TLSEXT_TICKET_KEYS 58 +#define SSL_CTRL_SET_TLSEXT_TICKET_KEYS 59 + +#define SSL_CTRL_SET_SRP_ARG 78 +#define SSL_CTRL_SET_TLS_EXT_SRP_USERNAME 79 +#define SSL_CTRL_SET_TLS_EXT_SRP_STRENGTH 80 +#define SSL_CTRL_SET_TLS_EXT_SRP_PASSWORD 81 + +#define SSL_CTRL_GET_EXTRA_CHAIN_CERTS 82 +#define SSL_CTRL_CLEAR_EXTRA_CHAIN_CERTS 83 + +#define SSL_CTRL_CHAIN 88 +#define SSL_CTRL_CHAIN_CERT 89 + +#define SSL_CTRL_GET_CURVES 90 +#define SSL_CTRL_SET_CURVES 91 +#define SSL_CTRL_SET_CURVES_LIST 92 +#define SSL_CTRL_SET_SIGALGS 97 +#define SSL_CTRL_SET_SIGALGS_LIST 98 +#define SSL_CTRL_SET_CLIENT_SIGALGS 101 +#define SSL_CTRL_SET_CLIENT_SIGALGS_LIST 102 +#define SSL_CTRL_GET_CLIENT_CERT_TYPES 103 +#define SSL_CTRL_SET_CLIENT_CERT_TYPES 104 +#define SSL_CTRL_BUILD_CERT_CHAIN 105 +#define SSL_CTRL_SET_VERIFY_CERT_STORE 106 +#define SSL_CTRL_SET_CHAIN_CERT_STORE 107 +#define SSL_CTRL_GET_SERVER_TMP_KEY 109 +#define SSL_CTRL_GET_EC_POINT_FORMATS 111 + +#define SSL_CTRL_GET_CHAIN_CERTS 115 +#define SSL_CTRL_SELECT_CURRENT_CERT 116 + +/* DTLSv1_get_timeout queries the next DTLS handshake timeout. If there is a + * timeout in progress, it sets |*out| to the time remaining and returns one. + * Otherwise, it returns zero. + * + * When the timeout expires, call |DTLSv1_handle_timeout| to handle the + * retransmit behavior. + * + * NOTE: This function must be queried again whenever the handshake state + * machine changes, including when |DTLSv1_handle_timeout| is called. */ +OPENSSL_EXPORT int DTLSv1_get_timeout(const SSL *ssl, struct timeval *out); + +/* DTLSv1_handle_timeout is called when a DTLS handshake timeout expires. If no + * timeout had expired, it returns 0. Otherwise, it retransmits the previous + * flight of handshake messages and returns 1. If too many timeouts had expired + * without progress or an error occurs, it returns -1. + * + * NOTE: The caller's external timer should be compatible with the one |ssl| + * queries within some fudge factor. Otherwise, the call will be a no-op, but + * |DTLSv1_get_timeout| will return an updated timeout. + * + * WARNING: This function breaks the usual return value convention. */ +OPENSSL_EXPORT int DTLSv1_handle_timeout(SSL *ssl); + +/* SSL_session_reused returns one if |ssl| performed an abbreviated handshake + * and zero otherwise. + * + * TODO(davidben): Hammer down the semantics of this API while a handshake, + * initial or renego, is in progress. */ +OPENSSL_EXPORT int SSL_session_reused(const SSL *ssl); + +/* SSL_total_renegotiations returns the total number of renegotiation handshakes + * peformed by |ssl|. This includes the pending renegotiation, if any. */ +OPENSSL_EXPORT int SSL_total_renegotiations(const SSL *ssl); + +/* SSL_CTX_set_tmp_dh configures |ctx| to use the group from |dh| as the group + * for DHE. Only the group is used, so |dh| needn't have a keypair. It returns + * one on success and zero on error. */ +OPENSSL_EXPORT int SSL_CTX_set_tmp_dh(SSL_CTX *ctx, const DH *dh); + +/* SSL_set_tmp_dh configures |ssl| to use the group from |dh| as the group for + * DHE. Only the group is used, so |dh| needn't have a keypair. It returns one + * on success and zero on error. */ +OPENSSL_EXPORT int SSL_set_tmp_dh(SSL *ssl, const DH *dh); + +/* SSL_CTX_set_tmp_ecdh configures |ctx| to use the curve from |ecdh| as the + * curve for ephemeral ECDH keys. For historical reasons, this API expects an + * |EC_KEY|, but only the curve is used. It returns one on success and zero on + * error. If unset, an appropriate curve will be chosen automatically. (This is + * recommended.) */ +OPENSSL_EXPORT int SSL_CTX_set_tmp_ecdh(SSL_CTX *ctx, const EC_KEY *ec_key); + +/* SSL_set_tmp_ecdh configures |ssl| to use the curve from |ecdh| as the curve + * for ephemeral ECDH keys. For historical reasons, this API expects an + * |EC_KEY|, but only the curve is used. It returns one on success and zero on + * error. If unset, an appropriate curve will be chosen automatically. (This is + * recommended.) */ +OPENSSL_EXPORT int SSL_set_tmp_ecdh(SSL *ssl, const EC_KEY *ec_key); + +/* SSL_CTX_enable_tls_channel_id either configures a TLS server to accept TLS + * client IDs from clients, or configures a client to send TLS client IDs to + * a server. It returns one. */ +OPENSSL_EXPORT int SSL_CTX_enable_tls_channel_id(SSL_CTX *ctx); + +/* SSL_enable_tls_channel_id either configures a TLS server to accept TLS + * client IDs from clients, or configure a client to send TLS client IDs to + * server. It returns one. */ +OPENSSL_EXPORT int SSL_enable_tls_channel_id(SSL *ssl); + +/* SSL_CTX_set1_tls_channel_id configures a TLS client to send a TLS Channel ID + * to compatible servers. |private_key| must be a P-256 EC key. It returns one + * on success and zero on error. */ +OPENSSL_EXPORT int SSL_CTX_set1_tls_channel_id(SSL_CTX *ctx, + EVP_PKEY *private_key); + +/* SSL_set1_tls_channel_id configures a TLS client to send a TLS Channel ID to + * compatible servers. |private_key| must be a P-256 EC key. It returns one on + * success and zero on error. */ +OPENSSL_EXPORT int SSL_set1_tls_channel_id(SSL *ssl, EVP_PKEY *private_key); + +/* SSL_get_tls_channel_id gets the client's TLS Channel ID from a server SSL* + * and copies up to the first |max_out| bytes into |out|. The Channel ID + * consists of the client's P-256 public key as an (x,y) pair where each is a + * 32-byte, big-endian field element. It returns 0 if the client didn't offer a + * Channel ID and the length of the complete Channel ID otherwise. */ +OPENSSL_EXPORT size_t SSL_get_tls_channel_id(SSL *ssl, uint8_t *out, + size_t max_out); + +#define SSL_CTX_add_extra_chain_cert(ctx, x509) \ + SSL_CTX_ctrl(ctx, SSL_CTRL_EXTRA_CHAIN_CERT, 0, (char *)x509) +#define SSL_CTX_get_extra_chain_certs(ctx, px509) \ + SSL_CTX_ctrl(ctx, SSL_CTRL_GET_EXTRA_CHAIN_CERTS, 0, px509) +#define SSL_CTX_get_extra_chain_certs_only(ctx, px509) \ + SSL_CTX_ctrl(ctx, SSL_CTRL_GET_EXTRA_CHAIN_CERTS, 1, px509) +#define SSL_CTX_clear_extra_chain_certs(ctx) \ + SSL_CTX_ctrl(ctx, SSL_CTRL_CLEAR_EXTRA_CHAIN_CERTS, 0, NULL) + +#define SSL_CTX_set0_chain(ctx, sk) \ + SSL_CTX_ctrl(ctx, SSL_CTRL_CHAIN, 0, (char *)sk) +#define SSL_CTX_set1_chain(ctx, sk) \ + SSL_CTX_ctrl(ctx, SSL_CTRL_CHAIN, 1, (char *)sk) +#define SSL_CTX_add0_chain_cert(ctx, x509) \ + SSL_CTX_ctrl(ctx, SSL_CTRL_CHAIN_CERT, 0, (char *)x509) +#define SSL_CTX_add1_chain_cert(ctx, x509) \ + SSL_CTX_ctrl(ctx, SSL_CTRL_CHAIN_CERT, 1, (char *)x509) +#define SSL_CTX_get0_chain_certs(ctx, px509) \ + SSL_CTX_ctrl(ctx, SSL_CTRL_GET_CHAIN_CERTS, 0, px509) +#define SSL_CTX_clear_chain_certs(ctx) SSL_CTX_set0_chain(ctx, NULL) +#define SSL_CTX_build_cert_chain(ctx, flags) \ + SSL_CTX_ctrl(ctx, SSL_CTRL_BUILD_CERT_CHAIN, flags, NULL) +#define SSL_CTX_select_current_cert(ctx, x509) \ + SSL_CTX_ctrl(ctx, SSL_CTRL_SELECT_CURRENT_CERT, 0, (char *)x509) + +#define SSL_CTX_set0_verify_cert_store(ctx, st) \ + SSL_CTX_ctrl(ctx, SSL_CTRL_SET_VERIFY_CERT_STORE, 0, (char *)st) +#define SSL_CTX_set1_verify_cert_store(ctx, st) \ + SSL_CTX_ctrl(ctx, SSL_CTRL_SET_VERIFY_CERT_STORE, 1, (char *)st) +#define SSL_CTX_set0_chain_cert_store(ctx, st) \ + SSL_CTX_ctrl(ctx, SSL_CTRL_SET_CHAIN_CERT_STORE, 0, (char *)st) +#define SSL_CTX_set1_chain_cert_store(ctx, st) \ + SSL_CTX_ctrl(ctx, SSL_CTRL_SET_CHAIN_CERT_STORE, 1, (char *)st) + +#define SSL_set0_chain(ctx, sk) SSL_ctrl(ctx, SSL_CTRL_CHAIN, 0, (char *)sk) +#define SSL_set1_chain(ctx, sk) SSL_ctrl(ctx, SSL_CTRL_CHAIN, 1, (char *)sk) +#define SSL_add0_chain_cert(ctx, x509) \ + SSL_ctrl(ctx, SSL_CTRL_CHAIN_CERT, 0, (char *)x509) +#define SSL_add1_chain_cert(ctx, x509) \ + SSL_ctrl(ctx, SSL_CTRL_CHAIN_CERT, 1, (char *)x509) +#define SSL_get0_chain_certs(ctx, px509) \ + SSL_ctrl(ctx, SSL_CTRL_GET_CHAIN_CERTS, 0, px509) +#define SSL_clear_chain_certs(ctx) SSL_set0_chain(ctx, NULL) +#define SSL_build_cert_chain(s, flags) \ + SSL_ctrl(s, SSL_CTRL_BUILD_CERT_CHAIN, flags, NULL) +#define SSL_select_current_cert(ctx, x509) \ + SSL_ctrl(ctx, SSL_CTRL_SELECT_CURRENT_CERT, 0, (char *)x509) + +#define SSL_set0_verify_cert_store(s, st) \ + SSL_ctrl(s, SSL_CTRL_SET_VERIFY_CERT_STORE, 0, (char *)st) +#define SSL_set1_verify_cert_store(s, st) \ + SSL_ctrl(s, SSL_CTRL_SET_VERIFY_CERT_STORE, 1, (char *)st) +#define SSL_set0_chain_cert_store(s, st) \ + SSL_ctrl(s, SSL_CTRL_SET_CHAIN_CERT_STORE, 0, (char *)st) +#define SSL_set1_chain_cert_store(s, st) \ + SSL_ctrl(s, SSL_CTRL_SET_CHAIN_CERT_STORE, 1, (char *)st) + +#define SSL_get1_curves(ctx, s) SSL_ctrl(ctx, SSL_CTRL_GET_CURVES, 0, (char *)s) +#define SSL_CTX_set1_curves(ctx, clist, clistlen) \ + SSL_CTX_ctrl(ctx, SSL_CTRL_SET_CURVES, clistlen, (char *)clist) +#define SSL_CTX_set1_curves_list(ctx, s) \ + SSL_CTX_ctrl(ctx, SSL_CTRL_SET_CURVES_LIST, 0, (char *)s) +#define SSL_set1_curves(ctx, clist, clistlen) \ + SSL_ctrl(ctx, SSL_CTRL_SET_CURVES, clistlen, (char *)clist) +#define SSL_set1_curves_list(ctx, s) \ + SSL_ctrl(ctx, SSL_CTRL_SET_CURVES_LIST, 0, (char *)s) + +#define SSL_CTX_set1_sigalgs(ctx, slist, slistlen) \ + SSL_CTX_ctrl(ctx, SSL_CTRL_SET_SIGALGS, slistlen, (int *)slist) +#define SSL_CTX_set1_sigalgs_list(ctx, s) \ + SSL_CTX_ctrl(ctx, SSL_CTRL_SET_SIGALGS_LIST, 0, (char *)s) +#define SSL_set1_sigalgs(ctx, slist, slistlen) \ + SSL_ctrl(ctx, SSL_CTRL_SET_SIGALGS, clistlen, (int *)slist) +#define SSL_set1_sigalgs_list(ctx, s) \ + SSL_ctrl(ctx, SSL_CTRL_SET_SIGALGS_LIST, 0, (char *)s) + +#define SSL_CTX_set1_client_sigalgs(ctx, slist, slistlen) \ + SSL_CTX_ctrl(ctx, SSL_CTRL_SET_CLIENT_SIGALGS, slistlen, (int *)slist) +#define SSL_CTX_set1_client_sigalgs_list(ctx, s) \ + SSL_CTX_ctrl(ctx, SSL_CTRL_SET_CLIENT_SIGALGS_LIST, 0, (char *)s) +#define SSL_set1_client_sigalgs(ctx, slist, slistlen) \ + SSL_ctrl(ctx, SSL_CTRL_SET_CLIENT_SIGALGS, clistlen, (int *)slist) +#define SSL_set1_client_sigalgs_list(ctx, s) \ + SSL_ctrl(ctx, SSL_CTRL_SET_CLIENT_SIGALGS_LIST, 0, (char *)s) + +#define SSL_get0_certificate_types(s, clist) \ + SSL_ctrl(s, SSL_CTRL_GET_CLIENT_CERT_TYPES, 0, (char *)clist) + +#define SSL_CTX_set1_client_certificate_types(ctx, clist, clistlen) \ + SSL_CTX_ctrl(ctx, SSL_CTRL_SET_CLIENT_CERT_TYPES, clistlen, (char *)clist) +#define SSL_set1_client_certificate_types(s, clist, clistlen) \ + SSL_ctrl(s, SSL_CTRL_SET_CLIENT_CERT_TYPES, clistlen, (char *)clist) + +#define SSL_get_server_tmp_key(s, pk) \ + SSL_ctrl(s, SSL_CTRL_GET_SERVER_TMP_KEY, 0, pk) + +#define SSL_get0_ec_point_formats(s, plst) \ + SSL_ctrl(s, SSL_CTRL_GET_EC_POINT_FORMATS, 0, (char *)plst) + +OPENSSL_EXPORT int SSL_CTX_set_cipher_list(SSL_CTX *, const char *str); +OPENSSL_EXPORT int SSL_CTX_set_cipher_list_tls11(SSL_CTX *, const char *str); +OPENSSL_EXPORT long SSL_CTX_set_timeout(SSL_CTX *ctx, long t); +OPENSSL_EXPORT long SSL_CTX_get_timeout(const SSL_CTX *ctx); +OPENSSL_EXPORT X509_STORE *SSL_CTX_get_cert_store(const SSL_CTX *); +OPENSSL_EXPORT void SSL_CTX_set_cert_store(SSL_CTX *, X509_STORE *); +OPENSSL_EXPORT int SSL_want(const SSL *s); + +OPENSSL_EXPORT void SSL_CTX_flush_sessions(SSL_CTX *ctx, long tm); + +/* SSL_get_current_cipher returns the cipher used in the current outgoing + * connection state, or NULL if the null cipher is active. */ +OPENSSL_EXPORT const SSL_CIPHER *SSL_get_current_cipher(const SSL *s); + +OPENSSL_EXPORT int SSL_get_fd(const SSL *s); +OPENSSL_EXPORT int SSL_get_rfd(const SSL *s); +OPENSSL_EXPORT int SSL_get_wfd(const SSL *s); +OPENSSL_EXPORT const char *SSL_get_cipher_list(const SSL *s, int n); +OPENSSL_EXPORT int SSL_pending(const SSL *s); +OPENSSL_EXPORT int SSL_set_fd(SSL *s, int fd); +OPENSSL_EXPORT int SSL_set_rfd(SSL *s, int fd); +OPENSSL_EXPORT int SSL_set_wfd(SSL *s, int fd); +OPENSSL_EXPORT void SSL_set_bio(SSL *s, BIO *rbio, BIO *wbio); +OPENSSL_EXPORT BIO *SSL_get_rbio(const SSL *s); +OPENSSL_EXPORT BIO *SSL_get_wbio(const SSL *s); +OPENSSL_EXPORT int SSL_set_cipher_list(SSL *s, const char *str); +OPENSSL_EXPORT int SSL_get_verify_mode(const SSL *s); +OPENSSL_EXPORT int SSL_get_verify_depth(const SSL *s); +OPENSSL_EXPORT int (*SSL_get_verify_callback(const SSL *s))(int, + X509_STORE_CTX *); +OPENSSL_EXPORT void SSL_set_verify(SSL *s, int mode, + int (*callback)(int ok, + X509_STORE_CTX *ctx)); +OPENSSL_EXPORT void SSL_set_verify_depth(SSL *s, int depth); +OPENSSL_EXPORT void SSL_set_cert_cb(SSL *s, int (*cb)(SSL *ssl, void *arg), + void *arg); +OPENSSL_EXPORT int SSL_use_RSAPrivateKey(SSL *ssl, RSA *rsa); +OPENSSL_EXPORT int SSL_use_RSAPrivateKey_ASN1(SSL *ssl, uint8_t *d, long len); +OPENSSL_EXPORT int SSL_use_PrivateKey(SSL *ssl, EVP_PKEY *pkey); +OPENSSL_EXPORT int SSL_use_PrivateKey_ASN1(int pk, SSL *ssl, const uint8_t *d, + long len); +OPENSSL_EXPORT int SSL_use_certificate(SSL *ssl, X509 *x); +OPENSSL_EXPORT int SSL_use_certificate_ASN1(SSL *ssl, const uint8_t *d, + int len); + +OPENSSL_EXPORT int SSL_use_RSAPrivateKey_file(SSL *ssl, const char *file, + int type); +OPENSSL_EXPORT int SSL_use_PrivateKey_file(SSL *ssl, const char *file, + int type); +OPENSSL_EXPORT int SSL_use_certificate_file(SSL *ssl, const char *file, + int type); +OPENSSL_EXPORT int SSL_CTX_use_RSAPrivateKey_file(SSL_CTX *ctx, + const char *file, int type); +OPENSSL_EXPORT int SSL_CTX_use_PrivateKey_file(SSL_CTX *ctx, const char *file, + int type); +OPENSSL_EXPORT int SSL_CTX_use_certificate_file(SSL_CTX *ctx, const char *file, + int type); +OPENSSL_EXPORT int SSL_CTX_use_certificate_chain_file( + SSL_CTX *ctx, const char *file); /* PEM type */ +OPENSSL_EXPORT STACK_OF(X509_NAME) *SSL_load_client_CA_file(const char *file); +OPENSSL_EXPORT int SSL_add_file_cert_subjects_to_stack(STACK_OF(X509_NAME) * + stackCAs, + const char *file); +OPENSSL_EXPORT int SSL_add_dir_cert_subjects_to_stack(STACK_OF(X509_NAME) * + stackCAs, + const char *dir); + +/* SSL_load_error_strings does nothing. */ +OPENSSL_EXPORT void SSL_load_error_strings(void); + +OPENSSL_EXPORT const char *SSL_state_string(const SSL *s); +OPENSSL_EXPORT const char *SSL_rstate_string(const SSL *s); +OPENSSL_EXPORT const char *SSL_state_string_long(const SSL *s); +OPENSSL_EXPORT const char *SSL_rstate_string_long(const SSL *s); +OPENSSL_EXPORT long SSL_SESSION_get_time(const SSL_SESSION *s); +OPENSSL_EXPORT long SSL_SESSION_set_time(SSL_SESSION *s, long t); +OPENSSL_EXPORT long SSL_SESSION_get_timeout(const SSL_SESSION *s); +OPENSSL_EXPORT long SSL_SESSION_set_timeout(SSL_SESSION *s, long t); +OPENSSL_EXPORT X509 *SSL_SESSION_get0_peer(SSL_SESSION *s); +OPENSSL_EXPORT int SSL_SESSION_set1_id_context(SSL_SESSION *s, + const uint8_t *sid_ctx, + unsigned int sid_ctx_len); + +OPENSSL_EXPORT SSL_SESSION *SSL_SESSION_new(void); +OPENSSL_EXPORT const uint8_t *SSL_SESSION_get_id(const SSL_SESSION *s, + unsigned int *len); +OPENSSL_EXPORT int SSL_SESSION_print_fp(FILE *fp, const SSL_SESSION *ses); +OPENSSL_EXPORT int SSL_SESSION_print(BIO *fp, const SSL_SESSION *ses); + +/* SSL_SESSION_up_ref, if |session| is not NULL, increments the reference count + * of |session|. It then returns |session|. */ +OPENSSL_EXPORT SSL_SESSION *SSL_SESSION_up_ref(SSL_SESSION *session); + +/* SSL_SESSION_free decrements the reference count of |session|. If it reaches + * zero, all data referenced by |session| and |session| itself are released. */ +OPENSSL_EXPORT void SSL_SESSION_free(SSL_SESSION *session); + +OPENSSL_EXPORT int SSL_set_session(SSL *to, SSL_SESSION *session); +OPENSSL_EXPORT int SSL_CTX_add_session(SSL_CTX *s, SSL_SESSION *c); +OPENSSL_EXPORT int SSL_CTX_remove_session(SSL_CTX *, SSL_SESSION *c); +OPENSSL_EXPORT int SSL_CTX_set_generate_session_id(SSL_CTX *, GEN_SESSION_CB); +OPENSSL_EXPORT int SSL_set_generate_session_id(SSL *, GEN_SESSION_CB); +OPENSSL_EXPORT int SSL_has_matching_session_id(const SSL *ssl, + const uint8_t *id, + unsigned int id_len); + +/* SSL_SESSION_to_bytes serializes |in| into a newly allocated buffer and sets + * |*out_data| to that buffer and |*out_len| to its length. The caller takes + * ownership of the buffer and must call |OPENSSL_free| when done. It returns + * one on success and zero on error. */ +OPENSSL_EXPORT int SSL_SESSION_to_bytes(SSL_SESSION *in, uint8_t **out_data, + size_t *out_len); + +/* SSL_SESSION_to_bytes_for_ticket serializes |in|, but excludes the session ID + * which is not necessary in a session ticket. */ +OPENSSL_EXPORT int SSL_SESSION_to_bytes_for_ticket(SSL_SESSION *in, + uint8_t **out_data, + size_t *out_len); + +/* Deprecated: i2d_SSL_SESSION serializes |in| to the bytes pointed to by + * |*pp|. On success, it returns the number of bytes written and advances |*pp| + * by that many bytes. On failure, it returns -1. If |pp| is NULL, no bytes are + * written and only the length is returned. + * + * Use SSL_SESSION_to_bytes instead. */ +OPENSSL_EXPORT int i2d_SSL_SESSION(SSL_SESSION *in, uint8_t **pp); + +/* d2i_SSL_SESSION deserializes a serialized buffer contained in the |length| + * bytes pointed to by |*pp|. It returns the new SSL_SESSION and advances |*pp| + * by the number of bytes consumed on success and NULL on failure. If |a| is + * NULL, the caller takes ownership of the new session and must call + * |SSL_SESSION_free| when done. + * + * If |a| and |*a| are not NULL, the SSL_SESSION at |*a| is overridden with the + * deserialized session rather than allocating a new one. In addition, |a| is + * not NULL, but |*a| is, |*a| is set to the new SSL_SESSION. + * + * Passing a value other than NULL to |a| is deprecated. */ +OPENSSL_EXPORT SSL_SESSION *d2i_SSL_SESSION(SSL_SESSION **a, const uint8_t **pp, + long length); + +OPENSSL_EXPORT X509 *SSL_get_peer_certificate(const SSL *s); + +OPENSSL_EXPORT STACK_OF(X509) *SSL_get_peer_cert_chain(const SSL *s); + +OPENSSL_EXPORT int SSL_CTX_get_verify_mode(const SSL_CTX *ctx); +OPENSSL_EXPORT int SSL_CTX_get_verify_depth(const SSL_CTX *ctx); +OPENSSL_EXPORT int (*SSL_CTX_get_verify_callback(const SSL_CTX *ctx))( + int, X509_STORE_CTX *); +OPENSSL_EXPORT void SSL_CTX_set_verify(SSL_CTX *ctx, int mode, + int (*callback)(int, X509_STORE_CTX *)); +OPENSSL_EXPORT void SSL_CTX_set_verify_depth(SSL_CTX *ctx, int depth); +OPENSSL_EXPORT void SSL_CTX_set_cert_verify_callback( + SSL_CTX *ctx, int (*cb)(X509_STORE_CTX *, void *), void *arg); +OPENSSL_EXPORT void SSL_CTX_set_cert_cb(SSL_CTX *c, + int (*cb)(SSL *ssl, void *arg), + void *arg); +OPENSSL_EXPORT int SSL_CTX_use_RSAPrivateKey(SSL_CTX *ctx, RSA *rsa); +OPENSSL_EXPORT int SSL_CTX_use_RSAPrivateKey_ASN1(SSL_CTX *ctx, + const uint8_t *d, long len); +OPENSSL_EXPORT int SSL_CTX_use_PrivateKey(SSL_CTX *ctx, EVP_PKEY *pkey); +OPENSSL_EXPORT int SSL_CTX_use_PrivateKey_ASN1(int pk, SSL_CTX *ctx, + const uint8_t *d, long len); +OPENSSL_EXPORT int SSL_CTX_use_certificate(SSL_CTX *ctx, X509 *x); +OPENSSL_EXPORT int SSL_CTX_use_certificate_ASN1(SSL_CTX *ctx, int len, + const uint8_t *d); + +OPENSSL_EXPORT void SSL_CTX_set_default_passwd_cb(SSL_CTX *ctx, + pem_password_cb *cb); +OPENSSL_EXPORT void SSL_CTX_set_default_passwd_cb_userdata(SSL_CTX *ctx, + void *u); + +OPENSSL_EXPORT int SSL_CTX_check_private_key(const SSL_CTX *ctx); +OPENSSL_EXPORT int SSL_check_private_key(const SSL *ctx); + +OPENSSL_EXPORT int SSL_CTX_set_session_id_context(SSL_CTX *ctx, + const uint8_t *sid_ctx, + unsigned int sid_ctx_len); + +OPENSSL_EXPORT int SSL_set_session_id_context(SSL *ssl, const uint8_t *sid_ctx, + unsigned int sid_ctx_len); + +OPENSSL_EXPORT int SSL_CTX_set_purpose(SSL_CTX *s, int purpose); +OPENSSL_EXPORT int SSL_set_purpose(SSL *s, int purpose); +OPENSSL_EXPORT int SSL_CTX_set_trust(SSL_CTX *s, int trust); +OPENSSL_EXPORT int SSL_set_trust(SSL *s, int trust); + +OPENSSL_EXPORT int SSL_CTX_set1_param(SSL_CTX *ctx, X509_VERIFY_PARAM *vpm); +OPENSSL_EXPORT int SSL_set1_param(SSL *ssl, X509_VERIFY_PARAM *vpm); + +OPENSSL_EXPORT X509_VERIFY_PARAM *SSL_CTX_get0_param(SSL_CTX *ctx); +OPENSSL_EXPORT X509_VERIFY_PARAM *SSL_get0_param(SSL *ssl); + +OPENSSL_EXPORT void SSL_certs_clear(SSL *s); +OPENSSL_EXPORT int SSL_accept(SSL *ssl); +OPENSSL_EXPORT int SSL_connect(SSL *ssl); +OPENSSL_EXPORT int SSL_read(SSL *ssl, void *buf, int num); +OPENSSL_EXPORT int SSL_peek(SSL *ssl, void *buf, int num); +OPENSSL_EXPORT int SSL_write(SSL *ssl, const void *buf, int num); +OPENSSL_EXPORT long SSL_ctrl(SSL *ssl, int cmd, long larg, void *parg); +OPENSSL_EXPORT long SSL_CTX_ctrl(SSL_CTX *ctx, int cmd, long larg, void *parg); + +OPENSSL_EXPORT int SSL_get_error(const SSL *s, int ret_code); +/* SSL_get_version returns a string describing the TLS version used by |s|. For + * example, "TLSv1.2" or "SSLv3". */ +OPENSSL_EXPORT const char *SSL_get_version(const SSL *s); +/* SSL_SESSION_get_version returns a string describing the TLS version used by + * |sess|. For example, "TLSv1.2" or "SSLv3". */ +OPENSSL_EXPORT const char *SSL_SESSION_get_version(const SSL_SESSION *sess); + +OPENSSL_EXPORT STACK_OF(SSL_CIPHER) *SSL_get_ciphers(const SSL *s); + +OPENSSL_EXPORT int SSL_do_handshake(SSL *s); + +/* SSL_renegotiate_pending returns one if |ssl| is in the middle of a + * renegotiation. */ +OPENSSL_EXPORT int SSL_renegotiate_pending(SSL *ssl); + +OPENSSL_EXPORT int SSL_shutdown(SSL *s); + +OPENSSL_EXPORT const char *SSL_alert_type_string_long(int value); +OPENSSL_EXPORT const char *SSL_alert_type_string(int value); +OPENSSL_EXPORT const char *SSL_alert_desc_string_long(int value); +OPENSSL_EXPORT const char *SSL_alert_desc_string(int value); + +OPENSSL_EXPORT void SSL_set_client_CA_list(SSL *s, + STACK_OF(X509_NAME) *name_list); +OPENSSL_EXPORT void SSL_CTX_set_client_CA_list(SSL_CTX *ctx, + STACK_OF(X509_NAME) *name_list); +OPENSSL_EXPORT STACK_OF(X509_NAME) *SSL_get_client_CA_list(const SSL *s); +OPENSSL_EXPORT STACK_OF(X509_NAME) * + SSL_CTX_get_client_CA_list(const SSL_CTX *s); +OPENSSL_EXPORT int SSL_add_client_CA(SSL *ssl, X509 *x); +OPENSSL_EXPORT int SSL_CTX_add_client_CA(SSL_CTX *ctx, X509 *x); + +OPENSSL_EXPORT long SSL_get_default_timeout(const SSL *s); + +OPENSSL_EXPORT STACK_OF(X509_NAME) *SSL_dup_CA_list(STACK_OF(X509_NAME) *sk); + +OPENSSL_EXPORT X509 *SSL_get_certificate(const SSL *ssl); +OPENSSL_EXPORT EVP_PKEY *SSL_get_privatekey(const SSL *ssl); + +OPENSSL_EXPORT X509 *SSL_CTX_get0_certificate(const SSL_CTX *ctx); +OPENSSL_EXPORT EVP_PKEY *SSL_CTX_get0_privatekey(const SSL_CTX *ctx); + +OPENSSL_EXPORT void SSL_CTX_set_quiet_shutdown(SSL_CTX *ctx, int mode); +OPENSSL_EXPORT int SSL_CTX_get_quiet_shutdown(const SSL_CTX *ctx); +OPENSSL_EXPORT void SSL_set_quiet_shutdown(SSL *ssl, int mode); +OPENSSL_EXPORT int SSL_get_quiet_shutdown(const SSL *ssl); +OPENSSL_EXPORT void SSL_set_shutdown(SSL *ssl, int mode); +OPENSSL_EXPORT int SSL_get_shutdown(const SSL *ssl); +OPENSSL_EXPORT int SSL_version(const SSL *ssl); +OPENSSL_EXPORT int SSL_CTX_set_default_verify_paths(SSL_CTX *ctx); +OPENSSL_EXPORT int SSL_CTX_load_verify_locations(SSL_CTX *ctx, + const char *CAfile, + const char *CApath); +#define SSL_get0_session SSL_get_session /* just peek at pointer */ +OPENSSL_EXPORT SSL_SESSION *SSL_get_session(const SSL *ssl); +OPENSSL_EXPORT SSL_SESSION *SSL_get1_session( + SSL *ssl); /* obtain a reference count */ +OPENSSL_EXPORT SSL_CTX *SSL_get_SSL_CTX(const SSL *ssl); +OPENSSL_EXPORT SSL_CTX *SSL_set_SSL_CTX(SSL *ssl, SSL_CTX *ctx); +OPENSSL_EXPORT void SSL_set_info_callback(SSL *ssl, + void (*cb)(const SSL *ssl, int type, + int val)); +OPENSSL_EXPORT void (*SSL_get_info_callback(const SSL *ssl))(const SSL *ssl, + int type, int val); +OPENSSL_EXPORT int SSL_state(const SSL *ssl); + +OPENSSL_EXPORT void SSL_set_verify_result(SSL *ssl, long v); +OPENSSL_EXPORT long SSL_get_verify_result(const SSL *ssl); + +OPENSSL_EXPORT int SSL_set_ex_data(SSL *ssl, int idx, void *data); +OPENSSL_EXPORT void *SSL_get_ex_data(const SSL *ssl, int idx); +OPENSSL_EXPORT int SSL_get_ex_new_index(long argl, void *argp, + CRYPTO_EX_new *new_func, + CRYPTO_EX_dup *dup_func, + CRYPTO_EX_free *free_func); + +OPENSSL_EXPORT int SSL_SESSION_set_ex_data(SSL_SESSION *ss, int idx, + void *data); +OPENSSL_EXPORT void *SSL_SESSION_get_ex_data(const SSL_SESSION *ss, int idx); +OPENSSL_EXPORT int SSL_SESSION_get_ex_new_index(long argl, void *argp, + CRYPTO_EX_new *new_func, + CRYPTO_EX_dup *dup_func, + CRYPTO_EX_free *free_func); + +OPENSSL_EXPORT int SSL_CTX_set_ex_data(SSL_CTX *ssl, int idx, void *data); +OPENSSL_EXPORT void *SSL_CTX_get_ex_data(const SSL_CTX *ssl, int idx); +OPENSSL_EXPORT int SSL_CTX_get_ex_new_index(long argl, void *argp, + CRYPTO_EX_new *new_func, + CRYPTO_EX_dup *dup_func, + CRYPTO_EX_free *free_func); + +OPENSSL_EXPORT int SSL_get_ex_data_X509_STORE_CTX_idx(void); + +/* SSL_CTX_sess_set_cache_size sets the maximum size of |ctx|'s session cache to + * |size|. It returns the previous value. */ +OPENSSL_EXPORT unsigned long SSL_CTX_sess_set_cache_size(SSL_CTX *ctx, + unsigned long size); + +/* SSL_CTX_sess_get_cache_size returns the maximum size of |ctx|'s session + * cache. */ +OPENSSL_EXPORT unsigned long SSL_CTX_sess_get_cache_size(const SSL_CTX *ctx); + +/* SSL_SESS_CACHE_* are the possible session cache mode bits. + * TODO(davidben): Document. */ +#define SSL_SESS_CACHE_OFF 0x0000 +#define SSL_SESS_CACHE_CLIENT 0x0001 +#define SSL_SESS_CACHE_SERVER 0x0002 +#define SSL_SESS_CACHE_BOTH (SSL_SESS_CACHE_CLIENT | SSL_SESS_CACHE_SERVER) +#define SSL_SESS_CACHE_NO_AUTO_CLEAR 0x0080 +#define SSL_SESS_CACHE_NO_INTERNAL_LOOKUP 0x0100 +#define SSL_SESS_CACHE_NO_INTERNAL_STORE 0x0200 +#define SSL_SESS_CACHE_NO_INTERNAL \ + (SSL_SESS_CACHE_NO_INTERNAL_LOOKUP | SSL_SESS_CACHE_NO_INTERNAL_STORE) + +/* SSL_CTX_set_session_cache_mode sets the session cache mode bits for |ctx| to + * |mode|. It returns the previous value. */ +OPENSSL_EXPORT int SSL_CTX_set_session_cache_mode(SSL_CTX *ctx, int mode); + +/* SSL_CTX_get_session_cache_mode returns the session cache mode bits for + * |ctx| */ +OPENSSL_EXPORT int SSL_CTX_get_session_cache_mode(const SSL_CTX *ctx); + +/* SSL_CTX_get_max_cert_list returns the maximum length, in bytes, of a peer + * certificate chain accepted by |ctx|. */ +OPENSSL_EXPORT size_t SSL_CTX_get_max_cert_list(const SSL_CTX *ctx); + +/* SSL_CTX_set_max_cert_list sets the maximum length, in bytes, of a peer + * certificate chain to |max_cert_list|. This affects how much memory may be + * consumed during the handshake. */ +OPENSSL_EXPORT void SSL_CTX_set_max_cert_list(SSL_CTX *ctx, + size_t max_cert_list); + +/* SSL_get_max_cert_list returns the maximum length, in bytes, of a peer + * certificate chain accepted by |ssl|. */ +OPENSSL_EXPORT size_t SSL_get_max_cert_list(const SSL *ssl); + +/* SSL_set_max_cert_list sets the maximum length, in bytes, of a peer + * certificate chain to |max_cert_list|. This affects how much memory may be + * consumed during the handshake. */ +OPENSSL_EXPORT void SSL_set_max_cert_list(SSL *ssl, size_t max_cert_list); + +/* SSL_CTX_set_max_send_fragment sets the maximum length, in bytes, of records + * sent by |ctx|. Beyond this length, handshake messages and application data + * will be split into multiple records. */ +OPENSSL_EXPORT void SSL_CTX_set_max_send_fragment(SSL_CTX *ctx, + size_t max_send_fragment); + +/* SSL_set_max_send_fragment sets the maximum length, in bytes, of records + * sent by |ssl|. Beyond this length, handshake messages and application data + * will be split into multiple records. */ +OPENSSL_EXPORT void SSL_set_max_send_fragment(SSL *ssl, + size_t max_send_fragment); + +/* SSL_CTX_set_tmp_dh_callback configures |ctx| to use |callback| to determine + * the group for DHE ciphers. |callback| should ignore |is_export| and + * |keylength| and return a |DH| of the selected group or NULL on error. Only + * the parameters are used, so the |DH| needn't have a generated keypair. + * + * WARNING: The caller does not take ownership of the resulting |DH|, so + * |callback| must save and release the object elsewhere. */ +OPENSSL_EXPORT void SSL_CTX_set_tmp_dh_callback( + SSL_CTX *ctx, DH *(*callback)(SSL *ssl, int is_export, int keylength)); + +/* SSL_set_tmp_dh_callback configures |ssl| to use |callback| to determine the + * group for DHE ciphers. |callback| should ignore |is_export| and |keylength| + * and return a |DH| of the selected group or NULL on error. Only the + * parameters are used, so the |DH| needn't have a generated keypair. + * + * WARNING: The caller does not take ownership of the resulting |DH|, so + * |callback| must save and release the object elsewhere. */ +OPENSSL_EXPORT void SSL_set_tmp_dh_callback(SSL *ssl, + DH *(*dh)(SSL *ssl, int is_export, + int keylength)); + +/* SSL_CTX_set_tmp_ecdh_callback configures |ctx| to use |callback| to determine + * the curve for ephemeral ECDH keys. |callback| should ignore |is_export| and + * |keylength| and return an |EC_KEY| of the selected curve or NULL on + * error. Only the curve is used, so the |EC_KEY| needn't have a generated + * keypair. + * + * If the callback is unset, an appropriate curve will be chosen automatically. + * (This is recommended.) + * + * WARNING: The caller does not take ownership of the resulting |EC_KEY|, so + * |callback| must save and release the object elsewhere. */ +OPENSSL_EXPORT void SSL_CTX_set_tmp_ecdh_callback( + SSL_CTX *ctx, EC_KEY *(*callback)(SSL *ssl, int is_export, int keylength)); + +/* SSL_set_tmp_ecdh_callback configures |ssl| to use |callback| to determine the + * curve for ephemeral ECDH keys. |callback| should ignore |is_export| and + * |keylength| and return an |EC_KEY| of the selected curve or NULL on + * error. Only the curve is used, so the |EC_KEY| needn't have a generated + * keypair. + * + * If the callback is unset, an appropriate curve will be chosen automatically. + * (This is recommended.) + * + * WARNING: The caller does not take ownership of the resulting |EC_KEY|, so + * |callback| must save and release the object elsewhere. */ +OPENSSL_EXPORT void SSL_set_tmp_ecdh_callback( + SSL *ssl, EC_KEY *(*callback)(SSL *ssl, int is_export, int keylength)); + +OPENSSL_EXPORT const void *SSL_get_current_compression(SSL *s); +OPENSSL_EXPORT const void *SSL_get_current_expansion(SSL *s); + +OPENSSL_EXPORT int SSL_cache_hit(SSL *s); +OPENSSL_EXPORT int SSL_is_server(SSL *s); + +/* SSL_CTX_set_dos_protection_cb sets a callback that is called once the + * resumption decision for a ClientHello has been made. It can return 1 to + * allow the handshake to continue or zero to cause the handshake to abort. */ +OPENSSL_EXPORT void SSL_CTX_set_dos_protection_cb( + SSL_CTX *ctx, int (*cb)(const struct ssl_early_callback_ctx *)); + +/* SSL_get_structure_sizes returns the sizes of the SSL, SSL_CTX and + * SSL_SESSION structures so that a test can ensure that outside code agrees on + * these values. */ +OPENSSL_EXPORT void SSL_get_structure_sizes(size_t *ssl_size, + size_t *ssl_ctx_size, + size_t *ssl_session_size); + +OPENSSL_EXPORT void ERR_load_SSL_strings(void); + +/* SSL_get_rc4_state sets |*read_key| and |*write_key| to the RC4 states for + * the read and write directions. It returns one on success or zero if |ssl| + * isn't using an RC4-based cipher suite. */ +OPENSSL_EXPORT int SSL_get_rc4_state(const SSL *ssl, const RC4_KEY **read_key, + const RC4_KEY **write_key); + + +/* Deprecated functions. */ + +/* SSL_CIPHER_description writes a description of |cipher| into |buf| and + * returns |buf|. If |buf| is NULL, it returns a newly allocated string, to be + * freed with |OPENSSL_free|, or NULL on error. + * + * The description includes a trailing newline and has the form: + * AES128-SHA SSLv3 Kx=RSA Au=RSA Enc=AES(128) Mac=SHA1 + * + * Consider |SSL_CIPHER_get_name| or |SSL_CIPHER_get_rfc_name| instead. */ +OPENSSL_EXPORT const char *SSL_CIPHER_description(const SSL_CIPHER *cipher, + char *buf, int len); + +/* SSL_CIPHER_get_version returns the string "TLSv1/SSLv3". */ +OPENSSL_EXPORT const char *SSL_CIPHER_get_version(const SSL_CIPHER *cipher); + +/* SSL_COMP_get_compression_methods returns NULL. */ +OPENSSL_EXPORT void *SSL_COMP_get_compression_methods(void); + +/* SSL_COMP_add_compression_method returns one. */ +OPENSSL_EXPORT int SSL_COMP_add_compression_method(int id, void *cm); + +/* SSL_COMP_get_name returns NULL. */ +OPENSSL_EXPORT const char *SSL_COMP_get_name(const void *comp); + +/* SSLv23_method calls |TLS_method|. */ +OPENSSL_EXPORT const SSL_METHOD *SSLv23_method(void); + +/* Version-specific methods behave exactly like |TLS_method| and |DTLS_method| + * except they also call |SSL_CTX_set_min_version| and |SSL_CTX_set_max_version| + * to lock connections to that protocol version. */ +OPENSSL_EXPORT const SSL_METHOD *SSLv3_method(void); +OPENSSL_EXPORT const SSL_METHOD *TLSv1_method(void); +OPENSSL_EXPORT const SSL_METHOD *TLSv1_1_method(void); +OPENSSL_EXPORT const SSL_METHOD *TLSv1_2_method(void); +OPENSSL_EXPORT const SSL_METHOD *DTLSv1_method(void); +OPENSSL_EXPORT const SSL_METHOD *DTLSv1_2_method(void); + +/* Client- and server-specific methods call their corresponding generic + * methods. */ +OPENSSL_EXPORT const SSL_METHOD *SSLv23_server_method(void); +OPENSSL_EXPORT const SSL_METHOD *SSLv23_client_method(void); +OPENSSL_EXPORT const SSL_METHOD *SSLv3_server_method(void); +OPENSSL_EXPORT const SSL_METHOD *SSLv3_client_method(void); +OPENSSL_EXPORT const SSL_METHOD *TLSv1_server_method(void); +OPENSSL_EXPORT const SSL_METHOD *TLSv1_client_method(void); +OPENSSL_EXPORT const SSL_METHOD *TLSv1_1_server_method(void); +OPENSSL_EXPORT const SSL_METHOD *TLSv1_1_client_method(void); +OPENSSL_EXPORT const SSL_METHOD *TLSv1_2_server_method(void); +OPENSSL_EXPORT const SSL_METHOD *TLSv1_2_client_method(void); +OPENSSL_EXPORT const SSL_METHOD *DTLS_server_method(void); +OPENSSL_EXPORT const SSL_METHOD *DTLS_client_method(void); +OPENSSL_EXPORT const SSL_METHOD *DTLSv1_server_method(void); +OPENSSL_EXPORT const SSL_METHOD *DTLSv1_client_method(void); +OPENSSL_EXPORT const SSL_METHOD *DTLSv1_2_server_method(void); +OPENSSL_EXPORT const SSL_METHOD *DTLSv1_2_client_method(void); + +/* SSL_clear resets |ssl| to allow another connection and returns one on success + * or zero on failure. It returns most configuration state but releases memory + * associated with the current connection. + * + * Free |ssl| and create a new one instead. */ +OPENSSL_EXPORT int SSL_clear(SSL *ssl); + +/* SSL_CTX_set_tmp_rsa_callback does nothing. */ +OPENSSL_EXPORT void SSL_CTX_set_tmp_rsa_callback( + SSL_CTX *ctx, RSA *(*cb)(SSL *ssl, int is_export, int keylength)); + +/* SSL_set_tmp_rsa_callback does nothing. */ +OPENSSL_EXPORT void SSL_set_tmp_rsa_callback(SSL *ssl, + RSA *(*cb)(SSL *ssl, int is_export, + int keylength)); + +/* SSL_CTX_sess_connect returns zero. */ +OPENSSL_EXPORT int SSL_CTX_sess_connect(const SSL_CTX *ctx); + +/* SSL_CTX_sess_connect_good returns zero. */ +OPENSSL_EXPORT int SSL_CTX_sess_connect_good(const SSL_CTX *ctx); + +/* SSL_CTX_sess_connect_renegotiate returns zero. */ +OPENSSL_EXPORT int SSL_CTX_sess_connect_renegotiate(const SSL_CTX *ctx); + +/* SSL_CTX_sess_accept returns zero. */ +OPENSSL_EXPORT int SSL_CTX_sess_accept(const SSL_CTX *ctx); + +/* SSL_CTX_sess_accept_renegotiate returns zero. */ +OPENSSL_EXPORT int SSL_CTX_sess_accept_renegotiate(const SSL_CTX *ctx); + +/* SSL_CTX_sess_accept_good returns zero. */ +OPENSSL_EXPORT int SSL_CTX_sess_accept_good(const SSL_CTX *ctx); + +/* SSL_CTX_sess_hits returns zero. */ +OPENSSL_EXPORT int SSL_CTX_sess_hits(const SSL_CTX *ctx); + +/* SSL_CTX_sess_cb_hits returns zero. */ +OPENSSL_EXPORT int SSL_CTX_sess_cb_hits(const SSL_CTX *ctx); + +/* SSL_CTX_sess_misses returns zero. */ +OPENSSL_EXPORT int SSL_CTX_sess_misses(const SSL_CTX *ctx); + +/* SSL_CTX_sess_timeouts returns zero. */ +OPENSSL_EXPORT int SSL_CTX_sess_timeouts(const SSL_CTX *ctx); + +/* SSL_CTX_sess_cache_full returns zero. */ +OPENSSL_EXPORT int SSL_CTX_sess_cache_full(const SSL_CTX *ctx); + +/* SSL_cutthrough_complete calls |SSL_in_false_start|. */ +OPENSSL_EXPORT int SSL_cutthrough_complete(const SSL *s); + +/* SSL_num_renegotiations calls |SSL_total_renegotiations|. */ +OPENSSL_EXPORT int SSL_num_renegotiations(const SSL *ssl); + +/* SSL_CTX_need_tmp_RSA returns zero. */ +OPENSSL_EXPORT int SSL_CTX_need_tmp_RSA(const SSL_CTX *ctx); + +/* SSL_need_tmp_RSA returns zero. */ +OPENSSL_EXPORT int SSL_need_tmp_RSA(const SSL *ssl); + +/* SSL_CTX_set_tmp_rsa returns one. */ +OPENSSL_EXPORT int SSL_CTX_set_tmp_rsa(SSL_CTX *ctx, const RSA *rsa); + +/* SSL_set_tmp_rsa returns one. */ +OPENSSL_EXPORT int SSL_set_tmp_rsa(SSL *ssl, const RSA *rsa); + +/* SSL_CTX_get_read_head returns zero. */ +OPENSSL_EXPORT int SSL_CTX_get_read_ahead(const SSL_CTX *ctx); + +/* SSL_CTX_set_read_ahead does nothing. */ +OPENSSL_EXPORT void SSL_CTX_set_read_ahead(SSL_CTX *ctx, int yes); + +/* SSL_get_read_head returns zero. */ +OPENSSL_EXPORT int SSL_get_read_ahead(const SSL *s); + +/* SSL_set_read_ahead does nothing. */ +OPENSSL_EXPORT void SSL_set_read_ahead(SSL *s, int yes); + +/* SSL_renegotiate put an error on the error queue and returns zero. */ +OPENSSL_EXPORT int SSL_renegotiate(SSL *ssl); + +/* SSL_set_state does nothing. */ +OPENSSL_EXPORT void SSL_set_state(SSL *ssl, int state); + + +/* Android compatibility section. + * + * These functions are declared, temporarily, for Android because + * wpa_supplicant will take a little time to sync with upstream. Outside of + * Android they'll have no definition. */ + +#define SSL_F_SSL_SET_SESSION_TICKET_EXT doesnt_exist + +OPENSSL_EXPORT int SSL_set_session_ticket_ext(SSL *s, void *ext_data, + int ext_len); +OPENSSL_EXPORT int SSL_set_session_secret_cb(SSL *s, void *cb, void *arg); +OPENSSL_EXPORT int SSL_set_session_ticket_ext_cb(SSL *s, void *cb, void *arg); +OPENSSL_EXPORT int SSL_set_ssl_method(SSL *s, const SSL_METHOD *method); + +#define OPENSSL_VERSION_TEXT "BoringSSL" + +#define SSLEAY_VERSION 0 + +/* SSLeay_version is a compatibility function that returns the string + * "BoringSSL". */ +OPENSSL_EXPORT const char *SSLeay_version(int unused); + + +/* Preprocessor compatibility section. + * + * Historically, a number of APIs were implemented in OpenSSL as macros and + * constants to 'ctrl' functions. To avoid breaking #ifdefs in consumers, this + * section defines a number of legacy macros. */ + +#define SSL_CTRL_NEED_TMP_RSA doesnt_exist +#define SSL_CTRL_SET_TMP_RSA doesnt_exist +#define SSL_CTRL_SET_TMP_DH doesnt_exist +#define SSL_CTRL_SET_TMP_ECDH doesnt_exist +#define SSL_CTRL_SET_TMP_RSA_CB doesnt_exist +#define SSL_CTRL_SET_TMP_DH_CB doesnt_exist +#define SSL_CTRL_SET_TMP_ECDH_CB doesnt_exist +#define SSL_CTRL_GET_SESSION_REUSED doesnt_exist +#define SSL_CTRL_GET_NUM_RENEGOTIATIONS doesnt_exist +#define SSL_CTRL_GET_TOTAL_RENEGOTIATIONS doesnt_exist +#define SSL_CTRL_SET_MSG_CALLBACK doesnt_exist +#define SSL_CTRL_SET_MSG_CALLBACK_ARG doesnt_exist +#define SSL_CTRL_SET_MTU doesnt_exist +#define SSL_CTRL_SESS_NUMBER doesnt_exist +#define SSL_CTRL_OPTIONS doesnt_exist +#define SSL_CTRL_MODE doesnt_exist +#define SSL_CTRL_GET_READ_AHEAD doesnt_exist +#define SSL_CTRL_SET_READ_AHEAD doesnt_exist +#define SSL_CTRL_SET_SESS_CACHE_SIZE doesnt_exist +#define SSL_CTRL_GET_SESS_CACHE_SIZE doesnt_exist +#define SSL_CTRL_SET_SESS_CACHE_MODE doesnt_exist +#define SSL_CTRL_GET_SESS_CACHE_MODE doesnt_exist +#define SSL_CTRL_GET_MAX_CERT_LIST doesnt_exist +#define SSL_CTRL_SET_MAX_CERT_LIST doesnt_exist +#define SSL_CTRL_SET_MAX_SEND_FRAGMENT doesnt_exist +#define SSL_CTRL_SET_TLSEXT_SERVERNAME_CB doesnt_exist +#define SSL_CTRL_SET_TLSEXT_SERVERNAME_ARG doesnt_exist +#define SSL_CTRL_SET_TLSEXT_HOSTNAME doesnt_exist +#define SSL_CTRL_SET_TLSEXT_TICKET_KEY_CB doesnt_exist +#define DTLS_CTRL_GET_TIMEOUT doesnt_exist +#define DTLS_CTRL_HANDLE_TIMEOUT doesnt_exist +#define SSL_CTRL_GET_RI_SUPPORT doesnt_exist +#define SSL_CTRL_CLEAR_OPTIONS doesnt_exist +#define SSL_CTRL_CLEAR_MODE doesnt_exist +#define SSL_CTRL_CHANNEL_ID doesnt_exist +#define SSL_CTRL_GET_CHANNEL_ID doesnt_exist +#define SSL_CTRL_SET_CHANNEL_ID doesnt_exist + +#define SSL_CTX_need_tmp_RSA SSL_CTX_need_tmp_RSA +#define SSL_need_tmp_RSA SSL_need_tmp_RSA +#define SSL_CTX_set_tmp_rsa SSL_CTX_set_tmp_rsa +#define SSL_set_tmp_rsa SSL_set_tmp_rsa +#define SSL_CTX_set_tmp_dh SSL_CTX_set_tmp_dh +#define SSL_set_tmp_dh SSL_set_tmp_dh +#define SSL_CTX_set_tmp_ecdh SSL_CTX_set_tmp_ecdh +#define SSL_set_tmp_ecdh SSL_set_tmp_ecdh +#define SSL_session_reused SSL_session_reused +#define SSL_num_renegotiations SSL_num_renegotiations +#define SSL_total_renegotiations SSL_total_renegotiations +#define SSL_CTX_set_msg_callback_arg SSL_CTX_set_msg_callback_arg +#define SSL_set_msg_callback_arg SSL_set_msg_callback_arg +#define SSL_set_mtu SSL_set_mtu +#define SSL_CTX_sess_number SSL_CTX_sess_number +#define SSL_CTX_get_options SSL_CTX_get_options +#define SSL_CTX_set_options SSL_CTX_set_options +#define SSL_get_options SSL_get_options +#define SSL_set_options SSL_set_options +#define SSL_CTX_get_mode SSL_CTX_get_mode +#define SSL_CTX_set_mode SSL_CTX_set_mode +#define SSL_get_mode SSL_get_mode +#define SSL_set_mode SSL_set_mode +#define SSL_CTX_get_read_ahead SSL_CTX_get_read_ahead +#define SSL_CTX_set_read_ahead SSL_CTX_set_read_ahead +#define SSL_CTX_sess_set_cache_size SSL_CTX_sess_set_cache_size +#define SSL_CTX_sess_get_cache_size SSL_CTX_sess_get_cache_size +#define SSL_CTX_set_session_cache_mode SSL_CTX_set_session_cache_mode +#define SSL_CTX_get_session_cache_mode SSL_CTX_get_session_cache_mode +#define SSL_CTX_get_max_cert_list SSL_CTX_get_max_cert_list +#define SSL_get_max_cert_list SSL_get_max_cert_list +#define SSL_CTX_set_max_cert_list SSL_CTX_set_max_cert_list +#define SSL_set_max_cert_list SSL_set_max_cert_list +#define SSL_CTX_set_max_send_fragment SSL_CTX_set_max_send_fragment +#define SSL_set_max_send_fragment SSL_set_max_send_fragment +#define SSL_CTX_set_tlsext_servername_callback \ + SSL_CTX_set_tlsext_servername_callback +#define SSL_CTX_set_tlsext_servername_arg SSL_CTX_set_tlsext_servername_arg +#define SSL_set_tlsext_host_name SSL_set_tlsext_host_name +#define SSL_CTX_set_tlsext_ticket_key_cb SSL_CTX_set_tlsext_ticket_key_cb +#define DTLSv1_get_timeout DTLSv1_get_timeout +#define DTLSv1_handle_timeout DTLSv1_handle_timeout +#define SSL_get_secure_renegotiation_support \ + SSL_get_secure_renegotiation_support +#define SSL_CTX_clear_options SSL_CTX_clear_options +#define SSL_clear_options SSL_clear_options +#define SSL_CTX_clear_mode SSL_CTX_clear_mode +#define SSL_clear_mode SSL_clear_mode +#define SSL_CTX_enable_tls_channel_id SSL_CTX_enable_tls_channel_id +#define SSL_enable_tls_channel_id SSL_enable_tls_channel_id +#define SSL_set1_tls_channel_id SSL_set1_tls_channel_id +#define SSL_CTX_set1_tls_channel_id SSL_CTX_set1_tls_channel_id +#define SSL_get_tls_channel_id SSL_get_tls_channel_id + + +#if defined(__cplusplus) +} /* extern C */ +#endif + + +/* Library consumers assume these headers are included by ssl.h, but they depend + * on ssl.h, so include them after all declarations. + * + * TODO(davidben): The separation between ssl.h and these version-specific + * headers introduces circular dependencies and is inconsistent. The function + * declarations should move to ssl.h. Many of the constants can probably be + * pruned or unexported. */ +#include +#include +#include /* This is mostly sslv3 with a few tweaks */ +#include +#include /* Support for the use_srtp extension */ + + +/* BEGIN ERROR CODES */ +/* The following lines are auto generated by the script make_errors.go. Any + * changes made after this point may be overwritten when the script is next run. + */ +#define SSL_F_SSL_CTX_check_private_key 100 +#define SSL_F_SSL_CTX_new 101 +#define SSL_F_SSL_CTX_set_cipher_list 102 +#define SSL_F_SSL_CTX_set_cipher_list_tls11 103 +#define SSL_F_SSL_CTX_set_session_id_context 104 +#define SSL_F_SSL_CTX_use_PrivateKey 105 +#define SSL_F_SSL_CTX_use_PrivateKey_ASN1 106 +#define SSL_F_SSL_CTX_use_PrivateKey_file 107 +#define SSL_F_SSL_CTX_use_RSAPrivateKey 108 +#define SSL_F_SSL_CTX_use_RSAPrivateKey_ASN1 109 +#define SSL_F_SSL_CTX_use_RSAPrivateKey_file 110 +#define SSL_F_SSL_CTX_use_certificate 111 +#define SSL_F_SSL_CTX_use_certificate_ASN1 112 +#define SSL_F_SSL_CTX_use_certificate_chain_file 113 +#define SSL_F_SSL_CTX_use_certificate_file 114 +#define SSL_F_SSL_CTX_use_psk_identity_hint 115 +#define SSL_F_SSL_SESSION_new 116 +#define SSL_F_SSL_SESSION_print_fp 117 +#define SSL_F_SSL_SESSION_set1_id_context 118 +#define SSL_F_SSL_SESSION_to_bytes_full 119 +#define SSL_F_SSL_accept 120 +#define SSL_F_SSL_add_dir_cert_subjects_to_stack 121 +#define SSL_F_SSL_add_file_cert_subjects_to_stack 122 +#define SSL_F_SSL_check_private_key 123 +#define SSL_F_SSL_clear 124 +#define SSL_F_SSL_connect 125 +#define SSL_F_SSL_do_handshake 126 +#define SSL_F_SSL_load_client_CA_file 127 +#define SSL_F_SSL_new 128 +#define SSL_F_SSL_peek 129 +#define SSL_F_SSL_read 130 +#define SSL_F_SSL_renegotiate 131 +#define SSL_F_SSL_set_cipher_list 132 +#define SSL_F_SSL_set_fd 133 +#define SSL_F_SSL_set_rfd 134 +#define SSL_F_SSL_set_session_id_context 135 +#define SSL_F_SSL_set_wfd 136 +#define SSL_F_SSL_shutdown 137 +#define SSL_F_SSL_use_PrivateKey 138 +#define SSL_F_SSL_use_PrivateKey_ASN1 139 +#define SSL_F_SSL_use_PrivateKey_file 140 +#define SSL_F_SSL_use_RSAPrivateKey 141 +#define SSL_F_SSL_use_RSAPrivateKey_ASN1 142 +#define SSL_F_SSL_use_RSAPrivateKey_file 143 +#define SSL_F_SSL_use_certificate 144 +#define SSL_F_SSL_use_certificate_ASN1 145 +#define SSL_F_SSL_use_certificate_file 146 +#define SSL_F_SSL_use_psk_identity_hint 147 +#define SSL_F_SSL_write 148 +#define SSL_F_d2i_SSL_SESSION 149 +#define SSL_F_d2i_SSL_SESSION_get_octet_string 150 +#define SSL_F_d2i_SSL_SESSION_get_string 151 +#define SSL_F_do_ssl3_write 152 +#define SSL_F_dtls1_accept 153 +#define SSL_F_dtls1_buffer_record 154 +#define SSL_F_dtls1_check_timeout_num 155 +#define SSL_F_dtls1_connect 156 +#define SSL_F_dtls1_do_write 157 +#define SSL_F_dtls1_get_hello_verify 158 +#define SSL_F_dtls1_get_message 159 +#define SSL_F_dtls1_get_message_fragment 160 +#define SSL_F_dtls1_preprocess_fragment 161 +#define SSL_F_dtls1_process_record 162 +#define SSL_F_dtls1_read_bytes 163 +#define SSL_F_dtls1_send_hello_verify_request 164 +#define SSL_F_dtls1_write_app_data 165 +#define SSL_F_i2d_SSL_SESSION 166 +#define SSL_F_ssl3_accept 167 +#define SSL_F_ssl3_cert_verify_hash 169 +#define SSL_F_ssl3_check_cert_and_algorithm 170 +#define SSL_F_ssl3_connect 171 +#define SSL_F_ssl3_ctrl 172 +#define SSL_F_ssl3_ctx_ctrl 173 +#define SSL_F_ssl3_digest_cached_records 174 +#define SSL_F_ssl3_do_change_cipher_spec 175 +#define SSL_F_ssl3_expect_change_cipher_spec 176 +#define SSL_F_ssl3_get_cert_status 177 +#define SSL_F_ssl3_get_cert_verify 178 +#define SSL_F_ssl3_get_certificate_request 179 +#define SSL_F_ssl3_get_channel_id 180 +#define SSL_F_ssl3_get_client_certificate 181 +#define SSL_F_ssl3_get_client_hello 182 +#define SSL_F_ssl3_get_client_key_exchange 183 +#define SSL_F_ssl3_get_finished 184 +#define SSL_F_ssl3_get_initial_bytes 185 +#define SSL_F_ssl3_get_message 186 +#define SSL_F_ssl3_get_new_session_ticket 187 +#define SSL_F_ssl3_get_next_proto 188 +#define SSL_F_ssl3_get_record 189 +#define SSL_F_ssl3_get_server_certificate 190 +#define SSL_F_ssl3_get_server_done 191 +#define SSL_F_ssl3_get_server_hello 192 +#define SSL_F_ssl3_get_server_key_exchange 193 +#define SSL_F_ssl3_get_v2_client_hello 194 +#define SSL_F_ssl3_handshake_mac 195 +#define SSL_F_ssl3_prf 196 +#define SSL_F_ssl3_read_bytes 197 +#define SSL_F_ssl3_read_n 198 +#define SSL_F_ssl3_send_cert_verify 199 +#define SSL_F_ssl3_send_certificate_request 200 +#define SSL_F_ssl3_send_channel_id 201 +#define SSL_F_ssl3_send_client_certificate 202 +#define SSL_F_ssl3_send_client_hello 203 +#define SSL_F_ssl3_send_client_key_exchange 204 +#define SSL_F_ssl3_send_server_certificate 205 +#define SSL_F_ssl3_send_server_hello 206 +#define SSL_F_ssl3_send_server_key_exchange 207 +#define SSL_F_ssl3_setup_read_buffer 208 +#define SSL_F_ssl3_setup_write_buffer 209 +#define SSL_F_ssl3_write_bytes 210 +#define SSL_F_ssl3_write_pending 211 +#define SSL_F_ssl_add_cert_chain 212 +#define SSL_F_ssl_add_cert_to_buf 213 +#define SSL_F_ssl_add_clienthello_renegotiate_ext 214 +#define SSL_F_ssl_add_clienthello_tlsext 215 +#define SSL_F_ssl_add_clienthello_use_srtp_ext 216 +#define SSL_F_ssl_add_serverhello_renegotiate_ext 217 +#define SSL_F_ssl_add_serverhello_tlsext 218 +#define SSL_F_ssl_add_serverhello_use_srtp_ext 219 +#define SSL_F_ssl_build_cert_chain 220 +#define SSL_F_ssl_bytes_to_cipher_list 221 +#define SSL_F_ssl_cert_dup 222 +#define SSL_F_ssl_cert_inst 223 +#define SSL_F_ssl_cert_new 224 +#define SSL_F_ssl_check_serverhello_tlsext 225 +#define SSL_F_ssl_check_srvr_ecc_cert_and_alg 226 +#define SSL_F_ssl_cipher_process_rulestr 227 +#define SSL_F_ssl_cipher_strength_sort 228 +#define SSL_F_ssl_create_cipher_list 229 +#define SSL_F_ssl_ctx_log_master_secret 230 +#define SSL_F_ssl_ctx_log_rsa_client_key_exchange 231 +#define SSL_F_ssl_ctx_make_profiles 232 +#define SSL_F_ssl_get_new_session 233 +#define SSL_F_ssl_get_prev_session 234 +#define SSL_F_ssl_get_server_cert_index 235 +#define SSL_F_ssl_get_sign_pkey 236 +#define SSL_F_ssl_init_wbio_buffer 237 +#define SSL_F_ssl_parse_clienthello_renegotiate_ext 238 +#define SSL_F_ssl_parse_clienthello_tlsext 239 +#define SSL_F_ssl_parse_clienthello_use_srtp_ext 240 +#define SSL_F_ssl_parse_serverhello_renegotiate_ext 241 +#define SSL_F_ssl_parse_serverhello_tlsext 242 +#define SSL_F_ssl_parse_serverhello_use_srtp_ext 243 +#define SSL_F_ssl_scan_clienthello_tlsext 244 +#define SSL_F_ssl_scan_serverhello_tlsext 245 +#define SSL_F_ssl_sess_cert_new 246 +#define SSL_F_ssl_set_cert 247 +#define SSL_F_ssl_set_pkey 248 +#define SSL_F_ssl_verify_cert_chain 252 +#define SSL_F_tls12_check_peer_sigalg 253 +#define SSL_F_tls1_aead_ctx_init 254 +#define SSL_F_tls1_cert_verify_mac 255 +#define SSL_F_tls1_change_cipher_state 256 +#define SSL_F_tls1_change_cipher_state_aead 257 +#define SSL_F_tls1_check_duplicate_extensions 258 +#define SSL_F_tls1_enc 259 +#define SSL_F_tls1_export_keying_material 260 +#define SSL_F_tls1_prf 261 +#define SSL_F_tls1_setup_key_block 262 +#define SSL_F_dtls1_get_buffered_message 263 +#define SSL_F_dtls1_process_fragment 264 +#define SSL_F_dtls1_hm_fragment_new 265 +#define SSL_F_ssl3_seal_record 266 +#define SSL_F_ssl3_record_sequence_update 267 +#define SSL_F_SSL_CTX_set_tmp_dh 268 +#define SSL_F_SSL_CTX_set_tmp_ecdh 269 +#define SSL_F_SSL_set_tmp_dh 270 +#define SSL_F_SSL_set_tmp_ecdh 271 +#define SSL_F_SSL_CTX_set1_tls_channel_id 272 +#define SSL_F_SSL_set1_tls_channel_id 273 +#define SSL_F_SSL_set_tlsext_host_name 274 +#define SSL_F_ssl3_output_cert_chain 275 +#define SSL_F_SSL_AEAD_CTX_new 276 +#define SSL_F_SSL_AEAD_CTX_open 277 +#define SSL_F_SSL_AEAD_CTX_seal 278 +#define SSL_F_dtls1_seal_record 279 +#define SSL_R_APP_DATA_IN_HANDSHAKE 100 +#define SSL_R_ATTEMPT_TO_REUSE_SESSION_IN_DIFFERENT_CONTEXT 101 +#define SSL_R_BAD_ALERT 102 +#define SSL_R_BAD_CHANGE_CIPHER_SPEC 103 +#define SSL_R_BAD_DATA_RETURNED_BY_CALLBACK 104 +#define SSL_R_BAD_DH_P_LENGTH 105 +#define SSL_R_BAD_DIGEST_LENGTH 106 +#define SSL_R_BAD_ECC_CERT 107 +#define SSL_R_BAD_ECPOINT 108 +#define SSL_R_BAD_HANDSHAKE_LENGTH 109 +#define SSL_R_BAD_HANDSHAKE_RECORD 110 +#define SSL_R_BAD_HELLO_REQUEST 111 +#define SSL_R_BAD_LENGTH 112 +#define SSL_R_BAD_PACKET_LENGTH 113 +#define SSL_R_BAD_RSA_ENCRYPT 114 +#define SSL_R_BAD_SIGNATURE 115 +#define SSL_R_BAD_SRTP_MKI_VALUE 116 +#define SSL_R_BAD_SRTP_PROTECTION_PROFILE_LIST 117 +#define SSL_R_BAD_SSL_FILETYPE 118 +#define SSL_R_BAD_WRITE_RETRY 119 +#define SSL_R_BIO_NOT_SET 120 +#define SSL_R_BN_LIB 121 +#define SSL_R_CANNOT_SERIALIZE_PUBLIC_KEY 122 +#define SSL_R_CA_DN_LENGTH_MISMATCH 123 +#define SSL_R_CA_DN_TOO_LONG 124 +#define SSL_R_CCS_RECEIVED_EARLY 125 +#define SSL_R_CERTIFICATE_VERIFY_FAILED 126 +#define SSL_R_CERT_CB_ERROR 127 +#define SSL_R_CERT_LENGTH_MISMATCH 128 +#define SSL_R_CHANNEL_ID_NOT_P256 129 +#define SSL_R_CHANNEL_ID_SIGNATURE_INVALID 130 +#define SSL_R_CIPHER_CODE_WRONG_LENGTH 131 +#define SSL_R_CIPHER_OR_HASH_UNAVAILABLE 132 +#define SSL_R_CLIENTHELLO_PARSE_FAILED 133 +#define SSL_R_CLIENTHELLO_TLSEXT 134 +#define SSL_R_CONNECTION_REJECTED 135 +#define SSL_R_CONNECTION_TYPE_NOT_SET 136 +#define SSL_R_COOKIE_MISMATCH 137 +#define SSL_R_D2I_ECDSA_SIG 138 +#define SSL_R_DATA_BETWEEN_CCS_AND_FINISHED 139 +#define SSL_R_DATA_LENGTH_TOO_LONG 140 +#define SSL_R_DECODE_ERROR 141 +#define SSL_R_DECRYPTION_FAILED 142 +#define SSL_R_DECRYPTION_FAILED_OR_BAD_RECORD_MAC 143 +#define SSL_R_DH_PUBLIC_VALUE_LENGTH_IS_WRONG 144 +#define SSL_R_DIGEST_CHECK_FAILED 145 +#define SSL_R_DTLS_MESSAGE_TOO_BIG 146 +#define SSL_R_ECC_CERT_NOT_FOR_SIGNING 147 +#define SSL_R_EMPTY_SRTP_PROTECTION_PROFILE_LIST 148 +#define SSL_R_ENCRYPTED_LENGTH_TOO_LONG 149 +#define SSL_R_ERROR_IN_RECEIVED_CIPHER_LIST 150 +#define SSL_R_EVP_DIGESTSIGNFINAL_FAILED 151 +#define SSL_R_EVP_DIGESTSIGNINIT_FAILED 152 +#define SSL_R_EXCESSIVE_MESSAGE_SIZE 153 +#define SSL_R_EXTRA_DATA_IN_MESSAGE 154 +#define SSL_R_GOT_A_FIN_BEFORE_A_CCS 155 +#define SSL_R_GOT_CHANNEL_ID_BEFORE_A_CCS 156 +#define SSL_R_GOT_NEXT_PROTO_BEFORE_A_CCS 157 +#define SSL_R_GOT_NEXT_PROTO_WITHOUT_EXTENSION 158 +#define SSL_R_HANDSHAKE_FAILURE_ON_CLIENT_HELLO 159 +#define SSL_R_HANDSHAKE_RECORD_BEFORE_CCS 160 +#define SSL_R_HTTPS_PROXY_REQUEST 161 +#define SSL_R_HTTP_REQUEST 162 +#define SSL_R_INAPPROPRIATE_FALLBACK 163 +#define SSL_R_INVALID_COMMAND 164 +#define SSL_R_INVALID_MESSAGE 165 +#define SSL_R_INVALID_SSL_SESSION 166 +#define SSL_R_INVALID_TICKET_KEYS_LENGTH 167 +#define SSL_R_LENGTH_MISMATCH 168 +#define SSL_R_LIBRARY_HAS_NO_CIPHERS 169 +#define SSL_R_MISSING_DH_KEY 170 +#define SSL_R_MISSING_ECDSA_SIGNING_CERT 171 +#define SSL_R_MISSING_RSA_CERTIFICATE 172 +#define SSL_R_MISSING_RSA_ENCRYPTING_CERT 173 +#define SSL_R_MISSING_RSA_SIGNING_CERT 174 +#define SSL_R_MISSING_TMP_DH_KEY 175 +#define SSL_R_MISSING_TMP_ECDH_KEY 176 +#define SSL_R_MIXED_SPECIAL_OPERATOR_WITH_GROUPS 177 +#define SSL_R_MTU_TOO_SMALL 178 +#define SSL_R_NESTED_GROUP 179 +#define SSL_R_NO_CERTIFICATES_RETURNED 180 +#define SSL_R_NO_CERTIFICATE_ASSIGNED 181 +#define SSL_R_NO_CERTIFICATE_SET 182 +#define SSL_R_NO_CIPHERS_AVAILABLE 183 +#define SSL_R_NO_CIPHERS_PASSED 184 +#define SSL_R_NO_CIPHERS_SPECIFIED 185 +#define SSL_R_NO_CIPHER_MATCH 186 +#define SSL_R_NO_COMPRESSION_SPECIFIED 187 +#define SSL_R_NO_METHOD_SPECIFIED 188 +#define SSL_R_NO_P256_SUPPORT 189 +#define SSL_R_NO_PRIVATE_KEY_ASSIGNED 190 +#define SSL_R_NO_RENEGOTIATION 191 +#define SSL_R_NO_REQUIRED_DIGEST 192 +#define SSL_R_NO_SHARED_CIPHER 193 +#define SSL_R_NO_SHARED_SIGATURE_ALGORITHMS 194 +#define SSL_R_NO_SRTP_PROFILES 195 +#define SSL_R_NULL_SSL_CTX 196 +#define SSL_R_NULL_SSL_METHOD_PASSED 197 +#define SSL_R_OLD_SESSION_CIPHER_NOT_RETURNED 198 +#define SSL_R_PACKET_LENGTH_TOO_LONG 199 +#define SSL_R_PARSE_TLSEXT 200 +#define SSL_R_PATH_TOO_LONG 201 +#define SSL_R_PEER_DID_NOT_RETURN_A_CERTIFICATE 202 +#define SSL_R_PEER_ERROR_UNSUPPORTED_CERTIFICATE_TYPE 203 +#define SSL_R_PROTOCOL_IS_SHUTDOWN 204 +#define SSL_R_PSK_IDENTITY_NOT_FOUND 205 +#define SSL_R_PSK_NO_CLIENT_CB 206 +#define SSL_R_PSK_NO_SERVER_CB 207 +#define SSL_R_READ_BIO_NOT_SET 208 +#define SSL_R_READ_TIMEOUT_EXPIRED 209 +#define SSL_R_RECORD_LENGTH_MISMATCH 210 +#define SSL_R_RECORD_TOO_LARGE 211 +#define SSL_R_RENEGOTIATE_EXT_TOO_LONG 212 +#define SSL_R_RENEGOTIATION_ENCODING_ERR 213 +#define SSL_R_RENEGOTIATION_MISMATCH 214 +#define SSL_R_REQUIRED_CIPHER_MISSING 215 +#define SSL_R_SCSV_RECEIVED_WHEN_RENEGOTIATING 216 +#define SSL_R_SERVERHELLO_TLSEXT 217 +#define SSL_R_SESSION_ID_CONTEXT_UNINITIALIZED 218 +#define SSL_R_SESSION_MAY_NOT_BE_CREATED 219 +#define SSL_R_SIGNATURE_ALGORITHMS_ERROR 220 +#define SSL_R_SRTP_COULD_NOT_ALLOCATE_PROFILES 221 +#define SSL_R_SRTP_PROTECTION_PROFILE_LIST_TOO_LONG 222 +#define SSL_R_SRTP_UNKNOWN_PROTECTION_PROFILE 223 +#define SSL_R_SSL3_EXT_INVALID_SERVERNAME 224 +#define SSL_R_SSL3_EXT_INVALID_SERVERNAME_TYPE 225 +#define SSL_R_SSL_CTX_HAS_NO_DEFAULT_SSL_VERSION 226 +#define SSL_R_SSL_HANDSHAKE_FAILURE 227 +#define SSL_R_SSL_SESSION_ID_CALLBACK_FAILED 228 +#define SSL_R_SSL_SESSION_ID_CONFLICT 229 +#define SSL_R_SSL_SESSION_ID_CONTEXT_TOO_LONG 230 +#define SSL_R_SSL_SESSION_ID_HAS_BAD_LENGTH 231 +#define SSL_R_TLS_CLIENT_CERT_REQ_WITH_ANON_CIPHER 232 +#define SSL_R_TLS_ILLEGAL_EXPORTER_LABEL 233 +#define SSL_R_TLS_INVALID_ECPOINTFORMAT_LIST 234 +#define SSL_R_TLS_PEER_DID_NOT_RESPOND_WITH_CERTIFICATE_LIST 235 +#define SSL_R_TLS_RSA_ENCRYPTED_VALUE_LENGTH_IS_WRONG 236 +#define SSL_R_TOO_MANY_EMPTY_FRAGMENTS 237 +#define SSL_R_UNABLE_TO_FIND_ECDH_PARAMETERS 238 +#define SSL_R_UNABLE_TO_FIND_PUBLIC_KEY_PARAMETERS 239 +#define SSL_R_UNEXPECTED_GROUP_CLOSE 240 +#define SSL_R_UNEXPECTED_MESSAGE 241 +#define SSL_R_UNEXPECTED_OPERATOR_IN_GROUP 242 +#define SSL_R_UNEXPECTED_RECORD 243 +#define SSL_R_UNINITIALIZED 244 +#define SSL_R_UNKNOWN_ALERT_TYPE 245 +#define SSL_R_UNKNOWN_CERTIFICATE_TYPE 246 +#define SSL_R_UNKNOWN_CIPHER_RETURNED 247 +#define SSL_R_UNKNOWN_CIPHER_TYPE 248 +#define SSL_R_UNKNOWN_DIGEST 249 +#define SSL_R_UNKNOWN_KEY_EXCHANGE_TYPE 250 +#define SSL_R_UNKNOWN_PROTOCOL 251 +#define SSL_R_UNKNOWN_SSL_VERSION 252 +#define SSL_R_UNKNOWN_STATE 253 +#define SSL_R_UNPROCESSED_HANDSHAKE_DATA 254 +#define SSL_R_UNSAFE_LEGACY_RENEGOTIATION_DISABLED 255 +#define SSL_R_UNSUPPORTED_CIPHER 256 +#define SSL_R_UNSUPPORTED_COMPRESSION_ALGORITHM 257 +#define SSL_R_UNSUPPORTED_ELLIPTIC_CURVE 258 +#define SSL_R_UNSUPPORTED_PROTOCOL 259 +#define SSL_R_UNSUPPORTED_SSL_VERSION 260 +#define SSL_R_USE_SRTP_NOT_NEGOTIATED 261 +#define SSL_R_WRONG_CERTIFICATE_TYPE 262 +#define SSL_R_WRONG_CIPHER_RETURNED 263 +#define SSL_R_WRONG_CURVE 264 +#define SSL_R_WRONG_MESSAGE_TYPE 265 +#define SSL_R_WRONG_SIGNATURE_TYPE 266 +#define SSL_R_WRONG_SSL_VERSION 267 +#define SSL_R_WRONG_VERSION_NUMBER 268 +#define SSL_R_X509_LIB 269 +#define SSL_R_X509_VERIFICATION_SETUP_PROBLEMS 270 +#define SSL_R_FRAGMENT_MISMATCH 271 +#define SSL_R_BUFFER_TOO_SMALL 272 +#define SSL_R_OLD_SESSION_VERSION_NOT_RETURNED 273 +#define SSL_R_OUTPUT_ALIASES_INPUT 274 +#define SSL_R_RESUMED_EMS_SESSION_WITHOUT_EMS_EXTENSION 275 +#define SSL_R_EMS_STATE_INCONSISTENT 276 +#define SSL_R_RESUMED_NON_EMS_SESSION_WITH_EMS_EXTENSION 277 +#define SSL_R_SSLV3_ALERT_CLOSE_NOTIFY 1000 +#define SSL_R_SSLV3_ALERT_UNEXPECTED_MESSAGE 1010 +#define SSL_R_SSLV3_ALERT_BAD_RECORD_MAC 1020 +#define SSL_R_TLSV1_ALERT_DECRYPTION_FAILED 1021 +#define SSL_R_TLSV1_ALERT_RECORD_OVERFLOW 1022 +#define SSL_R_SSLV3_ALERT_DECOMPRESSION_FAILURE 1030 +#define SSL_R_SSLV3_ALERT_HANDSHAKE_FAILURE 1040 +#define SSL_R_SSLV3_ALERT_NO_CERTIFICATE 1041 +#define SSL_R_SSLV3_ALERT_BAD_CERTIFICATE 1042 +#define SSL_R_SSLV3_ALERT_UNSUPPORTED_CERTIFICATE 1043 +#define SSL_R_SSLV3_ALERT_CERTIFICATE_REVOKED 1044 +#define SSL_R_SSLV3_ALERT_CERTIFICATE_EXPIRED 1045 +#define SSL_R_SSLV3_ALERT_CERTIFICATE_UNKNOWN 1046 +#define SSL_R_SSLV3_ALERT_ILLEGAL_PARAMETER 1047 +#define SSL_R_TLSV1_ALERT_UNKNOWN_CA 1048 +#define SSL_R_TLSV1_ALERT_ACCESS_DENIED 1049 +#define SSL_R_TLSV1_ALERT_DECODE_ERROR 1050 +#define SSL_R_TLSV1_ALERT_DECRYPT_ERROR 1051 +#define SSL_R_TLSV1_ALERT_EXPORT_RESTRICTION 1060 +#define SSL_R_TLSV1_ALERT_PROTOCOL_VERSION 1070 +#define SSL_R_TLSV1_ALERT_INSUFFICIENT_SECURITY 1071 +#define SSL_R_TLSV1_ALERT_INTERNAL_ERROR 1080 +#define SSL_R_TLSV1_ALERT_INAPPROPRIATE_FALLBACK 1086 +#define SSL_R_TLSV1_ALERT_USER_CANCELLED 1090 +#define SSL_R_TLSV1_ALERT_NO_RENEGOTIATION 1100 +#define SSL_R_TLSV1_UNSUPPORTED_EXTENSION 1110 +#define SSL_R_TLSV1_CERTIFICATE_UNOBTAINABLE 1111 +#define SSL_R_TLSV1_UNRECOGNIZED_NAME 1112 +#define SSL_R_TLSV1_BAD_CERTIFICATE_STATUS_RESPONSE 1113 +#define SSL_R_TLSV1_BAD_CERTIFICATE_HASH_VALUE 1114 + +#endif /* OPENSSL_HEADER_SSL_H */ diff --git a/phonelibs/boringssl/include/openssl/ssl2.h b/phonelibs/boringssl/include/openssl/ssl2.h new file mode 100644 index 00000000000000..b8401faaf6684a --- /dev/null +++ b/phonelibs/boringssl/include/openssl/ssl2.h @@ -0,0 +1,268 @@ +/* ssl/ssl2.h */ +/* Copyright (C) 1995-1998 Eric Young (eay@cryptsoft.com) + * All rights reserved. + * + * This package is an SSL implementation written + * by Eric Young (eay@cryptsoft.com). + * The implementation was written so as to conform with Netscapes SSL. + * + * This library is free for commercial and non-commercial use as long as + * the following conditions are aheared to. The following conditions + * apply to all code found in this distribution, be it the RC4, RSA, + * lhash, DES, etc., code; not just the SSL code. The SSL documentation + * included with this distribution is covered by the same copyright terms + * except that the holder is Tim Hudson (tjh@cryptsoft.com). + * + * Copyright remains Eric Young's, and as such any Copyright notices in + * the code are not to be removed. + * If this package is used in a product, Eric Young should be given attribution + * as the author of the parts of the library used. + * This can be in the form of a textual message at program startup or + * in documentation (online or textual) provided with the package. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must 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. All advertising materials mentioning features or use of this software + * must display the following acknowledgement: + * "This product includes cryptographic software written by + * Eric Young (eay@cryptsoft.com)" + * The word 'cryptographic' can be left out if the rouines from the library + * being used are not cryptographic related :-). + * 4. If you include any Windows specific code (or a derivative thereof) from + * the apps directory (application code) you must include an acknowledgement: + * "This product includes software written by Tim Hudson (tjh@cryptsoft.com)" + * + * THIS SOFTWARE IS PROVIDED BY ERIC YOUNG ``AS IS'' AND + * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHOR OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (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 licence and distribution terms for any publically available version or + * derivative of this code cannot be changed. i.e. this code cannot simply be + * copied and put under another distribution licence + * [including the GNU Public Licence.] + */ + +#ifndef HEADER_SSL2_H +#define HEADER_SSL2_H + +#ifdef __cplusplus +extern "C" { +#endif + +/* Protocol Version Codes */ +#define SSL2_VERSION 0x0002 +#define SSL2_VERSION_MAJOR 0x00 +#define SSL2_VERSION_MINOR 0x02 +/* #define SSL2_CLIENT_VERSION 0x0002 */ +/* #define SSL2_SERVER_VERSION 0x0002 */ + +/* Protocol Message Codes */ +#define SSL2_MT_ERROR 0 +#define SSL2_MT_CLIENT_HELLO 1 +#define SSL2_MT_CLIENT_MASTER_KEY 2 +#define SSL2_MT_CLIENT_FINISHED 3 +#define SSL2_MT_SERVER_HELLO 4 +#define SSL2_MT_SERVER_VERIFY 5 +#define SSL2_MT_SERVER_FINISHED 6 +#define SSL2_MT_REQUEST_CERTIFICATE 7 +#define SSL2_MT_CLIENT_CERTIFICATE 8 + +/* Error Message Codes */ +#define SSL2_PE_UNDEFINED_ERROR 0x0000 +#define SSL2_PE_NO_CIPHER 0x0001 +#define SSL2_PE_NO_CERTIFICATE 0x0002 +#define SSL2_PE_BAD_CERTIFICATE 0x0004 +#define SSL2_PE_UNSUPPORTED_CERTIFICATE_TYPE 0x0006 + +/* Cipher Kind Values */ +#define SSL2_CK_NULL_WITH_MD5 0x02000000 /* v3 */ +#define SSL2_CK_RC4_128_WITH_MD5 0x02010080 +#define SSL2_CK_RC4_128_EXPORT40_WITH_MD5 0x02020080 +#define SSL2_CK_RC2_128_CBC_WITH_MD5 0x02030080 +#define SSL2_CK_RC2_128_CBC_EXPORT40_WITH_MD5 0x02040080 +#define SSL2_CK_IDEA_128_CBC_WITH_MD5 0x02050080 +#define SSL2_CK_DES_64_CBC_WITH_MD5 0x02060040 +#define SSL2_CK_DES_64_CBC_WITH_SHA 0x02060140 /* v3 */ +#define SSL2_CK_DES_192_EDE3_CBC_WITH_MD5 0x020700c0 +#define SSL2_CK_DES_192_EDE3_CBC_WITH_SHA 0x020701c0 /* v3 */ +#define SSL2_CK_RC4_64_WITH_MD5 0x02080080 /* MS hack */ + +#define SSL2_CK_DES_64_CFB64_WITH_MD5_1 0x02ff0800 /* SSLeay */ +#define SSL2_CK_NULL 0x02ff0810 /* SSLeay */ + +#define SSL2_TXT_DES_64_CFB64_WITH_MD5_1 "DES-CFB-M1" +#define SSL2_TXT_NULL_WITH_MD5 "NULL-MD5" +#define SSL2_TXT_RC4_128_WITH_MD5 "RC4-MD5" +#define SSL2_TXT_RC4_128_EXPORT40_WITH_MD5 "EXP-RC4-MD5" +#define SSL2_TXT_RC2_128_CBC_WITH_MD5 "RC2-CBC-MD5" +#define SSL2_TXT_RC2_128_CBC_EXPORT40_WITH_MD5 "EXP-RC2-CBC-MD5" +#define SSL2_TXT_IDEA_128_CBC_WITH_MD5 "IDEA-CBC-MD5" +#define SSL2_TXT_DES_64_CBC_WITH_MD5 "DES-CBC-MD5" +#define SSL2_TXT_DES_64_CBC_WITH_SHA "DES-CBC-SHA" +#define SSL2_TXT_DES_192_EDE3_CBC_WITH_MD5 "DES-CBC3-MD5" +#define SSL2_TXT_DES_192_EDE3_CBC_WITH_SHA "DES-CBC3-SHA" +#define SSL2_TXT_RC4_64_WITH_MD5 "RC4-64-MD5" + +#define SSL2_TXT_NULL "NULL" + +/* Flags for the SSL_CIPHER.algorithm2 field */ +#define SSL2_CF_5_BYTE_ENC 0x01 +#define SSL2_CF_8_BYTE_ENC 0x02 + +/* Certificate Type Codes */ +#define SSL2_CT_X509_CERTIFICATE 0x01 + +/* Authentication Type Code */ +#define SSL2_AT_MD5_WITH_RSA_ENCRYPTION 0x01 + +#define SSL2_MAX_SSL_SESSION_ID_LENGTH 32 + +/* Upper/Lower Bounds */ +#define SSL2_MAX_MASTER_KEY_LENGTH_IN_BITS 256 +#ifdef OPENSSL_SYS_MPE +#define SSL2_MAX_RECORD_LENGTH_2_BYTE_HEADER 29998u +#else +#define SSL2_MAX_RECORD_LENGTH_2_BYTE_HEADER 32767u /* 2^15-1 */ +#endif +#define SSL2_MAX_RECORD_LENGTH_3_BYTE_HEADER 16383 /* 2^14-1 */ + +#define SSL2_CHALLENGE_LENGTH 16 +/*#define SSL2_CHALLENGE_LENGTH 32 */ +#define SSL2_MIN_CHALLENGE_LENGTH 16 +#define SSL2_MAX_CHALLENGE_LENGTH 32 +#define SSL2_CONNECTION_ID_LENGTH 16 +#define SSL2_MAX_CONNECTION_ID_LENGTH 16 +#define SSL2_SSL_SESSION_ID_LENGTH 16 +#define SSL2_MAX_CERT_CHALLENGE_LENGTH 32 +#define SSL2_MIN_CERT_CHALLENGE_LENGTH 16 +#define SSL2_MAX_KEY_MATERIAL_LENGTH 24 + +#ifndef OPENSSL_NO_SSL_INTERN + +typedef struct ssl2_state_st + { + int three_byte_header; + int clear_text; /* clear text */ + int escape; /* not used in SSLv2 */ + int ssl2_rollback; /* used if SSLv23 rolled back to SSLv2 */ + + /* non-blocking io info, used to make sure the same + * args were passwd */ + unsigned int wnum; /* number of bytes sent so far */ + int wpend_tot; + const unsigned char *wpend_buf; + + int wpend_off; /* offset to data to write */ + int wpend_len; /* number of bytes passwd to write */ + int wpend_ret; /* number of bytes to return to caller */ + + /* buffer raw data */ + int rbuf_left; + int rbuf_offs; + unsigned char *rbuf; + unsigned char *wbuf; + + unsigned char *write_ptr;/* used to point to the start due to + * 2/3 byte header. */ + + unsigned int padding; + unsigned int rlength; /* passed to ssl2_enc */ + int ract_data_length; /* Set when things are encrypted. */ + unsigned int wlength; /* passed to ssl2_enc */ + int wact_data_length; /* Set when things are decrypted. */ + unsigned char *ract_data; + unsigned char *wact_data; + unsigned char *mac_data; + + unsigned char *read_key; + unsigned char *write_key; + + /* Stuff specifically to do with this SSL session */ + unsigned int challenge_length; + unsigned char challenge[SSL2_MAX_CHALLENGE_LENGTH]; + unsigned int conn_id_length; + unsigned char conn_id[SSL2_MAX_CONNECTION_ID_LENGTH]; + unsigned int key_material_length; + unsigned char key_material[SSL2_MAX_KEY_MATERIAL_LENGTH*2]; + + unsigned long read_sequence; + unsigned long write_sequence; + + struct { + unsigned int conn_id_length; + unsigned int cert_type; + unsigned int cert_length; + unsigned int csl; + unsigned int clear; + unsigned int enc; + unsigned char ccl[SSL2_MAX_CERT_CHALLENGE_LENGTH]; + unsigned int cipher_spec_length; + unsigned int session_id_length; + unsigned int clen; + unsigned int rlen; + } tmp; + } SSL2_STATE; + +#endif + +/* SSLv2 */ +/* client */ +#define SSL2_ST_SEND_CLIENT_HELLO_A (0x10|SSL_ST_CONNECT) +#define SSL2_ST_SEND_CLIENT_HELLO_B (0x11|SSL_ST_CONNECT) +#define SSL2_ST_GET_SERVER_HELLO_A (0x20|SSL_ST_CONNECT) +#define SSL2_ST_GET_SERVER_HELLO_B (0x21|SSL_ST_CONNECT) +#define SSL2_ST_SEND_CLIENT_MASTER_KEY_A (0x30|SSL_ST_CONNECT) +#define SSL2_ST_SEND_CLIENT_MASTER_KEY_B (0x31|SSL_ST_CONNECT) +#define SSL2_ST_SEND_CLIENT_FINISHED_A (0x40|SSL_ST_CONNECT) +#define SSL2_ST_SEND_CLIENT_FINISHED_B (0x41|SSL_ST_CONNECT) +#define SSL2_ST_SEND_CLIENT_CERTIFICATE_A (0x50|SSL_ST_CONNECT) +#define SSL2_ST_SEND_CLIENT_CERTIFICATE_B (0x51|SSL_ST_CONNECT) +#define SSL2_ST_SEND_CLIENT_CERTIFICATE_C (0x52|SSL_ST_CONNECT) +#define SSL2_ST_SEND_CLIENT_CERTIFICATE_D (0x53|SSL_ST_CONNECT) +#define SSL2_ST_GET_SERVER_VERIFY_A (0x60|SSL_ST_CONNECT) +#define SSL2_ST_GET_SERVER_VERIFY_B (0x61|SSL_ST_CONNECT) +#define SSL2_ST_GET_SERVER_FINISHED_A (0x70|SSL_ST_CONNECT) +#define SSL2_ST_GET_SERVER_FINISHED_B (0x71|SSL_ST_CONNECT) +#define SSL2_ST_CLIENT_START_ENCRYPTION (0x80|SSL_ST_CONNECT) +#define SSL2_ST_X509_GET_CLIENT_CERTIFICATE (0x90|SSL_ST_CONNECT) +/* server */ +#define SSL2_ST_GET_CLIENT_HELLO_A (0x10|SSL_ST_ACCEPT) +#define SSL2_ST_GET_CLIENT_HELLO_B (0x11|SSL_ST_ACCEPT) +#define SSL2_ST_GET_CLIENT_HELLO_C (0x12|SSL_ST_ACCEPT) +#define SSL2_ST_SEND_SERVER_HELLO_A (0x20|SSL_ST_ACCEPT) +#define SSL2_ST_SEND_SERVER_HELLO_B (0x21|SSL_ST_ACCEPT) +#define SSL2_ST_GET_CLIENT_MASTER_KEY_A (0x30|SSL_ST_ACCEPT) +#define SSL2_ST_GET_CLIENT_MASTER_KEY_B (0x31|SSL_ST_ACCEPT) +#define SSL2_ST_SEND_SERVER_VERIFY_A (0x40|SSL_ST_ACCEPT) +#define SSL2_ST_SEND_SERVER_VERIFY_B (0x41|SSL_ST_ACCEPT) +#define SSL2_ST_SEND_SERVER_VERIFY_C (0x42|SSL_ST_ACCEPT) +#define SSL2_ST_GET_CLIENT_FINISHED_A (0x50|SSL_ST_ACCEPT) +#define SSL2_ST_GET_CLIENT_FINISHED_B (0x51|SSL_ST_ACCEPT) +#define SSL2_ST_SEND_SERVER_FINISHED_A (0x60|SSL_ST_ACCEPT) +#define SSL2_ST_SEND_SERVER_FINISHED_B (0x61|SSL_ST_ACCEPT) +#define SSL2_ST_SEND_REQUEST_CERTIFICATE_A (0x70|SSL_ST_ACCEPT) +#define SSL2_ST_SEND_REQUEST_CERTIFICATE_B (0x71|SSL_ST_ACCEPT) +#define SSL2_ST_SEND_REQUEST_CERTIFICATE_C (0x72|SSL_ST_ACCEPT) +#define SSL2_ST_SEND_REQUEST_CERTIFICATE_D (0x73|SSL_ST_ACCEPT) +#define SSL2_ST_SERVER_START_ENCRYPTION (0x80|SSL_ST_ACCEPT) +#define SSL2_ST_X509_GET_SERVER_CERTIFICATE (0x90|SSL_ST_ACCEPT) + +#ifdef __cplusplus +} +#endif +#endif + diff --git a/phonelibs/boringssl/include/openssl/ssl23.h b/phonelibs/boringssl/include/openssl/ssl23.h new file mode 100644 index 00000000000000..df395a8e978df7 --- /dev/null +++ b/phonelibs/boringssl/include/openssl/ssl23.h @@ -0,0 +1,85 @@ +/* ssl/ssl23.h */ +/* Copyright (C) 1995-1998 Eric Young (eay@cryptsoft.com) + * All rights reserved. + * + * This package is an SSL implementation written + * by Eric Young (eay@cryptsoft.com). + * The implementation was written so as to conform with Netscapes SSL. + * + * This library is free for commercial and non-commercial use as long as + * the following conditions are aheared to. The following conditions + * apply to all code found in this distribution, be it the RC4, RSA, + * lhash, DES, etc., code; not just the SSL code. The SSL documentation + * included with this distribution is covered by the same copyright terms + * except that the holder is Tim Hudson (tjh@cryptsoft.com). + * + * Copyright remains Eric Young's, and as such any Copyright notices in + * the code are not to be removed. + * If this package is used in a product, Eric Young should be given attribution + * as the author of the parts of the library used. + * This can be in the form of a textual message at program startup or + * in documentation (online or textual) provided with the package. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must 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. All advertising materials mentioning features or use of this software + * must display the following acknowledgement: + * "This product includes cryptographic software written by + * Eric Young (eay@cryptsoft.com)" + * The word 'cryptographic' can be left out if the rouines from the library + * being used are not cryptographic related :-). + * 4. If you include any Windows specific code (or a derivative thereof) from + * the apps directory (application code) you must include an acknowledgement: + * "This product includes software written by Tim Hudson (tjh@cryptsoft.com)" + * + * THIS SOFTWARE IS PROVIDED BY ERIC YOUNG ``AS IS'' AND + * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHOR OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (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 licence and distribution terms for any publically available version or + * derivative of this code cannot be changed. i.e. this code cannot simply be + * copied and put under another distribution licence + * [including the GNU Public Licence.] + */ + +#ifndef HEADER_SSL23_H +#define HEADER_SSL23_H + +#ifdef __cplusplus +extern "C" { +#endif + + +/*client */ +/* write to server */ +#define SSL23_ST_CW_CLNT_HELLO_A (0x210 | SSL_ST_CONNECT) +#define SSL23_ST_CW_CLNT_HELLO_B (0x211 | SSL_ST_CONNECT) +/* read from server */ +#define SSL23_ST_CR_SRVR_HELLO_A (0x220 | SSL_ST_CONNECT) +#define SSL23_ST_CR_SRVR_HELLO_B (0x221 | SSL_ST_CONNECT) + +/* server */ +/* read from client */ +#define SSL23_ST_SR_CLNT_HELLO (0x210 | SSL_ST_ACCEPT) +#define SSL23_ST_SR_V2_CLNT_HELLO (0x220 | SSL_ST_ACCEPT) +#define SSL23_ST_SR_SWITCH_VERSION (0x230 | SSL_ST_ACCEPT) + + +#ifdef __cplusplus +} +#endif +#endif diff --git a/phonelibs/boringssl/include/openssl/ssl3.h b/phonelibs/boringssl/include/openssl/ssl3.h new file mode 100644 index 00000000000000..640a22826ec1c1 --- /dev/null +++ b/phonelibs/boringssl/include/openssl/ssl3.h @@ -0,0 +1,681 @@ +/* ssl/ssl3.h */ +/* Copyright (C) 1995-1998 Eric Young (eay@cryptsoft.com) + * All rights reserved. + * + * This package is an SSL implementation written + * by Eric Young (eay@cryptsoft.com). + * The implementation was written so as to conform with Netscapes SSL. + * + * This library is free for commercial and non-commercial use as long as + * the following conditions are aheared to. The following conditions + * apply to all code found in this distribution, be it the RC4, RSA, + * lhash, DES, etc., code; not just the SSL code. The SSL documentation + * included with this distribution is covered by the same copyright terms + * except that the holder is Tim Hudson (tjh@cryptsoft.com). + * + * Copyright remains Eric Young's, and as such any Copyright notices in + * the code are not to be removed. + * If this package is used in a product, Eric Young should be given attribution + * as the author of the parts of the library used. + * This can be in the form of a textual message at program startup or + * in documentation (online or textual) provided with the package. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must 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. All advertising materials mentioning features or use of this software + * must display the following acknowledgement: + * "This product includes cryptographic software written by + * Eric Young (eay@cryptsoft.com)" + * The word 'cryptographic' can be left out if the rouines from the library + * being used are not cryptographic related :-). + * 4. If you include any Windows specific code (or a derivative thereof) from + * the apps directory (application code) you must include an acknowledgement: + * "This product includes software written by Tim Hudson (tjh@cryptsoft.com)" + * + * THIS SOFTWARE IS PROVIDED BY ERIC YOUNG ``AS IS'' AND + * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHOR OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (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 licence and distribution terms for any publically available version or + * derivative of this code cannot be changed. i.e. this code cannot simply be + * copied and put under another distribution licence + * [including the GNU Public Licence.] + */ +/* ==================================================================== + * Copyright (c) 1998-2002 The OpenSSL Project. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * + * 3. All advertising materials mentioning features or use of this + * software must display the following acknowledgment: + * "This product includes software developed by the OpenSSL Project + * for use in the OpenSSL Toolkit. (http://www.openssl.org/)" + * + * 4. The names "OpenSSL Toolkit" and "OpenSSL Project" must not be used to + * endorse or promote products derived from this software without + * prior written permission. For written permission, please contact + * openssl-core@openssl.org. + * + * 5. Products derived from this software may not be called "OpenSSL" + * nor may "OpenSSL" appear in their names without prior written + * permission of the OpenSSL Project. + * + * 6. Redistributions of any form whatsoever must retain the following + * acknowledgment: + * "This product includes software developed by the OpenSSL Project + * for use in the OpenSSL Toolkit (http://www.openssl.org/)" + * + * THIS SOFTWARE IS PROVIDED BY THE OpenSSL PROJECT ``AS IS'' AND ANY + * EXPRESSED OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR + * PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE OpenSSL PROJECT OR + * ITS CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, + * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT + * NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + * STRICT LIABILITY, OR TORT (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 product includes cryptographic software written by Eric Young + * (eay@cryptsoft.com). This product includes software written by Tim + * Hudson (tjh@cryptsoft.com). + * + */ +/* ==================================================================== + * Copyright 2002 Sun Microsystems, Inc. ALL RIGHTS RESERVED. + * ECC cipher suite support in OpenSSL originally developed by + * SUN MICROSYSTEMS, INC., and contributed to the OpenSSL project. + */ + +#ifndef HEADER_SSL3_H +#define HEADER_SSL3_H + +#include +#include +#include +#include +#include + +#ifdef __cplusplus +extern "C" { +#endif + + +/* Signalling cipher suite value: from RFC5746 */ +#define SSL3_CK_SCSV 0x030000FF +/* Fallback signalling cipher suite value: not IANA assigned. + * See https://tools.ietf.org/html/draft-bmoeller-tls-downgrade-scsv-01 */ +#define SSL3_CK_FALLBACK_SCSV 0x03005600 + +#define SSL3_CK_RSA_NULL_MD5 0x03000001 +#define SSL3_CK_RSA_NULL_SHA 0x03000002 +#define SSL3_CK_RSA_RC4_40_MD5 0x03000003 +#define SSL3_CK_RSA_RC4_128_MD5 0x03000004 +#define SSL3_CK_RSA_RC4_128_SHA 0x03000005 +#define SSL3_CK_RSA_RC2_40_MD5 0x03000006 +#define SSL3_CK_RSA_IDEA_128_SHA 0x03000007 +#define SSL3_CK_RSA_DES_40_CBC_SHA 0x03000008 +#define SSL3_CK_RSA_DES_64_CBC_SHA 0x03000009 +#define SSL3_CK_RSA_DES_192_CBC3_SHA 0x0300000A + +#define SSL3_CK_DH_DSS_DES_40_CBC_SHA 0x0300000B +#define SSL3_CK_DH_DSS_DES_64_CBC_SHA 0x0300000C +#define SSL3_CK_DH_DSS_DES_192_CBC3_SHA 0x0300000D +#define SSL3_CK_DH_RSA_DES_40_CBC_SHA 0x0300000E +#define SSL3_CK_DH_RSA_DES_64_CBC_SHA 0x0300000F +#define SSL3_CK_DH_RSA_DES_192_CBC3_SHA 0x03000010 + +#define SSL3_CK_EDH_DSS_DES_40_CBC_SHA 0x03000011 +#define SSL3_CK_EDH_DSS_DES_64_CBC_SHA 0x03000012 +#define SSL3_CK_EDH_DSS_DES_192_CBC3_SHA 0x03000013 +#define SSL3_CK_EDH_RSA_DES_40_CBC_SHA 0x03000014 +#define SSL3_CK_EDH_RSA_DES_64_CBC_SHA 0x03000015 +#define SSL3_CK_EDH_RSA_DES_192_CBC3_SHA 0x03000016 + +#define SSL3_CK_ADH_RC4_40_MD5 0x03000017 +#define SSL3_CK_ADH_RC4_128_MD5 0x03000018 +#define SSL3_CK_ADH_DES_40_CBC_SHA 0x03000019 +#define SSL3_CK_ADH_DES_64_CBC_SHA 0x0300001A +#define SSL3_CK_ADH_DES_192_CBC_SHA 0x0300001B + +#define SSL3_TXT_RSA_NULL_MD5 "NULL-MD5" +#define SSL3_TXT_RSA_NULL_SHA "NULL-SHA" +#define SSL3_TXT_RSA_RC4_40_MD5 "EXP-RC4-MD5" +#define SSL3_TXT_RSA_RC4_128_MD5 "RC4-MD5" +#define SSL3_TXT_RSA_RC4_128_SHA "RC4-SHA" +#define SSL3_TXT_RSA_RC2_40_MD5 "EXP-RC2-CBC-MD5" +#define SSL3_TXT_RSA_IDEA_128_SHA "IDEA-CBC-SHA" +#define SSL3_TXT_RSA_DES_40_CBC_SHA "EXP-DES-CBC-SHA" +#define SSL3_TXT_RSA_DES_64_CBC_SHA "DES-CBC-SHA" +#define SSL3_TXT_RSA_DES_192_CBC3_SHA "DES-CBC3-SHA" + +#define SSL3_TXT_DH_DSS_DES_40_CBC_SHA "EXP-DH-DSS-DES-CBC-SHA" +#define SSL3_TXT_DH_DSS_DES_64_CBC_SHA "DH-DSS-DES-CBC-SHA" +#define SSL3_TXT_DH_DSS_DES_192_CBC3_SHA "DH-DSS-DES-CBC3-SHA" +#define SSL3_TXT_DH_RSA_DES_40_CBC_SHA "EXP-DH-RSA-DES-CBC-SHA" +#define SSL3_TXT_DH_RSA_DES_64_CBC_SHA "DH-RSA-DES-CBC-SHA" +#define SSL3_TXT_DH_RSA_DES_192_CBC3_SHA "DH-RSA-DES-CBC3-SHA" + +#define SSL3_TXT_EDH_DSS_DES_40_CBC_SHA "EXP-EDH-DSS-DES-CBC-SHA" +#define SSL3_TXT_EDH_DSS_DES_64_CBC_SHA "EDH-DSS-DES-CBC-SHA" +#define SSL3_TXT_EDH_DSS_DES_192_CBC3_SHA "EDH-DSS-DES-CBC3-SHA" +#define SSL3_TXT_EDH_RSA_DES_40_CBC_SHA "EXP-EDH-RSA-DES-CBC-SHA" +#define SSL3_TXT_EDH_RSA_DES_64_CBC_SHA "EDH-RSA-DES-CBC-SHA" +#define SSL3_TXT_EDH_RSA_DES_192_CBC3_SHA "EDH-RSA-DES-CBC3-SHA" + +#define SSL3_TXT_ADH_RC4_40_MD5 "EXP-ADH-RC4-MD5" +#define SSL3_TXT_ADH_RC4_128_MD5 "ADH-RC4-MD5" +#define SSL3_TXT_ADH_DES_40_CBC_SHA "EXP-ADH-DES-CBC-SHA" +#define SSL3_TXT_ADH_DES_64_CBC_SHA "ADH-DES-CBC-SHA" +#define SSL3_TXT_ADH_DES_192_CBC_SHA "ADH-DES-CBC3-SHA" + +#define SSL3_SSL_SESSION_ID_LENGTH 32 +#define SSL3_MAX_SSL_SESSION_ID_LENGTH 32 + +#define SSL3_MASTER_SECRET_SIZE 48 +#define SSL3_RANDOM_SIZE 32 +#define SSL3_SESSION_ID_SIZE 32 +#define SSL3_RT_HEADER_LENGTH 5 + +#define SSL3_HM_HEADER_LENGTH 4 + +#ifndef SSL3_ALIGN_PAYLOAD +/* Some will argue that this increases memory footprint, but it's not actually + * true. Point is that malloc has to return at least 64-bit aligned pointers, + * meaning that allocating 5 bytes wastes 3 bytes in either case. Suggested + * pre-gaping simply moves these wasted bytes from the end of allocated region + * to its front, but makes data payload aligned, which improves performance. */ +#define SSL3_ALIGN_PAYLOAD 8 +#else +#if (SSL3_ALIGN_PAYLOAD & (SSL3_ALIGN_PAYLOAD - 1)) != 0 +#error "insane SSL3_ALIGN_PAYLOAD" +#undef SSL3_ALIGN_PAYLOAD +#endif +#endif + +/* This is the maximum MAC (digest) size used by the SSL library. Currently + * maximum of 20 is used by SHA1, but we reserve for future extension for + * 512-bit hashes. */ + +#define SSL3_RT_MAX_MD_SIZE 64 + +/* Maximum block size used in all ciphersuites. Currently 16 for AES. */ + +#define SSL_RT_MAX_CIPHER_BLOCK_SIZE 16 + +#define SSL3_RT_MAX_EXTRA (16384) + +/* Maximum plaintext length: defined by SSL/TLS standards */ +#define SSL3_RT_MAX_PLAIN_LENGTH 16384 +/* Maximum compression overhead: defined by SSL/TLS standards */ +#define SSL3_RT_MAX_COMPRESSED_OVERHEAD 1024 + +/* The standards give a maximum encryption overhead of 1024 bytes. In practice + * the value is lower than this. The overhead is the maximum number of padding + * bytes (256) plus the mac size. + * + * TODO(davidben): This derivation doesn't take AEADs into account, or TLS 1.1 + * explicit nonces. It happens to work because |SSL3_RT_MAX_MD_SIZE| is larger + * than necessary and no true AEAD has variable overhead in TLS 1.2. */ +#define SSL3_RT_MAX_ENCRYPTED_OVERHEAD (256 + SSL3_RT_MAX_MD_SIZE) + +/* SSL3_RT_SEND_MAX_ENCRYPTED_OVERHEAD is the maximum overhead in encrypting a + * record. This does not include the record header. Some ciphers use explicit + * nonces, so it includes both the AEAD overhead as well as the nonce. */ +#define SSL3_RT_SEND_MAX_ENCRYPTED_OVERHEAD \ + (EVP_AEAD_MAX_OVERHEAD + EVP_AEAD_MAX_NONCE_LENGTH) + +OPENSSL_COMPILE_ASSERT( + SSL3_RT_MAX_ENCRYPTED_OVERHEAD >= SSL3_RT_SEND_MAX_ENCRYPTED_OVERHEAD, + max_overheads_are_consistent); + +/* SSL3_RT_MAX_COMPRESSED_LENGTH is an alias for + * |SSL3_RT_MAX_PLAIN_LENGTH|. Compression is gone, so don't include the + * compression overhead. */ +#define SSL3_RT_MAX_COMPRESSED_LENGTH SSL3_RT_MAX_PLAIN_LENGTH + +#define SSL3_RT_MAX_ENCRYPTED_LENGTH \ + (SSL3_RT_MAX_ENCRYPTED_OVERHEAD + SSL3_RT_MAX_COMPRESSED_LENGTH) +#define SSL3_RT_MAX_PACKET_SIZE \ + (SSL3_RT_MAX_ENCRYPTED_LENGTH + SSL3_RT_HEADER_LENGTH) + +#define SSL3_MD_CLIENT_FINISHED_CONST "\x43\x4C\x4E\x54" +#define SSL3_MD_SERVER_FINISHED_CONST "\x53\x52\x56\x52" + +#define SSL3_VERSION 0x0300 +#define SSL3_VERSION_MAJOR 0x03 +#define SSL3_VERSION_MINOR 0x00 + +#define SSL3_RT_CHANGE_CIPHER_SPEC 20 +#define SSL3_RT_ALERT 21 +#define SSL3_RT_HANDSHAKE 22 +#define SSL3_RT_APPLICATION_DATA 23 + +/* Pseudo content types to indicate additional parameters */ +#define TLS1_RT_CRYPTO 0x1000 +#define TLS1_RT_CRYPTO_PREMASTER (TLS1_RT_CRYPTO | 0x1) +#define TLS1_RT_CRYPTO_CLIENT_RANDOM (TLS1_RT_CRYPTO | 0x2) +#define TLS1_RT_CRYPTO_SERVER_RANDOM (TLS1_RT_CRYPTO | 0x3) +#define TLS1_RT_CRYPTO_MASTER (TLS1_RT_CRYPTO | 0x4) + +#define TLS1_RT_CRYPTO_READ 0x0000 +#define TLS1_RT_CRYPTO_WRITE 0x0100 +#define TLS1_RT_CRYPTO_MAC (TLS1_RT_CRYPTO | 0x5) +#define TLS1_RT_CRYPTO_KEY (TLS1_RT_CRYPTO | 0x6) +#define TLS1_RT_CRYPTO_IV (TLS1_RT_CRYPTO | 0x7) +#define TLS1_RT_CRYPTO_FIXED_IV (TLS1_RT_CRYPTO | 0x8) + +/* Pseudo content type for SSL/TLS header info */ +#define SSL3_RT_HEADER 0x100 + +#define SSL3_AL_WARNING 1 +#define SSL3_AL_FATAL 2 + +#define SSL3_AD_CLOSE_NOTIFY 0 +#define SSL3_AD_UNEXPECTED_MESSAGE 10 /* fatal */ +#define SSL3_AD_BAD_RECORD_MAC 20 /* fatal */ +#define SSL3_AD_DECOMPRESSION_FAILURE 30 /* fatal */ +#define SSL3_AD_HANDSHAKE_FAILURE 40 /* fatal */ +#define SSL3_AD_NO_CERTIFICATE 41 +#define SSL3_AD_BAD_CERTIFICATE 42 +#define SSL3_AD_UNSUPPORTED_CERTIFICATE 43 +#define SSL3_AD_CERTIFICATE_REVOKED 44 +#define SSL3_AD_CERTIFICATE_EXPIRED 45 +#define SSL3_AD_CERTIFICATE_UNKNOWN 46 +#define SSL3_AD_ILLEGAL_PARAMETER 47 /* fatal */ +#define SSL3_AD_INAPPROPRIATE_FALLBACK 86 /* fatal */ + +typedef struct ssl3_record_st { + /* type is the record type. */ + uint8_t type; + /* length is the number of unconsumed bytes of |data|. */ + uint16_t length; + /* off is the number of consumed bytes of |data|. */ + uint16_t off; + /* data is a non-owning pointer to the record contents. The total length of + * the buffer is |off| + |length|. */ + uint8_t *data; + /* epoch, in DTLS, is the epoch number of the record. */ + uint16_t epoch; + /* seq_num, in DTLS, is the sequence number of the record. The top two bytes + * are always zero. + * + * TODO(davidben): This is confusing. They should include the epoch or the + * field should be six bytes. */ + uint8_t seq_num[8]; +} SSL3_RECORD; + +typedef struct ssl3_buffer_st { + uint8_t *buf; /* at least SSL3_RT_MAX_PACKET_SIZE bytes, see + ssl3_setup_buffers() */ + size_t len; /* buffer size */ + int offset; /* where to 'copy from' */ + int left; /* how many bytes left */ +} SSL3_BUFFER; + +#define SSL3_CT_RSA_SIGN 1 +#define SSL3_CT_DSS_SIGN 2 +#define SSL3_CT_RSA_FIXED_DH 3 +#define SSL3_CT_DSS_FIXED_DH 4 +#define SSL3_CT_RSA_EPHEMERAL_DH 5 +#define SSL3_CT_DSS_EPHEMERAL_DH 6 +#define SSL3_CT_FORTEZZA_DMS 20 + + +/* TODO(davidben): This flag can probably be merged into s3->change_cipher_spec + * to something tri-state. (Normal / Expect CCS / Between CCS and Finished). */ +#define SSL3_FLAGS_EXPECT_CCS 0x0080 + +typedef struct ssl3_state_st { + long flags; + + uint8_t read_sequence[8]; + int read_mac_secret_size; + uint8_t read_mac_secret[EVP_MAX_MD_SIZE]; + uint8_t write_sequence[8]; + int write_mac_secret_size; + uint8_t write_mac_secret[EVP_MAX_MD_SIZE]; + + uint8_t server_random[SSL3_RANDOM_SIZE]; + uint8_t client_random[SSL3_RANDOM_SIZE]; + + /* flags for countermeasure against known-IV weakness */ + int need_record_splitting; + + /* The value of 'extra' when the buffers were initialized */ + int init_extra; + + /* have_version is true if the connection's final version is known. Otherwise + * the version has not been negotiated yet. */ + char have_version; + + /* initial_handshake_complete is true if the initial handshake has + * completed. */ + char initial_handshake_complete; + + /* sniff_buffer is used by the server in the initial handshake to read a + * V2ClientHello before the record layer is initialized. */ + BUF_MEM *sniff_buffer; + size_t sniff_buffer_len; + + SSL3_BUFFER rbuf; /* read IO goes into here */ + SSL3_BUFFER wbuf; /* write IO goes into here */ + + SSL3_RECORD rrec; /* each decoded record goes in here */ + + /* storage for Handshake protocol data received but not yet processed by + * ssl3_read_bytes: */ + uint8_t handshake_fragment[4]; + unsigned int handshake_fragment_len; + + /* partial write - check the numbers match */ + unsigned int wnum; /* number of bytes sent so far */ + int wpend_tot; /* number bytes written */ + int wpend_type; + int wpend_ret; /* number of bytes submitted */ + const uint8_t *wpend_buf; + + /* used during startup, digest all incoming/outgoing packets */ + BIO *handshake_buffer; + /* When set of handshake digests is determined, buffer is hashed and freed + * and MD_CTX-es for all required digests are stored in this array */ + EVP_MD_CTX **handshake_dgst; + /* this is set whenerver we see a change_cipher_spec message come in when we + * are not looking for one */ + int change_cipher_spec; + + int warn_alert; + int fatal_alert; + /* we allow one fatal and one warning alert to be outstanding, send close + * alert via the warning alert */ + int alert_dispatch; + uint8_t send_alert[2]; + + int total_renegotiations; + + /* State pertaining to the pending handshake. + * + * TODO(davidben): State is current spread all over the place. Move + * pending handshake state here so it can be managed separately from + * established connection state in case of renegotiations. */ + struct { + /* actually only need to be 16+20 for SSLv3 and 12 for TLS */ + uint8_t finish_md[EVP_MAX_MD_SIZE * 2]; + int finish_md_len; + uint8_t peer_finish_md[EVP_MAX_MD_SIZE * 2]; + int peer_finish_md_len; + + unsigned long message_size; + int message_type; + + /* used to hold the new cipher we are going to use */ + const SSL_CIPHER *new_cipher; + DH *dh; + + EC_KEY *ecdh; /* holds short lived ECDH key */ + + /* used when SSL_ST_FLUSH_DATA is entered */ + int next_state; + + int reuse_message; + + /* Client-only: cert_req determines if a client certificate is to be sent. + * This is 0 if no client Certificate message is to be sent, 1 if there is + * a client certificate, and 2 to send an empty client Certificate + * message. */ + int cert_req; + + /* Client-only: ca_names contains the list of CAs received in a + * CertificateRequest message. */ + STACK_OF(X509_NAME) *ca_names; + + /* Client-only: certificate_types contains the set of certificate types + * received in a CertificateRequest message. */ + uint8_t *certificate_types; + size_t num_certificate_types; + + int key_block_length; + uint8_t *key_block; + + const EVP_AEAD *new_aead; + uint8_t new_mac_secret_len; + uint8_t new_fixed_iv_len; + uint8_t new_variable_iv_len; + + /* Server-only: cert_request is true if a client certificate was + * requested. */ + int cert_request; + + /* certificate_status_expected is true if OCSP stapling was negotiated and + * the server is expected to send a CertificateStatus message. */ + char certificate_status_expected; + + /* peer_ecpointformatlist contains the EC point formats advertised by the + * peer. */ + uint8_t *peer_ecpointformatlist; + size_t peer_ecpointformatlist_length; + + /* Server-only: peer_ellipticcurvelist contains the EC curve IDs advertised + * by the peer. This is only set on the server's end. The server does not + * advertise this extension to the client. */ + uint16_t *peer_ellipticcurvelist; + size_t peer_ellipticcurvelist_length; + + /* extended_master_secret indicates whether the extended master secret + * computation is used in this handshake. Note that this is different from + * whether it was used for the current session. If this is a resumption + * handshake then EMS might be negotiated in the client and server hello + * messages, but it doesn't matter if the session that's being resumed + * didn't use it to create the master secret initially. */ + char extended_master_secret; + + /* Client-only: peer_psk_identity_hint is the psk_identity_hint sent by the + * server when using a PSK key exchange. */ + char *peer_psk_identity_hint; + + /* new_mac_secret_size is unused and exists only until wpa_supplicant can + * be updated. It is only needed for EAP-FAST, which we don't support. */ + uint8_t new_mac_secret_size; + + /* Client-only: in_false_start is one if there is a pending handshake in + * False Start. The client may write data at this point. */ + char in_false_start; + } tmp; + + /* Connection binding to prevent renegotiation attacks */ + uint8_t previous_client_finished[EVP_MAX_MD_SIZE]; + uint8_t previous_client_finished_len; + uint8_t previous_server_finished[EVP_MAX_MD_SIZE]; + uint8_t previous_server_finished_len; + int send_connection_binding; /* TODOEKR */ + + /* Set if we saw the Next Protocol Negotiation extension from our peer. */ + int next_proto_neg_seen; + + /* ALPN information + * (we are in the process of transitioning from NPN to ALPN.) */ + + /* In a server these point to the selected ALPN protocol after the + * ClientHello has been processed. In a client these contain the protocol + * that the server selected once the ServerHello has been processed. */ + uint8_t *alpn_selected; + size_t alpn_selected_len; + + /* In a client, this means that the server supported Channel ID and that a + * Channel ID was sent. In a server it means that we echoed support for + * Channel IDs and that tlsext_channel_id will be valid after the + * handshake. */ + char tlsext_channel_id_valid; + /* tlsext_channel_id_new means that the updated Channel ID extension was + * negotiated. This is a temporary hack in the code to support both forms of + * Channel ID extension while we transition to the new format, which fixed a + * security issue. */ + char tlsext_channel_id_new; + /* For a server: + * If |tlsext_channel_id_valid| is true, then this contains the + * verified Channel ID from the client: a P256 point, (x,y), where + * each are big-endian values. */ + uint8_t tlsext_channel_id[64]; +} SSL3_STATE; + +/* SSLv3 */ +/* client */ +/* extra state */ +#define SSL3_ST_CW_FLUSH (0x100 | SSL_ST_CONNECT) +#define SSL3_ST_FALSE_START (0x101 | SSL_ST_CONNECT) +/* write to server */ +#define SSL3_ST_CW_CLNT_HELLO_A (0x110 | SSL_ST_CONNECT) +#define SSL3_ST_CW_CLNT_HELLO_B (0x111 | SSL_ST_CONNECT) +/* read from server */ +#define SSL3_ST_CR_SRVR_HELLO_A (0x120 | SSL_ST_CONNECT) +#define SSL3_ST_CR_SRVR_HELLO_B (0x121 | SSL_ST_CONNECT) +#define DTLS1_ST_CR_HELLO_VERIFY_REQUEST_A (0x126 | SSL_ST_CONNECT) +#define DTLS1_ST_CR_HELLO_VERIFY_REQUEST_B (0x127 | SSL_ST_CONNECT) +#define SSL3_ST_CR_CERT_A (0x130 | SSL_ST_CONNECT) +#define SSL3_ST_CR_CERT_B (0x131 | SSL_ST_CONNECT) +#define SSL3_ST_CR_KEY_EXCH_A (0x140 | SSL_ST_CONNECT) +#define SSL3_ST_CR_KEY_EXCH_B (0x141 | SSL_ST_CONNECT) +#define SSL3_ST_CR_CERT_REQ_A (0x150 | SSL_ST_CONNECT) +#define SSL3_ST_CR_CERT_REQ_B (0x151 | SSL_ST_CONNECT) +#define SSL3_ST_CR_SRVR_DONE_A (0x160 | SSL_ST_CONNECT) +#define SSL3_ST_CR_SRVR_DONE_B (0x161 | SSL_ST_CONNECT) +/* write to server */ +#define SSL3_ST_CW_CERT_A (0x170 | SSL_ST_CONNECT) +#define SSL3_ST_CW_CERT_B (0x171 | SSL_ST_CONNECT) +#define SSL3_ST_CW_CERT_C (0x172 | SSL_ST_CONNECT) +#define SSL3_ST_CW_CERT_D (0x173 | SSL_ST_CONNECT) +#define SSL3_ST_CW_KEY_EXCH_A (0x180 | SSL_ST_CONNECT) +#define SSL3_ST_CW_KEY_EXCH_B (0x181 | SSL_ST_CONNECT) +#define SSL3_ST_CW_CERT_VRFY_A (0x190 | SSL_ST_CONNECT) +#define SSL3_ST_CW_CERT_VRFY_B (0x191 | SSL_ST_CONNECT) +#define SSL3_ST_CW_CHANGE_A (0x1A0 | SSL_ST_CONNECT) +#define SSL3_ST_CW_CHANGE_B (0x1A1 | SSL_ST_CONNECT) +#define SSL3_ST_CW_NEXT_PROTO_A (0x200 | SSL_ST_CONNECT) +#define SSL3_ST_CW_NEXT_PROTO_B (0x201 | SSL_ST_CONNECT) +#define SSL3_ST_CW_CHANNEL_ID_A (0x220 | SSL_ST_CONNECT) +#define SSL3_ST_CW_CHANNEL_ID_B (0x221 | SSL_ST_CONNECT) +#define SSL3_ST_CW_FINISHED_A (0x1B0 | SSL_ST_CONNECT) +#define SSL3_ST_CW_FINISHED_B (0x1B1 | SSL_ST_CONNECT) +/* read from server */ +#define SSL3_ST_CR_CHANGE (0x1C0 | SSL_ST_CONNECT) +#define SSL3_ST_CR_FINISHED_A (0x1D0 | SSL_ST_CONNECT) +#define SSL3_ST_CR_FINISHED_B (0x1D1 | SSL_ST_CONNECT) +#define SSL3_ST_CR_SESSION_TICKET_A (0x1E0 | SSL_ST_CONNECT) +#define SSL3_ST_CR_SESSION_TICKET_B (0x1E1 | SSL_ST_CONNECT) +#define SSL3_ST_CR_CERT_STATUS_A (0x1F0 | SSL_ST_CONNECT) +#define SSL3_ST_CR_CERT_STATUS_B (0x1F1 | SSL_ST_CONNECT) + +/* server */ +/* extra state */ +#define SSL3_ST_SW_FLUSH (0x100 | SSL_ST_ACCEPT) +/* read from client */ +#define SSL3_ST_SR_INITIAL_BYTES (0x240 | SSL_ST_ACCEPT) +#define SSL3_ST_SR_V2_CLIENT_HELLO (0x241 | SSL_ST_ACCEPT) +/* Do not change the number values, they do matter */ +#define SSL3_ST_SR_CLNT_HELLO_A (0x110 | SSL_ST_ACCEPT) +#define SSL3_ST_SR_CLNT_HELLO_B (0x111 | SSL_ST_ACCEPT) +#define SSL3_ST_SR_CLNT_HELLO_C (0x112 | SSL_ST_ACCEPT) +#define SSL3_ST_SR_CLNT_HELLO_D (0x115 | SSL_ST_ACCEPT) +/* write to client */ +#define SSL3_ST_SW_HELLO_REQ_A (0x120 | SSL_ST_ACCEPT) +#define SSL3_ST_SW_HELLO_REQ_B (0x121 | SSL_ST_ACCEPT) +#define SSL3_ST_SW_HELLO_REQ_C (0x122 | SSL_ST_ACCEPT) +#define SSL3_ST_SW_SRVR_HELLO_A (0x130 | SSL_ST_ACCEPT) +#define SSL3_ST_SW_SRVR_HELLO_B (0x131 | SSL_ST_ACCEPT) +#define SSL3_ST_SW_CERT_A (0x140 | SSL_ST_ACCEPT) +#define SSL3_ST_SW_CERT_B (0x141 | SSL_ST_ACCEPT) +#define SSL3_ST_SW_KEY_EXCH_A (0x150 | SSL_ST_ACCEPT) +#define SSL3_ST_SW_KEY_EXCH_B (0x151 | SSL_ST_ACCEPT) +#define SSL3_ST_SW_CERT_REQ_A (0x160 | SSL_ST_ACCEPT) +#define SSL3_ST_SW_CERT_REQ_B (0x161 | SSL_ST_ACCEPT) +#define SSL3_ST_SW_SRVR_DONE_A (0x170 | SSL_ST_ACCEPT) +#define SSL3_ST_SW_SRVR_DONE_B (0x171 | SSL_ST_ACCEPT) +/* read from client */ +#define SSL3_ST_SR_CERT_A (0x180 | SSL_ST_ACCEPT) +#define SSL3_ST_SR_CERT_B (0x181 | SSL_ST_ACCEPT) +#define SSL3_ST_SR_KEY_EXCH_A (0x190 | SSL_ST_ACCEPT) +#define SSL3_ST_SR_KEY_EXCH_B (0x191 | SSL_ST_ACCEPT) +#define SSL3_ST_SR_CERT_VRFY_A (0x1A0 | SSL_ST_ACCEPT) +#define SSL3_ST_SR_CERT_VRFY_B (0x1A1 | SSL_ST_ACCEPT) +#define SSL3_ST_SR_CHANGE (0x1B0 | SSL_ST_ACCEPT) +#define SSL3_ST_SR_NEXT_PROTO_A (0x210 | SSL_ST_ACCEPT) +#define SSL3_ST_SR_NEXT_PROTO_B (0x211 | SSL_ST_ACCEPT) +#define SSL3_ST_SR_CHANNEL_ID_A (0x230 | SSL_ST_ACCEPT) +#define SSL3_ST_SR_CHANNEL_ID_B (0x231 | SSL_ST_ACCEPT) +#define SSL3_ST_SR_FINISHED_A (0x1C0 | SSL_ST_ACCEPT) +#define SSL3_ST_SR_FINISHED_B (0x1C1 | SSL_ST_ACCEPT) + +/* write to client */ +#define SSL3_ST_SW_CHANGE_A (0x1D0 | SSL_ST_ACCEPT) +#define SSL3_ST_SW_CHANGE_B (0x1D1 | SSL_ST_ACCEPT) +#define SSL3_ST_SW_FINISHED_A (0x1E0 | SSL_ST_ACCEPT) +#define SSL3_ST_SW_FINISHED_B (0x1E1 | SSL_ST_ACCEPT) +#define SSL3_ST_SW_SESSION_TICKET_A (0x1F0 | SSL_ST_ACCEPT) +#define SSL3_ST_SW_SESSION_TICKET_B (0x1F1 | SSL_ST_ACCEPT) +#define SSL3_ST_SW_CERT_STATUS_A (0x200 | SSL_ST_ACCEPT) +#define SSL3_ST_SW_CERT_STATUS_B (0x201 | SSL_ST_ACCEPT) +#define SSL3_ST_SW_SUPPLEMENTAL_DATA_A (0x220 | SSL_ST_ACCEPT) +#define SSL3_ST_SW_SUPPLEMENTAL_DATA_B (0x221 | SSL_ST_ACCEPT) + +#define SSL3_MT_HELLO_REQUEST 0 +#define SSL3_MT_CLIENT_HELLO 1 +#define SSL3_MT_SERVER_HELLO 2 +#define SSL3_MT_NEWSESSION_TICKET 4 +#define SSL3_MT_CERTIFICATE 11 +#define SSL3_MT_SERVER_KEY_EXCHANGE 12 +#define SSL3_MT_CERTIFICATE_REQUEST 13 +#define SSL3_MT_SERVER_DONE 14 +#define SSL3_MT_CERTIFICATE_VERIFY 15 +#define SSL3_MT_CLIENT_KEY_EXCHANGE 16 +#define SSL3_MT_FINISHED 20 +#define SSL3_MT_CERTIFICATE_STATUS 22 +#define SSL3_MT_SUPPLEMENTAL_DATA 23 +#define SSL3_MT_NEXT_PROTO 67 +#define SSL3_MT_ENCRYPTED_EXTENSIONS 203 +#define DTLS1_MT_HELLO_VERIFY_REQUEST 3 + + +#define SSL3_MT_CCS 1 + +/* These are used when changing over to a new cipher */ +#define SSL3_CC_READ 0x01 +#define SSL3_CC_WRITE 0x02 +#define SSL3_CC_CLIENT 0x10 +#define SSL3_CC_SERVER 0x20 +#define SSL3_CHANGE_CIPHER_CLIENT_WRITE (SSL3_CC_CLIENT | SSL3_CC_WRITE) +#define SSL3_CHANGE_CIPHER_SERVER_READ (SSL3_CC_SERVER | SSL3_CC_READ) +#define SSL3_CHANGE_CIPHER_CLIENT_READ (SSL3_CC_CLIENT | SSL3_CC_READ) +#define SSL3_CHANGE_CIPHER_SERVER_WRITE (SSL3_CC_SERVER | SSL3_CC_WRITE) + + +#ifdef __cplusplus +} +#endif +#endif diff --git a/phonelibs/boringssl/include/openssl/stack.h b/phonelibs/boringssl/include/openssl/stack.h new file mode 100644 index 00000000000000..350fa145781ea4 --- /dev/null +++ b/phonelibs/boringssl/include/openssl/stack.h @@ -0,0 +1,301 @@ +/* Copyright (C) 1995-1998 Eric Young (eay@cryptsoft.com) + * All rights reserved. + * + * This package is an SSL implementation written + * by Eric Young (eay@cryptsoft.com). + * The implementation was written so as to conform with Netscapes SSL. + * + * This library is free for commercial and non-commercial use as long as + * the following conditions are aheared to. The following conditions + * apply to all code found in this distribution, be it the RC4, RSA, + * lhash, DES, etc., code; not just the SSL code. The SSL documentation + * included with this distribution is covered by the same copyright terms + * except that the holder is Tim Hudson (tjh@cryptsoft.com). + * + * Copyright remains Eric Young's, and as such any Copyright notices in + * the code are not to be removed. + * If this package is used in a product, Eric Young should be given attribution + * as the author of the parts of the library used. + * This can be in the form of a textual message at program startup or + * in documentation (online or textual) provided with the package. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must 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. All advertising materials mentioning features or use of this software + * must display the following acknowledgement: + * "This product includes cryptographic software written by + * Eric Young (eay@cryptsoft.com)" + * The word 'cryptographic' can be left out if the rouines from the library + * being used are not cryptographic related :-). + * 4. If you include any Windows specific code (or a derivative thereof) from + * the apps directory (application code) you must include an acknowledgement: + * "This product includes software written by Tim Hudson (tjh@cryptsoft.com)" + * + * THIS SOFTWARE IS PROVIDED BY ERIC YOUNG ``AS IS'' AND + * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHOR OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (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 licence and distribution terms for any publically available version or + * derivative of this code cannot be changed. i.e. this code cannot simply be + * copied and put under another distribution licence + * [including the GNU Public Licence.] */ + +#ifndef OPENSSL_HEADER_STACK_H +#define OPENSSL_HEADER_STACK_H + +#include + +#include + +#if defined(__cplusplus) +extern "C" { +#endif + + +/* A stack, in OpenSSL, is an array of pointers. They are the most commonly + * used collection object. + * + * This file defines macros for type safe use of the stack functions. A stack + * of a specific type of object has type |STACK_OF(type)|. This can be defined + * (once) with |DEFINE_STACK_OF(type)| and declared where needed with + * |DECLARE_STACK_OF(type)|. For example: + * + * struct foo { + * int bar; + * }; + * + * DEFINE_STACK_OF(struct foo); + * + * Although note that the stack will contain /pointers/ to |foo|. + * + * A macro will be defined for each of the sk_* functions below. For + * STACK_OF(foo), the macros would be sk_foo_new, sk_foo_pop etc. */ + + +/* stack_cmp_func is a comparison function that returns a value < 0, 0 or > 0 + * if |*a| is less than, equal to or greater than |*b|, respectively. Note the + * extra indirection - the function is given a pointer to a pointer to the + * element. This differs from the usual qsort/bsearch comparison function. */ +typedef int (*stack_cmp_func)(const void **a, const void **b); + +/* stack_st contains an array of pointers. It is not designed to be used + * directly, rather the wrapper macros should be used. */ +typedef struct stack_st { + /* num contains the number of valid pointers in |data|. */ + size_t num; + void **data; + /* sorted is non-zero if the values pointed to by |data| are in ascending + * order, based on |comp|. */ + size_t sorted; + /* num_alloc contains the number of pointers allocated in the buffer pointed + * to by |data|, which may be larger than |num|. */ + size_t num_alloc; + /* comp is an optional comparison function. */ + stack_cmp_func comp; +} _STACK; + + +#define STACK_OF(type) struct stack_st_##type + +#define DEFINE_STACK_OF(type) \ +STACK_OF(type) {\ + _STACK stack; \ +} + +#define DECLARE_STACK_OF(type) STACK_OF(type); + +/* The make_macros.sh script in this directory parses the following lines and + * generates the stack_macros.h file that contains macros for the following + * types of stacks: + * + * STACK_OF:ACCESS_DESCRIPTION + * STACK_OF:ASN1_ADB_TABLE + * STACK_OF:ASN1_GENERALSTRING + * STACK_OF:ASN1_INTEGER + * STACK_OF:ASN1_OBJECT + * STACK_OF:ASN1_STRING_TABLE + * STACK_OF:ASN1_TYPE + * STACK_OF:ASN1_VALUE + * STACK_OF:BIO + * STACK_OF:BY_DIR_ENTRY + * STACK_OF:BY_DIR_HASH + * STACK_OF:CONF_VALUE + * STACK_OF:CRYPTO_EX_DATA_FUNCS + * STACK_OF:DIST_POINT + * STACK_OF:GENERAL_NAME + * STACK_OF:GENERAL_NAMES + * STACK_OF:GENERAL_SUBTREE + * STACK_OF:MIME_HEADER + * STACK_OF:PKCS7_SIGNER_INFO + * STACK_OF:PKCS7_RECIP_INFO + * STACK_OF:POLICYINFO + * STACK_OF:POLICYQUALINFO + * STACK_OF:POLICY_MAPPING + * STACK_OF:SSL_COMP + * STACK_OF:STACK_OF_X509_NAME_ENTRY + * STACK_OF:SXNETID + * STACK_OF:X509 + * STACK_OF:X509V3_EXT_METHOD + * STACK_OF:X509_ALGOR + * STACK_OF:X509_ATTRIBUTE + * STACK_OF:X509_CRL + * STACK_OF:X509_EXTENSION + * STACK_OF:X509_INFO + * STACK_OF:X509_LOOKUP + * STACK_OF:X509_NAME + * STACK_OF:X509_NAME_ENTRY + * STACK_OF:X509_OBJECT + * STACK_OF:X509_POLICY_DATA + * STACK_OF:X509_POLICY_NODE + * STACK_OF:X509_PURPOSE + * STACK_OF:X509_REVOKED + * STACK_OF:X509_TRUST + * STACK_OF:X509_VERIFY_PARAM + * STACK_OF:void + * + * Some stacks contain only const structures, so the stack should return const + * pointers to retain type-checking. + * + * CONST_STACK_OF:SRTP_PROTECTION_PROFILE + * CONST_STACK_OF:SSL_CIPHER */ + + +/* Some stacks are special because, although we would like STACK_OF(char *), + * that would actually be a stack of pointers to char*, but we just want to + * point to the string directly. In this case we call them "special" and use + * |DEFINE_SPECIAL_STACK_OF(type)| */ +#define DEFINE_SPECIAL_STACK_OF(type, inner) \ + STACK_OF(type) { _STACK special_stack; }; \ + OPENSSL_COMPILE_ASSERT(sizeof(type) == sizeof(void *), \ + special_stack_of_non_pointer_##type); + +typedef char *OPENSSL_STRING; + +DEFINE_SPECIAL_STACK_OF(OPENSSL_STRING, char) +DEFINE_SPECIAL_STACK_OF(OPENSSL_BLOCK, uint8_t) + +/* The make_macros.sh script in this directory parses the following lines and + * generates the stack_macros.h file that contains macros for the following + * types of stacks: + * + * SPECIAL_STACK_OF:OPENSSL_STRING + * SPECIAL_STACK_OF:OPENSSL_BLOCK */ + +#define IN_STACK_H +#include +#undef IN_STACK_H + + +/* These are the raw stack functions, you shouldn't be using them. Rather you + * should be using the type stack macros implemented above. */ + +/* sk_new creates a new, empty stack with the given comparison function, which + * may be zero. It returns the new stack or NULL on allocation failure. */ +OPENSSL_EXPORT _STACK *sk_new(stack_cmp_func comp); + +/* sk_new_null creates a new, empty stack. It returns the new stack or NULL on + * allocation failure. */ +OPENSSL_EXPORT _STACK *sk_new_null(void); + +/* sk_num returns the number of elements in |s|. */ +OPENSSL_EXPORT size_t sk_num(const _STACK *sk); + +/* sk_zero resets |sk| to the empty state but does nothing to free the + * individual elements themselves. */ +OPENSSL_EXPORT void sk_zero(_STACK *sk); + +/* sk_value returns the |i|th pointer in |sk|, or NULL if |i| is out of + * range. */ +OPENSSL_EXPORT void *sk_value(const _STACK *sk, size_t i); + +/* sk_set sets the |i|th pointer in |sk| to |p| and returns |p|. If |i| is out + * of range, it returns NULL. */ +OPENSSL_EXPORT void *sk_set(_STACK *sk, size_t i, void *p); + +/* sk_free frees the given stack and array of pointers, but does nothing to + * free the individual elements. Also see |sk_pop_free|. */ +OPENSSL_EXPORT void sk_free(_STACK *sk); + +/* sk_pop_free calls |free_func| on each element in the stack and then frees + * the stack itself. */ +OPENSSL_EXPORT void sk_pop_free(_STACK *sk, void (*free_func)(void *)); + +/* sk_insert inserts |p| into the stack at index |where|, moving existing + * elements if needed. It returns the length of the new stack, or zero on + * error. */ +OPENSSL_EXPORT size_t sk_insert(_STACK *sk, void *p, size_t where); + +/* sk_delete removes the pointer at index |where|, moving other elements down + * if needed. It returns the removed pointer, or NULL if |where| is out of + * range. */ +OPENSSL_EXPORT void *sk_delete(_STACK *sk, size_t where); + +/* sk_delete_ptr removes, at most, one instance of |p| from the stack based on + * pointer equality. If an instance of |p| is found then |p| is returned, + * otherwise it returns NULL. */ +OPENSSL_EXPORT void *sk_delete_ptr(_STACK *sk, void *p); + +/* sk_find returns the first value in the stack equal to |p|. If a comparison + * function has been set on the stack, then equality is defined by it and the + * stack will be sorted if need be so that a binary search can be used. + * Otherwise pointer equality is used. If a matching element is found, its + * index is written to |*out_index| (if |out_index| is not NULL) and one is + * returned. Otherwise zero is returned. */ +OPENSSL_EXPORT int sk_find(_STACK *sk, size_t *out_index, void *p); + +/* sk_shift removes and returns the first element in the stack, or returns NULL + * if the stack is empty. */ +OPENSSL_EXPORT void *sk_shift(_STACK *sk); + +/* sk_push appends |p| to the stack and returns the length of the new stack, or + * 0 on allocation failure. */ +OPENSSL_EXPORT size_t sk_push(_STACK *sk, void *p); + +/* sk_pop returns and removes the last element on the stack, or NULL if the + * stack is empty. */ +OPENSSL_EXPORT void *sk_pop(_STACK *sk); + +/* sk_dup performs a shallow copy of a stack and returns the new stack, or NULL + * on error. */ +OPENSSL_EXPORT _STACK *sk_dup(const _STACK *sk); + +/* sk_sort sorts the elements of |sk| into ascending order based on the + * comparison function. The stack maintains a |sorted| flag and sorting an + * already sorted stack is a no-op. */ +OPENSSL_EXPORT void sk_sort(_STACK *sk); + +/* sk_is_sorted returns one if |sk| is known to be sorted and zero + * otherwise. */ +OPENSSL_EXPORT int sk_is_sorted(const _STACK *sk); + +/* sk_set_cmp_func sets the comparison function to be used by |sk| and returns + * the previous one. */ +OPENSSL_EXPORT stack_cmp_func sk_set_cmp_func(_STACK *sk, stack_cmp_func comp); + +/* sk_deep_copy performs a copy of |sk| and of each of the non-NULL elements in + * |sk| by using |copy_func|. If an error occurs, |free_func| is used to free + * any copies already made and NULL is returned. */ +OPENSSL_EXPORT _STACK *sk_deep_copy(const _STACK *sk, + void *(*copy_func)(void *), + void (*free_func)(void *)); + + +#if defined(__cplusplus) +} /* extern C */ +#endif + +#endif /* OPENSSL_HEADER_STACK_H */ diff --git a/phonelibs/boringssl/include/openssl/stack_macros.h b/phonelibs/boringssl/include/openssl/stack_macros.h new file mode 100644 index 00000000000000..dadcf6bec5d818 --- /dev/null +++ b/phonelibs/boringssl/include/openssl/stack_macros.h @@ -0,0 +1,4004 @@ +/* Copyright (c) 2014, Google Inc. + * + * Permission to use, copy, modify, and/or distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY + * SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN ACTION + * OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF OR IN + * CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. */ + +#if !defined(IN_STACK_H) +#error "Don't include this file directly. Include stack.h." +#endif + +/* ACCESS_DESCRIPTION */ +#define sk_ACCESS_DESCRIPTION_new(comp) \ + ((STACK_OF(ACCESS_DESCRIPTION) *)sk_new(CHECKED_CAST( \ + stack_cmp_func, \ + int (*)(const ACCESS_DESCRIPTION **a, const ACCESS_DESCRIPTION **b), \ + comp))) + +#define sk_ACCESS_DESCRIPTION_new_null() \ + ((STACK_OF(ACCESS_DESCRIPTION) *)sk_new_null()) + +#define sk_ACCESS_DESCRIPTION_num(sk) \ + sk_num(CHECKED_CAST(_STACK *, STACK_OF(ACCESS_DESCRIPTION) *, sk)) + +#define sk_ACCESS_DESCRIPTION_zero(sk) \ + sk_zero(CHECKED_CAST(_STACK *, STACK_OF(ACCESS_DESCRIPTION) *, sk)); + +#define sk_ACCESS_DESCRIPTION_value(sk, i) \ + ((ACCESS_DESCRIPTION *)sk_value( \ + CHECKED_CAST(_STACK *, const STACK_OF(ACCESS_DESCRIPTION) *, sk), (i))) + +#define sk_ACCESS_DESCRIPTION_set(sk, i, p) \ + ((ACCESS_DESCRIPTION *)sk_set( \ + CHECKED_CAST(_STACK *, STACK_OF(ACCESS_DESCRIPTION) *, sk), (i), \ + CHECKED_CAST(void *, ACCESS_DESCRIPTION *, p))) + +#define sk_ACCESS_DESCRIPTION_free(sk) \ + sk_free(CHECKED_CAST(_STACK *, STACK_OF(ACCESS_DESCRIPTION) *, sk)) + +#define sk_ACCESS_DESCRIPTION_pop_free(sk, free_func) \ + sk_pop_free(CHECKED_CAST(_STACK *, STACK_OF(ACCESS_DESCRIPTION) *, sk), \ + CHECKED_CAST(void (*)(void *), void (*)(ACCESS_DESCRIPTION *), \ + free_func)) + +#define sk_ACCESS_DESCRIPTION_insert(sk, p, where) \ + sk_insert(CHECKED_CAST(_STACK *, STACK_OF(ACCESS_DESCRIPTION) *, sk), \ + CHECKED_CAST(void *, ACCESS_DESCRIPTION *, p), (where)) + +#define sk_ACCESS_DESCRIPTION_delete(sk, where) \ + ((ACCESS_DESCRIPTION *)sk_delete( \ + CHECKED_CAST(_STACK *, STACK_OF(ACCESS_DESCRIPTION) *, sk), (where))) + +#define sk_ACCESS_DESCRIPTION_delete_ptr(sk, p) \ + ((ACCESS_DESCRIPTION *)sk_delete_ptr( \ + CHECKED_CAST(_STACK *, STACK_OF(ACCESS_DESCRIPTION) *, sk), \ + CHECKED_CAST(void *, ACCESS_DESCRIPTION *, p))) + +#define sk_ACCESS_DESCRIPTION_find(sk, out_index, p) \ + sk_find(CHECKED_CAST(_STACK *, STACK_OF(ACCESS_DESCRIPTION) *, sk), \ + (out_index), CHECKED_CAST(void *, ACCESS_DESCRIPTION *, p)) + +#define sk_ACCESS_DESCRIPTION_shift(sk) \ + ((ACCESS_DESCRIPTION *)sk_shift( \ + CHECKED_CAST(_STACK *, STACK_OF(ACCESS_DESCRIPTION) *, sk))) + +#define sk_ACCESS_DESCRIPTION_push(sk, p) \ + sk_push(CHECKED_CAST(_STACK *, STACK_OF(ACCESS_DESCRIPTION) *, sk), \ + CHECKED_CAST(void *, ACCESS_DESCRIPTION *, p)) + +#define sk_ACCESS_DESCRIPTION_pop(sk) \ + ((ACCESS_DESCRIPTION *)sk_pop( \ + CHECKED_CAST(_STACK *, STACK_OF(ACCESS_DESCRIPTION) *, sk))) + +#define sk_ACCESS_DESCRIPTION_dup(sk) \ + ((STACK_OF(ACCESS_DESCRIPTION) *)sk_dup( \ + CHECKED_CAST(_STACK *, const STACK_OF(ACCESS_DESCRIPTION) *, sk))) + +#define sk_ACCESS_DESCRIPTION_sort(sk) \ + sk_sort(CHECKED_CAST(_STACK *, STACK_OF(ACCESS_DESCRIPTION) *, sk)) + +#define sk_ACCESS_DESCRIPTION_is_sorted(sk) \ + sk_is_sorted(CHECKED_CAST(_STACK *, const STACK_OF(ACCESS_DESCRIPTION) *, sk)) + +#define sk_ACCESS_DESCRIPTION_set_cmp_func(sk, comp) \ + ((int (*)(const ACCESS_DESCRIPTION **a, const ACCESS_DESCRIPTION **b)) \ + sk_set_cmp_func( \ + CHECKED_CAST(_STACK *, STACK_OF(ACCESS_DESCRIPTION) *, sk), \ + CHECKED_CAST(stack_cmp_func, int (*)(const ACCESS_DESCRIPTION **a, \ + const ACCESS_DESCRIPTION **b), \ + comp))) + +#define sk_ACCESS_DESCRIPTION_deep_copy(sk, copy_func, free_func) \ + ((STACK_OF(ACCESS_DESCRIPTION) *)sk_deep_copy( \ + CHECKED_CAST(const _STACK *, const STACK_OF(ACCESS_DESCRIPTION) *, sk), \ + CHECKED_CAST(void *(*)(void *), \ + ACCESS_DESCRIPTION *(*)(ACCESS_DESCRIPTION *), copy_func), \ + CHECKED_CAST(void (*)(void *), void (*)(ACCESS_DESCRIPTION *), \ + free_func))) + +/* ASN1_ADB_TABLE */ +#define sk_ASN1_ADB_TABLE_new(comp) \ + ((STACK_OF(ASN1_ADB_TABLE) *)sk_new(CHECKED_CAST( \ + stack_cmp_func, \ + int (*)(const ASN1_ADB_TABLE **a, const ASN1_ADB_TABLE **b), comp))) + +#define sk_ASN1_ADB_TABLE_new_null() ((STACK_OF(ASN1_ADB_TABLE) *)sk_new_null()) + +#define sk_ASN1_ADB_TABLE_num(sk) \ + sk_num(CHECKED_CAST(_STACK *, STACK_OF(ASN1_ADB_TABLE) *, sk)) + +#define sk_ASN1_ADB_TABLE_zero(sk) \ + sk_zero(CHECKED_CAST(_STACK *, STACK_OF(ASN1_ADB_TABLE) *, sk)); + +#define sk_ASN1_ADB_TABLE_value(sk, i) \ + ((ASN1_ADB_TABLE *)sk_value( \ + CHECKED_CAST(_STACK *, const STACK_OF(ASN1_ADB_TABLE) *, sk), (i))) + +#define sk_ASN1_ADB_TABLE_set(sk, i, p) \ + ((ASN1_ADB_TABLE *)sk_set( \ + CHECKED_CAST(_STACK *, STACK_OF(ASN1_ADB_TABLE) *, sk), (i), \ + CHECKED_CAST(void *, ASN1_ADB_TABLE *, p))) + +#define sk_ASN1_ADB_TABLE_free(sk) \ + sk_free(CHECKED_CAST(_STACK *, STACK_OF(ASN1_ADB_TABLE) *, sk)) + +#define sk_ASN1_ADB_TABLE_pop_free(sk, free_func) \ + sk_pop_free( \ + CHECKED_CAST(_STACK *, STACK_OF(ASN1_ADB_TABLE) *, sk), \ + CHECKED_CAST(void (*)(void *), void (*)(ASN1_ADB_TABLE *), free_func)) + +#define sk_ASN1_ADB_TABLE_insert(sk, p, where) \ + sk_insert(CHECKED_CAST(_STACK *, STACK_OF(ASN1_ADB_TABLE) *, sk), \ + CHECKED_CAST(void *, ASN1_ADB_TABLE *, p), (where)) + +#define sk_ASN1_ADB_TABLE_delete(sk, where) \ + ((ASN1_ADB_TABLE *)sk_delete( \ + CHECKED_CAST(_STACK *, STACK_OF(ASN1_ADB_TABLE) *, sk), (where))) + +#define sk_ASN1_ADB_TABLE_delete_ptr(sk, p) \ + ((ASN1_ADB_TABLE *)sk_delete_ptr( \ + CHECKED_CAST(_STACK *, STACK_OF(ASN1_ADB_TABLE) *, sk), \ + CHECKED_CAST(void *, ASN1_ADB_TABLE *, p))) + +#define sk_ASN1_ADB_TABLE_find(sk, out_index, p) \ + sk_find(CHECKED_CAST(_STACK *, STACK_OF(ASN1_ADB_TABLE) *, sk), (out_index), \ + CHECKED_CAST(void *, ASN1_ADB_TABLE *, p)) + +#define sk_ASN1_ADB_TABLE_shift(sk) \ + ((ASN1_ADB_TABLE *)sk_shift( \ + CHECKED_CAST(_STACK *, STACK_OF(ASN1_ADB_TABLE) *, sk))) + +#define sk_ASN1_ADB_TABLE_push(sk, p) \ + sk_push(CHECKED_CAST(_STACK *, STACK_OF(ASN1_ADB_TABLE) *, sk), \ + CHECKED_CAST(void *, ASN1_ADB_TABLE *, p)) + +#define sk_ASN1_ADB_TABLE_pop(sk) \ + ((ASN1_ADB_TABLE *)sk_pop( \ + CHECKED_CAST(_STACK *, STACK_OF(ASN1_ADB_TABLE) *, sk))) + +#define sk_ASN1_ADB_TABLE_dup(sk) \ + ((STACK_OF(ASN1_ADB_TABLE) *)sk_dup( \ + CHECKED_CAST(_STACK *, const STACK_OF(ASN1_ADB_TABLE) *, sk))) + +#define sk_ASN1_ADB_TABLE_sort(sk) \ + sk_sort(CHECKED_CAST(_STACK *, STACK_OF(ASN1_ADB_TABLE) *, sk)) + +#define sk_ASN1_ADB_TABLE_is_sorted(sk) \ + sk_is_sorted(CHECKED_CAST(_STACK *, const STACK_OF(ASN1_ADB_TABLE) *, sk)) + +#define sk_ASN1_ADB_TABLE_set_cmp_func(sk, comp) \ + ((int (*)(const ASN1_ADB_TABLE **a, const ASN1_ADB_TABLE **b)) \ + sk_set_cmp_func( \ + CHECKED_CAST(_STACK *, STACK_OF(ASN1_ADB_TABLE) *, sk), \ + CHECKED_CAST(stack_cmp_func, int (*)(const ASN1_ADB_TABLE **a, \ + const ASN1_ADB_TABLE **b), \ + comp))) + +#define sk_ASN1_ADB_TABLE_deep_copy(sk, copy_func, free_func) \ + ((STACK_OF(ASN1_ADB_TABLE) *)sk_deep_copy( \ + CHECKED_CAST(const _STACK *, const STACK_OF(ASN1_ADB_TABLE) *, sk), \ + CHECKED_CAST(void *(*)(void *), ASN1_ADB_TABLE *(*)(ASN1_ADB_TABLE *), \ + copy_func), \ + CHECKED_CAST(void (*)(void *), void (*)(ASN1_ADB_TABLE *), free_func))) + +/* ASN1_GENERALSTRING */ +#define sk_ASN1_GENERALSTRING_new(comp) \ + ((STACK_OF(ASN1_GENERALSTRING) *)sk_new(CHECKED_CAST( \ + stack_cmp_func, \ + int (*)(const ASN1_GENERALSTRING **a, const ASN1_GENERALSTRING **b), \ + comp))) + +#define sk_ASN1_GENERALSTRING_new_null() \ + ((STACK_OF(ASN1_GENERALSTRING) *)sk_new_null()) + +#define sk_ASN1_GENERALSTRING_num(sk) \ + sk_num(CHECKED_CAST(_STACK *, STACK_OF(ASN1_GENERALSTRING) *, sk)) + +#define sk_ASN1_GENERALSTRING_zero(sk) \ + sk_zero(CHECKED_CAST(_STACK *, STACK_OF(ASN1_GENERALSTRING) *, sk)); + +#define sk_ASN1_GENERALSTRING_value(sk, i) \ + ((ASN1_GENERALSTRING *)sk_value( \ + CHECKED_CAST(_STACK *, const STACK_OF(ASN1_GENERALSTRING) *, sk), (i))) + +#define sk_ASN1_GENERALSTRING_set(sk, i, p) \ + ((ASN1_GENERALSTRING *)sk_set( \ + CHECKED_CAST(_STACK *, STACK_OF(ASN1_GENERALSTRING) *, sk), (i), \ + CHECKED_CAST(void *, ASN1_GENERALSTRING *, p))) + +#define sk_ASN1_GENERALSTRING_free(sk) \ + sk_free(CHECKED_CAST(_STACK *, STACK_OF(ASN1_GENERALSTRING) *, sk)) + +#define sk_ASN1_GENERALSTRING_pop_free(sk, free_func) \ + sk_pop_free(CHECKED_CAST(_STACK *, STACK_OF(ASN1_GENERALSTRING) *, sk), \ + CHECKED_CAST(void (*)(void *), void (*)(ASN1_GENERALSTRING *), \ + free_func)) + +#define sk_ASN1_GENERALSTRING_insert(sk, p, where) \ + sk_insert(CHECKED_CAST(_STACK *, STACK_OF(ASN1_GENERALSTRING) *, sk), \ + CHECKED_CAST(void *, ASN1_GENERALSTRING *, p), (where)) + +#define sk_ASN1_GENERALSTRING_delete(sk, where) \ + ((ASN1_GENERALSTRING *)sk_delete( \ + CHECKED_CAST(_STACK *, STACK_OF(ASN1_GENERALSTRING) *, sk), (where))) + +#define sk_ASN1_GENERALSTRING_delete_ptr(sk, p) \ + ((ASN1_GENERALSTRING *)sk_delete_ptr( \ + CHECKED_CAST(_STACK *, STACK_OF(ASN1_GENERALSTRING) *, sk), \ + CHECKED_CAST(void *, ASN1_GENERALSTRING *, p))) + +#define sk_ASN1_GENERALSTRING_find(sk, out_index, p) \ + sk_find(CHECKED_CAST(_STACK *, STACK_OF(ASN1_GENERALSTRING) *, sk), \ + (out_index), CHECKED_CAST(void *, ASN1_GENERALSTRING *, p)) + +#define sk_ASN1_GENERALSTRING_shift(sk) \ + ((ASN1_GENERALSTRING *)sk_shift( \ + CHECKED_CAST(_STACK *, STACK_OF(ASN1_GENERALSTRING) *, sk))) + +#define sk_ASN1_GENERALSTRING_push(sk, p) \ + sk_push(CHECKED_CAST(_STACK *, STACK_OF(ASN1_GENERALSTRING) *, sk), \ + CHECKED_CAST(void *, ASN1_GENERALSTRING *, p)) + +#define sk_ASN1_GENERALSTRING_pop(sk) \ + ((ASN1_GENERALSTRING *)sk_pop( \ + CHECKED_CAST(_STACK *, STACK_OF(ASN1_GENERALSTRING) *, sk))) + +#define sk_ASN1_GENERALSTRING_dup(sk) \ + ((STACK_OF(ASN1_GENERALSTRING) *)sk_dup( \ + CHECKED_CAST(_STACK *, const STACK_OF(ASN1_GENERALSTRING) *, sk))) + +#define sk_ASN1_GENERALSTRING_sort(sk) \ + sk_sort(CHECKED_CAST(_STACK *, STACK_OF(ASN1_GENERALSTRING) *, sk)) + +#define sk_ASN1_GENERALSTRING_is_sorted(sk) \ + sk_is_sorted(CHECKED_CAST(_STACK *, const STACK_OF(ASN1_GENERALSTRING) *, sk)) + +#define sk_ASN1_GENERALSTRING_set_cmp_func(sk, comp) \ + ((int (*)(const ASN1_GENERALSTRING **a, const ASN1_GENERALSTRING **b)) \ + sk_set_cmp_func( \ + CHECKED_CAST(_STACK *, STACK_OF(ASN1_GENERALSTRING) *, sk), \ + CHECKED_CAST(stack_cmp_func, int (*)(const ASN1_GENERALSTRING **a, \ + const ASN1_GENERALSTRING **b), \ + comp))) + +#define sk_ASN1_GENERALSTRING_deep_copy(sk, copy_func, free_func) \ + ((STACK_OF(ASN1_GENERALSTRING) *)sk_deep_copy( \ + CHECKED_CAST(const _STACK *, const STACK_OF(ASN1_GENERALSTRING) *, sk), \ + CHECKED_CAST(void *(*)(void *), \ + ASN1_GENERALSTRING *(*)(ASN1_GENERALSTRING *), copy_func), \ + CHECKED_CAST(void (*)(void *), void (*)(ASN1_GENERALSTRING *), \ + free_func))) + +/* ASN1_INTEGER */ +#define sk_ASN1_INTEGER_new(comp) \ + ((STACK_OF(ASN1_INTEGER) *)sk_new(CHECKED_CAST( \ + stack_cmp_func, int (*)(const ASN1_INTEGER **a, const ASN1_INTEGER **b), \ + comp))) + +#define sk_ASN1_INTEGER_new_null() ((STACK_OF(ASN1_INTEGER) *)sk_new_null()) + +#define sk_ASN1_INTEGER_num(sk) \ + sk_num(CHECKED_CAST(_STACK *, STACK_OF(ASN1_INTEGER) *, sk)) + +#define sk_ASN1_INTEGER_zero(sk) \ + sk_zero(CHECKED_CAST(_STACK *, STACK_OF(ASN1_INTEGER) *, sk)); + +#define sk_ASN1_INTEGER_value(sk, i) \ + ((ASN1_INTEGER *)sk_value( \ + CHECKED_CAST(_STACK *, const STACK_OF(ASN1_INTEGER) *, sk), (i))) + +#define sk_ASN1_INTEGER_set(sk, i, p) \ + ((ASN1_INTEGER *)sk_set( \ + CHECKED_CAST(_STACK *, STACK_OF(ASN1_INTEGER) *, sk), (i), \ + CHECKED_CAST(void *, ASN1_INTEGER *, p))) + +#define sk_ASN1_INTEGER_free(sk) \ + sk_free(CHECKED_CAST(_STACK *, STACK_OF(ASN1_INTEGER) *, sk)) + +#define sk_ASN1_INTEGER_pop_free(sk, free_func) \ + sk_pop_free( \ + CHECKED_CAST(_STACK *, STACK_OF(ASN1_INTEGER) *, sk), \ + CHECKED_CAST(void (*)(void *), void (*)(ASN1_INTEGER *), free_func)) + +#define sk_ASN1_INTEGER_insert(sk, p, where) \ + sk_insert(CHECKED_CAST(_STACK *, STACK_OF(ASN1_INTEGER) *, sk), \ + CHECKED_CAST(void *, ASN1_INTEGER *, p), (where)) + +#define sk_ASN1_INTEGER_delete(sk, where) \ + ((ASN1_INTEGER *)sk_delete( \ + CHECKED_CAST(_STACK *, STACK_OF(ASN1_INTEGER) *, sk), (where))) + +#define sk_ASN1_INTEGER_delete_ptr(sk, p) \ + ((ASN1_INTEGER *)sk_delete_ptr( \ + CHECKED_CAST(_STACK *, STACK_OF(ASN1_INTEGER) *, sk), \ + CHECKED_CAST(void *, ASN1_INTEGER *, p))) + +#define sk_ASN1_INTEGER_find(sk, out_index, p) \ + sk_find(CHECKED_CAST(_STACK *, STACK_OF(ASN1_INTEGER) *, sk), (out_index), \ + CHECKED_CAST(void *, ASN1_INTEGER *, p)) + +#define sk_ASN1_INTEGER_shift(sk) \ + ((ASN1_INTEGER *)sk_shift( \ + CHECKED_CAST(_STACK *, STACK_OF(ASN1_INTEGER) *, sk))) + +#define sk_ASN1_INTEGER_push(sk, p) \ + sk_push(CHECKED_CAST(_STACK *, STACK_OF(ASN1_INTEGER) *, sk), \ + CHECKED_CAST(void *, ASN1_INTEGER *, p)) + +#define sk_ASN1_INTEGER_pop(sk) \ + ((ASN1_INTEGER *)sk_pop(CHECKED_CAST(_STACK *, STACK_OF(ASN1_INTEGER) *, sk))) + +#define sk_ASN1_INTEGER_dup(sk) \ + ((STACK_OF(ASN1_INTEGER) *)sk_dup( \ + CHECKED_CAST(_STACK *, const STACK_OF(ASN1_INTEGER) *, sk))) + +#define sk_ASN1_INTEGER_sort(sk) \ + sk_sort(CHECKED_CAST(_STACK *, STACK_OF(ASN1_INTEGER) *, sk)) + +#define sk_ASN1_INTEGER_is_sorted(sk) \ + sk_is_sorted(CHECKED_CAST(_STACK *, const STACK_OF(ASN1_INTEGER) *, sk)) + +#define sk_ASN1_INTEGER_set_cmp_func(sk, comp) \ + ((int (*)(const ASN1_INTEGER **a, const ASN1_INTEGER **b))sk_set_cmp_func( \ + CHECKED_CAST(_STACK *, STACK_OF(ASN1_INTEGER) *, sk), \ + CHECKED_CAST(stack_cmp_func, \ + int (*)(const ASN1_INTEGER **a, const ASN1_INTEGER **b), \ + comp))) + +#define sk_ASN1_INTEGER_deep_copy(sk, copy_func, free_func) \ + ((STACK_OF(ASN1_INTEGER) *)sk_deep_copy( \ + CHECKED_CAST(const _STACK *, const STACK_OF(ASN1_INTEGER) *, sk), \ + CHECKED_CAST(void *(*)(void *), ASN1_INTEGER *(*)(ASN1_INTEGER *), \ + copy_func), \ + CHECKED_CAST(void (*)(void *), void (*)(ASN1_INTEGER *), free_func))) + +/* ASN1_OBJECT */ +#define sk_ASN1_OBJECT_new(comp) \ + ((STACK_OF(ASN1_OBJECT) *)sk_new(CHECKED_CAST( \ + stack_cmp_func, int (*)(const ASN1_OBJECT **a, const ASN1_OBJECT **b), \ + comp))) + +#define sk_ASN1_OBJECT_new_null() ((STACK_OF(ASN1_OBJECT) *)sk_new_null()) + +#define sk_ASN1_OBJECT_num(sk) \ + sk_num(CHECKED_CAST(_STACK *, STACK_OF(ASN1_OBJECT) *, sk)) + +#define sk_ASN1_OBJECT_zero(sk) \ + sk_zero(CHECKED_CAST(_STACK *, STACK_OF(ASN1_OBJECT) *, sk)); + +#define sk_ASN1_OBJECT_value(sk, i) \ + ((ASN1_OBJECT *)sk_value( \ + CHECKED_CAST(_STACK *, const STACK_OF(ASN1_OBJECT) *, sk), (i))) + +#define sk_ASN1_OBJECT_set(sk, i, p) \ + ((ASN1_OBJECT *)sk_set(CHECKED_CAST(_STACK *, STACK_OF(ASN1_OBJECT) *, sk), \ + (i), CHECKED_CAST(void *, ASN1_OBJECT *, p))) + +#define sk_ASN1_OBJECT_free(sk) \ + sk_free(CHECKED_CAST(_STACK *, STACK_OF(ASN1_OBJECT) *, sk)) + +#define sk_ASN1_OBJECT_pop_free(sk, free_func) \ + sk_pop_free( \ + CHECKED_CAST(_STACK *, STACK_OF(ASN1_OBJECT) *, sk), \ + CHECKED_CAST(void (*)(void *), void (*)(ASN1_OBJECT *), free_func)) + +#define sk_ASN1_OBJECT_insert(sk, p, where) \ + sk_insert(CHECKED_CAST(_STACK *, STACK_OF(ASN1_OBJECT) *, sk), \ + CHECKED_CAST(void *, ASN1_OBJECT *, p), (where)) + +#define sk_ASN1_OBJECT_delete(sk, where) \ + ((ASN1_OBJECT *)sk_delete( \ + CHECKED_CAST(_STACK *, STACK_OF(ASN1_OBJECT) *, sk), (where))) + +#define sk_ASN1_OBJECT_delete_ptr(sk, p) \ + ((ASN1_OBJECT *)sk_delete_ptr( \ + CHECKED_CAST(_STACK *, STACK_OF(ASN1_OBJECT) *, sk), \ + CHECKED_CAST(void *, ASN1_OBJECT *, p))) + +#define sk_ASN1_OBJECT_find(sk, out_index, p) \ + sk_find(CHECKED_CAST(_STACK *, STACK_OF(ASN1_OBJECT) *, sk), (out_index), \ + CHECKED_CAST(void *, ASN1_OBJECT *, p)) + +#define sk_ASN1_OBJECT_shift(sk) \ + ((ASN1_OBJECT *)sk_shift(CHECKED_CAST(_STACK *, STACK_OF(ASN1_OBJECT) *, sk))) + +#define sk_ASN1_OBJECT_push(sk, p) \ + sk_push(CHECKED_CAST(_STACK *, STACK_OF(ASN1_OBJECT) *, sk), \ + CHECKED_CAST(void *, ASN1_OBJECT *, p)) + +#define sk_ASN1_OBJECT_pop(sk) \ + ((ASN1_OBJECT *)sk_pop(CHECKED_CAST(_STACK *, STACK_OF(ASN1_OBJECT) *, sk))) + +#define sk_ASN1_OBJECT_dup(sk) \ + ((STACK_OF(ASN1_OBJECT) *)sk_dup( \ + CHECKED_CAST(_STACK *, const STACK_OF(ASN1_OBJECT) *, sk))) + +#define sk_ASN1_OBJECT_sort(sk) \ + sk_sort(CHECKED_CAST(_STACK *, STACK_OF(ASN1_OBJECT) *, sk)) + +#define sk_ASN1_OBJECT_is_sorted(sk) \ + sk_is_sorted(CHECKED_CAST(_STACK *, const STACK_OF(ASN1_OBJECT) *, sk)) + +#define sk_ASN1_OBJECT_set_cmp_func(sk, comp) \ + ((int (*)(const ASN1_OBJECT **a, const ASN1_OBJECT **b))sk_set_cmp_func( \ + CHECKED_CAST(_STACK *, STACK_OF(ASN1_OBJECT) *, sk), \ + CHECKED_CAST(stack_cmp_func, \ + int (*)(const ASN1_OBJECT **a, const ASN1_OBJECT **b), \ + comp))) + +#define sk_ASN1_OBJECT_deep_copy(sk, copy_func, free_func) \ + ((STACK_OF(ASN1_OBJECT) *)sk_deep_copy( \ + CHECKED_CAST(const _STACK *, const STACK_OF(ASN1_OBJECT) *, sk), \ + CHECKED_CAST(void *(*)(void *), ASN1_OBJECT *(*)(ASN1_OBJECT *), \ + copy_func), \ + CHECKED_CAST(void (*)(void *), void (*)(ASN1_OBJECT *), free_func))) + +/* ASN1_STRING_TABLE */ +#define sk_ASN1_STRING_TABLE_new(comp) \ + ((STACK_OF(ASN1_STRING_TABLE) *)sk_new(CHECKED_CAST( \ + stack_cmp_func, \ + int (*)(const ASN1_STRING_TABLE **a, const ASN1_STRING_TABLE **b), \ + comp))) + +#define sk_ASN1_STRING_TABLE_new_null() \ + ((STACK_OF(ASN1_STRING_TABLE) *)sk_new_null()) + +#define sk_ASN1_STRING_TABLE_num(sk) \ + sk_num(CHECKED_CAST(_STACK *, STACK_OF(ASN1_STRING_TABLE) *, sk)) + +#define sk_ASN1_STRING_TABLE_zero(sk) \ + sk_zero(CHECKED_CAST(_STACK *, STACK_OF(ASN1_STRING_TABLE) *, sk)); + +#define sk_ASN1_STRING_TABLE_value(sk, i) \ + ((ASN1_STRING_TABLE *)sk_value( \ + CHECKED_CAST(_STACK *, const STACK_OF(ASN1_STRING_TABLE) *, sk), (i))) + +#define sk_ASN1_STRING_TABLE_set(sk, i, p) \ + ((ASN1_STRING_TABLE *)sk_set( \ + CHECKED_CAST(_STACK *, STACK_OF(ASN1_STRING_TABLE) *, sk), (i), \ + CHECKED_CAST(void *, ASN1_STRING_TABLE *, p))) + +#define sk_ASN1_STRING_TABLE_free(sk) \ + sk_free(CHECKED_CAST(_STACK *, STACK_OF(ASN1_STRING_TABLE) *, sk)) + +#define sk_ASN1_STRING_TABLE_pop_free(sk, free_func) \ + sk_pop_free(CHECKED_CAST(_STACK *, STACK_OF(ASN1_STRING_TABLE) *, sk), \ + CHECKED_CAST(void (*)(void *), void (*)(ASN1_STRING_TABLE *), \ + free_func)) + +#define sk_ASN1_STRING_TABLE_insert(sk, p, where) \ + sk_insert(CHECKED_CAST(_STACK *, STACK_OF(ASN1_STRING_TABLE) *, sk), \ + CHECKED_CAST(void *, ASN1_STRING_TABLE *, p), (where)) + +#define sk_ASN1_STRING_TABLE_delete(sk, where) \ + ((ASN1_STRING_TABLE *)sk_delete( \ + CHECKED_CAST(_STACK *, STACK_OF(ASN1_STRING_TABLE) *, sk), (where))) + +#define sk_ASN1_STRING_TABLE_delete_ptr(sk, p) \ + ((ASN1_STRING_TABLE *)sk_delete_ptr( \ + CHECKED_CAST(_STACK *, STACK_OF(ASN1_STRING_TABLE) *, sk), \ + CHECKED_CAST(void *, ASN1_STRING_TABLE *, p))) + +#define sk_ASN1_STRING_TABLE_find(sk, out_index, p) \ + sk_find(CHECKED_CAST(_STACK *, STACK_OF(ASN1_STRING_TABLE) *, sk), \ + (out_index), CHECKED_CAST(void *, ASN1_STRING_TABLE *, p)) + +#define sk_ASN1_STRING_TABLE_shift(sk) \ + ((ASN1_STRING_TABLE *)sk_shift( \ + CHECKED_CAST(_STACK *, STACK_OF(ASN1_STRING_TABLE) *, sk))) + +#define sk_ASN1_STRING_TABLE_push(sk, p) \ + sk_push(CHECKED_CAST(_STACK *, STACK_OF(ASN1_STRING_TABLE) *, sk), \ + CHECKED_CAST(void *, ASN1_STRING_TABLE *, p)) + +#define sk_ASN1_STRING_TABLE_pop(sk) \ + ((ASN1_STRING_TABLE *)sk_pop( \ + CHECKED_CAST(_STACK *, STACK_OF(ASN1_STRING_TABLE) *, sk))) + +#define sk_ASN1_STRING_TABLE_dup(sk) \ + ((STACK_OF(ASN1_STRING_TABLE) *)sk_dup( \ + CHECKED_CAST(_STACK *, const STACK_OF(ASN1_STRING_TABLE) *, sk))) + +#define sk_ASN1_STRING_TABLE_sort(sk) \ + sk_sort(CHECKED_CAST(_STACK *, STACK_OF(ASN1_STRING_TABLE) *, sk)) + +#define sk_ASN1_STRING_TABLE_is_sorted(sk) \ + sk_is_sorted(CHECKED_CAST(_STACK *, const STACK_OF(ASN1_STRING_TABLE) *, sk)) + +#define sk_ASN1_STRING_TABLE_set_cmp_func(sk, comp) \ + ((int (*)(const ASN1_STRING_TABLE **a, const ASN1_STRING_TABLE **b)) \ + sk_set_cmp_func( \ + CHECKED_CAST(_STACK *, STACK_OF(ASN1_STRING_TABLE) *, sk), \ + CHECKED_CAST(stack_cmp_func, int (*)(const ASN1_STRING_TABLE **a, \ + const ASN1_STRING_TABLE **b), \ + comp))) + +#define sk_ASN1_STRING_TABLE_deep_copy(sk, copy_func, free_func) \ + ((STACK_OF(ASN1_STRING_TABLE) *)sk_deep_copy( \ + CHECKED_CAST(const _STACK *, const STACK_OF(ASN1_STRING_TABLE) *, sk), \ + CHECKED_CAST(void *(*)(void *), \ + ASN1_STRING_TABLE *(*)(ASN1_STRING_TABLE *), copy_func), \ + CHECKED_CAST(void (*)(void *), void (*)(ASN1_STRING_TABLE *), \ + free_func))) + +/* ASN1_TYPE */ +#define sk_ASN1_TYPE_new(comp) \ + ((STACK_OF(ASN1_TYPE) *)sk_new( \ + CHECKED_CAST(stack_cmp_func, \ + int (*)(const ASN1_TYPE **a, const ASN1_TYPE **b), comp))) + +#define sk_ASN1_TYPE_new_null() ((STACK_OF(ASN1_TYPE) *)sk_new_null()) + +#define sk_ASN1_TYPE_num(sk) \ + sk_num(CHECKED_CAST(_STACK *, STACK_OF(ASN1_TYPE) *, sk)) + +#define sk_ASN1_TYPE_zero(sk) \ + sk_zero(CHECKED_CAST(_STACK *, STACK_OF(ASN1_TYPE) *, sk)); + +#define sk_ASN1_TYPE_value(sk, i) \ + ((ASN1_TYPE *)sk_value( \ + CHECKED_CAST(_STACK *, const STACK_OF(ASN1_TYPE) *, sk), (i))) + +#define sk_ASN1_TYPE_set(sk, i, p) \ + ((ASN1_TYPE *)sk_set(CHECKED_CAST(_STACK *, STACK_OF(ASN1_TYPE) *, sk), (i), \ + CHECKED_CAST(void *, ASN1_TYPE *, p))) + +#define sk_ASN1_TYPE_free(sk) \ + sk_free(CHECKED_CAST(_STACK *, STACK_OF(ASN1_TYPE) *, sk)) + +#define sk_ASN1_TYPE_pop_free(sk, free_func) \ + sk_pop_free( \ + CHECKED_CAST(_STACK *, STACK_OF(ASN1_TYPE) *, sk), \ + CHECKED_CAST(void (*)(void *), void (*)(ASN1_TYPE *), free_func)) + +#define sk_ASN1_TYPE_insert(sk, p, where) \ + sk_insert(CHECKED_CAST(_STACK *, STACK_OF(ASN1_TYPE) *, sk), \ + CHECKED_CAST(void *, ASN1_TYPE *, p), (where)) + +#define sk_ASN1_TYPE_delete(sk, where) \ + ((ASN1_TYPE *)sk_delete(CHECKED_CAST(_STACK *, STACK_OF(ASN1_TYPE) *, sk), \ + (where))) + +#define sk_ASN1_TYPE_delete_ptr(sk, p) \ + ((ASN1_TYPE *)sk_delete_ptr( \ + CHECKED_CAST(_STACK *, STACK_OF(ASN1_TYPE) *, sk), \ + CHECKED_CAST(void *, ASN1_TYPE *, p))) + +#define sk_ASN1_TYPE_find(sk, out_index, p) \ + sk_find(CHECKED_CAST(_STACK *, STACK_OF(ASN1_TYPE) *, sk), (out_index), \ + CHECKED_CAST(void *, ASN1_TYPE *, p)) + +#define sk_ASN1_TYPE_shift(sk) \ + ((ASN1_TYPE *)sk_shift(CHECKED_CAST(_STACK *, STACK_OF(ASN1_TYPE) *, sk))) + +#define sk_ASN1_TYPE_push(sk, p) \ + sk_push(CHECKED_CAST(_STACK *, STACK_OF(ASN1_TYPE) *, sk), \ + CHECKED_CAST(void *, ASN1_TYPE *, p)) + +#define sk_ASN1_TYPE_pop(sk) \ + ((ASN1_TYPE *)sk_pop(CHECKED_CAST(_STACK *, STACK_OF(ASN1_TYPE) *, sk))) + +#define sk_ASN1_TYPE_dup(sk) \ + ((STACK_OF(ASN1_TYPE) *)sk_dup( \ + CHECKED_CAST(_STACK *, const STACK_OF(ASN1_TYPE) *, sk))) + +#define sk_ASN1_TYPE_sort(sk) \ + sk_sort(CHECKED_CAST(_STACK *, STACK_OF(ASN1_TYPE) *, sk)) + +#define sk_ASN1_TYPE_is_sorted(sk) \ + sk_is_sorted(CHECKED_CAST(_STACK *, const STACK_OF(ASN1_TYPE) *, sk)) + +#define sk_ASN1_TYPE_set_cmp_func(sk, comp) \ + ((int (*)(const ASN1_TYPE **a, const ASN1_TYPE **b))sk_set_cmp_func( \ + CHECKED_CAST(_STACK *, STACK_OF(ASN1_TYPE) *, sk), \ + CHECKED_CAST(stack_cmp_func, \ + int (*)(const ASN1_TYPE **a, const ASN1_TYPE **b), comp))) + +#define sk_ASN1_TYPE_deep_copy(sk, copy_func, free_func) \ + ((STACK_OF(ASN1_TYPE) *)sk_deep_copy( \ + CHECKED_CAST(const _STACK *, const STACK_OF(ASN1_TYPE) *, sk), \ + CHECKED_CAST(void *(*)(void *), ASN1_TYPE *(*)(ASN1_TYPE *), copy_func), \ + CHECKED_CAST(void (*)(void *), void (*)(ASN1_TYPE *), free_func))) + +/* ASN1_VALUE */ +#define sk_ASN1_VALUE_new(comp) \ + ((STACK_OF(ASN1_VALUE) *)sk_new(CHECKED_CAST( \ + stack_cmp_func, int (*)(const ASN1_VALUE **a, const ASN1_VALUE **b), \ + comp))) + +#define sk_ASN1_VALUE_new_null() ((STACK_OF(ASN1_VALUE) *)sk_new_null()) + +#define sk_ASN1_VALUE_num(sk) \ + sk_num(CHECKED_CAST(_STACK *, STACK_OF(ASN1_VALUE) *, sk)) + +#define sk_ASN1_VALUE_zero(sk) \ + sk_zero(CHECKED_CAST(_STACK *, STACK_OF(ASN1_VALUE) *, sk)); + +#define sk_ASN1_VALUE_value(sk, i) \ + ((ASN1_VALUE *)sk_value( \ + CHECKED_CAST(_STACK *, const STACK_OF(ASN1_VALUE) *, sk), (i))) + +#define sk_ASN1_VALUE_set(sk, i, p) \ + ((ASN1_VALUE *)sk_set(CHECKED_CAST(_STACK *, STACK_OF(ASN1_VALUE) *, sk), \ + (i), CHECKED_CAST(void *, ASN1_VALUE *, p))) + +#define sk_ASN1_VALUE_free(sk) \ + sk_free(CHECKED_CAST(_STACK *, STACK_OF(ASN1_VALUE) *, sk)) + +#define sk_ASN1_VALUE_pop_free(sk, free_func) \ + sk_pop_free( \ + CHECKED_CAST(_STACK *, STACK_OF(ASN1_VALUE) *, sk), \ + CHECKED_CAST(void (*)(void *), void (*)(ASN1_VALUE *), free_func)) + +#define sk_ASN1_VALUE_insert(sk, p, where) \ + sk_insert(CHECKED_CAST(_STACK *, STACK_OF(ASN1_VALUE) *, sk), \ + CHECKED_CAST(void *, ASN1_VALUE *, p), (where)) + +#define sk_ASN1_VALUE_delete(sk, where) \ + ((ASN1_VALUE *)sk_delete(CHECKED_CAST(_STACK *, STACK_OF(ASN1_VALUE) *, sk), \ + (where))) + +#define sk_ASN1_VALUE_delete_ptr(sk, p) \ + ((ASN1_VALUE *)sk_delete_ptr( \ + CHECKED_CAST(_STACK *, STACK_OF(ASN1_VALUE) *, sk), \ + CHECKED_CAST(void *, ASN1_VALUE *, p))) + +#define sk_ASN1_VALUE_find(sk, out_index, p) \ + sk_find(CHECKED_CAST(_STACK *, STACK_OF(ASN1_VALUE) *, sk), (out_index), \ + CHECKED_CAST(void *, ASN1_VALUE *, p)) + +#define sk_ASN1_VALUE_shift(sk) \ + ((ASN1_VALUE *)sk_shift(CHECKED_CAST(_STACK *, STACK_OF(ASN1_VALUE) *, sk))) + +#define sk_ASN1_VALUE_push(sk, p) \ + sk_push(CHECKED_CAST(_STACK *, STACK_OF(ASN1_VALUE) *, sk), \ + CHECKED_CAST(void *, ASN1_VALUE *, p)) + +#define sk_ASN1_VALUE_pop(sk) \ + ((ASN1_VALUE *)sk_pop(CHECKED_CAST(_STACK *, STACK_OF(ASN1_VALUE) *, sk))) + +#define sk_ASN1_VALUE_dup(sk) \ + ((STACK_OF(ASN1_VALUE) *)sk_dup( \ + CHECKED_CAST(_STACK *, const STACK_OF(ASN1_VALUE) *, sk))) + +#define sk_ASN1_VALUE_sort(sk) \ + sk_sort(CHECKED_CAST(_STACK *, STACK_OF(ASN1_VALUE) *, sk)) + +#define sk_ASN1_VALUE_is_sorted(sk) \ + sk_is_sorted(CHECKED_CAST(_STACK *, const STACK_OF(ASN1_VALUE) *, sk)) + +#define sk_ASN1_VALUE_set_cmp_func(sk, comp) \ + ((int (*)(const ASN1_VALUE **a, const ASN1_VALUE **b))sk_set_cmp_func( \ + CHECKED_CAST(_STACK *, STACK_OF(ASN1_VALUE) *, sk), \ + CHECKED_CAST(stack_cmp_func, \ + int (*)(const ASN1_VALUE **a, const ASN1_VALUE **b), \ + comp))) + +#define sk_ASN1_VALUE_deep_copy(sk, copy_func, free_func) \ + ((STACK_OF(ASN1_VALUE) *)sk_deep_copy( \ + CHECKED_CAST(const _STACK *, const STACK_OF(ASN1_VALUE) *, sk), \ + CHECKED_CAST(void *(*)(void *), ASN1_VALUE *(*)(ASN1_VALUE *), \ + copy_func), \ + CHECKED_CAST(void (*)(void *), void (*)(ASN1_VALUE *), free_func))) + +/* BIO */ +#define sk_BIO_new(comp) \ + ((STACK_OF(BIO) *)sk_new(CHECKED_CAST( \ + stack_cmp_func, int (*)(const BIO **a, const BIO **b), comp))) + +#define sk_BIO_new_null() ((STACK_OF(BIO) *)sk_new_null()) + +#define sk_BIO_num(sk) sk_num(CHECKED_CAST(_STACK *, STACK_OF(BIO) *, sk)) + +#define sk_BIO_zero(sk) sk_zero(CHECKED_CAST(_STACK *, STACK_OF(BIO) *, sk)); + +#define sk_BIO_value(sk, i) \ + ((BIO *)sk_value(CHECKED_CAST(_STACK *, const STACK_OF(BIO) *, sk), (i))) + +#define sk_BIO_set(sk, i, p) \ + ((BIO *)sk_set(CHECKED_CAST(_STACK *, STACK_OF(BIO) *, sk), (i), \ + CHECKED_CAST(void *, BIO *, p))) + +#define sk_BIO_free(sk) sk_free(CHECKED_CAST(_STACK *, STACK_OF(BIO) *, sk)) + +#define sk_BIO_pop_free(sk, free_func) \ + sk_pop_free(CHECKED_CAST(_STACK *, STACK_OF(BIO) *, sk), \ + CHECKED_CAST(void (*)(void *), void (*)(BIO *), free_func)) + +#define sk_BIO_insert(sk, p, where) \ + sk_insert(CHECKED_CAST(_STACK *, STACK_OF(BIO) *, sk), \ + CHECKED_CAST(void *, BIO *, p), (where)) + +#define sk_BIO_delete(sk, where) \ + ((BIO *)sk_delete(CHECKED_CAST(_STACK *, STACK_OF(BIO) *, sk), (where))) + +#define sk_BIO_delete_ptr(sk, p) \ + ((BIO *)sk_delete_ptr(CHECKED_CAST(_STACK *, STACK_OF(BIO) *, sk), \ + CHECKED_CAST(void *, BIO *, p))) + +#define sk_BIO_find(sk, out_index, p) \ + sk_find(CHECKED_CAST(_STACK *, STACK_OF(BIO) *, sk), (out_index), \ + CHECKED_CAST(void *, BIO *, p)) + +#define sk_BIO_shift(sk) \ + ((BIO *)sk_shift(CHECKED_CAST(_STACK *, STACK_OF(BIO) *, sk))) + +#define sk_BIO_push(sk, p) \ + sk_push(CHECKED_CAST(_STACK *, STACK_OF(BIO) *, sk), \ + CHECKED_CAST(void *, BIO *, p)) + +#define sk_BIO_pop(sk) \ + ((BIO *)sk_pop(CHECKED_CAST(_STACK *, STACK_OF(BIO) *, sk))) + +#define sk_BIO_dup(sk) \ + ((STACK_OF(BIO) *)sk_dup(CHECKED_CAST(_STACK *, const STACK_OF(BIO) *, sk))) + +#define sk_BIO_sort(sk) sk_sort(CHECKED_CAST(_STACK *, STACK_OF(BIO) *, sk)) + +#define sk_BIO_is_sorted(sk) \ + sk_is_sorted(CHECKED_CAST(_STACK *, const STACK_OF(BIO) *, sk)) + +#define sk_BIO_set_cmp_func(sk, comp) \ + ((int (*)(const BIO **a, const BIO **b))sk_set_cmp_func( \ + CHECKED_CAST(_STACK *, STACK_OF(BIO) *, sk), \ + CHECKED_CAST(stack_cmp_func, int (*)(const BIO **a, const BIO **b), \ + comp))) + +#define sk_BIO_deep_copy(sk, copy_func, free_func) \ + ((STACK_OF(BIO) *)sk_deep_copy( \ + CHECKED_CAST(const _STACK *, const STACK_OF(BIO) *, sk), \ + CHECKED_CAST(void *(*)(void *), BIO *(*)(BIO *), copy_func), \ + CHECKED_CAST(void (*)(void *), void (*)(BIO *), free_func))) + +/* BY_DIR_ENTRY */ +#define sk_BY_DIR_ENTRY_new(comp) \ + ((STACK_OF(BY_DIR_ENTRY) *)sk_new(CHECKED_CAST( \ + stack_cmp_func, int (*)(const BY_DIR_ENTRY **a, const BY_DIR_ENTRY **b), \ + comp))) + +#define sk_BY_DIR_ENTRY_new_null() ((STACK_OF(BY_DIR_ENTRY) *)sk_new_null()) + +#define sk_BY_DIR_ENTRY_num(sk) \ + sk_num(CHECKED_CAST(_STACK *, STACK_OF(BY_DIR_ENTRY) *, sk)) + +#define sk_BY_DIR_ENTRY_zero(sk) \ + sk_zero(CHECKED_CAST(_STACK *, STACK_OF(BY_DIR_ENTRY) *, sk)); + +#define sk_BY_DIR_ENTRY_value(sk, i) \ + ((BY_DIR_ENTRY *)sk_value( \ + CHECKED_CAST(_STACK *, const STACK_OF(BY_DIR_ENTRY) *, sk), (i))) + +#define sk_BY_DIR_ENTRY_set(sk, i, p) \ + ((BY_DIR_ENTRY *)sk_set( \ + CHECKED_CAST(_STACK *, STACK_OF(BY_DIR_ENTRY) *, sk), (i), \ + CHECKED_CAST(void *, BY_DIR_ENTRY *, p))) + +#define sk_BY_DIR_ENTRY_free(sk) \ + sk_free(CHECKED_CAST(_STACK *, STACK_OF(BY_DIR_ENTRY) *, sk)) + +#define sk_BY_DIR_ENTRY_pop_free(sk, free_func) \ + sk_pop_free( \ + CHECKED_CAST(_STACK *, STACK_OF(BY_DIR_ENTRY) *, sk), \ + CHECKED_CAST(void (*)(void *), void (*)(BY_DIR_ENTRY *), free_func)) + +#define sk_BY_DIR_ENTRY_insert(sk, p, where) \ + sk_insert(CHECKED_CAST(_STACK *, STACK_OF(BY_DIR_ENTRY) *, sk), \ + CHECKED_CAST(void *, BY_DIR_ENTRY *, p), (where)) + +#define sk_BY_DIR_ENTRY_delete(sk, where) \ + ((BY_DIR_ENTRY *)sk_delete( \ + CHECKED_CAST(_STACK *, STACK_OF(BY_DIR_ENTRY) *, sk), (where))) + +#define sk_BY_DIR_ENTRY_delete_ptr(sk, p) \ + ((BY_DIR_ENTRY *)sk_delete_ptr( \ + CHECKED_CAST(_STACK *, STACK_OF(BY_DIR_ENTRY) *, sk), \ + CHECKED_CAST(void *, BY_DIR_ENTRY *, p))) + +#define sk_BY_DIR_ENTRY_find(sk, out_index, p) \ + sk_find(CHECKED_CAST(_STACK *, STACK_OF(BY_DIR_ENTRY) *, sk), (out_index), \ + CHECKED_CAST(void *, BY_DIR_ENTRY *, p)) + +#define sk_BY_DIR_ENTRY_shift(sk) \ + ((BY_DIR_ENTRY *)sk_shift( \ + CHECKED_CAST(_STACK *, STACK_OF(BY_DIR_ENTRY) *, sk))) + +#define sk_BY_DIR_ENTRY_push(sk, p) \ + sk_push(CHECKED_CAST(_STACK *, STACK_OF(BY_DIR_ENTRY) *, sk), \ + CHECKED_CAST(void *, BY_DIR_ENTRY *, p)) + +#define sk_BY_DIR_ENTRY_pop(sk) \ + ((BY_DIR_ENTRY *)sk_pop(CHECKED_CAST(_STACK *, STACK_OF(BY_DIR_ENTRY) *, sk))) + +#define sk_BY_DIR_ENTRY_dup(sk) \ + ((STACK_OF(BY_DIR_ENTRY) *)sk_dup( \ + CHECKED_CAST(_STACK *, const STACK_OF(BY_DIR_ENTRY) *, sk))) + +#define sk_BY_DIR_ENTRY_sort(sk) \ + sk_sort(CHECKED_CAST(_STACK *, STACK_OF(BY_DIR_ENTRY) *, sk)) + +#define sk_BY_DIR_ENTRY_is_sorted(sk) \ + sk_is_sorted(CHECKED_CAST(_STACK *, const STACK_OF(BY_DIR_ENTRY) *, sk)) + +#define sk_BY_DIR_ENTRY_set_cmp_func(sk, comp) \ + ((int (*)(const BY_DIR_ENTRY **a, const BY_DIR_ENTRY **b))sk_set_cmp_func( \ + CHECKED_CAST(_STACK *, STACK_OF(BY_DIR_ENTRY) *, sk), \ + CHECKED_CAST(stack_cmp_func, \ + int (*)(const BY_DIR_ENTRY **a, const BY_DIR_ENTRY **b), \ + comp))) + +#define sk_BY_DIR_ENTRY_deep_copy(sk, copy_func, free_func) \ + ((STACK_OF(BY_DIR_ENTRY) *)sk_deep_copy( \ + CHECKED_CAST(const _STACK *, const STACK_OF(BY_DIR_ENTRY) *, sk), \ + CHECKED_CAST(void *(*)(void *), BY_DIR_ENTRY *(*)(BY_DIR_ENTRY *), \ + copy_func), \ + CHECKED_CAST(void (*)(void *), void (*)(BY_DIR_ENTRY *), free_func))) + +/* BY_DIR_HASH */ +#define sk_BY_DIR_HASH_new(comp) \ + ((STACK_OF(BY_DIR_HASH) *)sk_new(CHECKED_CAST( \ + stack_cmp_func, int (*)(const BY_DIR_HASH **a, const BY_DIR_HASH **b), \ + comp))) + +#define sk_BY_DIR_HASH_new_null() ((STACK_OF(BY_DIR_HASH) *)sk_new_null()) + +#define sk_BY_DIR_HASH_num(sk) \ + sk_num(CHECKED_CAST(_STACK *, STACK_OF(BY_DIR_HASH) *, sk)) + +#define sk_BY_DIR_HASH_zero(sk) \ + sk_zero(CHECKED_CAST(_STACK *, STACK_OF(BY_DIR_HASH) *, sk)); + +#define sk_BY_DIR_HASH_value(sk, i) \ + ((BY_DIR_HASH *)sk_value( \ + CHECKED_CAST(_STACK *, const STACK_OF(BY_DIR_HASH) *, sk), (i))) + +#define sk_BY_DIR_HASH_set(sk, i, p) \ + ((BY_DIR_HASH *)sk_set(CHECKED_CAST(_STACK *, STACK_OF(BY_DIR_HASH) *, sk), \ + (i), CHECKED_CAST(void *, BY_DIR_HASH *, p))) + +#define sk_BY_DIR_HASH_free(sk) \ + sk_free(CHECKED_CAST(_STACK *, STACK_OF(BY_DIR_HASH) *, sk)) + +#define sk_BY_DIR_HASH_pop_free(sk, free_func) \ + sk_pop_free( \ + CHECKED_CAST(_STACK *, STACK_OF(BY_DIR_HASH) *, sk), \ + CHECKED_CAST(void (*)(void *), void (*)(BY_DIR_HASH *), free_func)) + +#define sk_BY_DIR_HASH_insert(sk, p, where) \ + sk_insert(CHECKED_CAST(_STACK *, STACK_OF(BY_DIR_HASH) *, sk), \ + CHECKED_CAST(void *, BY_DIR_HASH *, p), (where)) + +#define sk_BY_DIR_HASH_delete(sk, where) \ + ((BY_DIR_HASH *)sk_delete( \ + CHECKED_CAST(_STACK *, STACK_OF(BY_DIR_HASH) *, sk), (where))) + +#define sk_BY_DIR_HASH_delete_ptr(sk, p) \ + ((BY_DIR_HASH *)sk_delete_ptr( \ + CHECKED_CAST(_STACK *, STACK_OF(BY_DIR_HASH) *, sk), \ + CHECKED_CAST(void *, BY_DIR_HASH *, p))) + +#define sk_BY_DIR_HASH_find(sk, out_index, p) \ + sk_find(CHECKED_CAST(_STACK *, STACK_OF(BY_DIR_HASH) *, sk), (out_index), \ + CHECKED_CAST(void *, BY_DIR_HASH *, p)) + +#define sk_BY_DIR_HASH_shift(sk) \ + ((BY_DIR_HASH *)sk_shift(CHECKED_CAST(_STACK *, STACK_OF(BY_DIR_HASH) *, sk))) + +#define sk_BY_DIR_HASH_push(sk, p) \ + sk_push(CHECKED_CAST(_STACK *, STACK_OF(BY_DIR_HASH) *, sk), \ + CHECKED_CAST(void *, BY_DIR_HASH *, p)) + +#define sk_BY_DIR_HASH_pop(sk) \ + ((BY_DIR_HASH *)sk_pop(CHECKED_CAST(_STACK *, STACK_OF(BY_DIR_HASH) *, sk))) + +#define sk_BY_DIR_HASH_dup(sk) \ + ((STACK_OF(BY_DIR_HASH) *)sk_dup( \ + CHECKED_CAST(_STACK *, const STACK_OF(BY_DIR_HASH) *, sk))) + +#define sk_BY_DIR_HASH_sort(sk) \ + sk_sort(CHECKED_CAST(_STACK *, STACK_OF(BY_DIR_HASH) *, sk)) + +#define sk_BY_DIR_HASH_is_sorted(sk) \ + sk_is_sorted(CHECKED_CAST(_STACK *, const STACK_OF(BY_DIR_HASH) *, sk)) + +#define sk_BY_DIR_HASH_set_cmp_func(sk, comp) \ + ((int (*)(const BY_DIR_HASH **a, const BY_DIR_HASH **b))sk_set_cmp_func( \ + CHECKED_CAST(_STACK *, STACK_OF(BY_DIR_HASH) *, sk), \ + CHECKED_CAST(stack_cmp_func, \ + int (*)(const BY_DIR_HASH **a, const BY_DIR_HASH **b), \ + comp))) + +#define sk_BY_DIR_HASH_deep_copy(sk, copy_func, free_func) \ + ((STACK_OF(BY_DIR_HASH) *)sk_deep_copy( \ + CHECKED_CAST(const _STACK *, const STACK_OF(BY_DIR_HASH) *, sk), \ + CHECKED_CAST(void *(*)(void *), BY_DIR_HASH *(*)(BY_DIR_HASH *), \ + copy_func), \ + CHECKED_CAST(void (*)(void *), void (*)(BY_DIR_HASH *), free_func))) + +/* CONF_VALUE */ +#define sk_CONF_VALUE_new(comp) \ + ((STACK_OF(CONF_VALUE) *)sk_new(CHECKED_CAST( \ + stack_cmp_func, int (*)(const CONF_VALUE **a, const CONF_VALUE **b), \ + comp))) + +#define sk_CONF_VALUE_new_null() ((STACK_OF(CONF_VALUE) *)sk_new_null()) + +#define sk_CONF_VALUE_num(sk) \ + sk_num(CHECKED_CAST(_STACK *, STACK_OF(CONF_VALUE) *, sk)) + +#define sk_CONF_VALUE_zero(sk) \ + sk_zero(CHECKED_CAST(_STACK *, STACK_OF(CONF_VALUE) *, sk)); + +#define sk_CONF_VALUE_value(sk, i) \ + ((CONF_VALUE *)sk_value( \ + CHECKED_CAST(_STACK *, const STACK_OF(CONF_VALUE) *, sk), (i))) + +#define sk_CONF_VALUE_set(sk, i, p) \ + ((CONF_VALUE *)sk_set(CHECKED_CAST(_STACK *, STACK_OF(CONF_VALUE) *, sk), \ + (i), CHECKED_CAST(void *, CONF_VALUE *, p))) + +#define sk_CONF_VALUE_free(sk) \ + sk_free(CHECKED_CAST(_STACK *, STACK_OF(CONF_VALUE) *, sk)) + +#define sk_CONF_VALUE_pop_free(sk, free_func) \ + sk_pop_free( \ + CHECKED_CAST(_STACK *, STACK_OF(CONF_VALUE) *, sk), \ + CHECKED_CAST(void (*)(void *), void (*)(CONF_VALUE *), free_func)) + +#define sk_CONF_VALUE_insert(sk, p, where) \ + sk_insert(CHECKED_CAST(_STACK *, STACK_OF(CONF_VALUE) *, sk), \ + CHECKED_CAST(void *, CONF_VALUE *, p), (where)) + +#define sk_CONF_VALUE_delete(sk, where) \ + ((CONF_VALUE *)sk_delete(CHECKED_CAST(_STACK *, STACK_OF(CONF_VALUE) *, sk), \ + (where))) + +#define sk_CONF_VALUE_delete_ptr(sk, p) \ + ((CONF_VALUE *)sk_delete_ptr( \ + CHECKED_CAST(_STACK *, STACK_OF(CONF_VALUE) *, sk), \ + CHECKED_CAST(void *, CONF_VALUE *, p))) + +#define sk_CONF_VALUE_find(sk, out_index, p) \ + sk_find(CHECKED_CAST(_STACK *, STACK_OF(CONF_VALUE) *, sk), (out_index), \ + CHECKED_CAST(void *, CONF_VALUE *, p)) + +#define sk_CONF_VALUE_shift(sk) \ + ((CONF_VALUE *)sk_shift(CHECKED_CAST(_STACK *, STACK_OF(CONF_VALUE) *, sk))) + +#define sk_CONF_VALUE_push(sk, p) \ + sk_push(CHECKED_CAST(_STACK *, STACK_OF(CONF_VALUE) *, sk), \ + CHECKED_CAST(void *, CONF_VALUE *, p)) + +#define sk_CONF_VALUE_pop(sk) \ + ((CONF_VALUE *)sk_pop(CHECKED_CAST(_STACK *, STACK_OF(CONF_VALUE) *, sk))) + +#define sk_CONF_VALUE_dup(sk) \ + ((STACK_OF(CONF_VALUE) *)sk_dup( \ + CHECKED_CAST(_STACK *, const STACK_OF(CONF_VALUE) *, sk))) + +#define sk_CONF_VALUE_sort(sk) \ + sk_sort(CHECKED_CAST(_STACK *, STACK_OF(CONF_VALUE) *, sk)) + +#define sk_CONF_VALUE_is_sorted(sk) \ + sk_is_sorted(CHECKED_CAST(_STACK *, const STACK_OF(CONF_VALUE) *, sk)) + +#define sk_CONF_VALUE_set_cmp_func(sk, comp) \ + ((int (*)(const CONF_VALUE **a, const CONF_VALUE **b))sk_set_cmp_func( \ + CHECKED_CAST(_STACK *, STACK_OF(CONF_VALUE) *, sk), \ + CHECKED_CAST(stack_cmp_func, \ + int (*)(const CONF_VALUE **a, const CONF_VALUE **b), \ + comp))) + +#define sk_CONF_VALUE_deep_copy(sk, copy_func, free_func) \ + ((STACK_OF(CONF_VALUE) *)sk_deep_copy( \ + CHECKED_CAST(const _STACK *, const STACK_OF(CONF_VALUE) *, sk), \ + CHECKED_CAST(void *(*)(void *), CONF_VALUE *(*)(CONF_VALUE *), \ + copy_func), \ + CHECKED_CAST(void (*)(void *), void (*)(CONF_VALUE *), free_func))) + +/* CRYPTO_EX_DATA_FUNCS */ +#define sk_CRYPTO_EX_DATA_FUNCS_new(comp) \ + ((STACK_OF(CRYPTO_EX_DATA_FUNCS) *)sk_new(CHECKED_CAST( \ + stack_cmp_func, \ + int (*)(const CRYPTO_EX_DATA_FUNCS **a, const CRYPTO_EX_DATA_FUNCS **b), \ + comp))) + +#define sk_CRYPTO_EX_DATA_FUNCS_new_null() \ + ((STACK_OF(CRYPTO_EX_DATA_FUNCS) *)sk_new_null()) + +#define sk_CRYPTO_EX_DATA_FUNCS_num(sk) \ + sk_num(CHECKED_CAST(_STACK *, STACK_OF(CRYPTO_EX_DATA_FUNCS) *, sk)) + +#define sk_CRYPTO_EX_DATA_FUNCS_zero(sk) \ + sk_zero(CHECKED_CAST(_STACK *, STACK_OF(CRYPTO_EX_DATA_FUNCS) *, sk)); + +#define sk_CRYPTO_EX_DATA_FUNCS_value(sk, i) \ + ((CRYPTO_EX_DATA_FUNCS *)sk_value( \ + CHECKED_CAST(_STACK *, const STACK_OF(CRYPTO_EX_DATA_FUNCS) *, sk), \ + (i))) + +#define sk_CRYPTO_EX_DATA_FUNCS_set(sk, i, p) \ + ((CRYPTO_EX_DATA_FUNCS *)sk_set( \ + CHECKED_CAST(_STACK *, STACK_OF(CRYPTO_EX_DATA_FUNCS) *, sk), (i), \ + CHECKED_CAST(void *, CRYPTO_EX_DATA_FUNCS *, p))) + +#define sk_CRYPTO_EX_DATA_FUNCS_free(sk) \ + sk_free(CHECKED_CAST(_STACK *, STACK_OF(CRYPTO_EX_DATA_FUNCS) *, sk)) + +#define sk_CRYPTO_EX_DATA_FUNCS_pop_free(sk, free_func) \ + sk_pop_free(CHECKED_CAST(_STACK *, STACK_OF(CRYPTO_EX_DATA_FUNCS) *, sk), \ + CHECKED_CAST(void (*)(void *), void (*)(CRYPTO_EX_DATA_FUNCS *), \ + free_func)) + +#define sk_CRYPTO_EX_DATA_FUNCS_insert(sk, p, where) \ + sk_insert(CHECKED_CAST(_STACK *, STACK_OF(CRYPTO_EX_DATA_FUNCS) *, sk), \ + CHECKED_CAST(void *, CRYPTO_EX_DATA_FUNCS *, p), (where)) + +#define sk_CRYPTO_EX_DATA_FUNCS_delete(sk, where) \ + ((CRYPTO_EX_DATA_FUNCS *)sk_delete( \ + CHECKED_CAST(_STACK *, STACK_OF(CRYPTO_EX_DATA_FUNCS) *, sk), (where))) + +#define sk_CRYPTO_EX_DATA_FUNCS_delete_ptr(sk, p) \ + ((CRYPTO_EX_DATA_FUNCS *)sk_delete_ptr( \ + CHECKED_CAST(_STACK *, STACK_OF(CRYPTO_EX_DATA_FUNCS) *, sk), \ + CHECKED_CAST(void *, CRYPTO_EX_DATA_FUNCS *, p))) + +#define sk_CRYPTO_EX_DATA_FUNCS_find(sk, out_index, p) \ + sk_find(CHECKED_CAST(_STACK *, STACK_OF(CRYPTO_EX_DATA_FUNCS) *, sk), \ + (out_index), CHECKED_CAST(void *, CRYPTO_EX_DATA_FUNCS *, p)) + +#define sk_CRYPTO_EX_DATA_FUNCS_shift(sk) \ + ((CRYPTO_EX_DATA_FUNCS *)sk_shift( \ + CHECKED_CAST(_STACK *, STACK_OF(CRYPTO_EX_DATA_FUNCS) *, sk))) + +#define sk_CRYPTO_EX_DATA_FUNCS_push(sk, p) \ + sk_push(CHECKED_CAST(_STACK *, STACK_OF(CRYPTO_EX_DATA_FUNCS) *, sk), \ + CHECKED_CAST(void *, CRYPTO_EX_DATA_FUNCS *, p)) + +#define sk_CRYPTO_EX_DATA_FUNCS_pop(sk) \ + ((CRYPTO_EX_DATA_FUNCS *)sk_pop( \ + CHECKED_CAST(_STACK *, STACK_OF(CRYPTO_EX_DATA_FUNCS) *, sk))) + +#define sk_CRYPTO_EX_DATA_FUNCS_dup(sk) \ + ((STACK_OF(CRYPTO_EX_DATA_FUNCS) *)sk_dup( \ + CHECKED_CAST(_STACK *, const STACK_OF(CRYPTO_EX_DATA_FUNCS) *, sk))) + +#define sk_CRYPTO_EX_DATA_FUNCS_sort(sk) \ + sk_sort(CHECKED_CAST(_STACK *, STACK_OF(CRYPTO_EX_DATA_FUNCS) *, sk)) + +#define sk_CRYPTO_EX_DATA_FUNCS_is_sorted(sk) \ + sk_is_sorted( \ + CHECKED_CAST(_STACK *, const STACK_OF(CRYPTO_EX_DATA_FUNCS) *, sk)) + +#define sk_CRYPTO_EX_DATA_FUNCS_set_cmp_func(sk, comp) \ + ((int (*)(const CRYPTO_EX_DATA_FUNCS **a, const CRYPTO_EX_DATA_FUNCS **b)) \ + sk_set_cmp_func( \ + CHECKED_CAST(_STACK *, STACK_OF(CRYPTO_EX_DATA_FUNCS) *, sk), \ + CHECKED_CAST(stack_cmp_func, \ + int (*)(const CRYPTO_EX_DATA_FUNCS **a, \ + const CRYPTO_EX_DATA_FUNCS **b), \ + comp))) + +#define sk_CRYPTO_EX_DATA_FUNCS_deep_copy(sk, copy_func, free_func) \ + ((STACK_OF(CRYPTO_EX_DATA_FUNCS) *)sk_deep_copy( \ + CHECKED_CAST(const _STACK *, const STACK_OF(CRYPTO_EX_DATA_FUNCS) *, \ + sk), \ + CHECKED_CAST(void *(*)(void *), \ + CRYPTO_EX_DATA_FUNCS *(*)(CRYPTO_EX_DATA_FUNCS *), \ + copy_func), \ + CHECKED_CAST(void (*)(void *), void (*)(CRYPTO_EX_DATA_FUNCS *), \ + free_func))) + +/* DIST_POINT */ +#define sk_DIST_POINT_new(comp) \ + ((STACK_OF(DIST_POINT) *)sk_new(CHECKED_CAST( \ + stack_cmp_func, int (*)(const DIST_POINT **a, const DIST_POINT **b), \ + comp))) + +#define sk_DIST_POINT_new_null() ((STACK_OF(DIST_POINT) *)sk_new_null()) + +#define sk_DIST_POINT_num(sk) \ + sk_num(CHECKED_CAST(_STACK *, STACK_OF(DIST_POINT) *, sk)) + +#define sk_DIST_POINT_zero(sk) \ + sk_zero(CHECKED_CAST(_STACK *, STACK_OF(DIST_POINT) *, sk)); + +#define sk_DIST_POINT_value(sk, i) \ + ((DIST_POINT *)sk_value( \ + CHECKED_CAST(_STACK *, const STACK_OF(DIST_POINT) *, sk), (i))) + +#define sk_DIST_POINT_set(sk, i, p) \ + ((DIST_POINT *)sk_set(CHECKED_CAST(_STACK *, STACK_OF(DIST_POINT) *, sk), \ + (i), CHECKED_CAST(void *, DIST_POINT *, p))) + +#define sk_DIST_POINT_free(sk) \ + sk_free(CHECKED_CAST(_STACK *, STACK_OF(DIST_POINT) *, sk)) + +#define sk_DIST_POINT_pop_free(sk, free_func) \ + sk_pop_free( \ + CHECKED_CAST(_STACK *, STACK_OF(DIST_POINT) *, sk), \ + CHECKED_CAST(void (*)(void *), void (*)(DIST_POINT *), free_func)) + +#define sk_DIST_POINT_insert(sk, p, where) \ + sk_insert(CHECKED_CAST(_STACK *, STACK_OF(DIST_POINT) *, sk), \ + CHECKED_CAST(void *, DIST_POINT *, p), (where)) + +#define sk_DIST_POINT_delete(sk, where) \ + ((DIST_POINT *)sk_delete(CHECKED_CAST(_STACK *, STACK_OF(DIST_POINT) *, sk), \ + (where))) + +#define sk_DIST_POINT_delete_ptr(sk, p) \ + ((DIST_POINT *)sk_delete_ptr( \ + CHECKED_CAST(_STACK *, STACK_OF(DIST_POINT) *, sk), \ + CHECKED_CAST(void *, DIST_POINT *, p))) + +#define sk_DIST_POINT_find(sk, out_index, p) \ + sk_find(CHECKED_CAST(_STACK *, STACK_OF(DIST_POINT) *, sk), (out_index), \ + CHECKED_CAST(void *, DIST_POINT *, p)) + +#define sk_DIST_POINT_shift(sk) \ + ((DIST_POINT *)sk_shift(CHECKED_CAST(_STACK *, STACK_OF(DIST_POINT) *, sk))) + +#define sk_DIST_POINT_push(sk, p) \ + sk_push(CHECKED_CAST(_STACK *, STACK_OF(DIST_POINT) *, sk), \ + CHECKED_CAST(void *, DIST_POINT *, p)) + +#define sk_DIST_POINT_pop(sk) \ + ((DIST_POINT *)sk_pop(CHECKED_CAST(_STACK *, STACK_OF(DIST_POINT) *, sk))) + +#define sk_DIST_POINT_dup(sk) \ + ((STACK_OF(DIST_POINT) *)sk_dup( \ + CHECKED_CAST(_STACK *, const STACK_OF(DIST_POINT) *, sk))) + +#define sk_DIST_POINT_sort(sk) \ + sk_sort(CHECKED_CAST(_STACK *, STACK_OF(DIST_POINT) *, sk)) + +#define sk_DIST_POINT_is_sorted(sk) \ + sk_is_sorted(CHECKED_CAST(_STACK *, const STACK_OF(DIST_POINT) *, sk)) + +#define sk_DIST_POINT_set_cmp_func(sk, comp) \ + ((int (*)(const DIST_POINT **a, const DIST_POINT **b))sk_set_cmp_func( \ + CHECKED_CAST(_STACK *, STACK_OF(DIST_POINT) *, sk), \ + CHECKED_CAST(stack_cmp_func, \ + int (*)(const DIST_POINT **a, const DIST_POINT **b), \ + comp))) + +#define sk_DIST_POINT_deep_copy(sk, copy_func, free_func) \ + ((STACK_OF(DIST_POINT) *)sk_deep_copy( \ + CHECKED_CAST(const _STACK *, const STACK_OF(DIST_POINT) *, sk), \ + CHECKED_CAST(void *(*)(void *), DIST_POINT *(*)(DIST_POINT *), \ + copy_func), \ + CHECKED_CAST(void (*)(void *), void (*)(DIST_POINT *), free_func))) + +/* GENERAL_NAME */ +#define sk_GENERAL_NAME_new(comp) \ + ((STACK_OF(GENERAL_NAME) *)sk_new(CHECKED_CAST( \ + stack_cmp_func, int (*)(const GENERAL_NAME **a, const GENERAL_NAME **b), \ + comp))) + +#define sk_GENERAL_NAME_new_null() ((STACK_OF(GENERAL_NAME) *)sk_new_null()) + +#define sk_GENERAL_NAME_num(sk) \ + sk_num(CHECKED_CAST(_STACK *, STACK_OF(GENERAL_NAME) *, sk)) + +#define sk_GENERAL_NAME_zero(sk) \ + sk_zero(CHECKED_CAST(_STACK *, STACK_OF(GENERAL_NAME) *, sk)); + +#define sk_GENERAL_NAME_value(sk, i) \ + ((GENERAL_NAME *)sk_value( \ + CHECKED_CAST(_STACK *, const STACK_OF(GENERAL_NAME) *, sk), (i))) + +#define sk_GENERAL_NAME_set(sk, i, p) \ + ((GENERAL_NAME *)sk_set( \ + CHECKED_CAST(_STACK *, STACK_OF(GENERAL_NAME) *, sk), (i), \ + CHECKED_CAST(void *, GENERAL_NAME *, p))) + +#define sk_GENERAL_NAME_free(sk) \ + sk_free(CHECKED_CAST(_STACK *, STACK_OF(GENERAL_NAME) *, sk)) + +#define sk_GENERAL_NAME_pop_free(sk, free_func) \ + sk_pop_free( \ + CHECKED_CAST(_STACK *, STACK_OF(GENERAL_NAME) *, sk), \ + CHECKED_CAST(void (*)(void *), void (*)(GENERAL_NAME *), free_func)) + +#define sk_GENERAL_NAME_insert(sk, p, where) \ + sk_insert(CHECKED_CAST(_STACK *, STACK_OF(GENERAL_NAME) *, sk), \ + CHECKED_CAST(void *, GENERAL_NAME *, p), (where)) + +#define sk_GENERAL_NAME_delete(sk, where) \ + ((GENERAL_NAME *)sk_delete( \ + CHECKED_CAST(_STACK *, STACK_OF(GENERAL_NAME) *, sk), (where))) + +#define sk_GENERAL_NAME_delete_ptr(sk, p) \ + ((GENERAL_NAME *)sk_delete_ptr( \ + CHECKED_CAST(_STACK *, STACK_OF(GENERAL_NAME) *, sk), \ + CHECKED_CAST(void *, GENERAL_NAME *, p))) + +#define sk_GENERAL_NAME_find(sk, out_index, p) \ + sk_find(CHECKED_CAST(_STACK *, STACK_OF(GENERAL_NAME) *, sk), (out_index), \ + CHECKED_CAST(void *, GENERAL_NAME *, p)) + +#define sk_GENERAL_NAME_shift(sk) \ + ((GENERAL_NAME *)sk_shift( \ + CHECKED_CAST(_STACK *, STACK_OF(GENERAL_NAME) *, sk))) + +#define sk_GENERAL_NAME_push(sk, p) \ + sk_push(CHECKED_CAST(_STACK *, STACK_OF(GENERAL_NAME) *, sk), \ + CHECKED_CAST(void *, GENERAL_NAME *, p)) + +#define sk_GENERAL_NAME_pop(sk) \ + ((GENERAL_NAME *)sk_pop(CHECKED_CAST(_STACK *, STACK_OF(GENERAL_NAME) *, sk))) + +#define sk_GENERAL_NAME_dup(sk) \ + ((STACK_OF(GENERAL_NAME) *)sk_dup( \ + CHECKED_CAST(_STACK *, const STACK_OF(GENERAL_NAME) *, sk))) + +#define sk_GENERAL_NAME_sort(sk) \ + sk_sort(CHECKED_CAST(_STACK *, STACK_OF(GENERAL_NAME) *, sk)) + +#define sk_GENERAL_NAME_is_sorted(sk) \ + sk_is_sorted(CHECKED_CAST(_STACK *, const STACK_OF(GENERAL_NAME) *, sk)) + +#define sk_GENERAL_NAME_set_cmp_func(sk, comp) \ + ((int (*)(const GENERAL_NAME **a, const GENERAL_NAME **b))sk_set_cmp_func( \ + CHECKED_CAST(_STACK *, STACK_OF(GENERAL_NAME) *, sk), \ + CHECKED_CAST(stack_cmp_func, \ + int (*)(const GENERAL_NAME **a, const GENERAL_NAME **b), \ + comp))) + +#define sk_GENERAL_NAME_deep_copy(sk, copy_func, free_func) \ + ((STACK_OF(GENERAL_NAME) *)sk_deep_copy( \ + CHECKED_CAST(const _STACK *, const STACK_OF(GENERAL_NAME) *, sk), \ + CHECKED_CAST(void *(*)(void *), GENERAL_NAME *(*)(GENERAL_NAME *), \ + copy_func), \ + CHECKED_CAST(void (*)(void *), void (*)(GENERAL_NAME *), free_func))) + +/* GENERAL_NAMES */ +#define sk_GENERAL_NAMES_new(comp) \ + ((STACK_OF(GENERAL_NAMES) *)sk_new(CHECKED_CAST( \ + stack_cmp_func, \ + int (*)(const GENERAL_NAMES **a, const GENERAL_NAMES **b), comp))) + +#define sk_GENERAL_NAMES_new_null() ((STACK_OF(GENERAL_NAMES) *)sk_new_null()) + +#define sk_GENERAL_NAMES_num(sk) \ + sk_num(CHECKED_CAST(_STACK *, STACK_OF(GENERAL_NAMES) *, sk)) + +#define sk_GENERAL_NAMES_zero(sk) \ + sk_zero(CHECKED_CAST(_STACK *, STACK_OF(GENERAL_NAMES) *, sk)); + +#define sk_GENERAL_NAMES_value(sk, i) \ + ((GENERAL_NAMES *)sk_value( \ + CHECKED_CAST(_STACK *, const STACK_OF(GENERAL_NAMES) *, sk), (i))) + +#define sk_GENERAL_NAMES_set(sk, i, p) \ + ((GENERAL_NAMES *)sk_set( \ + CHECKED_CAST(_STACK *, STACK_OF(GENERAL_NAMES) *, sk), (i), \ + CHECKED_CAST(void *, GENERAL_NAMES *, p))) + +#define sk_GENERAL_NAMES_free(sk) \ + sk_free(CHECKED_CAST(_STACK *, STACK_OF(GENERAL_NAMES) *, sk)) + +#define sk_GENERAL_NAMES_pop_free(sk, free_func) \ + sk_pop_free( \ + CHECKED_CAST(_STACK *, STACK_OF(GENERAL_NAMES) *, sk), \ + CHECKED_CAST(void (*)(void *), void (*)(GENERAL_NAMES *), free_func)) + +#define sk_GENERAL_NAMES_insert(sk, p, where) \ + sk_insert(CHECKED_CAST(_STACK *, STACK_OF(GENERAL_NAMES) *, sk), \ + CHECKED_CAST(void *, GENERAL_NAMES *, p), (where)) + +#define sk_GENERAL_NAMES_delete(sk, where) \ + ((GENERAL_NAMES *)sk_delete( \ + CHECKED_CAST(_STACK *, STACK_OF(GENERAL_NAMES) *, sk), (where))) + +#define sk_GENERAL_NAMES_delete_ptr(sk, p) \ + ((GENERAL_NAMES *)sk_delete_ptr( \ + CHECKED_CAST(_STACK *, STACK_OF(GENERAL_NAMES) *, sk), \ + CHECKED_CAST(void *, GENERAL_NAMES *, p))) + +#define sk_GENERAL_NAMES_find(sk, out_index, p) \ + sk_find(CHECKED_CAST(_STACK *, STACK_OF(GENERAL_NAMES) *, sk), (out_index), \ + CHECKED_CAST(void *, GENERAL_NAMES *, p)) + +#define sk_GENERAL_NAMES_shift(sk) \ + ((GENERAL_NAMES *)sk_shift( \ + CHECKED_CAST(_STACK *, STACK_OF(GENERAL_NAMES) *, sk))) + +#define sk_GENERAL_NAMES_push(sk, p) \ + sk_push(CHECKED_CAST(_STACK *, STACK_OF(GENERAL_NAMES) *, sk), \ + CHECKED_CAST(void *, GENERAL_NAMES *, p)) + +#define sk_GENERAL_NAMES_pop(sk) \ + ((GENERAL_NAMES *)sk_pop( \ + CHECKED_CAST(_STACK *, STACK_OF(GENERAL_NAMES) *, sk))) + +#define sk_GENERAL_NAMES_dup(sk) \ + ((STACK_OF(GENERAL_NAMES) *)sk_dup( \ + CHECKED_CAST(_STACK *, const STACK_OF(GENERAL_NAMES) *, sk))) + +#define sk_GENERAL_NAMES_sort(sk) \ + sk_sort(CHECKED_CAST(_STACK *, STACK_OF(GENERAL_NAMES) *, sk)) + +#define sk_GENERAL_NAMES_is_sorted(sk) \ + sk_is_sorted(CHECKED_CAST(_STACK *, const STACK_OF(GENERAL_NAMES) *, sk)) + +#define sk_GENERAL_NAMES_set_cmp_func(sk, comp) \ + ((int (*)(const GENERAL_NAMES **a, const GENERAL_NAMES **b))sk_set_cmp_func( \ + CHECKED_CAST(_STACK *, STACK_OF(GENERAL_NAMES) *, sk), \ + CHECKED_CAST(stack_cmp_func, \ + int (*)(const GENERAL_NAMES **a, const GENERAL_NAMES **b), \ + comp))) + +#define sk_GENERAL_NAMES_deep_copy(sk, copy_func, free_func) \ + ((STACK_OF(GENERAL_NAMES) *)sk_deep_copy( \ + CHECKED_CAST(const _STACK *, const STACK_OF(GENERAL_NAMES) *, sk), \ + CHECKED_CAST(void *(*)(void *), GENERAL_NAMES *(*)(GENERAL_NAMES *), \ + copy_func), \ + CHECKED_CAST(void (*)(void *), void (*)(GENERAL_NAMES *), free_func))) + +/* GENERAL_SUBTREE */ +#define sk_GENERAL_SUBTREE_new(comp) \ + ((STACK_OF(GENERAL_SUBTREE) *)sk_new(CHECKED_CAST( \ + stack_cmp_func, \ + int (*)(const GENERAL_SUBTREE **a, const GENERAL_SUBTREE **b), comp))) + +#define sk_GENERAL_SUBTREE_new_null() \ + ((STACK_OF(GENERAL_SUBTREE) *)sk_new_null()) + +#define sk_GENERAL_SUBTREE_num(sk) \ + sk_num(CHECKED_CAST(_STACK *, STACK_OF(GENERAL_SUBTREE) *, sk)) + +#define sk_GENERAL_SUBTREE_zero(sk) \ + sk_zero(CHECKED_CAST(_STACK *, STACK_OF(GENERAL_SUBTREE) *, sk)); + +#define sk_GENERAL_SUBTREE_value(sk, i) \ + ((GENERAL_SUBTREE *)sk_value( \ + CHECKED_CAST(_STACK *, const STACK_OF(GENERAL_SUBTREE) *, sk), (i))) + +#define sk_GENERAL_SUBTREE_set(sk, i, p) \ + ((GENERAL_SUBTREE *)sk_set( \ + CHECKED_CAST(_STACK *, STACK_OF(GENERAL_SUBTREE) *, sk), (i), \ + CHECKED_CAST(void *, GENERAL_SUBTREE *, p))) + +#define sk_GENERAL_SUBTREE_free(sk) \ + sk_free(CHECKED_CAST(_STACK *, STACK_OF(GENERAL_SUBTREE) *, sk)) + +#define sk_GENERAL_SUBTREE_pop_free(sk, free_func) \ + sk_pop_free( \ + CHECKED_CAST(_STACK *, STACK_OF(GENERAL_SUBTREE) *, sk), \ + CHECKED_CAST(void (*)(void *), void (*)(GENERAL_SUBTREE *), free_func)) + +#define sk_GENERAL_SUBTREE_insert(sk, p, where) \ + sk_insert(CHECKED_CAST(_STACK *, STACK_OF(GENERAL_SUBTREE) *, sk), \ + CHECKED_CAST(void *, GENERAL_SUBTREE *, p), (where)) + +#define sk_GENERAL_SUBTREE_delete(sk, where) \ + ((GENERAL_SUBTREE *)sk_delete( \ + CHECKED_CAST(_STACK *, STACK_OF(GENERAL_SUBTREE) *, sk), (where))) + +#define sk_GENERAL_SUBTREE_delete_ptr(sk, p) \ + ((GENERAL_SUBTREE *)sk_delete_ptr( \ + CHECKED_CAST(_STACK *, STACK_OF(GENERAL_SUBTREE) *, sk), \ + CHECKED_CAST(void *, GENERAL_SUBTREE *, p))) + +#define sk_GENERAL_SUBTREE_find(sk, out_index, p) \ + sk_find(CHECKED_CAST(_STACK *, STACK_OF(GENERAL_SUBTREE) *, sk), \ + (out_index), CHECKED_CAST(void *, GENERAL_SUBTREE *, p)) + +#define sk_GENERAL_SUBTREE_shift(sk) \ + ((GENERAL_SUBTREE *)sk_shift( \ + CHECKED_CAST(_STACK *, STACK_OF(GENERAL_SUBTREE) *, sk))) + +#define sk_GENERAL_SUBTREE_push(sk, p) \ + sk_push(CHECKED_CAST(_STACK *, STACK_OF(GENERAL_SUBTREE) *, sk), \ + CHECKED_CAST(void *, GENERAL_SUBTREE *, p)) + +#define sk_GENERAL_SUBTREE_pop(sk) \ + ((GENERAL_SUBTREE *)sk_pop( \ + CHECKED_CAST(_STACK *, STACK_OF(GENERAL_SUBTREE) *, sk))) + +#define sk_GENERAL_SUBTREE_dup(sk) \ + ((STACK_OF(GENERAL_SUBTREE) *)sk_dup( \ + CHECKED_CAST(_STACK *, const STACK_OF(GENERAL_SUBTREE) *, sk))) + +#define sk_GENERAL_SUBTREE_sort(sk) \ + sk_sort(CHECKED_CAST(_STACK *, STACK_OF(GENERAL_SUBTREE) *, sk)) + +#define sk_GENERAL_SUBTREE_is_sorted(sk) \ + sk_is_sorted(CHECKED_CAST(_STACK *, const STACK_OF(GENERAL_SUBTREE) *, sk)) + +#define sk_GENERAL_SUBTREE_set_cmp_func(sk, comp) \ + ((int (*)(const GENERAL_SUBTREE **a, const GENERAL_SUBTREE **b)) \ + sk_set_cmp_func( \ + CHECKED_CAST(_STACK *, STACK_OF(GENERAL_SUBTREE) *, sk), \ + CHECKED_CAST(stack_cmp_func, int (*)(const GENERAL_SUBTREE **a, \ + const GENERAL_SUBTREE **b), \ + comp))) + +#define sk_GENERAL_SUBTREE_deep_copy(sk, copy_func, free_func) \ + ((STACK_OF(GENERAL_SUBTREE) *)sk_deep_copy( \ + CHECKED_CAST(const _STACK *, const STACK_OF(GENERAL_SUBTREE) *, sk), \ + CHECKED_CAST(void *(*)(void *), GENERAL_SUBTREE *(*)(GENERAL_SUBTREE *), \ + copy_func), \ + CHECKED_CAST(void (*)(void *), void (*)(GENERAL_SUBTREE *), free_func))) + +/* MIME_HEADER */ +#define sk_MIME_HEADER_new(comp) \ + ((STACK_OF(MIME_HEADER) *)sk_new(CHECKED_CAST( \ + stack_cmp_func, int (*)(const MIME_HEADER **a, const MIME_HEADER **b), \ + comp))) + +#define sk_MIME_HEADER_new_null() ((STACK_OF(MIME_HEADER) *)sk_new_null()) + +#define sk_MIME_HEADER_num(sk) \ + sk_num(CHECKED_CAST(_STACK *, STACK_OF(MIME_HEADER) *, sk)) + +#define sk_MIME_HEADER_zero(sk) \ + sk_zero(CHECKED_CAST(_STACK *, STACK_OF(MIME_HEADER) *, sk)); + +#define sk_MIME_HEADER_value(sk, i) \ + ((MIME_HEADER *)sk_value( \ + CHECKED_CAST(_STACK *, const STACK_OF(MIME_HEADER) *, sk), (i))) + +#define sk_MIME_HEADER_set(sk, i, p) \ + ((MIME_HEADER *)sk_set(CHECKED_CAST(_STACK *, STACK_OF(MIME_HEADER) *, sk), \ + (i), CHECKED_CAST(void *, MIME_HEADER *, p))) + +#define sk_MIME_HEADER_free(sk) \ + sk_free(CHECKED_CAST(_STACK *, STACK_OF(MIME_HEADER) *, sk)) + +#define sk_MIME_HEADER_pop_free(sk, free_func) \ + sk_pop_free( \ + CHECKED_CAST(_STACK *, STACK_OF(MIME_HEADER) *, sk), \ + CHECKED_CAST(void (*)(void *), void (*)(MIME_HEADER *), free_func)) + +#define sk_MIME_HEADER_insert(sk, p, where) \ + sk_insert(CHECKED_CAST(_STACK *, STACK_OF(MIME_HEADER) *, sk), \ + CHECKED_CAST(void *, MIME_HEADER *, p), (where)) + +#define sk_MIME_HEADER_delete(sk, where) \ + ((MIME_HEADER *)sk_delete( \ + CHECKED_CAST(_STACK *, STACK_OF(MIME_HEADER) *, sk), (where))) + +#define sk_MIME_HEADER_delete_ptr(sk, p) \ + ((MIME_HEADER *)sk_delete_ptr( \ + CHECKED_CAST(_STACK *, STACK_OF(MIME_HEADER) *, sk), \ + CHECKED_CAST(void *, MIME_HEADER *, p))) + +#define sk_MIME_HEADER_find(sk, out_index, p) \ + sk_find(CHECKED_CAST(_STACK *, STACK_OF(MIME_HEADER) *, sk), (out_index), \ + CHECKED_CAST(void *, MIME_HEADER *, p)) + +#define sk_MIME_HEADER_shift(sk) \ + ((MIME_HEADER *)sk_shift(CHECKED_CAST(_STACK *, STACK_OF(MIME_HEADER) *, sk))) + +#define sk_MIME_HEADER_push(sk, p) \ + sk_push(CHECKED_CAST(_STACK *, STACK_OF(MIME_HEADER) *, sk), \ + CHECKED_CAST(void *, MIME_HEADER *, p)) + +#define sk_MIME_HEADER_pop(sk) \ + ((MIME_HEADER *)sk_pop(CHECKED_CAST(_STACK *, STACK_OF(MIME_HEADER) *, sk))) + +#define sk_MIME_HEADER_dup(sk) \ + ((STACK_OF(MIME_HEADER) *)sk_dup( \ + CHECKED_CAST(_STACK *, const STACK_OF(MIME_HEADER) *, sk))) + +#define sk_MIME_HEADER_sort(sk) \ + sk_sort(CHECKED_CAST(_STACK *, STACK_OF(MIME_HEADER) *, sk)) + +#define sk_MIME_HEADER_is_sorted(sk) \ + sk_is_sorted(CHECKED_CAST(_STACK *, const STACK_OF(MIME_HEADER) *, sk)) + +#define sk_MIME_HEADER_set_cmp_func(sk, comp) \ + ((int (*)(const MIME_HEADER **a, const MIME_HEADER **b))sk_set_cmp_func( \ + CHECKED_CAST(_STACK *, STACK_OF(MIME_HEADER) *, sk), \ + CHECKED_CAST(stack_cmp_func, \ + int (*)(const MIME_HEADER **a, const MIME_HEADER **b), \ + comp))) + +#define sk_MIME_HEADER_deep_copy(sk, copy_func, free_func) \ + ((STACK_OF(MIME_HEADER) *)sk_deep_copy( \ + CHECKED_CAST(const _STACK *, const STACK_OF(MIME_HEADER) *, sk), \ + CHECKED_CAST(void *(*)(void *), MIME_HEADER *(*)(MIME_HEADER *), \ + copy_func), \ + CHECKED_CAST(void (*)(void *), void (*)(MIME_HEADER *), free_func))) + +/* PKCS7_SIGNER_INFO */ +#define sk_PKCS7_SIGNER_INFO_new(comp) \ + ((STACK_OF(PKCS7_SIGNER_INFO) *)sk_new(CHECKED_CAST( \ + stack_cmp_func, \ + int (*)(const PKCS7_SIGNER_INFO **a, const PKCS7_SIGNER_INFO **b), \ + comp))) + +#define sk_PKCS7_SIGNER_INFO_new_null() \ + ((STACK_OF(PKCS7_SIGNER_INFO) *)sk_new_null()) + +#define sk_PKCS7_SIGNER_INFO_num(sk) \ + sk_num(CHECKED_CAST(_STACK *, STACK_OF(PKCS7_SIGNER_INFO) *, sk)) + +#define sk_PKCS7_SIGNER_INFO_zero(sk) \ + sk_zero(CHECKED_CAST(_STACK *, STACK_OF(PKCS7_SIGNER_INFO) *, sk)); + +#define sk_PKCS7_SIGNER_INFO_value(sk, i) \ + ((PKCS7_SIGNER_INFO *)sk_value( \ + CHECKED_CAST(_STACK *, const STACK_OF(PKCS7_SIGNER_INFO) *, sk), (i))) + +#define sk_PKCS7_SIGNER_INFO_set(sk, i, p) \ + ((PKCS7_SIGNER_INFO *)sk_set( \ + CHECKED_CAST(_STACK *, STACK_OF(PKCS7_SIGNER_INFO) *, sk), (i), \ + CHECKED_CAST(void *, PKCS7_SIGNER_INFO *, p))) + +#define sk_PKCS7_SIGNER_INFO_free(sk) \ + sk_free(CHECKED_CAST(_STACK *, STACK_OF(PKCS7_SIGNER_INFO) *, sk)) + +#define sk_PKCS7_SIGNER_INFO_pop_free(sk, free_func) \ + sk_pop_free(CHECKED_CAST(_STACK *, STACK_OF(PKCS7_SIGNER_INFO) *, sk), \ + CHECKED_CAST(void (*)(void *), void (*)(PKCS7_SIGNER_INFO *), \ + free_func)) + +#define sk_PKCS7_SIGNER_INFO_insert(sk, p, where) \ + sk_insert(CHECKED_CAST(_STACK *, STACK_OF(PKCS7_SIGNER_INFO) *, sk), \ + CHECKED_CAST(void *, PKCS7_SIGNER_INFO *, p), (where)) + +#define sk_PKCS7_SIGNER_INFO_delete(sk, where) \ + ((PKCS7_SIGNER_INFO *)sk_delete( \ + CHECKED_CAST(_STACK *, STACK_OF(PKCS7_SIGNER_INFO) *, sk), (where))) + +#define sk_PKCS7_SIGNER_INFO_delete_ptr(sk, p) \ + ((PKCS7_SIGNER_INFO *)sk_delete_ptr( \ + CHECKED_CAST(_STACK *, STACK_OF(PKCS7_SIGNER_INFO) *, sk), \ + CHECKED_CAST(void *, PKCS7_SIGNER_INFO *, p))) + +#define sk_PKCS7_SIGNER_INFO_find(sk, out_index, p) \ + sk_find(CHECKED_CAST(_STACK *, STACK_OF(PKCS7_SIGNER_INFO) *, sk), \ + (out_index), CHECKED_CAST(void *, PKCS7_SIGNER_INFO *, p)) + +#define sk_PKCS7_SIGNER_INFO_shift(sk) \ + ((PKCS7_SIGNER_INFO *)sk_shift( \ + CHECKED_CAST(_STACK *, STACK_OF(PKCS7_SIGNER_INFO) *, sk))) + +#define sk_PKCS7_SIGNER_INFO_push(sk, p) \ + sk_push(CHECKED_CAST(_STACK *, STACK_OF(PKCS7_SIGNER_INFO) *, sk), \ + CHECKED_CAST(void *, PKCS7_SIGNER_INFO *, p)) + +#define sk_PKCS7_SIGNER_INFO_pop(sk) \ + ((PKCS7_SIGNER_INFO *)sk_pop( \ + CHECKED_CAST(_STACK *, STACK_OF(PKCS7_SIGNER_INFO) *, sk))) + +#define sk_PKCS7_SIGNER_INFO_dup(sk) \ + ((STACK_OF(PKCS7_SIGNER_INFO) *)sk_dup( \ + CHECKED_CAST(_STACK *, const STACK_OF(PKCS7_SIGNER_INFO) *, sk))) + +#define sk_PKCS7_SIGNER_INFO_sort(sk) \ + sk_sort(CHECKED_CAST(_STACK *, STACK_OF(PKCS7_SIGNER_INFO) *, sk)) + +#define sk_PKCS7_SIGNER_INFO_is_sorted(sk) \ + sk_is_sorted(CHECKED_CAST(_STACK *, const STACK_OF(PKCS7_SIGNER_INFO) *, sk)) + +#define sk_PKCS7_SIGNER_INFO_set_cmp_func(sk, comp) \ + ((int (*)(const PKCS7_SIGNER_INFO **a, const PKCS7_SIGNER_INFO **b)) \ + sk_set_cmp_func( \ + CHECKED_CAST(_STACK *, STACK_OF(PKCS7_SIGNER_INFO) *, sk), \ + CHECKED_CAST(stack_cmp_func, int (*)(const PKCS7_SIGNER_INFO **a, \ + const PKCS7_SIGNER_INFO **b), \ + comp))) + +#define sk_PKCS7_SIGNER_INFO_deep_copy(sk, copy_func, free_func) \ + ((STACK_OF(PKCS7_SIGNER_INFO) *)sk_deep_copy( \ + CHECKED_CAST(const _STACK *, const STACK_OF(PKCS7_SIGNER_INFO) *, sk), \ + CHECKED_CAST(void *(*)(void *), \ + PKCS7_SIGNER_INFO *(*)(PKCS7_SIGNER_INFO *), copy_func), \ + CHECKED_CAST(void (*)(void *), void (*)(PKCS7_SIGNER_INFO *), \ + free_func))) + +/* PKCS7_RECIP_INFO */ +#define sk_PKCS7_RECIP_INFO_new(comp) \ + ((STACK_OF(PKCS7_RECIP_INFO) *)sk_new(CHECKED_CAST( \ + stack_cmp_func, \ + int (*)(const PKCS7_RECIP_INFO **a, const PKCS7_RECIP_INFO **b), comp))) + +#define sk_PKCS7_RECIP_INFO_new_null() \ + ((STACK_OF(PKCS7_RECIP_INFO) *)sk_new_null()) + +#define sk_PKCS7_RECIP_INFO_num(sk) \ + sk_num(CHECKED_CAST(_STACK *, STACK_OF(PKCS7_RECIP_INFO) *, sk)) + +#define sk_PKCS7_RECIP_INFO_zero(sk) \ + sk_zero(CHECKED_CAST(_STACK *, STACK_OF(PKCS7_RECIP_INFO) *, sk)); + +#define sk_PKCS7_RECIP_INFO_value(sk, i) \ + ((PKCS7_RECIP_INFO *)sk_value( \ + CHECKED_CAST(_STACK *, const STACK_OF(PKCS7_RECIP_INFO) *, sk), (i))) + +#define sk_PKCS7_RECIP_INFO_set(sk, i, p) \ + ((PKCS7_RECIP_INFO *)sk_set( \ + CHECKED_CAST(_STACK *, STACK_OF(PKCS7_RECIP_INFO) *, sk), (i), \ + CHECKED_CAST(void *, PKCS7_RECIP_INFO *, p))) + +#define sk_PKCS7_RECIP_INFO_free(sk) \ + sk_free(CHECKED_CAST(_STACK *, STACK_OF(PKCS7_RECIP_INFO) *, sk)) + +#define sk_PKCS7_RECIP_INFO_pop_free(sk, free_func) \ + sk_pop_free( \ + CHECKED_CAST(_STACK *, STACK_OF(PKCS7_RECIP_INFO) *, sk), \ + CHECKED_CAST(void (*)(void *), void (*)(PKCS7_RECIP_INFO *), free_func)) + +#define sk_PKCS7_RECIP_INFO_insert(sk, p, where) \ + sk_insert(CHECKED_CAST(_STACK *, STACK_OF(PKCS7_RECIP_INFO) *, sk), \ + CHECKED_CAST(void *, PKCS7_RECIP_INFO *, p), (where)) + +#define sk_PKCS7_RECIP_INFO_delete(sk, where) \ + ((PKCS7_RECIP_INFO *)sk_delete( \ + CHECKED_CAST(_STACK *, STACK_OF(PKCS7_RECIP_INFO) *, sk), (where))) + +#define sk_PKCS7_RECIP_INFO_delete_ptr(sk, p) \ + ((PKCS7_RECIP_INFO *)sk_delete_ptr( \ + CHECKED_CAST(_STACK *, STACK_OF(PKCS7_RECIP_INFO) *, sk), \ + CHECKED_CAST(void *, PKCS7_RECIP_INFO *, p))) + +#define sk_PKCS7_RECIP_INFO_find(sk, out_index, p) \ + sk_find(CHECKED_CAST(_STACK *, STACK_OF(PKCS7_RECIP_INFO) *, sk), \ + (out_index), CHECKED_CAST(void *, PKCS7_RECIP_INFO *, p)) + +#define sk_PKCS7_RECIP_INFO_shift(sk) \ + ((PKCS7_RECIP_INFO *)sk_shift( \ + CHECKED_CAST(_STACK *, STACK_OF(PKCS7_RECIP_INFO) *, sk))) + +#define sk_PKCS7_RECIP_INFO_push(sk, p) \ + sk_push(CHECKED_CAST(_STACK *, STACK_OF(PKCS7_RECIP_INFO) *, sk), \ + CHECKED_CAST(void *, PKCS7_RECIP_INFO *, p)) + +#define sk_PKCS7_RECIP_INFO_pop(sk) \ + ((PKCS7_RECIP_INFO *)sk_pop( \ + CHECKED_CAST(_STACK *, STACK_OF(PKCS7_RECIP_INFO) *, sk))) + +#define sk_PKCS7_RECIP_INFO_dup(sk) \ + ((STACK_OF(PKCS7_RECIP_INFO) *)sk_dup( \ + CHECKED_CAST(_STACK *, const STACK_OF(PKCS7_RECIP_INFO) *, sk))) + +#define sk_PKCS7_RECIP_INFO_sort(sk) \ + sk_sort(CHECKED_CAST(_STACK *, STACK_OF(PKCS7_RECIP_INFO) *, sk)) + +#define sk_PKCS7_RECIP_INFO_is_sorted(sk) \ + sk_is_sorted(CHECKED_CAST(_STACK *, const STACK_OF(PKCS7_RECIP_INFO) *, sk)) + +#define sk_PKCS7_RECIP_INFO_set_cmp_func(sk, comp) \ + ((int (*)(const PKCS7_RECIP_INFO **a, const PKCS7_RECIP_INFO **b)) \ + sk_set_cmp_func( \ + CHECKED_CAST(_STACK *, STACK_OF(PKCS7_RECIP_INFO) *, sk), \ + CHECKED_CAST(stack_cmp_func, int (*)(const PKCS7_RECIP_INFO **a, \ + const PKCS7_RECIP_INFO **b), \ + comp))) + +#define sk_PKCS7_RECIP_INFO_deep_copy(sk, copy_func, free_func) \ + ((STACK_OF(PKCS7_RECIP_INFO) *)sk_deep_copy( \ + CHECKED_CAST(const _STACK *, const STACK_OF(PKCS7_RECIP_INFO) *, sk), \ + CHECKED_CAST(void *(*)(void *), \ + PKCS7_RECIP_INFO *(*)(PKCS7_RECIP_INFO *), copy_func), \ + CHECKED_CAST(void (*)(void *), void (*)(PKCS7_RECIP_INFO *), \ + free_func))) + +/* POLICYINFO */ +#define sk_POLICYINFO_new(comp) \ + ((STACK_OF(POLICYINFO) *)sk_new(CHECKED_CAST( \ + stack_cmp_func, int (*)(const POLICYINFO **a, const POLICYINFO **b), \ + comp))) + +#define sk_POLICYINFO_new_null() ((STACK_OF(POLICYINFO) *)sk_new_null()) + +#define sk_POLICYINFO_num(sk) \ + sk_num(CHECKED_CAST(_STACK *, STACK_OF(POLICYINFO) *, sk)) + +#define sk_POLICYINFO_zero(sk) \ + sk_zero(CHECKED_CAST(_STACK *, STACK_OF(POLICYINFO) *, sk)); + +#define sk_POLICYINFO_value(sk, i) \ + ((POLICYINFO *)sk_value( \ + CHECKED_CAST(_STACK *, const STACK_OF(POLICYINFO) *, sk), (i))) + +#define sk_POLICYINFO_set(sk, i, p) \ + ((POLICYINFO *)sk_set(CHECKED_CAST(_STACK *, STACK_OF(POLICYINFO) *, sk), \ + (i), CHECKED_CAST(void *, POLICYINFO *, p))) + +#define sk_POLICYINFO_free(sk) \ + sk_free(CHECKED_CAST(_STACK *, STACK_OF(POLICYINFO) *, sk)) + +#define sk_POLICYINFO_pop_free(sk, free_func) \ + sk_pop_free( \ + CHECKED_CAST(_STACK *, STACK_OF(POLICYINFO) *, sk), \ + CHECKED_CAST(void (*)(void *), void (*)(POLICYINFO *), free_func)) + +#define sk_POLICYINFO_insert(sk, p, where) \ + sk_insert(CHECKED_CAST(_STACK *, STACK_OF(POLICYINFO) *, sk), \ + CHECKED_CAST(void *, POLICYINFO *, p), (where)) + +#define sk_POLICYINFO_delete(sk, where) \ + ((POLICYINFO *)sk_delete(CHECKED_CAST(_STACK *, STACK_OF(POLICYINFO) *, sk), \ + (where))) + +#define sk_POLICYINFO_delete_ptr(sk, p) \ + ((POLICYINFO *)sk_delete_ptr( \ + CHECKED_CAST(_STACK *, STACK_OF(POLICYINFO) *, sk), \ + CHECKED_CAST(void *, POLICYINFO *, p))) + +#define sk_POLICYINFO_find(sk, out_index, p) \ + sk_find(CHECKED_CAST(_STACK *, STACK_OF(POLICYINFO) *, sk), (out_index), \ + CHECKED_CAST(void *, POLICYINFO *, p)) + +#define sk_POLICYINFO_shift(sk) \ + ((POLICYINFO *)sk_shift(CHECKED_CAST(_STACK *, STACK_OF(POLICYINFO) *, sk))) + +#define sk_POLICYINFO_push(sk, p) \ + sk_push(CHECKED_CAST(_STACK *, STACK_OF(POLICYINFO) *, sk), \ + CHECKED_CAST(void *, POLICYINFO *, p)) + +#define sk_POLICYINFO_pop(sk) \ + ((POLICYINFO *)sk_pop(CHECKED_CAST(_STACK *, STACK_OF(POLICYINFO) *, sk))) + +#define sk_POLICYINFO_dup(sk) \ + ((STACK_OF(POLICYINFO) *)sk_dup( \ + CHECKED_CAST(_STACK *, const STACK_OF(POLICYINFO) *, sk))) + +#define sk_POLICYINFO_sort(sk) \ + sk_sort(CHECKED_CAST(_STACK *, STACK_OF(POLICYINFO) *, sk)) + +#define sk_POLICYINFO_is_sorted(sk) \ + sk_is_sorted(CHECKED_CAST(_STACK *, const STACK_OF(POLICYINFO) *, sk)) + +#define sk_POLICYINFO_set_cmp_func(sk, comp) \ + ((int (*)(const POLICYINFO **a, const POLICYINFO **b))sk_set_cmp_func( \ + CHECKED_CAST(_STACK *, STACK_OF(POLICYINFO) *, sk), \ + CHECKED_CAST(stack_cmp_func, \ + int (*)(const POLICYINFO **a, const POLICYINFO **b), \ + comp))) + +#define sk_POLICYINFO_deep_copy(sk, copy_func, free_func) \ + ((STACK_OF(POLICYINFO) *)sk_deep_copy( \ + CHECKED_CAST(const _STACK *, const STACK_OF(POLICYINFO) *, sk), \ + CHECKED_CAST(void *(*)(void *), POLICYINFO *(*)(POLICYINFO *), \ + copy_func), \ + CHECKED_CAST(void (*)(void *), void (*)(POLICYINFO *), free_func))) + +/* POLICYQUALINFO */ +#define sk_POLICYQUALINFO_new(comp) \ + ((STACK_OF(POLICYQUALINFO) *)sk_new(CHECKED_CAST( \ + stack_cmp_func, \ + int (*)(const POLICYQUALINFO **a, const POLICYQUALINFO **b), comp))) + +#define sk_POLICYQUALINFO_new_null() ((STACK_OF(POLICYQUALINFO) *)sk_new_null()) + +#define sk_POLICYQUALINFO_num(sk) \ + sk_num(CHECKED_CAST(_STACK *, STACK_OF(POLICYQUALINFO) *, sk)) + +#define sk_POLICYQUALINFO_zero(sk) \ + sk_zero(CHECKED_CAST(_STACK *, STACK_OF(POLICYQUALINFO) *, sk)); + +#define sk_POLICYQUALINFO_value(sk, i) \ + ((POLICYQUALINFO *)sk_value( \ + CHECKED_CAST(_STACK *, const STACK_OF(POLICYQUALINFO) *, sk), (i))) + +#define sk_POLICYQUALINFO_set(sk, i, p) \ + ((POLICYQUALINFO *)sk_set( \ + CHECKED_CAST(_STACK *, STACK_OF(POLICYQUALINFO) *, sk), (i), \ + CHECKED_CAST(void *, POLICYQUALINFO *, p))) + +#define sk_POLICYQUALINFO_free(sk) \ + sk_free(CHECKED_CAST(_STACK *, STACK_OF(POLICYQUALINFO) *, sk)) + +#define sk_POLICYQUALINFO_pop_free(sk, free_func) \ + sk_pop_free( \ + CHECKED_CAST(_STACK *, STACK_OF(POLICYQUALINFO) *, sk), \ + CHECKED_CAST(void (*)(void *), void (*)(POLICYQUALINFO *), free_func)) + +#define sk_POLICYQUALINFO_insert(sk, p, where) \ + sk_insert(CHECKED_CAST(_STACK *, STACK_OF(POLICYQUALINFO) *, sk), \ + CHECKED_CAST(void *, POLICYQUALINFO *, p), (where)) + +#define sk_POLICYQUALINFO_delete(sk, where) \ + ((POLICYQUALINFO *)sk_delete( \ + CHECKED_CAST(_STACK *, STACK_OF(POLICYQUALINFO) *, sk), (where))) + +#define sk_POLICYQUALINFO_delete_ptr(sk, p) \ + ((POLICYQUALINFO *)sk_delete_ptr( \ + CHECKED_CAST(_STACK *, STACK_OF(POLICYQUALINFO) *, sk), \ + CHECKED_CAST(void *, POLICYQUALINFO *, p))) + +#define sk_POLICYQUALINFO_find(sk, out_index, p) \ + sk_find(CHECKED_CAST(_STACK *, STACK_OF(POLICYQUALINFO) *, sk), (out_index), \ + CHECKED_CAST(void *, POLICYQUALINFO *, p)) + +#define sk_POLICYQUALINFO_shift(sk) \ + ((POLICYQUALINFO *)sk_shift( \ + CHECKED_CAST(_STACK *, STACK_OF(POLICYQUALINFO) *, sk))) + +#define sk_POLICYQUALINFO_push(sk, p) \ + sk_push(CHECKED_CAST(_STACK *, STACK_OF(POLICYQUALINFO) *, sk), \ + CHECKED_CAST(void *, POLICYQUALINFO *, p)) + +#define sk_POLICYQUALINFO_pop(sk) \ + ((POLICYQUALINFO *)sk_pop( \ + CHECKED_CAST(_STACK *, STACK_OF(POLICYQUALINFO) *, sk))) + +#define sk_POLICYQUALINFO_dup(sk) \ + ((STACK_OF(POLICYQUALINFO) *)sk_dup( \ + CHECKED_CAST(_STACK *, const STACK_OF(POLICYQUALINFO) *, sk))) + +#define sk_POLICYQUALINFO_sort(sk) \ + sk_sort(CHECKED_CAST(_STACK *, STACK_OF(POLICYQUALINFO) *, sk)) + +#define sk_POLICYQUALINFO_is_sorted(sk) \ + sk_is_sorted(CHECKED_CAST(_STACK *, const STACK_OF(POLICYQUALINFO) *, sk)) + +#define sk_POLICYQUALINFO_set_cmp_func(sk, comp) \ + ((int (*)(const POLICYQUALINFO **a, const POLICYQUALINFO **b)) \ + sk_set_cmp_func( \ + CHECKED_CAST(_STACK *, STACK_OF(POLICYQUALINFO) *, sk), \ + CHECKED_CAST(stack_cmp_func, int (*)(const POLICYQUALINFO **a, \ + const POLICYQUALINFO **b), \ + comp))) + +#define sk_POLICYQUALINFO_deep_copy(sk, copy_func, free_func) \ + ((STACK_OF(POLICYQUALINFO) *)sk_deep_copy( \ + CHECKED_CAST(const _STACK *, const STACK_OF(POLICYQUALINFO) *, sk), \ + CHECKED_CAST(void *(*)(void *), POLICYQUALINFO *(*)(POLICYQUALINFO *), \ + copy_func), \ + CHECKED_CAST(void (*)(void *), void (*)(POLICYQUALINFO *), free_func))) + +/* POLICY_MAPPING */ +#define sk_POLICY_MAPPING_new(comp) \ + ((STACK_OF(POLICY_MAPPING) *)sk_new(CHECKED_CAST( \ + stack_cmp_func, \ + int (*)(const POLICY_MAPPING **a, const POLICY_MAPPING **b), comp))) + +#define sk_POLICY_MAPPING_new_null() ((STACK_OF(POLICY_MAPPING) *)sk_new_null()) + +#define sk_POLICY_MAPPING_num(sk) \ + sk_num(CHECKED_CAST(_STACK *, STACK_OF(POLICY_MAPPING) *, sk)) + +#define sk_POLICY_MAPPING_zero(sk) \ + sk_zero(CHECKED_CAST(_STACK *, STACK_OF(POLICY_MAPPING) *, sk)); + +#define sk_POLICY_MAPPING_value(sk, i) \ + ((POLICY_MAPPING *)sk_value( \ + CHECKED_CAST(_STACK *, const STACK_OF(POLICY_MAPPING) *, sk), (i))) + +#define sk_POLICY_MAPPING_set(sk, i, p) \ + ((POLICY_MAPPING *)sk_set( \ + CHECKED_CAST(_STACK *, STACK_OF(POLICY_MAPPING) *, sk), (i), \ + CHECKED_CAST(void *, POLICY_MAPPING *, p))) + +#define sk_POLICY_MAPPING_free(sk) \ + sk_free(CHECKED_CAST(_STACK *, STACK_OF(POLICY_MAPPING) *, sk)) + +#define sk_POLICY_MAPPING_pop_free(sk, free_func) \ + sk_pop_free( \ + CHECKED_CAST(_STACK *, STACK_OF(POLICY_MAPPING) *, sk), \ + CHECKED_CAST(void (*)(void *), void (*)(POLICY_MAPPING *), free_func)) + +#define sk_POLICY_MAPPING_insert(sk, p, where) \ + sk_insert(CHECKED_CAST(_STACK *, STACK_OF(POLICY_MAPPING) *, sk), \ + CHECKED_CAST(void *, POLICY_MAPPING *, p), (where)) + +#define sk_POLICY_MAPPING_delete(sk, where) \ + ((POLICY_MAPPING *)sk_delete( \ + CHECKED_CAST(_STACK *, STACK_OF(POLICY_MAPPING) *, sk), (where))) + +#define sk_POLICY_MAPPING_delete_ptr(sk, p) \ + ((POLICY_MAPPING *)sk_delete_ptr( \ + CHECKED_CAST(_STACK *, STACK_OF(POLICY_MAPPING) *, sk), \ + CHECKED_CAST(void *, POLICY_MAPPING *, p))) + +#define sk_POLICY_MAPPING_find(sk, out_index, p) \ + sk_find(CHECKED_CAST(_STACK *, STACK_OF(POLICY_MAPPING) *, sk), (out_index), \ + CHECKED_CAST(void *, POLICY_MAPPING *, p)) + +#define sk_POLICY_MAPPING_shift(sk) \ + ((POLICY_MAPPING *)sk_shift( \ + CHECKED_CAST(_STACK *, STACK_OF(POLICY_MAPPING) *, sk))) + +#define sk_POLICY_MAPPING_push(sk, p) \ + sk_push(CHECKED_CAST(_STACK *, STACK_OF(POLICY_MAPPING) *, sk), \ + CHECKED_CAST(void *, POLICY_MAPPING *, p)) + +#define sk_POLICY_MAPPING_pop(sk) \ + ((POLICY_MAPPING *)sk_pop( \ + CHECKED_CAST(_STACK *, STACK_OF(POLICY_MAPPING) *, sk))) + +#define sk_POLICY_MAPPING_dup(sk) \ + ((STACK_OF(POLICY_MAPPING) *)sk_dup( \ + CHECKED_CAST(_STACK *, const STACK_OF(POLICY_MAPPING) *, sk))) + +#define sk_POLICY_MAPPING_sort(sk) \ + sk_sort(CHECKED_CAST(_STACK *, STACK_OF(POLICY_MAPPING) *, sk)) + +#define sk_POLICY_MAPPING_is_sorted(sk) \ + sk_is_sorted(CHECKED_CAST(_STACK *, const STACK_OF(POLICY_MAPPING) *, sk)) + +#define sk_POLICY_MAPPING_set_cmp_func(sk, comp) \ + ((int (*)(const POLICY_MAPPING **a, const POLICY_MAPPING **b)) \ + sk_set_cmp_func( \ + CHECKED_CAST(_STACK *, STACK_OF(POLICY_MAPPING) *, sk), \ + CHECKED_CAST(stack_cmp_func, int (*)(const POLICY_MAPPING **a, \ + const POLICY_MAPPING **b), \ + comp))) + +#define sk_POLICY_MAPPING_deep_copy(sk, copy_func, free_func) \ + ((STACK_OF(POLICY_MAPPING) *)sk_deep_copy( \ + CHECKED_CAST(const _STACK *, const STACK_OF(POLICY_MAPPING) *, sk), \ + CHECKED_CAST(void *(*)(void *), POLICY_MAPPING *(*)(POLICY_MAPPING *), \ + copy_func), \ + CHECKED_CAST(void (*)(void *), void (*)(POLICY_MAPPING *), free_func))) + +/* SSL_COMP */ +#define sk_SSL_COMP_new(comp) \ + ((STACK_OF(SSL_COMP) *)sk_new(CHECKED_CAST( \ + stack_cmp_func, int (*)(const SSL_COMP **a, const SSL_COMP **b), comp))) + +#define sk_SSL_COMP_new_null() ((STACK_OF(SSL_COMP) *)sk_new_null()) + +#define sk_SSL_COMP_num(sk) \ + sk_num(CHECKED_CAST(_STACK *, STACK_OF(SSL_COMP) *, sk)) + +#define sk_SSL_COMP_zero(sk) \ + sk_zero(CHECKED_CAST(_STACK *, STACK_OF(SSL_COMP) *, sk)); + +#define sk_SSL_COMP_value(sk, i) \ + ((SSL_COMP *)sk_value( \ + CHECKED_CAST(_STACK *, const STACK_OF(SSL_COMP) *, sk), (i))) + +#define sk_SSL_COMP_set(sk, i, p) \ + ((SSL_COMP *)sk_set(CHECKED_CAST(_STACK *, STACK_OF(SSL_COMP) *, sk), (i), \ + CHECKED_CAST(void *, SSL_COMP *, p))) + +#define sk_SSL_COMP_free(sk) \ + sk_free(CHECKED_CAST(_STACK *, STACK_OF(SSL_COMP) *, sk)) + +#define sk_SSL_COMP_pop_free(sk, free_func) \ + sk_pop_free(CHECKED_CAST(_STACK *, STACK_OF(SSL_COMP) *, sk), \ + CHECKED_CAST(void (*)(void *), void (*)(SSL_COMP *), free_func)) + +#define sk_SSL_COMP_insert(sk, p, where) \ + sk_insert(CHECKED_CAST(_STACK *, STACK_OF(SSL_COMP) *, sk), \ + CHECKED_CAST(void *, SSL_COMP *, p), (where)) + +#define sk_SSL_COMP_delete(sk, where) \ + ((SSL_COMP *)sk_delete(CHECKED_CAST(_STACK *, STACK_OF(SSL_COMP) *, sk), \ + (where))) + +#define sk_SSL_COMP_delete_ptr(sk, p) \ + ((SSL_COMP *)sk_delete_ptr(CHECKED_CAST(_STACK *, STACK_OF(SSL_COMP) *, sk), \ + CHECKED_CAST(void *, SSL_COMP *, p))) + +#define sk_SSL_COMP_find(sk, out_index, p) \ + sk_find(CHECKED_CAST(_STACK *, STACK_OF(SSL_COMP) *, sk), (out_index), \ + CHECKED_CAST(void *, SSL_COMP *, p)) + +#define sk_SSL_COMP_shift(sk) \ + ((SSL_COMP *)sk_shift(CHECKED_CAST(_STACK *, STACK_OF(SSL_COMP) *, sk))) + +#define sk_SSL_COMP_push(sk, p) \ + sk_push(CHECKED_CAST(_STACK *, STACK_OF(SSL_COMP) *, sk), \ + CHECKED_CAST(void *, SSL_COMP *, p)) + +#define sk_SSL_COMP_pop(sk) \ + ((SSL_COMP *)sk_pop(CHECKED_CAST(_STACK *, STACK_OF(SSL_COMP) *, sk))) + +#define sk_SSL_COMP_dup(sk) \ + ((STACK_OF(SSL_COMP) *)sk_dup( \ + CHECKED_CAST(_STACK *, const STACK_OF(SSL_COMP) *, sk))) + +#define sk_SSL_COMP_sort(sk) \ + sk_sort(CHECKED_CAST(_STACK *, STACK_OF(SSL_COMP) *, sk)) + +#define sk_SSL_COMP_is_sorted(sk) \ + sk_is_sorted(CHECKED_CAST(_STACK *, const STACK_OF(SSL_COMP) *, sk)) + +#define sk_SSL_COMP_set_cmp_func(sk, comp) \ + ((int (*)(const SSL_COMP **a, const SSL_COMP **b))sk_set_cmp_func( \ + CHECKED_CAST(_STACK *, STACK_OF(SSL_COMP) *, sk), \ + CHECKED_CAST(stack_cmp_func, \ + int (*)(const SSL_COMP **a, const SSL_COMP **b), comp))) + +#define sk_SSL_COMP_deep_copy(sk, copy_func, free_func) \ + ((STACK_OF(SSL_COMP) *)sk_deep_copy( \ + CHECKED_CAST(const _STACK *, const STACK_OF(SSL_COMP) *, sk), \ + CHECKED_CAST(void *(*)(void *), SSL_COMP *(*)(SSL_COMP *), copy_func), \ + CHECKED_CAST(void (*)(void *), void (*)(SSL_COMP *), free_func))) + +/* STACK_OF_X509_NAME_ENTRY */ +#define sk_STACK_OF_X509_NAME_ENTRY_new(comp) \ + ((STACK_OF(STACK_OF_X509_NAME_ENTRY) *)sk_new(CHECKED_CAST( \ + stack_cmp_func, int (*)(const STACK_OF_X509_NAME_ENTRY **a, \ + const STACK_OF_X509_NAME_ENTRY **b), \ + comp))) + +#define sk_STACK_OF_X509_NAME_ENTRY_new_null() \ + ((STACK_OF(STACK_OF_X509_NAME_ENTRY) *)sk_new_null()) + +#define sk_STACK_OF_X509_NAME_ENTRY_num(sk) \ + sk_num(CHECKED_CAST(_STACK *, STACK_OF(STACK_OF_X509_NAME_ENTRY) *, sk)) + +#define sk_STACK_OF_X509_NAME_ENTRY_zero(sk) \ + sk_zero(CHECKED_CAST(_STACK *, STACK_OF(STACK_OF_X509_NAME_ENTRY) *, sk)); + +#define sk_STACK_OF_X509_NAME_ENTRY_value(sk, i) \ + ((STACK_OF_X509_NAME_ENTRY *)sk_value( \ + CHECKED_CAST(_STACK *, const STACK_OF(STACK_OF_X509_NAME_ENTRY) *, sk), \ + (i))) + +#define sk_STACK_OF_X509_NAME_ENTRY_set(sk, i, p) \ + ((STACK_OF_X509_NAME_ENTRY *)sk_set( \ + CHECKED_CAST(_STACK *, STACK_OF(STACK_OF_X509_NAME_ENTRY) *, sk), (i), \ + CHECKED_CAST(void *, STACK_OF_X509_NAME_ENTRY *, p))) + +#define sk_STACK_OF_X509_NAME_ENTRY_free(sk) \ + sk_free(CHECKED_CAST(_STACK *, STACK_OF(STACK_OF_X509_NAME_ENTRY) *, sk)) + +#define sk_STACK_OF_X509_NAME_ENTRY_pop_free(sk, free_func) \ + sk_pop_free( \ + CHECKED_CAST(_STACK *, STACK_OF(STACK_OF_X509_NAME_ENTRY) *, sk), \ + CHECKED_CAST(void (*)(void *), void (*)(STACK_OF_X509_NAME_ENTRY *), \ + free_func)) + +#define sk_STACK_OF_X509_NAME_ENTRY_insert(sk, p, where) \ + sk_insert(CHECKED_CAST(_STACK *, STACK_OF(STACK_OF_X509_NAME_ENTRY) *, sk), \ + CHECKED_CAST(void *, STACK_OF_X509_NAME_ENTRY *, p), (where)) + +#define sk_STACK_OF_X509_NAME_ENTRY_delete(sk, where) \ + ((STACK_OF_X509_NAME_ENTRY *)sk_delete( \ + CHECKED_CAST(_STACK *, STACK_OF(STACK_OF_X509_NAME_ENTRY) *, sk), \ + (where))) + +#define sk_STACK_OF_X509_NAME_ENTRY_delete_ptr(sk, p) \ + ((STACK_OF_X509_NAME_ENTRY *)sk_delete_ptr( \ + CHECKED_CAST(_STACK *, STACK_OF(STACK_OF_X509_NAME_ENTRY) *, sk), \ + CHECKED_CAST(void *, STACK_OF_X509_NAME_ENTRY *, p))) + +#define sk_STACK_OF_X509_NAME_ENTRY_find(sk, out_index, p) \ + sk_find(CHECKED_CAST(_STACK *, STACK_OF(STACK_OF_X509_NAME_ENTRY) *, sk), \ + (out_index), CHECKED_CAST(void *, STACK_OF_X509_NAME_ENTRY *, p)) + +#define sk_STACK_OF_X509_NAME_ENTRY_shift(sk) \ + ((STACK_OF_X509_NAME_ENTRY *)sk_shift( \ + CHECKED_CAST(_STACK *, STACK_OF(STACK_OF_X509_NAME_ENTRY) *, sk))) + +#define sk_STACK_OF_X509_NAME_ENTRY_push(sk, p) \ + sk_push(CHECKED_CAST(_STACK *, STACK_OF(STACK_OF_X509_NAME_ENTRY) *, sk), \ + CHECKED_CAST(void *, STACK_OF_X509_NAME_ENTRY *, p)) + +#define sk_STACK_OF_X509_NAME_ENTRY_pop(sk) \ + ((STACK_OF_X509_NAME_ENTRY *)sk_pop( \ + CHECKED_CAST(_STACK *, STACK_OF(STACK_OF_X509_NAME_ENTRY) *, sk))) + +#define sk_STACK_OF_X509_NAME_ENTRY_dup(sk) \ + ((STACK_OF(STACK_OF_X509_NAME_ENTRY) *)sk_dup( \ + CHECKED_CAST(_STACK *, const STACK_OF(STACK_OF_X509_NAME_ENTRY) *, sk))) + +#define sk_STACK_OF_X509_NAME_ENTRY_sort(sk) \ + sk_sort(CHECKED_CAST(_STACK *, STACK_OF(STACK_OF_X509_NAME_ENTRY) *, sk)) + +#define sk_STACK_OF_X509_NAME_ENTRY_is_sorted(sk) \ + sk_is_sorted( \ + CHECKED_CAST(_STACK *, const STACK_OF(STACK_OF_X509_NAME_ENTRY) *, sk)) + +#define sk_STACK_OF_X509_NAME_ENTRY_set_cmp_func(sk, comp) \ + ((int (*)(const STACK_OF_X509_NAME_ENTRY **a, \ + const STACK_OF_X509_NAME_ENTRY **b)) \ + sk_set_cmp_func( \ + CHECKED_CAST(_STACK *, STACK_OF(STACK_OF_X509_NAME_ENTRY) *, sk), \ + CHECKED_CAST(stack_cmp_func, \ + int (*)(const STACK_OF_X509_NAME_ENTRY **a, \ + const STACK_OF_X509_NAME_ENTRY **b), \ + comp))) + +#define sk_STACK_OF_X509_NAME_ENTRY_deep_copy(sk, copy_func, free_func) \ + ((STACK_OF(STACK_OF_X509_NAME_ENTRY) *)sk_deep_copy( \ + CHECKED_CAST(const _STACK *, const STACK_OF(STACK_OF_X509_NAME_ENTRY) *, \ + sk), \ + CHECKED_CAST(void *(*)(void *), \ + STACK_OF_X509_NAME_ENTRY *(*)(STACK_OF_X509_NAME_ENTRY *), \ + copy_func), \ + CHECKED_CAST(void (*)(void *), void (*)(STACK_OF_X509_NAME_ENTRY *), \ + free_func))) + +/* SXNETID */ +#define sk_SXNETID_new(comp) \ + ((STACK_OF(SXNETID) *)sk_new(CHECKED_CAST( \ + stack_cmp_func, int (*)(const SXNETID **a, const SXNETID **b), comp))) + +#define sk_SXNETID_new_null() ((STACK_OF(SXNETID) *)sk_new_null()) + +#define sk_SXNETID_num(sk) \ + sk_num(CHECKED_CAST(_STACK *, STACK_OF(SXNETID) *, sk)) + +#define sk_SXNETID_zero(sk) \ + sk_zero(CHECKED_CAST(_STACK *, STACK_OF(SXNETID) *, sk)); + +#define sk_SXNETID_value(sk, i) \ + ((SXNETID *)sk_value(CHECKED_CAST(_STACK *, const STACK_OF(SXNETID) *, sk), \ + (i))) + +#define sk_SXNETID_set(sk, i, p) \ + ((SXNETID *)sk_set(CHECKED_CAST(_STACK *, STACK_OF(SXNETID) *, sk), (i), \ + CHECKED_CAST(void *, SXNETID *, p))) + +#define sk_SXNETID_free(sk) \ + sk_free(CHECKED_CAST(_STACK *, STACK_OF(SXNETID) *, sk)) + +#define sk_SXNETID_pop_free(sk, free_func) \ + sk_pop_free(CHECKED_CAST(_STACK *, STACK_OF(SXNETID) *, sk), \ + CHECKED_CAST(void (*)(void *), void (*)(SXNETID *), free_func)) + +#define sk_SXNETID_insert(sk, p, where) \ + sk_insert(CHECKED_CAST(_STACK *, STACK_OF(SXNETID) *, sk), \ + CHECKED_CAST(void *, SXNETID *, p), (where)) + +#define sk_SXNETID_delete(sk, where) \ + ((SXNETID *)sk_delete(CHECKED_CAST(_STACK *, STACK_OF(SXNETID) *, sk), \ + (where))) + +#define sk_SXNETID_delete_ptr(sk, p) \ + ((SXNETID *)sk_delete_ptr(CHECKED_CAST(_STACK *, STACK_OF(SXNETID) *, sk), \ + CHECKED_CAST(void *, SXNETID *, p))) + +#define sk_SXNETID_find(sk, out_index, p) \ + sk_find(CHECKED_CAST(_STACK *, STACK_OF(SXNETID) *, sk), (out_index), \ + CHECKED_CAST(void *, SXNETID *, p)) + +#define sk_SXNETID_shift(sk) \ + ((SXNETID *)sk_shift(CHECKED_CAST(_STACK *, STACK_OF(SXNETID) *, sk))) + +#define sk_SXNETID_push(sk, p) \ + sk_push(CHECKED_CAST(_STACK *, STACK_OF(SXNETID) *, sk), \ + CHECKED_CAST(void *, SXNETID *, p)) + +#define sk_SXNETID_pop(sk) \ + ((SXNETID *)sk_pop(CHECKED_CAST(_STACK *, STACK_OF(SXNETID) *, sk))) + +#define sk_SXNETID_dup(sk) \ + ((STACK_OF(SXNETID) *)sk_dup( \ + CHECKED_CAST(_STACK *, const STACK_OF(SXNETID) *, sk))) + +#define sk_SXNETID_sort(sk) \ + sk_sort(CHECKED_CAST(_STACK *, STACK_OF(SXNETID) *, sk)) + +#define sk_SXNETID_is_sorted(sk) \ + sk_is_sorted(CHECKED_CAST(_STACK *, const STACK_OF(SXNETID) *, sk)) + +#define sk_SXNETID_set_cmp_func(sk, comp) \ + ((int (*)(const SXNETID **a, const SXNETID **b))sk_set_cmp_func( \ + CHECKED_CAST(_STACK *, STACK_OF(SXNETID) *, sk), \ + CHECKED_CAST(stack_cmp_func, \ + int (*)(const SXNETID **a, const SXNETID **b), comp))) + +#define sk_SXNETID_deep_copy(sk, copy_func, free_func) \ + ((STACK_OF(SXNETID) *)sk_deep_copy( \ + CHECKED_CAST(const _STACK *, const STACK_OF(SXNETID) *, sk), \ + CHECKED_CAST(void *(*)(void *), SXNETID *(*)(SXNETID *), copy_func), \ + CHECKED_CAST(void (*)(void *), void (*)(SXNETID *), free_func))) + +/* X509 */ +#define sk_X509_new(comp) \ + ((STACK_OF(X509) *)sk_new(CHECKED_CAST( \ + stack_cmp_func, int (*)(const X509 **a, const X509 **b), comp))) + +#define sk_X509_new_null() ((STACK_OF(X509) *)sk_new_null()) + +#define sk_X509_num(sk) sk_num(CHECKED_CAST(_STACK *, STACK_OF(X509) *, sk)) + +#define sk_X509_zero(sk) sk_zero(CHECKED_CAST(_STACK *, STACK_OF(X509) *, sk)); + +#define sk_X509_value(sk, i) \ + ((X509 *)sk_value(CHECKED_CAST(_STACK *, const STACK_OF(X509) *, sk), (i))) + +#define sk_X509_set(sk, i, p) \ + ((X509 *)sk_set(CHECKED_CAST(_STACK *, STACK_OF(X509) *, sk), (i), \ + CHECKED_CAST(void *, X509 *, p))) + +#define sk_X509_free(sk) sk_free(CHECKED_CAST(_STACK *, STACK_OF(X509) *, sk)) + +#define sk_X509_pop_free(sk, free_func) \ + sk_pop_free(CHECKED_CAST(_STACK *, STACK_OF(X509) *, sk), \ + CHECKED_CAST(void (*)(void *), void (*)(X509 *), free_func)) + +#define sk_X509_insert(sk, p, where) \ + sk_insert(CHECKED_CAST(_STACK *, STACK_OF(X509) *, sk), \ + CHECKED_CAST(void *, X509 *, p), (where)) + +#define sk_X509_delete(sk, where) \ + ((X509 *)sk_delete(CHECKED_CAST(_STACK *, STACK_OF(X509) *, sk), (where))) + +#define sk_X509_delete_ptr(sk, p) \ + ((X509 *)sk_delete_ptr(CHECKED_CAST(_STACK *, STACK_OF(X509) *, sk), \ + CHECKED_CAST(void *, X509 *, p))) + +#define sk_X509_find(sk, out_index, p) \ + sk_find(CHECKED_CAST(_STACK *, STACK_OF(X509) *, sk), (out_index), \ + CHECKED_CAST(void *, X509 *, p)) + +#define sk_X509_shift(sk) \ + ((X509 *)sk_shift(CHECKED_CAST(_STACK *, STACK_OF(X509) *, sk))) + +#define sk_X509_push(sk, p) \ + sk_push(CHECKED_CAST(_STACK *, STACK_OF(X509) *, sk), \ + CHECKED_CAST(void *, X509 *, p)) + +#define sk_X509_pop(sk) \ + ((X509 *)sk_pop(CHECKED_CAST(_STACK *, STACK_OF(X509) *, sk))) + +#define sk_X509_dup(sk) \ + ((STACK_OF(X509) *)sk_dup(CHECKED_CAST(_STACK *, const STACK_OF(X509) *, sk))) + +#define sk_X509_sort(sk) sk_sort(CHECKED_CAST(_STACK *, STACK_OF(X509) *, sk)) + +#define sk_X509_is_sorted(sk) \ + sk_is_sorted(CHECKED_CAST(_STACK *, const STACK_OF(X509) *, sk)) + +#define sk_X509_set_cmp_func(sk, comp) \ + ((int (*)(const X509 **a, const X509 **b))sk_set_cmp_func( \ + CHECKED_CAST(_STACK *, STACK_OF(X509) *, sk), \ + CHECKED_CAST(stack_cmp_func, int (*)(const X509 **a, const X509 **b), \ + comp))) + +#define sk_X509_deep_copy(sk, copy_func, free_func) \ + ((STACK_OF(X509) *)sk_deep_copy( \ + CHECKED_CAST(const _STACK *, const STACK_OF(X509) *, sk), \ + CHECKED_CAST(void *(*)(void *), X509 *(*)(X509 *), copy_func), \ + CHECKED_CAST(void (*)(void *), void (*)(X509 *), free_func))) + +/* X509V3_EXT_METHOD */ +#define sk_X509V3_EXT_METHOD_new(comp) \ + ((STACK_OF(X509V3_EXT_METHOD) *)sk_new(CHECKED_CAST( \ + stack_cmp_func, \ + int (*)(const X509V3_EXT_METHOD **a, const X509V3_EXT_METHOD **b), \ + comp))) + +#define sk_X509V3_EXT_METHOD_new_null() \ + ((STACK_OF(X509V3_EXT_METHOD) *)sk_new_null()) + +#define sk_X509V3_EXT_METHOD_num(sk) \ + sk_num(CHECKED_CAST(_STACK *, STACK_OF(X509V3_EXT_METHOD) *, sk)) + +#define sk_X509V3_EXT_METHOD_zero(sk) \ + sk_zero(CHECKED_CAST(_STACK *, STACK_OF(X509V3_EXT_METHOD) *, sk)); + +#define sk_X509V3_EXT_METHOD_value(sk, i) \ + ((X509V3_EXT_METHOD *)sk_value( \ + CHECKED_CAST(_STACK *, const STACK_OF(X509V3_EXT_METHOD) *, sk), (i))) + +#define sk_X509V3_EXT_METHOD_set(sk, i, p) \ + ((X509V3_EXT_METHOD *)sk_set( \ + CHECKED_CAST(_STACK *, STACK_OF(X509V3_EXT_METHOD) *, sk), (i), \ + CHECKED_CAST(void *, X509V3_EXT_METHOD *, p))) + +#define sk_X509V3_EXT_METHOD_free(sk) \ + sk_free(CHECKED_CAST(_STACK *, STACK_OF(X509V3_EXT_METHOD) *, sk)) + +#define sk_X509V3_EXT_METHOD_pop_free(sk, free_func) \ + sk_pop_free(CHECKED_CAST(_STACK *, STACK_OF(X509V3_EXT_METHOD) *, sk), \ + CHECKED_CAST(void (*)(void *), void (*)(X509V3_EXT_METHOD *), \ + free_func)) + +#define sk_X509V3_EXT_METHOD_insert(sk, p, where) \ + sk_insert(CHECKED_CAST(_STACK *, STACK_OF(X509V3_EXT_METHOD) *, sk), \ + CHECKED_CAST(void *, X509V3_EXT_METHOD *, p), (where)) + +#define sk_X509V3_EXT_METHOD_delete(sk, where) \ + ((X509V3_EXT_METHOD *)sk_delete( \ + CHECKED_CAST(_STACK *, STACK_OF(X509V3_EXT_METHOD) *, sk), (where))) + +#define sk_X509V3_EXT_METHOD_delete_ptr(sk, p) \ + ((X509V3_EXT_METHOD *)sk_delete_ptr( \ + CHECKED_CAST(_STACK *, STACK_OF(X509V3_EXT_METHOD) *, sk), \ + CHECKED_CAST(void *, X509V3_EXT_METHOD *, p))) + +#define sk_X509V3_EXT_METHOD_find(sk, out_index, p) \ + sk_find(CHECKED_CAST(_STACK *, STACK_OF(X509V3_EXT_METHOD) *, sk), \ + (out_index), CHECKED_CAST(void *, X509V3_EXT_METHOD *, p)) + +#define sk_X509V3_EXT_METHOD_shift(sk) \ + ((X509V3_EXT_METHOD *)sk_shift( \ + CHECKED_CAST(_STACK *, STACK_OF(X509V3_EXT_METHOD) *, sk))) + +#define sk_X509V3_EXT_METHOD_push(sk, p) \ + sk_push(CHECKED_CAST(_STACK *, STACK_OF(X509V3_EXT_METHOD) *, sk), \ + CHECKED_CAST(void *, X509V3_EXT_METHOD *, p)) + +#define sk_X509V3_EXT_METHOD_pop(sk) \ + ((X509V3_EXT_METHOD *)sk_pop( \ + CHECKED_CAST(_STACK *, STACK_OF(X509V3_EXT_METHOD) *, sk))) + +#define sk_X509V3_EXT_METHOD_dup(sk) \ + ((STACK_OF(X509V3_EXT_METHOD) *)sk_dup( \ + CHECKED_CAST(_STACK *, const STACK_OF(X509V3_EXT_METHOD) *, sk))) + +#define sk_X509V3_EXT_METHOD_sort(sk) \ + sk_sort(CHECKED_CAST(_STACK *, STACK_OF(X509V3_EXT_METHOD) *, sk)) + +#define sk_X509V3_EXT_METHOD_is_sorted(sk) \ + sk_is_sorted(CHECKED_CAST(_STACK *, const STACK_OF(X509V3_EXT_METHOD) *, sk)) + +#define sk_X509V3_EXT_METHOD_set_cmp_func(sk, comp) \ + ((int (*)(const X509V3_EXT_METHOD **a, const X509V3_EXT_METHOD **b)) \ + sk_set_cmp_func( \ + CHECKED_CAST(_STACK *, STACK_OF(X509V3_EXT_METHOD) *, sk), \ + CHECKED_CAST(stack_cmp_func, int (*)(const X509V3_EXT_METHOD **a, \ + const X509V3_EXT_METHOD **b), \ + comp))) + +#define sk_X509V3_EXT_METHOD_deep_copy(sk, copy_func, free_func) \ + ((STACK_OF(X509V3_EXT_METHOD) *)sk_deep_copy( \ + CHECKED_CAST(const _STACK *, const STACK_OF(X509V3_EXT_METHOD) *, sk), \ + CHECKED_CAST(void *(*)(void *), \ + X509V3_EXT_METHOD *(*)(X509V3_EXT_METHOD *), copy_func), \ + CHECKED_CAST(void (*)(void *), void (*)(X509V3_EXT_METHOD *), \ + free_func))) + +/* X509_ALGOR */ +#define sk_X509_ALGOR_new(comp) \ + ((STACK_OF(X509_ALGOR) *)sk_new(CHECKED_CAST( \ + stack_cmp_func, int (*)(const X509_ALGOR **a, const X509_ALGOR **b), \ + comp))) + +#define sk_X509_ALGOR_new_null() ((STACK_OF(X509_ALGOR) *)sk_new_null()) + +#define sk_X509_ALGOR_num(sk) \ + sk_num(CHECKED_CAST(_STACK *, STACK_OF(X509_ALGOR) *, sk)) + +#define sk_X509_ALGOR_zero(sk) \ + sk_zero(CHECKED_CAST(_STACK *, STACK_OF(X509_ALGOR) *, sk)); + +#define sk_X509_ALGOR_value(sk, i) \ + ((X509_ALGOR *)sk_value( \ + CHECKED_CAST(_STACK *, const STACK_OF(X509_ALGOR) *, sk), (i))) + +#define sk_X509_ALGOR_set(sk, i, p) \ + ((X509_ALGOR *)sk_set(CHECKED_CAST(_STACK *, STACK_OF(X509_ALGOR) *, sk), \ + (i), CHECKED_CAST(void *, X509_ALGOR *, p))) + +#define sk_X509_ALGOR_free(sk) \ + sk_free(CHECKED_CAST(_STACK *, STACK_OF(X509_ALGOR) *, sk)) + +#define sk_X509_ALGOR_pop_free(sk, free_func) \ + sk_pop_free( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_ALGOR) *, sk), \ + CHECKED_CAST(void (*)(void *), void (*)(X509_ALGOR *), free_func)) + +#define sk_X509_ALGOR_insert(sk, p, where) \ + sk_insert(CHECKED_CAST(_STACK *, STACK_OF(X509_ALGOR) *, sk), \ + CHECKED_CAST(void *, X509_ALGOR *, p), (where)) + +#define sk_X509_ALGOR_delete(sk, where) \ + ((X509_ALGOR *)sk_delete(CHECKED_CAST(_STACK *, STACK_OF(X509_ALGOR) *, sk), \ + (where))) + +#define sk_X509_ALGOR_delete_ptr(sk, p) \ + ((X509_ALGOR *)sk_delete_ptr( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_ALGOR) *, sk), \ + CHECKED_CAST(void *, X509_ALGOR *, p))) + +#define sk_X509_ALGOR_find(sk, out_index, p) \ + sk_find(CHECKED_CAST(_STACK *, STACK_OF(X509_ALGOR) *, sk), (out_index), \ + CHECKED_CAST(void *, X509_ALGOR *, p)) + +#define sk_X509_ALGOR_shift(sk) \ + ((X509_ALGOR *)sk_shift(CHECKED_CAST(_STACK *, STACK_OF(X509_ALGOR) *, sk))) + +#define sk_X509_ALGOR_push(sk, p) \ + sk_push(CHECKED_CAST(_STACK *, STACK_OF(X509_ALGOR) *, sk), \ + CHECKED_CAST(void *, X509_ALGOR *, p)) + +#define sk_X509_ALGOR_pop(sk) \ + ((X509_ALGOR *)sk_pop(CHECKED_CAST(_STACK *, STACK_OF(X509_ALGOR) *, sk))) + +#define sk_X509_ALGOR_dup(sk) \ + ((STACK_OF(X509_ALGOR) *)sk_dup( \ + CHECKED_CAST(_STACK *, const STACK_OF(X509_ALGOR) *, sk))) + +#define sk_X509_ALGOR_sort(sk) \ + sk_sort(CHECKED_CAST(_STACK *, STACK_OF(X509_ALGOR) *, sk)) + +#define sk_X509_ALGOR_is_sorted(sk) \ + sk_is_sorted(CHECKED_CAST(_STACK *, const STACK_OF(X509_ALGOR) *, sk)) + +#define sk_X509_ALGOR_set_cmp_func(sk, comp) \ + ((int (*)(const X509_ALGOR **a, const X509_ALGOR **b))sk_set_cmp_func( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_ALGOR) *, sk), \ + CHECKED_CAST(stack_cmp_func, \ + int (*)(const X509_ALGOR **a, const X509_ALGOR **b), \ + comp))) + +#define sk_X509_ALGOR_deep_copy(sk, copy_func, free_func) \ + ((STACK_OF(X509_ALGOR) *)sk_deep_copy( \ + CHECKED_CAST(const _STACK *, const STACK_OF(X509_ALGOR) *, sk), \ + CHECKED_CAST(void *(*)(void *), X509_ALGOR *(*)(X509_ALGOR *), \ + copy_func), \ + CHECKED_CAST(void (*)(void *), void (*)(X509_ALGOR *), free_func))) + +/* X509_ATTRIBUTE */ +#define sk_X509_ATTRIBUTE_new(comp) \ + ((STACK_OF(X509_ATTRIBUTE) *)sk_new(CHECKED_CAST( \ + stack_cmp_func, \ + int (*)(const X509_ATTRIBUTE **a, const X509_ATTRIBUTE **b), comp))) + +#define sk_X509_ATTRIBUTE_new_null() ((STACK_OF(X509_ATTRIBUTE) *)sk_new_null()) + +#define sk_X509_ATTRIBUTE_num(sk) \ + sk_num(CHECKED_CAST(_STACK *, STACK_OF(X509_ATTRIBUTE) *, sk)) + +#define sk_X509_ATTRIBUTE_zero(sk) \ + sk_zero(CHECKED_CAST(_STACK *, STACK_OF(X509_ATTRIBUTE) *, sk)); + +#define sk_X509_ATTRIBUTE_value(sk, i) \ + ((X509_ATTRIBUTE *)sk_value( \ + CHECKED_CAST(_STACK *, const STACK_OF(X509_ATTRIBUTE) *, sk), (i))) + +#define sk_X509_ATTRIBUTE_set(sk, i, p) \ + ((X509_ATTRIBUTE *)sk_set( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_ATTRIBUTE) *, sk), (i), \ + CHECKED_CAST(void *, X509_ATTRIBUTE *, p))) + +#define sk_X509_ATTRIBUTE_free(sk) \ + sk_free(CHECKED_CAST(_STACK *, STACK_OF(X509_ATTRIBUTE) *, sk)) + +#define sk_X509_ATTRIBUTE_pop_free(sk, free_func) \ + sk_pop_free( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_ATTRIBUTE) *, sk), \ + CHECKED_CAST(void (*)(void *), void (*)(X509_ATTRIBUTE *), free_func)) + +#define sk_X509_ATTRIBUTE_insert(sk, p, where) \ + sk_insert(CHECKED_CAST(_STACK *, STACK_OF(X509_ATTRIBUTE) *, sk), \ + CHECKED_CAST(void *, X509_ATTRIBUTE *, p), (where)) + +#define sk_X509_ATTRIBUTE_delete(sk, where) \ + ((X509_ATTRIBUTE *)sk_delete( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_ATTRIBUTE) *, sk), (where))) + +#define sk_X509_ATTRIBUTE_delete_ptr(sk, p) \ + ((X509_ATTRIBUTE *)sk_delete_ptr( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_ATTRIBUTE) *, sk), \ + CHECKED_CAST(void *, X509_ATTRIBUTE *, p))) + +#define sk_X509_ATTRIBUTE_find(sk, out_index, p) \ + sk_find(CHECKED_CAST(_STACK *, STACK_OF(X509_ATTRIBUTE) *, sk), (out_index), \ + CHECKED_CAST(void *, X509_ATTRIBUTE *, p)) + +#define sk_X509_ATTRIBUTE_shift(sk) \ + ((X509_ATTRIBUTE *)sk_shift( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_ATTRIBUTE) *, sk))) + +#define sk_X509_ATTRIBUTE_push(sk, p) \ + sk_push(CHECKED_CAST(_STACK *, STACK_OF(X509_ATTRIBUTE) *, sk), \ + CHECKED_CAST(void *, X509_ATTRIBUTE *, p)) + +#define sk_X509_ATTRIBUTE_pop(sk) \ + ((X509_ATTRIBUTE *)sk_pop( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_ATTRIBUTE) *, sk))) + +#define sk_X509_ATTRIBUTE_dup(sk) \ + ((STACK_OF(X509_ATTRIBUTE) *)sk_dup( \ + CHECKED_CAST(_STACK *, const STACK_OF(X509_ATTRIBUTE) *, sk))) + +#define sk_X509_ATTRIBUTE_sort(sk) \ + sk_sort(CHECKED_CAST(_STACK *, STACK_OF(X509_ATTRIBUTE) *, sk)) + +#define sk_X509_ATTRIBUTE_is_sorted(sk) \ + sk_is_sorted(CHECKED_CAST(_STACK *, const STACK_OF(X509_ATTRIBUTE) *, sk)) + +#define sk_X509_ATTRIBUTE_set_cmp_func(sk, comp) \ + ((int (*)(const X509_ATTRIBUTE **a, const X509_ATTRIBUTE **b)) \ + sk_set_cmp_func( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_ATTRIBUTE) *, sk), \ + CHECKED_CAST(stack_cmp_func, int (*)(const X509_ATTRIBUTE **a, \ + const X509_ATTRIBUTE **b), \ + comp))) + +#define sk_X509_ATTRIBUTE_deep_copy(sk, copy_func, free_func) \ + ((STACK_OF(X509_ATTRIBUTE) *)sk_deep_copy( \ + CHECKED_CAST(const _STACK *, const STACK_OF(X509_ATTRIBUTE) *, sk), \ + CHECKED_CAST(void *(*)(void *), X509_ATTRIBUTE *(*)(X509_ATTRIBUTE *), \ + copy_func), \ + CHECKED_CAST(void (*)(void *), void (*)(X509_ATTRIBUTE *), free_func))) + +/* X509_CRL */ +#define sk_X509_CRL_new(comp) \ + ((STACK_OF(X509_CRL) *)sk_new(CHECKED_CAST( \ + stack_cmp_func, int (*)(const X509_CRL **a, const X509_CRL **b), comp))) + +#define sk_X509_CRL_new_null() ((STACK_OF(X509_CRL) *)sk_new_null()) + +#define sk_X509_CRL_num(sk) \ + sk_num(CHECKED_CAST(_STACK *, STACK_OF(X509_CRL) *, sk)) + +#define sk_X509_CRL_zero(sk) \ + sk_zero(CHECKED_CAST(_STACK *, STACK_OF(X509_CRL) *, sk)); + +#define sk_X509_CRL_value(sk, i) \ + ((X509_CRL *)sk_value( \ + CHECKED_CAST(_STACK *, const STACK_OF(X509_CRL) *, sk), (i))) + +#define sk_X509_CRL_set(sk, i, p) \ + ((X509_CRL *)sk_set(CHECKED_CAST(_STACK *, STACK_OF(X509_CRL) *, sk), (i), \ + CHECKED_CAST(void *, X509_CRL *, p))) + +#define sk_X509_CRL_free(sk) \ + sk_free(CHECKED_CAST(_STACK *, STACK_OF(X509_CRL) *, sk)) + +#define sk_X509_CRL_pop_free(sk, free_func) \ + sk_pop_free(CHECKED_CAST(_STACK *, STACK_OF(X509_CRL) *, sk), \ + CHECKED_CAST(void (*)(void *), void (*)(X509_CRL *), free_func)) + +#define sk_X509_CRL_insert(sk, p, where) \ + sk_insert(CHECKED_CAST(_STACK *, STACK_OF(X509_CRL) *, sk), \ + CHECKED_CAST(void *, X509_CRL *, p), (where)) + +#define sk_X509_CRL_delete(sk, where) \ + ((X509_CRL *)sk_delete(CHECKED_CAST(_STACK *, STACK_OF(X509_CRL) *, sk), \ + (where))) + +#define sk_X509_CRL_delete_ptr(sk, p) \ + ((X509_CRL *)sk_delete_ptr(CHECKED_CAST(_STACK *, STACK_OF(X509_CRL) *, sk), \ + CHECKED_CAST(void *, X509_CRL *, p))) + +#define sk_X509_CRL_find(sk, out_index, p) \ + sk_find(CHECKED_CAST(_STACK *, STACK_OF(X509_CRL) *, sk), (out_index), \ + CHECKED_CAST(void *, X509_CRL *, p)) + +#define sk_X509_CRL_shift(sk) \ + ((X509_CRL *)sk_shift(CHECKED_CAST(_STACK *, STACK_OF(X509_CRL) *, sk))) + +#define sk_X509_CRL_push(sk, p) \ + sk_push(CHECKED_CAST(_STACK *, STACK_OF(X509_CRL) *, sk), \ + CHECKED_CAST(void *, X509_CRL *, p)) + +#define sk_X509_CRL_pop(sk) \ + ((X509_CRL *)sk_pop(CHECKED_CAST(_STACK *, STACK_OF(X509_CRL) *, sk))) + +#define sk_X509_CRL_dup(sk) \ + ((STACK_OF(X509_CRL) *)sk_dup( \ + CHECKED_CAST(_STACK *, const STACK_OF(X509_CRL) *, sk))) + +#define sk_X509_CRL_sort(sk) \ + sk_sort(CHECKED_CAST(_STACK *, STACK_OF(X509_CRL) *, sk)) + +#define sk_X509_CRL_is_sorted(sk) \ + sk_is_sorted(CHECKED_CAST(_STACK *, const STACK_OF(X509_CRL) *, sk)) + +#define sk_X509_CRL_set_cmp_func(sk, comp) \ + ((int (*)(const X509_CRL **a, const X509_CRL **b))sk_set_cmp_func( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_CRL) *, sk), \ + CHECKED_CAST(stack_cmp_func, \ + int (*)(const X509_CRL **a, const X509_CRL **b), comp))) + +#define sk_X509_CRL_deep_copy(sk, copy_func, free_func) \ + ((STACK_OF(X509_CRL) *)sk_deep_copy( \ + CHECKED_CAST(const _STACK *, const STACK_OF(X509_CRL) *, sk), \ + CHECKED_CAST(void *(*)(void *), X509_CRL *(*)(X509_CRL *), copy_func), \ + CHECKED_CAST(void (*)(void *), void (*)(X509_CRL *), free_func))) + +/* X509_EXTENSION */ +#define sk_X509_EXTENSION_new(comp) \ + ((STACK_OF(X509_EXTENSION) *)sk_new(CHECKED_CAST( \ + stack_cmp_func, \ + int (*)(const X509_EXTENSION **a, const X509_EXTENSION **b), comp))) + +#define sk_X509_EXTENSION_new_null() ((STACK_OF(X509_EXTENSION) *)sk_new_null()) + +#define sk_X509_EXTENSION_num(sk) \ + sk_num(CHECKED_CAST(_STACK *, STACK_OF(X509_EXTENSION) *, sk)) + +#define sk_X509_EXTENSION_zero(sk) \ + sk_zero(CHECKED_CAST(_STACK *, STACK_OF(X509_EXTENSION) *, sk)); + +#define sk_X509_EXTENSION_value(sk, i) \ + ((X509_EXTENSION *)sk_value( \ + CHECKED_CAST(_STACK *, const STACK_OF(X509_EXTENSION) *, sk), (i))) + +#define sk_X509_EXTENSION_set(sk, i, p) \ + ((X509_EXTENSION *)sk_set( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_EXTENSION) *, sk), (i), \ + CHECKED_CAST(void *, X509_EXTENSION *, p))) + +#define sk_X509_EXTENSION_free(sk) \ + sk_free(CHECKED_CAST(_STACK *, STACK_OF(X509_EXTENSION) *, sk)) + +#define sk_X509_EXTENSION_pop_free(sk, free_func) \ + sk_pop_free( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_EXTENSION) *, sk), \ + CHECKED_CAST(void (*)(void *), void (*)(X509_EXTENSION *), free_func)) + +#define sk_X509_EXTENSION_insert(sk, p, where) \ + sk_insert(CHECKED_CAST(_STACK *, STACK_OF(X509_EXTENSION) *, sk), \ + CHECKED_CAST(void *, X509_EXTENSION *, p), (where)) + +#define sk_X509_EXTENSION_delete(sk, where) \ + ((X509_EXTENSION *)sk_delete( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_EXTENSION) *, sk), (where))) + +#define sk_X509_EXTENSION_delete_ptr(sk, p) \ + ((X509_EXTENSION *)sk_delete_ptr( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_EXTENSION) *, sk), \ + CHECKED_CAST(void *, X509_EXTENSION *, p))) + +#define sk_X509_EXTENSION_find(sk, out_index, p) \ + sk_find(CHECKED_CAST(_STACK *, STACK_OF(X509_EXTENSION) *, sk), (out_index), \ + CHECKED_CAST(void *, X509_EXTENSION *, p)) + +#define sk_X509_EXTENSION_shift(sk) \ + ((X509_EXTENSION *)sk_shift( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_EXTENSION) *, sk))) + +#define sk_X509_EXTENSION_push(sk, p) \ + sk_push(CHECKED_CAST(_STACK *, STACK_OF(X509_EXTENSION) *, sk), \ + CHECKED_CAST(void *, X509_EXTENSION *, p)) + +#define sk_X509_EXTENSION_pop(sk) \ + ((X509_EXTENSION *)sk_pop( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_EXTENSION) *, sk))) + +#define sk_X509_EXTENSION_dup(sk) \ + ((STACK_OF(X509_EXTENSION) *)sk_dup( \ + CHECKED_CAST(_STACK *, const STACK_OF(X509_EXTENSION) *, sk))) + +#define sk_X509_EXTENSION_sort(sk) \ + sk_sort(CHECKED_CAST(_STACK *, STACK_OF(X509_EXTENSION) *, sk)) + +#define sk_X509_EXTENSION_is_sorted(sk) \ + sk_is_sorted(CHECKED_CAST(_STACK *, const STACK_OF(X509_EXTENSION) *, sk)) + +#define sk_X509_EXTENSION_set_cmp_func(sk, comp) \ + ((int (*)(const X509_EXTENSION **a, const X509_EXTENSION **b)) \ + sk_set_cmp_func( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_EXTENSION) *, sk), \ + CHECKED_CAST(stack_cmp_func, int (*)(const X509_EXTENSION **a, \ + const X509_EXTENSION **b), \ + comp))) + +#define sk_X509_EXTENSION_deep_copy(sk, copy_func, free_func) \ + ((STACK_OF(X509_EXTENSION) *)sk_deep_copy( \ + CHECKED_CAST(const _STACK *, const STACK_OF(X509_EXTENSION) *, sk), \ + CHECKED_CAST(void *(*)(void *), X509_EXTENSION *(*)(X509_EXTENSION *), \ + copy_func), \ + CHECKED_CAST(void (*)(void *), void (*)(X509_EXTENSION *), free_func))) + +/* X509_INFO */ +#define sk_X509_INFO_new(comp) \ + ((STACK_OF(X509_INFO) *)sk_new( \ + CHECKED_CAST(stack_cmp_func, \ + int (*)(const X509_INFO **a, const X509_INFO **b), comp))) + +#define sk_X509_INFO_new_null() ((STACK_OF(X509_INFO) *)sk_new_null()) + +#define sk_X509_INFO_num(sk) \ + sk_num(CHECKED_CAST(_STACK *, STACK_OF(X509_INFO) *, sk)) + +#define sk_X509_INFO_zero(sk) \ + sk_zero(CHECKED_CAST(_STACK *, STACK_OF(X509_INFO) *, sk)); + +#define sk_X509_INFO_value(sk, i) \ + ((X509_INFO *)sk_value( \ + CHECKED_CAST(_STACK *, const STACK_OF(X509_INFO) *, sk), (i))) + +#define sk_X509_INFO_set(sk, i, p) \ + ((X509_INFO *)sk_set(CHECKED_CAST(_STACK *, STACK_OF(X509_INFO) *, sk), (i), \ + CHECKED_CAST(void *, X509_INFO *, p))) + +#define sk_X509_INFO_free(sk) \ + sk_free(CHECKED_CAST(_STACK *, STACK_OF(X509_INFO) *, sk)) + +#define sk_X509_INFO_pop_free(sk, free_func) \ + sk_pop_free( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_INFO) *, sk), \ + CHECKED_CAST(void (*)(void *), void (*)(X509_INFO *), free_func)) + +#define sk_X509_INFO_insert(sk, p, where) \ + sk_insert(CHECKED_CAST(_STACK *, STACK_OF(X509_INFO) *, sk), \ + CHECKED_CAST(void *, X509_INFO *, p), (where)) + +#define sk_X509_INFO_delete(sk, where) \ + ((X509_INFO *)sk_delete(CHECKED_CAST(_STACK *, STACK_OF(X509_INFO) *, sk), \ + (where))) + +#define sk_X509_INFO_delete_ptr(sk, p) \ + ((X509_INFO *)sk_delete_ptr( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_INFO) *, sk), \ + CHECKED_CAST(void *, X509_INFO *, p))) + +#define sk_X509_INFO_find(sk, out_index, p) \ + sk_find(CHECKED_CAST(_STACK *, STACK_OF(X509_INFO) *, sk), (out_index), \ + CHECKED_CAST(void *, X509_INFO *, p)) + +#define sk_X509_INFO_shift(sk) \ + ((X509_INFO *)sk_shift(CHECKED_CAST(_STACK *, STACK_OF(X509_INFO) *, sk))) + +#define sk_X509_INFO_push(sk, p) \ + sk_push(CHECKED_CAST(_STACK *, STACK_OF(X509_INFO) *, sk), \ + CHECKED_CAST(void *, X509_INFO *, p)) + +#define sk_X509_INFO_pop(sk) \ + ((X509_INFO *)sk_pop(CHECKED_CAST(_STACK *, STACK_OF(X509_INFO) *, sk))) + +#define sk_X509_INFO_dup(sk) \ + ((STACK_OF(X509_INFO) *)sk_dup( \ + CHECKED_CAST(_STACK *, const STACK_OF(X509_INFO) *, sk))) + +#define sk_X509_INFO_sort(sk) \ + sk_sort(CHECKED_CAST(_STACK *, STACK_OF(X509_INFO) *, sk)) + +#define sk_X509_INFO_is_sorted(sk) \ + sk_is_sorted(CHECKED_CAST(_STACK *, const STACK_OF(X509_INFO) *, sk)) + +#define sk_X509_INFO_set_cmp_func(sk, comp) \ + ((int (*)(const X509_INFO **a, const X509_INFO **b))sk_set_cmp_func( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_INFO) *, sk), \ + CHECKED_CAST(stack_cmp_func, \ + int (*)(const X509_INFO **a, const X509_INFO **b), comp))) + +#define sk_X509_INFO_deep_copy(sk, copy_func, free_func) \ + ((STACK_OF(X509_INFO) *)sk_deep_copy( \ + CHECKED_CAST(const _STACK *, const STACK_OF(X509_INFO) *, sk), \ + CHECKED_CAST(void *(*)(void *), X509_INFO *(*)(X509_INFO *), copy_func), \ + CHECKED_CAST(void (*)(void *), void (*)(X509_INFO *), free_func))) + +/* X509_LOOKUP */ +#define sk_X509_LOOKUP_new(comp) \ + ((STACK_OF(X509_LOOKUP) *)sk_new(CHECKED_CAST( \ + stack_cmp_func, int (*)(const X509_LOOKUP **a, const X509_LOOKUP **b), \ + comp))) + +#define sk_X509_LOOKUP_new_null() ((STACK_OF(X509_LOOKUP) *)sk_new_null()) + +#define sk_X509_LOOKUP_num(sk) \ + sk_num(CHECKED_CAST(_STACK *, STACK_OF(X509_LOOKUP) *, sk)) + +#define sk_X509_LOOKUP_zero(sk) \ + sk_zero(CHECKED_CAST(_STACK *, STACK_OF(X509_LOOKUP) *, sk)); + +#define sk_X509_LOOKUP_value(sk, i) \ + ((X509_LOOKUP *)sk_value( \ + CHECKED_CAST(_STACK *, const STACK_OF(X509_LOOKUP) *, sk), (i))) + +#define sk_X509_LOOKUP_set(sk, i, p) \ + ((X509_LOOKUP *)sk_set(CHECKED_CAST(_STACK *, STACK_OF(X509_LOOKUP) *, sk), \ + (i), CHECKED_CAST(void *, X509_LOOKUP *, p))) + +#define sk_X509_LOOKUP_free(sk) \ + sk_free(CHECKED_CAST(_STACK *, STACK_OF(X509_LOOKUP) *, sk)) + +#define sk_X509_LOOKUP_pop_free(sk, free_func) \ + sk_pop_free( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_LOOKUP) *, sk), \ + CHECKED_CAST(void (*)(void *), void (*)(X509_LOOKUP *), free_func)) + +#define sk_X509_LOOKUP_insert(sk, p, where) \ + sk_insert(CHECKED_CAST(_STACK *, STACK_OF(X509_LOOKUP) *, sk), \ + CHECKED_CAST(void *, X509_LOOKUP *, p), (where)) + +#define sk_X509_LOOKUP_delete(sk, where) \ + ((X509_LOOKUP *)sk_delete( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_LOOKUP) *, sk), (where))) + +#define sk_X509_LOOKUP_delete_ptr(sk, p) \ + ((X509_LOOKUP *)sk_delete_ptr( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_LOOKUP) *, sk), \ + CHECKED_CAST(void *, X509_LOOKUP *, p))) + +#define sk_X509_LOOKUP_find(sk, out_index, p) \ + sk_find(CHECKED_CAST(_STACK *, STACK_OF(X509_LOOKUP) *, sk), (out_index), \ + CHECKED_CAST(void *, X509_LOOKUP *, p)) + +#define sk_X509_LOOKUP_shift(sk) \ + ((X509_LOOKUP *)sk_shift(CHECKED_CAST(_STACK *, STACK_OF(X509_LOOKUP) *, sk))) + +#define sk_X509_LOOKUP_push(sk, p) \ + sk_push(CHECKED_CAST(_STACK *, STACK_OF(X509_LOOKUP) *, sk), \ + CHECKED_CAST(void *, X509_LOOKUP *, p)) + +#define sk_X509_LOOKUP_pop(sk) \ + ((X509_LOOKUP *)sk_pop(CHECKED_CAST(_STACK *, STACK_OF(X509_LOOKUP) *, sk))) + +#define sk_X509_LOOKUP_dup(sk) \ + ((STACK_OF(X509_LOOKUP) *)sk_dup( \ + CHECKED_CAST(_STACK *, const STACK_OF(X509_LOOKUP) *, sk))) + +#define sk_X509_LOOKUP_sort(sk) \ + sk_sort(CHECKED_CAST(_STACK *, STACK_OF(X509_LOOKUP) *, sk)) + +#define sk_X509_LOOKUP_is_sorted(sk) \ + sk_is_sorted(CHECKED_CAST(_STACK *, const STACK_OF(X509_LOOKUP) *, sk)) + +#define sk_X509_LOOKUP_set_cmp_func(sk, comp) \ + ((int (*)(const X509_LOOKUP **a, const X509_LOOKUP **b))sk_set_cmp_func( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_LOOKUP) *, sk), \ + CHECKED_CAST(stack_cmp_func, \ + int (*)(const X509_LOOKUP **a, const X509_LOOKUP **b), \ + comp))) + +#define sk_X509_LOOKUP_deep_copy(sk, copy_func, free_func) \ + ((STACK_OF(X509_LOOKUP) *)sk_deep_copy( \ + CHECKED_CAST(const _STACK *, const STACK_OF(X509_LOOKUP) *, sk), \ + CHECKED_CAST(void *(*)(void *), X509_LOOKUP *(*)(X509_LOOKUP *), \ + copy_func), \ + CHECKED_CAST(void (*)(void *), void (*)(X509_LOOKUP *), free_func))) + +/* X509_NAME */ +#define sk_X509_NAME_new(comp) \ + ((STACK_OF(X509_NAME) *)sk_new( \ + CHECKED_CAST(stack_cmp_func, \ + int (*)(const X509_NAME **a, const X509_NAME **b), comp))) + +#define sk_X509_NAME_new_null() ((STACK_OF(X509_NAME) *)sk_new_null()) + +#define sk_X509_NAME_num(sk) \ + sk_num(CHECKED_CAST(_STACK *, STACK_OF(X509_NAME) *, sk)) + +#define sk_X509_NAME_zero(sk) \ + sk_zero(CHECKED_CAST(_STACK *, STACK_OF(X509_NAME) *, sk)); + +#define sk_X509_NAME_value(sk, i) \ + ((X509_NAME *)sk_value( \ + CHECKED_CAST(_STACK *, const STACK_OF(X509_NAME) *, sk), (i))) + +#define sk_X509_NAME_set(sk, i, p) \ + ((X509_NAME *)sk_set(CHECKED_CAST(_STACK *, STACK_OF(X509_NAME) *, sk), (i), \ + CHECKED_CAST(void *, X509_NAME *, p))) + +#define sk_X509_NAME_free(sk) \ + sk_free(CHECKED_CAST(_STACK *, STACK_OF(X509_NAME) *, sk)) + +#define sk_X509_NAME_pop_free(sk, free_func) \ + sk_pop_free( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_NAME) *, sk), \ + CHECKED_CAST(void (*)(void *), void (*)(X509_NAME *), free_func)) + +#define sk_X509_NAME_insert(sk, p, where) \ + sk_insert(CHECKED_CAST(_STACK *, STACK_OF(X509_NAME) *, sk), \ + CHECKED_CAST(void *, X509_NAME *, p), (where)) + +#define sk_X509_NAME_delete(sk, where) \ + ((X509_NAME *)sk_delete(CHECKED_CAST(_STACK *, STACK_OF(X509_NAME) *, sk), \ + (where))) + +#define sk_X509_NAME_delete_ptr(sk, p) \ + ((X509_NAME *)sk_delete_ptr( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_NAME) *, sk), \ + CHECKED_CAST(void *, X509_NAME *, p))) + +#define sk_X509_NAME_find(sk, out_index, p) \ + sk_find(CHECKED_CAST(_STACK *, STACK_OF(X509_NAME) *, sk), (out_index), \ + CHECKED_CAST(void *, X509_NAME *, p)) + +#define sk_X509_NAME_shift(sk) \ + ((X509_NAME *)sk_shift(CHECKED_CAST(_STACK *, STACK_OF(X509_NAME) *, sk))) + +#define sk_X509_NAME_push(sk, p) \ + sk_push(CHECKED_CAST(_STACK *, STACK_OF(X509_NAME) *, sk), \ + CHECKED_CAST(void *, X509_NAME *, p)) + +#define sk_X509_NAME_pop(sk) \ + ((X509_NAME *)sk_pop(CHECKED_CAST(_STACK *, STACK_OF(X509_NAME) *, sk))) + +#define sk_X509_NAME_dup(sk) \ + ((STACK_OF(X509_NAME) *)sk_dup( \ + CHECKED_CAST(_STACK *, const STACK_OF(X509_NAME) *, sk))) + +#define sk_X509_NAME_sort(sk) \ + sk_sort(CHECKED_CAST(_STACK *, STACK_OF(X509_NAME) *, sk)) + +#define sk_X509_NAME_is_sorted(sk) \ + sk_is_sorted(CHECKED_CAST(_STACK *, const STACK_OF(X509_NAME) *, sk)) + +#define sk_X509_NAME_set_cmp_func(sk, comp) \ + ((int (*)(const X509_NAME **a, const X509_NAME **b))sk_set_cmp_func( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_NAME) *, sk), \ + CHECKED_CAST(stack_cmp_func, \ + int (*)(const X509_NAME **a, const X509_NAME **b), comp))) + +#define sk_X509_NAME_deep_copy(sk, copy_func, free_func) \ + ((STACK_OF(X509_NAME) *)sk_deep_copy( \ + CHECKED_CAST(const _STACK *, const STACK_OF(X509_NAME) *, sk), \ + CHECKED_CAST(void *(*)(void *), X509_NAME *(*)(X509_NAME *), copy_func), \ + CHECKED_CAST(void (*)(void *), void (*)(X509_NAME *), free_func))) + +/* X509_NAME_ENTRY */ +#define sk_X509_NAME_ENTRY_new(comp) \ + ((STACK_OF(X509_NAME_ENTRY) *)sk_new(CHECKED_CAST( \ + stack_cmp_func, \ + int (*)(const X509_NAME_ENTRY **a, const X509_NAME_ENTRY **b), comp))) + +#define sk_X509_NAME_ENTRY_new_null() \ + ((STACK_OF(X509_NAME_ENTRY) *)sk_new_null()) + +#define sk_X509_NAME_ENTRY_num(sk) \ + sk_num(CHECKED_CAST(_STACK *, STACK_OF(X509_NAME_ENTRY) *, sk)) + +#define sk_X509_NAME_ENTRY_zero(sk) \ + sk_zero(CHECKED_CAST(_STACK *, STACK_OF(X509_NAME_ENTRY) *, sk)); + +#define sk_X509_NAME_ENTRY_value(sk, i) \ + ((X509_NAME_ENTRY *)sk_value( \ + CHECKED_CAST(_STACK *, const STACK_OF(X509_NAME_ENTRY) *, sk), (i))) + +#define sk_X509_NAME_ENTRY_set(sk, i, p) \ + ((X509_NAME_ENTRY *)sk_set( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_NAME_ENTRY) *, sk), (i), \ + CHECKED_CAST(void *, X509_NAME_ENTRY *, p))) + +#define sk_X509_NAME_ENTRY_free(sk) \ + sk_free(CHECKED_CAST(_STACK *, STACK_OF(X509_NAME_ENTRY) *, sk)) + +#define sk_X509_NAME_ENTRY_pop_free(sk, free_func) \ + sk_pop_free( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_NAME_ENTRY) *, sk), \ + CHECKED_CAST(void (*)(void *), void (*)(X509_NAME_ENTRY *), free_func)) + +#define sk_X509_NAME_ENTRY_insert(sk, p, where) \ + sk_insert(CHECKED_CAST(_STACK *, STACK_OF(X509_NAME_ENTRY) *, sk), \ + CHECKED_CAST(void *, X509_NAME_ENTRY *, p), (where)) + +#define sk_X509_NAME_ENTRY_delete(sk, where) \ + ((X509_NAME_ENTRY *)sk_delete( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_NAME_ENTRY) *, sk), (where))) + +#define sk_X509_NAME_ENTRY_delete_ptr(sk, p) \ + ((X509_NAME_ENTRY *)sk_delete_ptr( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_NAME_ENTRY) *, sk), \ + CHECKED_CAST(void *, X509_NAME_ENTRY *, p))) + +#define sk_X509_NAME_ENTRY_find(sk, out_index, p) \ + sk_find(CHECKED_CAST(_STACK *, STACK_OF(X509_NAME_ENTRY) *, sk), \ + (out_index), CHECKED_CAST(void *, X509_NAME_ENTRY *, p)) + +#define sk_X509_NAME_ENTRY_shift(sk) \ + ((X509_NAME_ENTRY *)sk_shift( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_NAME_ENTRY) *, sk))) + +#define sk_X509_NAME_ENTRY_push(sk, p) \ + sk_push(CHECKED_CAST(_STACK *, STACK_OF(X509_NAME_ENTRY) *, sk), \ + CHECKED_CAST(void *, X509_NAME_ENTRY *, p)) + +#define sk_X509_NAME_ENTRY_pop(sk) \ + ((X509_NAME_ENTRY *)sk_pop( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_NAME_ENTRY) *, sk))) + +#define sk_X509_NAME_ENTRY_dup(sk) \ + ((STACK_OF(X509_NAME_ENTRY) *)sk_dup( \ + CHECKED_CAST(_STACK *, const STACK_OF(X509_NAME_ENTRY) *, sk))) + +#define sk_X509_NAME_ENTRY_sort(sk) \ + sk_sort(CHECKED_CAST(_STACK *, STACK_OF(X509_NAME_ENTRY) *, sk)) + +#define sk_X509_NAME_ENTRY_is_sorted(sk) \ + sk_is_sorted(CHECKED_CAST(_STACK *, const STACK_OF(X509_NAME_ENTRY) *, sk)) + +#define sk_X509_NAME_ENTRY_set_cmp_func(sk, comp) \ + ((int (*)(const X509_NAME_ENTRY **a, const X509_NAME_ENTRY **b)) \ + sk_set_cmp_func( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_NAME_ENTRY) *, sk), \ + CHECKED_CAST(stack_cmp_func, int (*)(const X509_NAME_ENTRY **a, \ + const X509_NAME_ENTRY **b), \ + comp))) + +#define sk_X509_NAME_ENTRY_deep_copy(sk, copy_func, free_func) \ + ((STACK_OF(X509_NAME_ENTRY) *)sk_deep_copy( \ + CHECKED_CAST(const _STACK *, const STACK_OF(X509_NAME_ENTRY) *, sk), \ + CHECKED_CAST(void *(*)(void *), X509_NAME_ENTRY *(*)(X509_NAME_ENTRY *), \ + copy_func), \ + CHECKED_CAST(void (*)(void *), void (*)(X509_NAME_ENTRY *), free_func))) + +/* X509_OBJECT */ +#define sk_X509_OBJECT_new(comp) \ + ((STACK_OF(X509_OBJECT) *)sk_new(CHECKED_CAST( \ + stack_cmp_func, int (*)(const X509_OBJECT **a, const X509_OBJECT **b), \ + comp))) + +#define sk_X509_OBJECT_new_null() ((STACK_OF(X509_OBJECT) *)sk_new_null()) + +#define sk_X509_OBJECT_num(sk) \ + sk_num(CHECKED_CAST(_STACK *, STACK_OF(X509_OBJECT) *, sk)) + +#define sk_X509_OBJECT_zero(sk) \ + sk_zero(CHECKED_CAST(_STACK *, STACK_OF(X509_OBJECT) *, sk)); + +#define sk_X509_OBJECT_value(sk, i) \ + ((X509_OBJECT *)sk_value( \ + CHECKED_CAST(_STACK *, const STACK_OF(X509_OBJECT) *, sk), (i))) + +#define sk_X509_OBJECT_set(sk, i, p) \ + ((X509_OBJECT *)sk_set(CHECKED_CAST(_STACK *, STACK_OF(X509_OBJECT) *, sk), \ + (i), CHECKED_CAST(void *, X509_OBJECT *, p))) + +#define sk_X509_OBJECT_free(sk) \ + sk_free(CHECKED_CAST(_STACK *, STACK_OF(X509_OBJECT) *, sk)) + +#define sk_X509_OBJECT_pop_free(sk, free_func) \ + sk_pop_free( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_OBJECT) *, sk), \ + CHECKED_CAST(void (*)(void *), void (*)(X509_OBJECT *), free_func)) + +#define sk_X509_OBJECT_insert(sk, p, where) \ + sk_insert(CHECKED_CAST(_STACK *, STACK_OF(X509_OBJECT) *, sk), \ + CHECKED_CAST(void *, X509_OBJECT *, p), (where)) + +#define sk_X509_OBJECT_delete(sk, where) \ + ((X509_OBJECT *)sk_delete( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_OBJECT) *, sk), (where))) + +#define sk_X509_OBJECT_delete_ptr(sk, p) \ + ((X509_OBJECT *)sk_delete_ptr( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_OBJECT) *, sk), \ + CHECKED_CAST(void *, X509_OBJECT *, p))) + +#define sk_X509_OBJECT_find(sk, out_index, p) \ + sk_find(CHECKED_CAST(_STACK *, STACK_OF(X509_OBJECT) *, sk), (out_index), \ + CHECKED_CAST(void *, X509_OBJECT *, p)) + +#define sk_X509_OBJECT_shift(sk) \ + ((X509_OBJECT *)sk_shift(CHECKED_CAST(_STACK *, STACK_OF(X509_OBJECT) *, sk))) + +#define sk_X509_OBJECT_push(sk, p) \ + sk_push(CHECKED_CAST(_STACK *, STACK_OF(X509_OBJECT) *, sk), \ + CHECKED_CAST(void *, X509_OBJECT *, p)) + +#define sk_X509_OBJECT_pop(sk) \ + ((X509_OBJECT *)sk_pop(CHECKED_CAST(_STACK *, STACK_OF(X509_OBJECT) *, sk))) + +#define sk_X509_OBJECT_dup(sk) \ + ((STACK_OF(X509_OBJECT) *)sk_dup( \ + CHECKED_CAST(_STACK *, const STACK_OF(X509_OBJECT) *, sk))) + +#define sk_X509_OBJECT_sort(sk) \ + sk_sort(CHECKED_CAST(_STACK *, STACK_OF(X509_OBJECT) *, sk)) + +#define sk_X509_OBJECT_is_sorted(sk) \ + sk_is_sorted(CHECKED_CAST(_STACK *, const STACK_OF(X509_OBJECT) *, sk)) + +#define sk_X509_OBJECT_set_cmp_func(sk, comp) \ + ((int (*)(const X509_OBJECT **a, const X509_OBJECT **b))sk_set_cmp_func( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_OBJECT) *, sk), \ + CHECKED_CAST(stack_cmp_func, \ + int (*)(const X509_OBJECT **a, const X509_OBJECT **b), \ + comp))) + +#define sk_X509_OBJECT_deep_copy(sk, copy_func, free_func) \ + ((STACK_OF(X509_OBJECT) *)sk_deep_copy( \ + CHECKED_CAST(const _STACK *, const STACK_OF(X509_OBJECT) *, sk), \ + CHECKED_CAST(void *(*)(void *), X509_OBJECT *(*)(X509_OBJECT *), \ + copy_func), \ + CHECKED_CAST(void (*)(void *), void (*)(X509_OBJECT *), free_func))) + +/* X509_POLICY_DATA */ +#define sk_X509_POLICY_DATA_new(comp) \ + ((STACK_OF(X509_POLICY_DATA) *)sk_new(CHECKED_CAST( \ + stack_cmp_func, \ + int (*)(const X509_POLICY_DATA **a, const X509_POLICY_DATA **b), comp))) + +#define sk_X509_POLICY_DATA_new_null() \ + ((STACK_OF(X509_POLICY_DATA) *)sk_new_null()) + +#define sk_X509_POLICY_DATA_num(sk) \ + sk_num(CHECKED_CAST(_STACK *, STACK_OF(X509_POLICY_DATA) *, sk)) + +#define sk_X509_POLICY_DATA_zero(sk) \ + sk_zero(CHECKED_CAST(_STACK *, STACK_OF(X509_POLICY_DATA) *, sk)); + +#define sk_X509_POLICY_DATA_value(sk, i) \ + ((X509_POLICY_DATA *)sk_value( \ + CHECKED_CAST(_STACK *, const STACK_OF(X509_POLICY_DATA) *, sk), (i))) + +#define sk_X509_POLICY_DATA_set(sk, i, p) \ + ((X509_POLICY_DATA *)sk_set( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_POLICY_DATA) *, sk), (i), \ + CHECKED_CAST(void *, X509_POLICY_DATA *, p))) + +#define sk_X509_POLICY_DATA_free(sk) \ + sk_free(CHECKED_CAST(_STACK *, STACK_OF(X509_POLICY_DATA) *, sk)) + +#define sk_X509_POLICY_DATA_pop_free(sk, free_func) \ + sk_pop_free( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_POLICY_DATA) *, sk), \ + CHECKED_CAST(void (*)(void *), void (*)(X509_POLICY_DATA *), free_func)) + +#define sk_X509_POLICY_DATA_insert(sk, p, where) \ + sk_insert(CHECKED_CAST(_STACK *, STACK_OF(X509_POLICY_DATA) *, sk), \ + CHECKED_CAST(void *, X509_POLICY_DATA *, p), (where)) + +#define sk_X509_POLICY_DATA_delete(sk, where) \ + ((X509_POLICY_DATA *)sk_delete( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_POLICY_DATA) *, sk), (where))) + +#define sk_X509_POLICY_DATA_delete_ptr(sk, p) \ + ((X509_POLICY_DATA *)sk_delete_ptr( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_POLICY_DATA) *, sk), \ + CHECKED_CAST(void *, X509_POLICY_DATA *, p))) + +#define sk_X509_POLICY_DATA_find(sk, out_index, p) \ + sk_find(CHECKED_CAST(_STACK *, STACK_OF(X509_POLICY_DATA) *, sk), \ + (out_index), CHECKED_CAST(void *, X509_POLICY_DATA *, p)) + +#define sk_X509_POLICY_DATA_shift(sk) \ + ((X509_POLICY_DATA *)sk_shift( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_POLICY_DATA) *, sk))) + +#define sk_X509_POLICY_DATA_push(sk, p) \ + sk_push(CHECKED_CAST(_STACK *, STACK_OF(X509_POLICY_DATA) *, sk), \ + CHECKED_CAST(void *, X509_POLICY_DATA *, p)) + +#define sk_X509_POLICY_DATA_pop(sk) \ + ((X509_POLICY_DATA *)sk_pop( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_POLICY_DATA) *, sk))) + +#define sk_X509_POLICY_DATA_dup(sk) \ + ((STACK_OF(X509_POLICY_DATA) *)sk_dup( \ + CHECKED_CAST(_STACK *, const STACK_OF(X509_POLICY_DATA) *, sk))) + +#define sk_X509_POLICY_DATA_sort(sk) \ + sk_sort(CHECKED_CAST(_STACK *, STACK_OF(X509_POLICY_DATA) *, sk)) + +#define sk_X509_POLICY_DATA_is_sorted(sk) \ + sk_is_sorted(CHECKED_CAST(_STACK *, const STACK_OF(X509_POLICY_DATA) *, sk)) + +#define sk_X509_POLICY_DATA_set_cmp_func(sk, comp) \ + ((int (*)(const X509_POLICY_DATA **a, const X509_POLICY_DATA **b)) \ + sk_set_cmp_func( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_POLICY_DATA) *, sk), \ + CHECKED_CAST(stack_cmp_func, int (*)(const X509_POLICY_DATA **a, \ + const X509_POLICY_DATA **b), \ + comp))) + +#define sk_X509_POLICY_DATA_deep_copy(sk, copy_func, free_func) \ + ((STACK_OF(X509_POLICY_DATA) *)sk_deep_copy( \ + CHECKED_CAST(const _STACK *, const STACK_OF(X509_POLICY_DATA) *, sk), \ + CHECKED_CAST(void *(*)(void *), \ + X509_POLICY_DATA *(*)(X509_POLICY_DATA *), copy_func), \ + CHECKED_CAST(void (*)(void *), void (*)(X509_POLICY_DATA *), \ + free_func))) + +/* X509_POLICY_NODE */ +#define sk_X509_POLICY_NODE_new(comp) \ + ((STACK_OF(X509_POLICY_NODE) *)sk_new(CHECKED_CAST( \ + stack_cmp_func, \ + int (*)(const X509_POLICY_NODE **a, const X509_POLICY_NODE **b), comp))) + +#define sk_X509_POLICY_NODE_new_null() \ + ((STACK_OF(X509_POLICY_NODE) *)sk_new_null()) + +#define sk_X509_POLICY_NODE_num(sk) \ + sk_num(CHECKED_CAST(_STACK *, STACK_OF(X509_POLICY_NODE) *, sk)) + +#define sk_X509_POLICY_NODE_zero(sk) \ + sk_zero(CHECKED_CAST(_STACK *, STACK_OF(X509_POLICY_NODE) *, sk)); + +#define sk_X509_POLICY_NODE_value(sk, i) \ + ((X509_POLICY_NODE *)sk_value( \ + CHECKED_CAST(_STACK *, const STACK_OF(X509_POLICY_NODE) *, sk), (i))) + +#define sk_X509_POLICY_NODE_set(sk, i, p) \ + ((X509_POLICY_NODE *)sk_set( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_POLICY_NODE) *, sk), (i), \ + CHECKED_CAST(void *, X509_POLICY_NODE *, p))) + +#define sk_X509_POLICY_NODE_free(sk) \ + sk_free(CHECKED_CAST(_STACK *, STACK_OF(X509_POLICY_NODE) *, sk)) + +#define sk_X509_POLICY_NODE_pop_free(sk, free_func) \ + sk_pop_free( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_POLICY_NODE) *, sk), \ + CHECKED_CAST(void (*)(void *), void (*)(X509_POLICY_NODE *), free_func)) + +#define sk_X509_POLICY_NODE_insert(sk, p, where) \ + sk_insert(CHECKED_CAST(_STACK *, STACK_OF(X509_POLICY_NODE) *, sk), \ + CHECKED_CAST(void *, X509_POLICY_NODE *, p), (where)) + +#define sk_X509_POLICY_NODE_delete(sk, where) \ + ((X509_POLICY_NODE *)sk_delete( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_POLICY_NODE) *, sk), (where))) + +#define sk_X509_POLICY_NODE_delete_ptr(sk, p) \ + ((X509_POLICY_NODE *)sk_delete_ptr( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_POLICY_NODE) *, sk), \ + CHECKED_CAST(void *, X509_POLICY_NODE *, p))) + +#define sk_X509_POLICY_NODE_find(sk, out_index, p) \ + sk_find(CHECKED_CAST(_STACK *, STACK_OF(X509_POLICY_NODE) *, sk), \ + (out_index), CHECKED_CAST(void *, X509_POLICY_NODE *, p)) + +#define sk_X509_POLICY_NODE_shift(sk) \ + ((X509_POLICY_NODE *)sk_shift( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_POLICY_NODE) *, sk))) + +#define sk_X509_POLICY_NODE_push(sk, p) \ + sk_push(CHECKED_CAST(_STACK *, STACK_OF(X509_POLICY_NODE) *, sk), \ + CHECKED_CAST(void *, X509_POLICY_NODE *, p)) + +#define sk_X509_POLICY_NODE_pop(sk) \ + ((X509_POLICY_NODE *)sk_pop( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_POLICY_NODE) *, sk))) + +#define sk_X509_POLICY_NODE_dup(sk) \ + ((STACK_OF(X509_POLICY_NODE) *)sk_dup( \ + CHECKED_CAST(_STACK *, const STACK_OF(X509_POLICY_NODE) *, sk))) + +#define sk_X509_POLICY_NODE_sort(sk) \ + sk_sort(CHECKED_CAST(_STACK *, STACK_OF(X509_POLICY_NODE) *, sk)) + +#define sk_X509_POLICY_NODE_is_sorted(sk) \ + sk_is_sorted(CHECKED_CAST(_STACK *, const STACK_OF(X509_POLICY_NODE) *, sk)) + +#define sk_X509_POLICY_NODE_set_cmp_func(sk, comp) \ + ((int (*)(const X509_POLICY_NODE **a, const X509_POLICY_NODE **b)) \ + sk_set_cmp_func( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_POLICY_NODE) *, sk), \ + CHECKED_CAST(stack_cmp_func, int (*)(const X509_POLICY_NODE **a, \ + const X509_POLICY_NODE **b), \ + comp))) + +#define sk_X509_POLICY_NODE_deep_copy(sk, copy_func, free_func) \ + ((STACK_OF(X509_POLICY_NODE) *)sk_deep_copy( \ + CHECKED_CAST(const _STACK *, const STACK_OF(X509_POLICY_NODE) *, sk), \ + CHECKED_CAST(void *(*)(void *), \ + X509_POLICY_NODE *(*)(X509_POLICY_NODE *), copy_func), \ + CHECKED_CAST(void (*)(void *), void (*)(X509_POLICY_NODE *), \ + free_func))) + +/* X509_PURPOSE */ +#define sk_X509_PURPOSE_new(comp) \ + ((STACK_OF(X509_PURPOSE) *)sk_new(CHECKED_CAST( \ + stack_cmp_func, int (*)(const X509_PURPOSE **a, const X509_PURPOSE **b), \ + comp))) + +#define sk_X509_PURPOSE_new_null() ((STACK_OF(X509_PURPOSE) *)sk_new_null()) + +#define sk_X509_PURPOSE_num(sk) \ + sk_num(CHECKED_CAST(_STACK *, STACK_OF(X509_PURPOSE) *, sk)) + +#define sk_X509_PURPOSE_zero(sk) \ + sk_zero(CHECKED_CAST(_STACK *, STACK_OF(X509_PURPOSE) *, sk)); + +#define sk_X509_PURPOSE_value(sk, i) \ + ((X509_PURPOSE *)sk_value( \ + CHECKED_CAST(_STACK *, const STACK_OF(X509_PURPOSE) *, sk), (i))) + +#define sk_X509_PURPOSE_set(sk, i, p) \ + ((X509_PURPOSE *)sk_set( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_PURPOSE) *, sk), (i), \ + CHECKED_CAST(void *, X509_PURPOSE *, p))) + +#define sk_X509_PURPOSE_free(sk) \ + sk_free(CHECKED_CAST(_STACK *, STACK_OF(X509_PURPOSE) *, sk)) + +#define sk_X509_PURPOSE_pop_free(sk, free_func) \ + sk_pop_free( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_PURPOSE) *, sk), \ + CHECKED_CAST(void (*)(void *), void (*)(X509_PURPOSE *), free_func)) + +#define sk_X509_PURPOSE_insert(sk, p, where) \ + sk_insert(CHECKED_CAST(_STACK *, STACK_OF(X509_PURPOSE) *, sk), \ + CHECKED_CAST(void *, X509_PURPOSE *, p), (where)) + +#define sk_X509_PURPOSE_delete(sk, where) \ + ((X509_PURPOSE *)sk_delete( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_PURPOSE) *, sk), (where))) + +#define sk_X509_PURPOSE_delete_ptr(sk, p) \ + ((X509_PURPOSE *)sk_delete_ptr( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_PURPOSE) *, sk), \ + CHECKED_CAST(void *, X509_PURPOSE *, p))) + +#define sk_X509_PURPOSE_find(sk, out_index, p) \ + sk_find(CHECKED_CAST(_STACK *, STACK_OF(X509_PURPOSE) *, sk), (out_index), \ + CHECKED_CAST(void *, X509_PURPOSE *, p)) + +#define sk_X509_PURPOSE_shift(sk) \ + ((X509_PURPOSE *)sk_shift( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_PURPOSE) *, sk))) + +#define sk_X509_PURPOSE_push(sk, p) \ + sk_push(CHECKED_CAST(_STACK *, STACK_OF(X509_PURPOSE) *, sk), \ + CHECKED_CAST(void *, X509_PURPOSE *, p)) + +#define sk_X509_PURPOSE_pop(sk) \ + ((X509_PURPOSE *)sk_pop(CHECKED_CAST(_STACK *, STACK_OF(X509_PURPOSE) *, sk))) + +#define sk_X509_PURPOSE_dup(sk) \ + ((STACK_OF(X509_PURPOSE) *)sk_dup( \ + CHECKED_CAST(_STACK *, const STACK_OF(X509_PURPOSE) *, sk))) + +#define sk_X509_PURPOSE_sort(sk) \ + sk_sort(CHECKED_CAST(_STACK *, STACK_OF(X509_PURPOSE) *, sk)) + +#define sk_X509_PURPOSE_is_sorted(sk) \ + sk_is_sorted(CHECKED_CAST(_STACK *, const STACK_OF(X509_PURPOSE) *, sk)) + +#define sk_X509_PURPOSE_set_cmp_func(sk, comp) \ + ((int (*)(const X509_PURPOSE **a, const X509_PURPOSE **b))sk_set_cmp_func( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_PURPOSE) *, sk), \ + CHECKED_CAST(stack_cmp_func, \ + int (*)(const X509_PURPOSE **a, const X509_PURPOSE **b), \ + comp))) + +#define sk_X509_PURPOSE_deep_copy(sk, copy_func, free_func) \ + ((STACK_OF(X509_PURPOSE) *)sk_deep_copy( \ + CHECKED_CAST(const _STACK *, const STACK_OF(X509_PURPOSE) *, sk), \ + CHECKED_CAST(void *(*)(void *), X509_PURPOSE *(*)(X509_PURPOSE *), \ + copy_func), \ + CHECKED_CAST(void (*)(void *), void (*)(X509_PURPOSE *), free_func))) + +/* X509_REVOKED */ +#define sk_X509_REVOKED_new(comp) \ + ((STACK_OF(X509_REVOKED) *)sk_new(CHECKED_CAST( \ + stack_cmp_func, int (*)(const X509_REVOKED **a, const X509_REVOKED **b), \ + comp))) + +#define sk_X509_REVOKED_new_null() ((STACK_OF(X509_REVOKED) *)sk_new_null()) + +#define sk_X509_REVOKED_num(sk) \ + sk_num(CHECKED_CAST(_STACK *, STACK_OF(X509_REVOKED) *, sk)) + +#define sk_X509_REVOKED_zero(sk) \ + sk_zero(CHECKED_CAST(_STACK *, STACK_OF(X509_REVOKED) *, sk)); + +#define sk_X509_REVOKED_value(sk, i) \ + ((X509_REVOKED *)sk_value( \ + CHECKED_CAST(_STACK *, const STACK_OF(X509_REVOKED) *, sk), (i))) + +#define sk_X509_REVOKED_set(sk, i, p) \ + ((X509_REVOKED *)sk_set( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_REVOKED) *, sk), (i), \ + CHECKED_CAST(void *, X509_REVOKED *, p))) + +#define sk_X509_REVOKED_free(sk) \ + sk_free(CHECKED_CAST(_STACK *, STACK_OF(X509_REVOKED) *, sk)) + +#define sk_X509_REVOKED_pop_free(sk, free_func) \ + sk_pop_free( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_REVOKED) *, sk), \ + CHECKED_CAST(void (*)(void *), void (*)(X509_REVOKED *), free_func)) + +#define sk_X509_REVOKED_insert(sk, p, where) \ + sk_insert(CHECKED_CAST(_STACK *, STACK_OF(X509_REVOKED) *, sk), \ + CHECKED_CAST(void *, X509_REVOKED *, p), (where)) + +#define sk_X509_REVOKED_delete(sk, where) \ + ((X509_REVOKED *)sk_delete( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_REVOKED) *, sk), (where))) + +#define sk_X509_REVOKED_delete_ptr(sk, p) \ + ((X509_REVOKED *)sk_delete_ptr( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_REVOKED) *, sk), \ + CHECKED_CAST(void *, X509_REVOKED *, p))) + +#define sk_X509_REVOKED_find(sk, out_index, p) \ + sk_find(CHECKED_CAST(_STACK *, STACK_OF(X509_REVOKED) *, sk), (out_index), \ + CHECKED_CAST(void *, X509_REVOKED *, p)) + +#define sk_X509_REVOKED_shift(sk) \ + ((X509_REVOKED *)sk_shift( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_REVOKED) *, sk))) + +#define sk_X509_REVOKED_push(sk, p) \ + sk_push(CHECKED_CAST(_STACK *, STACK_OF(X509_REVOKED) *, sk), \ + CHECKED_CAST(void *, X509_REVOKED *, p)) + +#define sk_X509_REVOKED_pop(sk) \ + ((X509_REVOKED *)sk_pop(CHECKED_CAST(_STACK *, STACK_OF(X509_REVOKED) *, sk))) + +#define sk_X509_REVOKED_dup(sk) \ + ((STACK_OF(X509_REVOKED) *)sk_dup( \ + CHECKED_CAST(_STACK *, const STACK_OF(X509_REVOKED) *, sk))) + +#define sk_X509_REVOKED_sort(sk) \ + sk_sort(CHECKED_CAST(_STACK *, STACK_OF(X509_REVOKED) *, sk)) + +#define sk_X509_REVOKED_is_sorted(sk) \ + sk_is_sorted(CHECKED_CAST(_STACK *, const STACK_OF(X509_REVOKED) *, sk)) + +#define sk_X509_REVOKED_set_cmp_func(sk, comp) \ + ((int (*)(const X509_REVOKED **a, const X509_REVOKED **b))sk_set_cmp_func( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_REVOKED) *, sk), \ + CHECKED_CAST(stack_cmp_func, \ + int (*)(const X509_REVOKED **a, const X509_REVOKED **b), \ + comp))) + +#define sk_X509_REVOKED_deep_copy(sk, copy_func, free_func) \ + ((STACK_OF(X509_REVOKED) *)sk_deep_copy( \ + CHECKED_CAST(const _STACK *, const STACK_OF(X509_REVOKED) *, sk), \ + CHECKED_CAST(void *(*)(void *), X509_REVOKED *(*)(X509_REVOKED *), \ + copy_func), \ + CHECKED_CAST(void (*)(void *), void (*)(X509_REVOKED *), free_func))) + +/* X509_TRUST */ +#define sk_X509_TRUST_new(comp) \ + ((STACK_OF(X509_TRUST) *)sk_new(CHECKED_CAST( \ + stack_cmp_func, int (*)(const X509_TRUST **a, const X509_TRUST **b), \ + comp))) + +#define sk_X509_TRUST_new_null() ((STACK_OF(X509_TRUST) *)sk_new_null()) + +#define sk_X509_TRUST_num(sk) \ + sk_num(CHECKED_CAST(_STACK *, STACK_OF(X509_TRUST) *, sk)) + +#define sk_X509_TRUST_zero(sk) \ + sk_zero(CHECKED_CAST(_STACK *, STACK_OF(X509_TRUST) *, sk)); + +#define sk_X509_TRUST_value(sk, i) \ + ((X509_TRUST *)sk_value( \ + CHECKED_CAST(_STACK *, const STACK_OF(X509_TRUST) *, sk), (i))) + +#define sk_X509_TRUST_set(sk, i, p) \ + ((X509_TRUST *)sk_set(CHECKED_CAST(_STACK *, STACK_OF(X509_TRUST) *, sk), \ + (i), CHECKED_CAST(void *, X509_TRUST *, p))) + +#define sk_X509_TRUST_free(sk) \ + sk_free(CHECKED_CAST(_STACK *, STACK_OF(X509_TRUST) *, sk)) + +#define sk_X509_TRUST_pop_free(sk, free_func) \ + sk_pop_free( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_TRUST) *, sk), \ + CHECKED_CAST(void (*)(void *), void (*)(X509_TRUST *), free_func)) + +#define sk_X509_TRUST_insert(sk, p, where) \ + sk_insert(CHECKED_CAST(_STACK *, STACK_OF(X509_TRUST) *, sk), \ + CHECKED_CAST(void *, X509_TRUST *, p), (where)) + +#define sk_X509_TRUST_delete(sk, where) \ + ((X509_TRUST *)sk_delete(CHECKED_CAST(_STACK *, STACK_OF(X509_TRUST) *, sk), \ + (where))) + +#define sk_X509_TRUST_delete_ptr(sk, p) \ + ((X509_TRUST *)sk_delete_ptr( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_TRUST) *, sk), \ + CHECKED_CAST(void *, X509_TRUST *, p))) + +#define sk_X509_TRUST_find(sk, out_index, p) \ + sk_find(CHECKED_CAST(_STACK *, STACK_OF(X509_TRUST) *, sk), (out_index), \ + CHECKED_CAST(void *, X509_TRUST *, p)) + +#define sk_X509_TRUST_shift(sk) \ + ((X509_TRUST *)sk_shift(CHECKED_CAST(_STACK *, STACK_OF(X509_TRUST) *, sk))) + +#define sk_X509_TRUST_push(sk, p) \ + sk_push(CHECKED_CAST(_STACK *, STACK_OF(X509_TRUST) *, sk), \ + CHECKED_CAST(void *, X509_TRUST *, p)) + +#define sk_X509_TRUST_pop(sk) \ + ((X509_TRUST *)sk_pop(CHECKED_CAST(_STACK *, STACK_OF(X509_TRUST) *, sk))) + +#define sk_X509_TRUST_dup(sk) \ + ((STACK_OF(X509_TRUST) *)sk_dup( \ + CHECKED_CAST(_STACK *, const STACK_OF(X509_TRUST) *, sk))) + +#define sk_X509_TRUST_sort(sk) \ + sk_sort(CHECKED_CAST(_STACK *, STACK_OF(X509_TRUST) *, sk)) + +#define sk_X509_TRUST_is_sorted(sk) \ + sk_is_sorted(CHECKED_CAST(_STACK *, const STACK_OF(X509_TRUST) *, sk)) + +#define sk_X509_TRUST_set_cmp_func(sk, comp) \ + ((int (*)(const X509_TRUST **a, const X509_TRUST **b))sk_set_cmp_func( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_TRUST) *, sk), \ + CHECKED_CAST(stack_cmp_func, \ + int (*)(const X509_TRUST **a, const X509_TRUST **b), \ + comp))) + +#define sk_X509_TRUST_deep_copy(sk, copy_func, free_func) \ + ((STACK_OF(X509_TRUST) *)sk_deep_copy( \ + CHECKED_CAST(const _STACK *, const STACK_OF(X509_TRUST) *, sk), \ + CHECKED_CAST(void *(*)(void *), X509_TRUST *(*)(X509_TRUST *), \ + copy_func), \ + CHECKED_CAST(void (*)(void *), void (*)(X509_TRUST *), free_func))) + +/* X509_VERIFY_PARAM */ +#define sk_X509_VERIFY_PARAM_new(comp) \ + ((STACK_OF(X509_VERIFY_PARAM) *)sk_new(CHECKED_CAST( \ + stack_cmp_func, \ + int (*)(const X509_VERIFY_PARAM **a, const X509_VERIFY_PARAM **b), \ + comp))) + +#define sk_X509_VERIFY_PARAM_new_null() \ + ((STACK_OF(X509_VERIFY_PARAM) *)sk_new_null()) + +#define sk_X509_VERIFY_PARAM_num(sk) \ + sk_num(CHECKED_CAST(_STACK *, STACK_OF(X509_VERIFY_PARAM) *, sk)) + +#define sk_X509_VERIFY_PARAM_zero(sk) \ + sk_zero(CHECKED_CAST(_STACK *, STACK_OF(X509_VERIFY_PARAM) *, sk)); + +#define sk_X509_VERIFY_PARAM_value(sk, i) \ + ((X509_VERIFY_PARAM *)sk_value( \ + CHECKED_CAST(_STACK *, const STACK_OF(X509_VERIFY_PARAM) *, sk), (i))) + +#define sk_X509_VERIFY_PARAM_set(sk, i, p) \ + ((X509_VERIFY_PARAM *)sk_set( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_VERIFY_PARAM) *, sk), (i), \ + CHECKED_CAST(void *, X509_VERIFY_PARAM *, p))) + +#define sk_X509_VERIFY_PARAM_free(sk) \ + sk_free(CHECKED_CAST(_STACK *, STACK_OF(X509_VERIFY_PARAM) *, sk)) + +#define sk_X509_VERIFY_PARAM_pop_free(sk, free_func) \ + sk_pop_free(CHECKED_CAST(_STACK *, STACK_OF(X509_VERIFY_PARAM) *, sk), \ + CHECKED_CAST(void (*)(void *), void (*)(X509_VERIFY_PARAM *), \ + free_func)) + +#define sk_X509_VERIFY_PARAM_insert(sk, p, where) \ + sk_insert(CHECKED_CAST(_STACK *, STACK_OF(X509_VERIFY_PARAM) *, sk), \ + CHECKED_CAST(void *, X509_VERIFY_PARAM *, p), (where)) + +#define sk_X509_VERIFY_PARAM_delete(sk, where) \ + ((X509_VERIFY_PARAM *)sk_delete( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_VERIFY_PARAM) *, sk), (where))) + +#define sk_X509_VERIFY_PARAM_delete_ptr(sk, p) \ + ((X509_VERIFY_PARAM *)sk_delete_ptr( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_VERIFY_PARAM) *, sk), \ + CHECKED_CAST(void *, X509_VERIFY_PARAM *, p))) + +#define sk_X509_VERIFY_PARAM_find(sk, out_index, p) \ + sk_find(CHECKED_CAST(_STACK *, STACK_OF(X509_VERIFY_PARAM) *, sk), \ + (out_index), CHECKED_CAST(void *, X509_VERIFY_PARAM *, p)) + +#define sk_X509_VERIFY_PARAM_shift(sk) \ + ((X509_VERIFY_PARAM *)sk_shift( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_VERIFY_PARAM) *, sk))) + +#define sk_X509_VERIFY_PARAM_push(sk, p) \ + sk_push(CHECKED_CAST(_STACK *, STACK_OF(X509_VERIFY_PARAM) *, sk), \ + CHECKED_CAST(void *, X509_VERIFY_PARAM *, p)) + +#define sk_X509_VERIFY_PARAM_pop(sk) \ + ((X509_VERIFY_PARAM *)sk_pop( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_VERIFY_PARAM) *, sk))) + +#define sk_X509_VERIFY_PARAM_dup(sk) \ + ((STACK_OF(X509_VERIFY_PARAM) *)sk_dup( \ + CHECKED_CAST(_STACK *, const STACK_OF(X509_VERIFY_PARAM) *, sk))) + +#define sk_X509_VERIFY_PARAM_sort(sk) \ + sk_sort(CHECKED_CAST(_STACK *, STACK_OF(X509_VERIFY_PARAM) *, sk)) + +#define sk_X509_VERIFY_PARAM_is_sorted(sk) \ + sk_is_sorted(CHECKED_CAST(_STACK *, const STACK_OF(X509_VERIFY_PARAM) *, sk)) + +#define sk_X509_VERIFY_PARAM_set_cmp_func(sk, comp) \ + ((int (*)(const X509_VERIFY_PARAM **a, const X509_VERIFY_PARAM **b)) \ + sk_set_cmp_func( \ + CHECKED_CAST(_STACK *, STACK_OF(X509_VERIFY_PARAM) *, sk), \ + CHECKED_CAST(stack_cmp_func, int (*)(const X509_VERIFY_PARAM **a, \ + const X509_VERIFY_PARAM **b), \ + comp))) + +#define sk_X509_VERIFY_PARAM_deep_copy(sk, copy_func, free_func) \ + ((STACK_OF(X509_VERIFY_PARAM) *)sk_deep_copy( \ + CHECKED_CAST(const _STACK *, const STACK_OF(X509_VERIFY_PARAM) *, sk), \ + CHECKED_CAST(void *(*)(void *), \ + X509_VERIFY_PARAM *(*)(X509_VERIFY_PARAM *), copy_func), \ + CHECKED_CAST(void (*)(void *), void (*)(X509_VERIFY_PARAM *), \ + free_func))) + +/* void */ +#define sk_void_new(comp) \ + ((STACK_OF(void)*)sk_new(CHECKED_CAST( \ + stack_cmp_func, int (*)(const void **a, const void **b), comp))) + +#define sk_void_new_null() ((STACK_OF(void)*)sk_new_null()) + +#define sk_void_num(sk) sk_num(CHECKED_CAST(_STACK *, STACK_OF(void)*, sk)) + +#define sk_void_zero(sk) sk_zero(CHECKED_CAST(_STACK *, STACK_OF(void)*, sk)); + +#define sk_void_value(sk, i) \ + ((void *)sk_value(CHECKED_CAST(_STACK *, const STACK_OF(void)*, sk), (i))) + +#define sk_void_set(sk, i, p) \ + ((void *)sk_set(CHECKED_CAST(_STACK *, STACK_OF(void)*, sk), (i), \ + CHECKED_CAST(void *, void *, p))) + +#define sk_void_free(sk) sk_free(CHECKED_CAST(_STACK *, STACK_OF(void)*, sk)) + +#define sk_void_pop_free(sk, free_func) \ + sk_pop_free(CHECKED_CAST(_STACK *, STACK_OF(void)*, sk), \ + CHECKED_CAST(void (*)(void *), void (*)(void *), free_func)) + +#define sk_void_insert(sk, p, where) \ + sk_insert(CHECKED_CAST(_STACK *, STACK_OF(void)*, sk), \ + CHECKED_CAST(void *, void *, p), (where)) + +#define sk_void_delete(sk, where) \ + ((void *)sk_delete(CHECKED_CAST(_STACK *, STACK_OF(void)*, sk), (where))) + +#define sk_void_delete_ptr(sk, p) \ + ((void *)sk_delete_ptr(CHECKED_CAST(_STACK *, STACK_OF(void)*, sk), \ + CHECKED_CAST(void *, void *, p))) + +#define sk_void_find(sk, out_index, p) \ + sk_find(CHECKED_CAST(_STACK *, STACK_OF(void)*, sk), (out_index), \ + CHECKED_CAST(void *, void *, p)) + +#define sk_void_shift(sk) \ + ((void *)sk_shift(CHECKED_CAST(_STACK *, STACK_OF(void)*, sk))) + +#define sk_void_push(sk, p) \ + sk_push(CHECKED_CAST(_STACK *, STACK_OF(void)*, sk), \ + CHECKED_CAST(void *, void *, p)) + +#define sk_void_pop(sk) \ + ((void *)sk_pop(CHECKED_CAST(_STACK *, STACK_OF(void)*, sk))) + +#define sk_void_dup(sk) \ + ((STACK_OF(void)*)sk_dup(CHECKED_CAST(_STACK *, const STACK_OF(void)*, sk))) + +#define sk_void_sort(sk) sk_sort(CHECKED_CAST(_STACK *, STACK_OF(void)*, sk)) + +#define sk_void_is_sorted(sk) \ + sk_is_sorted(CHECKED_CAST(_STACK *, const STACK_OF(void)*, sk)) + +#define sk_void_set_cmp_func(sk, comp) \ + ((int (*)(const void **a, const void **b))sk_set_cmp_func( \ + CHECKED_CAST(_STACK *, STACK_OF(void)*, sk), \ + CHECKED_CAST(stack_cmp_func, int (*)(const void **a, const void **b), \ + comp))) + +#define sk_void_deep_copy(sk, copy_func, free_func) \ + ((STACK_OF(void)*)sk_deep_copy( \ + CHECKED_CAST(const _STACK *, const STACK_OF(void)*, sk), \ + CHECKED_CAST(void *(*)(void *), void *(*)(void *), copy_func), \ + CHECKED_CAST(void (*)(void *), void (*)(void *), free_func))) + +/* SRTP_PROTECTION_PROFILE */ +#define sk_SRTP_PROTECTION_PROFILE_new(comp) \ + ((STACK_OF(SRTP_PROTECTION_PROFILE) *)sk_new(CHECKED_CAST( \ + stack_cmp_func, int (*)(const const SRTP_PROTECTION_PROFILE **a, \ + const const SRTP_PROTECTION_PROFILE **b), \ + comp))) + +#define sk_SRTP_PROTECTION_PROFILE_new_null() \ + ((STACK_OF(SRTP_PROTECTION_PROFILE) *)sk_new_null()) + +#define sk_SRTP_PROTECTION_PROFILE_num(sk) \ + sk_num(CHECKED_CAST(_STACK *, STACK_OF(SRTP_PROTECTION_PROFILE) *, sk)) + +#define sk_SRTP_PROTECTION_PROFILE_zero(sk) \ + sk_zero(CHECKED_CAST(_STACK *, STACK_OF(SRTP_PROTECTION_PROFILE) *, sk)); + +#define sk_SRTP_PROTECTION_PROFILE_value(sk, i) \ + ((const SRTP_PROTECTION_PROFILE *)sk_value( \ + CHECKED_CAST(_STACK *, const STACK_OF(SRTP_PROTECTION_PROFILE) *, sk), \ + (i))) + +#define sk_SRTP_PROTECTION_PROFILE_set(sk, i, p) \ + ((const SRTP_PROTECTION_PROFILE *)sk_set( \ + CHECKED_CAST(_STACK *, STACK_OF(SRTP_PROTECTION_PROFILE) *, sk), (i), \ + CHECKED_CAST(void *, const SRTP_PROTECTION_PROFILE *, p))) + +#define sk_SRTP_PROTECTION_PROFILE_free(sk) \ + sk_free(CHECKED_CAST(_STACK *, STACK_OF(SRTP_PROTECTION_PROFILE) *, sk)) + +#define sk_SRTP_PROTECTION_PROFILE_pop_free(sk, free_func) \ + sk_pop_free( \ + CHECKED_CAST(_STACK *, STACK_OF(SRTP_PROTECTION_PROFILE) *, sk), \ + CHECKED_CAST(void (*)(void *), \ + void (*)(const SRTP_PROTECTION_PROFILE *), free_func)) + +#define sk_SRTP_PROTECTION_PROFILE_insert(sk, p, where) \ + sk_insert(CHECKED_CAST(_STACK *, STACK_OF(SRTP_PROTECTION_PROFILE) *, sk), \ + CHECKED_CAST(void *, const SRTP_PROTECTION_PROFILE *, p), (where)) + +#define sk_SRTP_PROTECTION_PROFILE_delete(sk, where) \ + ((const SRTP_PROTECTION_PROFILE *)sk_delete( \ + CHECKED_CAST(_STACK *, STACK_OF(SRTP_PROTECTION_PROFILE) *, sk), \ + (where))) + +#define sk_SRTP_PROTECTION_PROFILE_delete_ptr(sk, p) \ + ((const SRTP_PROTECTION_PROFILE *)sk_delete_ptr( \ + CHECKED_CAST(_STACK *, STACK_OF(SRTP_PROTECTION_PROFILE) *, sk), \ + CHECKED_CAST(void *, const SRTP_PROTECTION_PROFILE *, p))) + +#define sk_SRTP_PROTECTION_PROFILE_find(sk, out_index, p) \ + sk_find(CHECKED_CAST(_STACK *, STACK_OF(SRTP_PROTECTION_PROFILE) *, sk), \ + (out_index), \ + CHECKED_CAST(void *, const SRTP_PROTECTION_PROFILE *, p)) + +#define sk_SRTP_PROTECTION_PROFILE_shift(sk) \ + ((const SRTP_PROTECTION_PROFILE *)sk_shift( \ + CHECKED_CAST(_STACK *, STACK_OF(SRTP_PROTECTION_PROFILE) *, sk))) + +#define sk_SRTP_PROTECTION_PROFILE_push(sk, p) \ + sk_push(CHECKED_CAST(_STACK *, STACK_OF(SRTP_PROTECTION_PROFILE) *, sk), \ + CHECKED_CAST(void *, const SRTP_PROTECTION_PROFILE *, p)) + +#define sk_SRTP_PROTECTION_PROFILE_pop(sk) \ + ((const SRTP_PROTECTION_PROFILE *)sk_pop( \ + CHECKED_CAST(_STACK *, STACK_OF(SRTP_PROTECTION_PROFILE) *, sk))) + +#define sk_SRTP_PROTECTION_PROFILE_dup(sk) \ + ((STACK_OF(SRTP_PROTECTION_PROFILE) *)sk_dup( \ + CHECKED_CAST(_STACK *, const STACK_OF(SRTP_PROTECTION_PROFILE) *, sk))) + +#define sk_SRTP_PROTECTION_PROFILE_sort(sk) \ + sk_sort(CHECKED_CAST(_STACK *, STACK_OF(SRTP_PROTECTION_PROFILE) *, sk)) + +#define sk_SRTP_PROTECTION_PROFILE_is_sorted(sk) \ + sk_is_sorted( \ + CHECKED_CAST(_STACK *, const STACK_OF(SRTP_PROTECTION_PROFILE) *, sk)) + +#define sk_SRTP_PROTECTION_PROFILE_set_cmp_func(sk, comp) \ + ((int (*)(const SRTP_PROTECTION_PROFILE **a, \ + const SRTP_PROTECTION_PROFILE **b)) \ + sk_set_cmp_func( \ + CHECKED_CAST(_STACK *, STACK_OF(SRTP_PROTECTION_PROFILE) *, sk), \ + CHECKED_CAST(stack_cmp_func, \ + int (*)(const SRTP_PROTECTION_PROFILE **a, \ + const SRTP_PROTECTION_PROFILE **b), \ + comp))) + +#define sk_SRTP_PROTECTION_PROFILE_deep_copy(sk, copy_func, free_func) \ + ((STACK_OF(SRTP_PROTECTION_PROFILE) *)sk_deep_copy( \ + CHECKED_CAST(const _STACK *, const STACK_OF(SRTP_PROTECTION_PROFILE) *, \ + sk), \ + CHECKED_CAST(void *(*)(void *), const SRTP_PROTECTION_PROFILE *(*)( \ + const SRTP_PROTECTION_PROFILE *), \ + copy_func), \ + CHECKED_CAST(void (*)(void *), \ + void (*)(const SRTP_PROTECTION_PROFILE *), free_func))) + +/* SSL_CIPHER */ +#define sk_SSL_CIPHER_new(comp) \ + ((STACK_OF(SSL_CIPHER) *)sk_new(CHECKED_CAST( \ + stack_cmp_func, \ + int (*)(const const SSL_CIPHER **a, const const SSL_CIPHER **b), comp))) + +#define sk_SSL_CIPHER_new_null() ((STACK_OF(SSL_CIPHER) *)sk_new_null()) + +#define sk_SSL_CIPHER_num(sk) \ + sk_num(CHECKED_CAST(_STACK *, STACK_OF(SSL_CIPHER) *, sk)) + +#define sk_SSL_CIPHER_zero(sk) \ + sk_zero(CHECKED_CAST(_STACK *, STACK_OF(SSL_CIPHER) *, sk)); + +#define sk_SSL_CIPHER_value(sk, i) \ + ((const SSL_CIPHER *)sk_value( \ + CHECKED_CAST(_STACK *, const STACK_OF(SSL_CIPHER) *, sk), (i))) + +#define sk_SSL_CIPHER_set(sk, i, p) \ + ((const SSL_CIPHER *)sk_set( \ + CHECKED_CAST(_STACK *, STACK_OF(SSL_CIPHER) *, sk), (i), \ + CHECKED_CAST(void *, const SSL_CIPHER *, p))) + +#define sk_SSL_CIPHER_free(sk) \ + sk_free(CHECKED_CAST(_STACK *, STACK_OF(SSL_CIPHER) *, sk)) + +#define sk_SSL_CIPHER_pop_free(sk, free_func) \ + sk_pop_free( \ + CHECKED_CAST(_STACK *, STACK_OF(SSL_CIPHER) *, sk), \ + CHECKED_CAST(void (*)(void *), void (*)(const SSL_CIPHER *), free_func)) + +#define sk_SSL_CIPHER_insert(sk, p, where) \ + sk_insert(CHECKED_CAST(_STACK *, STACK_OF(SSL_CIPHER) *, sk), \ + CHECKED_CAST(void *, const SSL_CIPHER *, p), (where)) + +#define sk_SSL_CIPHER_delete(sk, where) \ + ((const SSL_CIPHER *)sk_delete( \ + CHECKED_CAST(_STACK *, STACK_OF(SSL_CIPHER) *, sk), (where))) + +#define sk_SSL_CIPHER_delete_ptr(sk, p) \ + ((const SSL_CIPHER *)sk_delete_ptr( \ + CHECKED_CAST(_STACK *, STACK_OF(SSL_CIPHER) *, sk), \ + CHECKED_CAST(void *, const SSL_CIPHER *, p))) + +#define sk_SSL_CIPHER_find(sk, out_index, p) \ + sk_find(CHECKED_CAST(_STACK *, STACK_OF(SSL_CIPHER) *, sk), (out_index), \ + CHECKED_CAST(void *, const SSL_CIPHER *, p)) + +#define sk_SSL_CIPHER_shift(sk) \ + ((const SSL_CIPHER *)sk_shift( \ + CHECKED_CAST(_STACK *, STACK_OF(SSL_CIPHER) *, sk))) + +#define sk_SSL_CIPHER_push(sk, p) \ + sk_push(CHECKED_CAST(_STACK *, STACK_OF(SSL_CIPHER) *, sk), \ + CHECKED_CAST(void *, const SSL_CIPHER *, p)) + +#define sk_SSL_CIPHER_pop(sk) \ + ((const SSL_CIPHER *)sk_pop( \ + CHECKED_CAST(_STACK *, STACK_OF(SSL_CIPHER) *, sk))) + +#define sk_SSL_CIPHER_dup(sk) \ + ((STACK_OF(SSL_CIPHER) *)sk_dup( \ + CHECKED_CAST(_STACK *, const STACK_OF(SSL_CIPHER) *, sk))) + +#define sk_SSL_CIPHER_sort(sk) \ + sk_sort(CHECKED_CAST(_STACK *, STACK_OF(SSL_CIPHER) *, sk)) + +#define sk_SSL_CIPHER_is_sorted(sk) \ + sk_is_sorted(CHECKED_CAST(_STACK *, const STACK_OF(SSL_CIPHER) *, sk)) + +#define sk_SSL_CIPHER_set_cmp_func(sk, comp) \ + ((int (*)(const SSL_CIPHER **a, const SSL_CIPHER **b))sk_set_cmp_func( \ + CHECKED_CAST(_STACK *, STACK_OF(SSL_CIPHER) *, sk), \ + CHECKED_CAST(stack_cmp_func, \ + int (*)(const SSL_CIPHER **a, const SSL_CIPHER **b), \ + comp))) + +#define sk_SSL_CIPHER_deep_copy(sk, copy_func, free_func) \ + ((STACK_OF(SSL_CIPHER) *)sk_deep_copy( \ + CHECKED_CAST(const _STACK *, const STACK_OF(SSL_CIPHER) *, sk), \ + CHECKED_CAST(void *(*)(void *), \ + const SSL_CIPHER *(*)(const SSL_CIPHER *), copy_func), \ + CHECKED_CAST(void (*)(void *), void (*)(const SSL_CIPHER *), \ + free_func))) + +/* OPENSSL_STRING */ +#define sk_OPENSSL_STRING_new(comp) \ + ((STACK_OF(OPENSSL_STRING) *)sk_new(CHECKED_CAST( \ + stack_cmp_func, \ + int (*)(const OPENSSL_STRING *a, const OPENSSL_STRING *b), comp))) + +#define sk_OPENSSL_STRING_new_null() ((STACK_OF(OPENSSL_STRING) *)sk_new_null()) + +#define sk_OPENSSL_STRING_num(sk) \ + sk_num(CHECKED_CAST(_STACK *, STACK_OF(OPENSSL_STRING) *, sk)) + +#define sk_OPENSSL_STRING_zero(sk) \ + sk_zero(CHECKED_CAST(_STACK *, STACK_OF(OPENSSL_STRING) *, sk)); + +#define sk_OPENSSL_STRING_value(sk, i) \ + ((OPENSSL_STRING)sk_value( \ + CHECKED_CAST(_STACK *, const STACK_OF(OPENSSL_STRING) *, sk), (i))) + +#define sk_OPENSSL_STRING_set(sk, i, p) \ + ((OPENSSL_STRING)sk_set( \ + CHECKED_CAST(_STACK *, STACK_OF(OPENSSL_STRING) *, sk), (i), \ + CHECKED_CAST(void *, OPENSSL_STRING, p))) + +#define sk_OPENSSL_STRING_free(sk) \ + sk_free(CHECKED_CAST(_STACK *, STACK_OF(OPENSSL_STRING) *, sk)) + +#define sk_OPENSSL_STRING_pop_free(sk, free_func) \ + sk_pop_free( \ + CHECKED_CAST(_STACK *, STACK_OF(OPENSSL_STRING) *, sk), \ + CHECKED_CAST(void (*)(void *), void (*)(OPENSSL_STRING), free_func)) + +#define sk_OPENSSL_STRING_insert(sk, p, where) \ + sk_insert(CHECKED_CAST(_STACK *, STACK_OF(OPENSSL_STRING) *, sk), \ + CHECKED_CAST(void *, OPENSSL_STRING, p), (where)) + +#define sk_OPENSSL_STRING_delete(sk, where) \ + ((OPENSSL_STRING)sk_delete( \ + CHECKED_CAST(_STACK *, STACK_OF(OPENSSL_STRING) *, sk), (where))) + +#define sk_OPENSSL_STRING_delete_ptr(sk, p) \ + ((OPENSSL_STRING)sk_delete_ptr( \ + CHECKED_CAST(_STACK *, STACK_OF(OPENSSL_STRING) *, sk), \ + CHECKED_CAST(void *, OPENSSL_STRING, p))) + +#define sk_OPENSSL_STRING_find(sk, out_index, p) \ + sk_find(CHECKED_CAST(_STACK *, STACK_OF(OPENSSL_STRING) *, sk), (out_index), \ + CHECKED_CAST(void *, OPENSSL_STRING, p)) + +#define sk_OPENSSL_STRING_shift(sk) \ + ((OPENSSL_STRING)sk_shift( \ + CHECKED_CAST(_STACK *, STACK_OF(OPENSSL_STRING) *, sk))) + +#define sk_OPENSSL_STRING_push(sk, p) \ + sk_push(CHECKED_CAST(_STACK *, STACK_OF(OPENSSL_STRING) *, sk), \ + CHECKED_CAST(void *, OPENSSL_STRING, p)) + +#define sk_OPENSSL_STRING_pop(sk) \ + ((OPENSSL_STRING)sk_pop( \ + CHECKED_CAST(_STACK *, STACK_OF(OPENSSL_STRING) *, sk))) + +#define sk_OPENSSL_STRING_dup(sk) \ + ((STACK_OF(OPENSSL_STRING) *)sk_dup( \ + CHECKED_CAST(_STACK *, const STACK_OF(OPENSSL_STRING) *, sk))) + +#define sk_OPENSSL_STRING_sort(sk) \ + sk_sort(CHECKED_CAST(_STACK *, STACK_OF(OPENSSL_STRING) *, sk)) + +#define sk_OPENSSL_STRING_is_sorted(sk) \ + sk_is_sorted(CHECKED_CAST(_STACK *, const STACK_OF(OPENSSL_STRING) *, sk)) + +#define sk_OPENSSL_STRING_set_cmp_func(sk, comp) \ + ((int (*)(const OPENSSL_STRING **a, const OPENSSL_STRING **b)) \ + sk_set_cmp_func( \ + CHECKED_CAST(_STACK *, STACK_OF(OPENSSL_STRING) *, sk), \ + CHECKED_CAST(stack_cmp_func, int (*)(const OPENSSL_STRING **a, \ + const OPENSSL_STRING **b), \ + comp))) + +#define sk_OPENSSL_STRING_deep_copy(sk, copy_func, free_func) \ + ((STACK_OF(OPENSSL_STRING) *)sk_deep_copy( \ + CHECKED_CAST(const _STACK *, const STACK_OF(OPENSSL_STRING) *, sk), \ + CHECKED_CAST(void *(*)(void *), OPENSSL_STRING (*)(OPENSSL_STRING), \ + copy_func), \ + CHECKED_CAST(void (*)(void *), void (*)(OPENSSL_STRING), free_func))) + +/* OPENSSL_BLOCK */ +#define sk_OPENSSL_BLOCK_new(comp) \ + ((STACK_OF(OPENSSL_BLOCK) *)sk_new(CHECKED_CAST( \ + stack_cmp_func, int (*)(const OPENSSL_BLOCK *a, const OPENSSL_BLOCK *b), \ + comp))) + +#define sk_OPENSSL_BLOCK_new_null() ((STACK_OF(OPENSSL_BLOCK) *)sk_new_null()) + +#define sk_OPENSSL_BLOCK_num(sk) \ + sk_num(CHECKED_CAST(_STACK *, STACK_OF(OPENSSL_BLOCK) *, sk)) + +#define sk_OPENSSL_BLOCK_zero(sk) \ + sk_zero(CHECKED_CAST(_STACK *, STACK_OF(OPENSSL_BLOCK) *, sk)); + +#define sk_OPENSSL_BLOCK_value(sk, i) \ + ((OPENSSL_BLOCK)sk_value( \ + CHECKED_CAST(_STACK *, const STACK_OF(OPENSSL_BLOCK) *, sk), (i))) + +#define sk_OPENSSL_BLOCK_set(sk, i, p) \ + ((OPENSSL_BLOCK)sk_set( \ + CHECKED_CAST(_STACK *, STACK_OF(OPENSSL_BLOCK) *, sk), (i), \ + CHECKED_CAST(void *, OPENSSL_BLOCK, p))) + +#define sk_OPENSSL_BLOCK_free(sk) \ + sk_free(CHECKED_CAST(_STACK *, STACK_OF(OPENSSL_BLOCK) *, sk)) + +#define sk_OPENSSL_BLOCK_pop_free(sk, free_func) \ + sk_pop_free( \ + CHECKED_CAST(_STACK *, STACK_OF(OPENSSL_BLOCK) *, sk), \ + CHECKED_CAST(void (*)(void *), void (*)(OPENSSL_BLOCK), free_func)) + +#define sk_OPENSSL_BLOCK_insert(sk, p, where) \ + sk_insert(CHECKED_CAST(_STACK *, STACK_OF(OPENSSL_BLOCK) *, sk), \ + CHECKED_CAST(void *, OPENSSL_BLOCK, p), (where)) + +#define sk_OPENSSL_BLOCK_delete(sk, where) \ + ((OPENSSL_BLOCK)sk_delete( \ + CHECKED_CAST(_STACK *, STACK_OF(OPENSSL_BLOCK) *, sk), (where))) + +#define sk_OPENSSL_BLOCK_delete_ptr(sk, p) \ + ((OPENSSL_BLOCK)sk_delete_ptr( \ + CHECKED_CAST(_STACK *, STACK_OF(OPENSSL_BLOCK) *, sk), \ + CHECKED_CAST(void *, OPENSSL_BLOCK, p))) + +#define sk_OPENSSL_BLOCK_find(sk, out_index, p) \ + sk_find(CHECKED_CAST(_STACK *, STACK_OF(OPENSSL_BLOCK) *, sk), (out_index), \ + CHECKED_CAST(void *, OPENSSL_BLOCK, p)) + +#define sk_OPENSSL_BLOCK_shift(sk) \ + ((OPENSSL_BLOCK)sk_shift( \ + CHECKED_CAST(_STACK *, STACK_OF(OPENSSL_BLOCK) *, sk))) + +#define sk_OPENSSL_BLOCK_push(sk, p) \ + sk_push(CHECKED_CAST(_STACK *, STACK_OF(OPENSSL_BLOCK) *, sk), \ + CHECKED_CAST(void *, OPENSSL_BLOCK, p)) + +#define sk_OPENSSL_BLOCK_pop(sk) \ + ((OPENSSL_BLOCK)sk_pop(CHECKED_CAST(_STACK *, STACK_OF(OPENSSL_BLOCK) *, sk))) + +#define sk_OPENSSL_BLOCK_dup(sk) \ + ((STACK_OF(OPENSSL_BLOCK) *)sk_dup( \ + CHECKED_CAST(_STACK *, const STACK_OF(OPENSSL_BLOCK) *, sk))) + +#define sk_OPENSSL_BLOCK_sort(sk) \ + sk_sort(CHECKED_CAST(_STACK *, STACK_OF(OPENSSL_BLOCK) *, sk)) + +#define sk_OPENSSL_BLOCK_is_sorted(sk) \ + sk_is_sorted(CHECKED_CAST(_STACK *, const STACK_OF(OPENSSL_BLOCK) *, sk)) + +#define sk_OPENSSL_BLOCK_set_cmp_func(sk, comp) \ + ((int (*)(const OPENSSL_BLOCK **a, const OPENSSL_BLOCK **b))sk_set_cmp_func( \ + CHECKED_CAST(_STACK *, STACK_OF(OPENSSL_BLOCK) *, sk), \ + CHECKED_CAST(stack_cmp_func, \ + int (*)(const OPENSSL_BLOCK **a, const OPENSSL_BLOCK **b), \ + comp))) + +#define sk_OPENSSL_BLOCK_deep_copy(sk, copy_func, free_func) \ + ((STACK_OF(OPENSSL_BLOCK) *)sk_deep_copy( \ + CHECKED_CAST(const _STACK *, const STACK_OF(OPENSSL_BLOCK) *, sk), \ + CHECKED_CAST(void *(*)(void *), OPENSSL_BLOCK (*)(OPENSSL_BLOCK), \ + copy_func), \ + CHECKED_CAST(void (*)(void *), void (*)(OPENSSL_BLOCK), free_func))) diff --git a/phonelibs/boringssl/include/openssl/thread.h b/phonelibs/boringssl/include/openssl/thread.h new file mode 100644 index 00000000000000..568a858332ac8c --- /dev/null +++ b/phonelibs/boringssl/include/openssl/thread.h @@ -0,0 +1,173 @@ +/* Copyright (C) 1995-1998 Eric Young (eay@cryptsoft.com) + * All rights reserved. + * + * This package is an SSL implementation written + * by Eric Young (eay@cryptsoft.com). + * The implementation was written so as to conform with Netscapes SSL. + * + * This library is free for commercial and non-commercial use as long as + * the following conditions are aheared to. The following conditions + * apply to all code found in this distribution, be it the RC4, RSA, + * lhash, DES, etc., code; not just the SSL code. The SSL documentation + * included with this distribution is covered by the same copyright terms + * except that the holder is Tim Hudson (tjh@cryptsoft.com). + * + * Copyright remains Eric Young's, and as such any Copyright notices in + * the code are not to be removed. + * If this package is used in a product, Eric Young should be given attribution + * as the author of the parts of the library used. + * This can be in the form of a textual message at program startup or + * in documentation (online or textual) provided with the package. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must 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. All advertising materials mentioning features or use of this software + * must display the following acknowledgement: + * "This product includes cryptographic software written by + * Eric Young (eay@cryptsoft.com)" + * The word 'cryptographic' can be left out if the rouines from the library + * being used are not cryptographic related :-). + * 4. If you include any Windows specific code (or a derivative thereof) from + * the apps directory (application code) you must include an acknowledgement: + * "This product includes software written by Tim Hudson (tjh@cryptsoft.com)" + * + * THIS SOFTWARE IS PROVIDED BY ERIC YOUNG ``AS IS'' AND + * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHOR OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (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 licence and distribution terms for any publically available version or + * derivative of this code cannot be changed. i.e. this code cannot simply be + * copied and put under another distribution licence + * [including the GNU Public Licence.] */ + +#ifndef OPENSSL_HEADER_THREAD_H +#define OPENSSL_HEADER_THREAD_H + +#include + +#include + +#if defined(__cplusplus) +extern "C" { +#endif + + +#if defined(OPENSSL_NO_THREADS) +typedef struct crypto_mutex_st {} CRYPTO_MUTEX; +#elif defined(OPENSSL_WINDOWS) +/* CRYPTO_MUTEX can appear in public header files so we really don't want to + * pull in windows.h. It's statically asserted that this structure is large + * enough to contain a Windows CRITICAL_SECTION by thread_win.c. */ +typedef union crypto_mutex_st { + double alignment; + uint8_t padding[4*sizeof(void*) + 2*sizeof(int)]; +} CRYPTO_MUTEX; +#elif defined(__MACH__) && defined(__APPLE__) +typedef pthread_rwlock_t CRYPTO_MUTEX; +#else +/* It is reasonable to include pthread.h on non-Windows systems, however the + * |pthread_rwlock_t| that we need is hidden under feature flags, and we can't + * ensure that we'll be able to get it. It's statically asserted that this + * structure is large enough to contain a |pthread_rwlock_t| by + * thread_pthread.c. */ +typedef union crypto_mutex_st { + double alignment; + uint8_t padding[3*sizeof(int) + 5*sizeof(unsigned) + 16 + 8]; +} CRYPTO_MUTEX; +#endif + +/* CRYPTO_refcount_t is the type of a reference count. + * + * Since some platforms use C11 atomics to access this, it should have the + * _Atomic qualifier. However, this header is included by C++ programs as well + * as C code that might not set -std=c11. So, in practice, it's not possible to + * do that. Instead we statically assert that the size and native alignment of + * a plain uint32_t and an _Atomic uint32_t are equal in refcount_c11.c. */ +typedef uint32_t CRYPTO_refcount_t; + + +/* Deprecated functions */ + +/* These defines do nothing but are provided to make old code easier to + * compile. */ +#define CRYPTO_LOCK 1 +#define CRYPTO_UNLOCK 2 +#define CRYPTO_READ 4 +#define CRYPTO_WRITE 8 + +/* CRYPTO_num_locks returns one. (This is non-zero that callers who allocate + * sizeof(lock) times this value don't get zero and then fail because malloc(0) + * returned NULL.) */ +OPENSSL_EXPORT int CRYPTO_num_locks(void); + +/* CRYPTO_set_locking_callback does nothing. */ +OPENSSL_EXPORT void CRYPTO_set_locking_callback( + void (*func)(int mode, int lock_num, const char *file, int line)); + +/* CRYPTO_set_add_lock_callback does nothing. */ +OPENSSL_EXPORT void CRYPTO_set_add_lock_callback(int (*func)( + int *num, int amount, int lock_num, const char *file, int line)); + +/* CRYPTO_get_lock_name returns a fixed, dummy string. */ +OPENSSL_EXPORT const char *CRYPTO_get_lock_name(int lock_num); + +/* CRYPTO_THREADID_set_callback returns one. */ +OPENSSL_EXPORT int CRYPTO_THREADID_set_callback( + void (*threadid_func)(CRYPTO_THREADID *threadid)); + +/* CRYPTO_THREADID_set_numeric does nothing. */ +OPENSSL_EXPORT void CRYPTO_THREADID_set_numeric(CRYPTO_THREADID *id, + unsigned long val); + +/* CRYPTO_THREADID_set_pointer does nothing. */ +OPENSSL_EXPORT void CRYPTO_THREADID_set_pointer(CRYPTO_THREADID *id, void *ptr); + +/* CRYPTO_THREADID_current does nothing. */ +OPENSSL_EXPORT void CRYPTO_THREADID_current(CRYPTO_THREADID *id); + + +/* Private functions. + * + * Some old code calls these functions and so no-op implementations are + * provided. + * + * TODO(fork): cleanup callers and remove. */ + +OPENSSL_EXPORT void CRYPTO_set_id_callback(unsigned long (*func)(void)); + +typedef struct { + int references; + struct CRYPTO_dynlock_value *data; +} CRYPTO_dynlock; + +OPENSSL_EXPORT void CRYPTO_set_dynlock_create_callback( + struct CRYPTO_dynlock_value *(*dyn_create_function)(const char *file, + int line)); + +OPENSSL_EXPORT void CRYPTO_set_dynlock_lock_callback(void (*dyn_lock_function)( + int mode, struct CRYPTO_dynlock_value *l, const char *file, int line)); + +OPENSSL_EXPORT void CRYPTO_set_dynlock_destroy_callback( + void (*dyn_destroy_function)(struct CRYPTO_dynlock_value *l, + const char *file, int line)); + + +#if defined(__cplusplus) +} /* extern C */ +#endif + +#endif /* OPENSSL_HEADER_THREAD_H */ diff --git a/phonelibs/boringssl/include/openssl/time_support.h b/phonelibs/boringssl/include/openssl/time_support.h new file mode 100644 index 00000000000000..912e6724152f7a --- /dev/null +++ b/phonelibs/boringssl/include/openssl/time_support.h @@ -0,0 +1,90 @@ +/* Written by Richard Levitte (richard@levitte.org) for the OpenSSL + * project 2001. + * Written by Dr Stephen N Henson (steve@openssl.org) for the OpenSSL + * project 2008. + */ +/* ==================================================================== + * Copyright (c) 2001 The OpenSSL Project. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * + * 3. All advertising materials mentioning features or use of this + * software must display the following acknowledgment: + * "This product includes software developed by the OpenSSL Project + * for use in the OpenSSL Toolkit. (http://www.OpenSSL.org/)" + * + * 4. The names "OpenSSL Toolkit" and "OpenSSL Project" must not be used to + * endorse or promote products derived from this software without + * prior written permission. For written permission, please contact + * licensing@OpenSSL.org. + * + * 5. Products derived from this software may not be called "OpenSSL" + * nor may "OpenSSL" appear in their names without prior written + * permission of the OpenSSL Project. + * + * 6. Redistributions of any form whatsoever must retain the following + * acknowledgment: + * "This product includes software developed by the OpenSSL Project + * for use in the OpenSSL Toolkit (http://www.OpenSSL.org/)" + * + * THIS SOFTWARE IS PROVIDED BY THE OpenSSL PROJECT ``AS IS'' AND ANY + * EXPRESSED OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR + * PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE OpenSSL PROJECT OR + * ITS CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, + * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT + * NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + * STRICT LIABILITY, OR TORT (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 product includes cryptographic software written by Eric Young + * (eay@cryptsoft.com). This product includes software written by Tim + * Hudson (tjh@cryptsoft.com). */ + +#ifndef OPENSSL_HEADER_TIME_H +#define OPENSSL_HEADER_TIME_H + +#include + + +#if defined(__cplusplus) +extern "C" { +#endif + + +/* Wrapper functions for time functions. */ + + +/* OPENSSL_gmtime wraps |gmtime_r|. See the manual page for that function. */ +struct tm *OPENSSL_gmtime(const time_t *timer, struct tm *result); + +/* OPENSSL_gmtime_adj updates |tm| by adding |offset_day| days and |offset_sec| + * seconds. */ +int OPENSSL_gmtime_adj(struct tm *tm, int offset_day, long offset_sec); + +/* OPENSSL_gmtime_diff calculates the difference between |from| and |to| and + * outputs the difference as a number of days and seconds in |*out_days| and + * |*out_secs|. */ +int OPENSSL_gmtime_diff(int *out_days, int *out_secs, const struct tm *from, + const struct tm *to); + + +#if defined(__cplusplus) +} /* extern C */ +#endif + +#endif /* OPENSSL_HEADER_TIME_H */ diff --git a/phonelibs/boringssl/include/openssl/tls1.h b/phonelibs/boringssl/include/openssl/tls1.h new file mode 100644 index 00000000000000..f2bee2738f956e --- /dev/null +++ b/phonelibs/boringssl/include/openssl/tls1.h @@ -0,0 +1,714 @@ +/* ssl/tls1.h */ +/* Copyright (C) 1995-1998 Eric Young (eay@cryptsoft.com) + * All rights reserved. + * + * This package is an SSL implementation written + * by Eric Young (eay@cryptsoft.com). + * The implementation was written so as to conform with Netscapes SSL. + * + * This library is free for commercial and non-commercial use as long as + * the following conditions are aheared to. The following conditions + * apply to all code found in this distribution, be it the RC4, RSA, + * lhash, DES, etc., code; not just the SSL code. The SSL documentation + * included with this distribution is covered by the same copyright terms + * except that the holder is Tim Hudson (tjh@cryptsoft.com). + * + * Copyright remains Eric Young's, and as such any Copyright notices in + * the code are not to be removed. + * If this package is used in a product, Eric Young should be given attribution + * as the author of the parts of the library used. + * This can be in the form of a textual message at program startup or + * in documentation (online or textual) provided with the package. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must 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. All advertising materials mentioning features or use of this software + * must display the following acknowledgement: + * "This product includes cryptographic software written by + * Eric Young (eay@cryptsoft.com)" + * The word 'cryptographic' can be left out if the rouines from the library + * being used are not cryptographic related :-). + * 4. If you include any Windows specific code (or a derivative thereof) from + * the apps directory (application code) you must include an acknowledgement: + * "This product includes software written by Tim Hudson (tjh@cryptsoft.com)" + * + * THIS SOFTWARE IS PROVIDED BY ERIC YOUNG ``AS IS'' AND + * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHOR OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (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 licence and distribution terms for any publically available version or + * derivative of this code cannot be changed. i.e. this code cannot simply be + * copied and put under another distribution licence + * [including the GNU Public Licence.] + */ +/* ==================================================================== + * Copyright (c) 1998-2006 The OpenSSL Project. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * + * 3. All advertising materials mentioning features or use of this + * software must display the following acknowledgment: + * "This product includes software developed by the OpenSSL Project + * for use in the OpenSSL Toolkit. (http://www.openssl.org/)" + * + * 4. The names "OpenSSL Toolkit" and "OpenSSL Project" must not be used to + * endorse or promote products derived from this software without + * prior written permission. For written permission, please contact + * openssl-core@openssl.org. + * + * 5. Products derived from this software may not be called "OpenSSL" + * nor may "OpenSSL" appear in their names without prior written + * permission of the OpenSSL Project. + * + * 6. Redistributions of any form whatsoever must retain the following + * acknowledgment: + * "This product includes software developed by the OpenSSL Project + * for use in the OpenSSL Toolkit (http://www.openssl.org/)" + * + * THIS SOFTWARE IS PROVIDED BY THE OpenSSL PROJECT ``AS IS'' AND ANY + * EXPRESSED OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR + * PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE OpenSSL PROJECT OR + * ITS CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, + * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT + * NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + * STRICT LIABILITY, OR TORT (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 product includes cryptographic software written by Eric Young + * (eay@cryptsoft.com). This product includes software written by Tim + * Hudson (tjh@cryptsoft.com). + * + */ +/* ==================================================================== + * Copyright 2002 Sun Microsystems, Inc. ALL RIGHTS RESERVED. + * + * Portions of the attached software ("Contribution") are developed by + * SUN MICROSYSTEMS, INC., and are contributed to the OpenSSL project. + * + * The Contribution is licensed pursuant to the OpenSSL open source + * license provided above. + * + * ECC cipher suite support in OpenSSL originally written by + * Vipul Gupta and Sumit Gupta of Sun Microsystems Laboratories. + * + */ +/* ==================================================================== + * Copyright 2005 Nokia. All rights reserved. + * + * The portions of the attached software ("Contribution") is developed by + * Nokia Corporation and is licensed pursuant to the OpenSSL open source + * license. + * + * The Contribution, originally written by Mika Kousa and Pasi Eronen of + * Nokia Corporation, consists of the "PSK" (Pre-Shared Key) ciphersuites + * support (see RFC 4279) to OpenSSL. + * + * No patent licenses or other rights except those expressly stated in + * the OpenSSL open source license shall be deemed granted or received + * expressly, by implication, estoppel, or otherwise. + * + * No assurances are provided by Nokia that the Contribution does not + * infringe the patent or other intellectual property rights of any third + * party or that the license provides you with all the necessary rights + * to make use of the Contribution. + * + * THE SOFTWARE IS PROVIDED "AS IS" WITHOUT WARRANTY OF ANY KIND. IN + * ADDITION TO THE DISCLAIMERS INCLUDED IN THE LICENSE, NOKIA + * SPECIFICALLY DISCLAIMS ANY LIABILITY FOR CLAIMS BROUGHT BY YOU OR ANY + * OTHER ENTITY BASED ON INFRINGEMENT OF INTELLECTUAL PROPERTY RIGHTS OR + * OTHERWISE. + */ + +#ifndef HEADER_TLS1_H +#define HEADER_TLS1_H + +#include +#include + +#ifdef __cplusplus +extern "C" { +#endif + + +#define TLS1_ALLOW_EXPERIMENTAL_CIPHERSUITES 0 + +#define TLS1_AD_DECRYPTION_FAILED 21 +#define TLS1_AD_RECORD_OVERFLOW 22 +#define TLS1_AD_UNKNOWN_CA 48 /* fatal */ +#define TLS1_AD_ACCESS_DENIED 49 /* fatal */ +#define TLS1_AD_DECODE_ERROR 50 /* fatal */ +#define TLS1_AD_DECRYPT_ERROR 51 +#define TLS1_AD_EXPORT_RESTRICTION 60 /* fatal */ +#define TLS1_AD_PROTOCOL_VERSION 70 /* fatal */ +#define TLS1_AD_INSUFFICIENT_SECURITY 71 /* fatal */ +#define TLS1_AD_INTERNAL_ERROR 80 /* fatal */ +#define TLS1_AD_USER_CANCELLED 90 +#define TLS1_AD_NO_RENEGOTIATION 100 +/* codes 110-114 are from RFC3546 */ +#define TLS1_AD_UNSUPPORTED_EXTENSION 110 +#define TLS1_AD_CERTIFICATE_UNOBTAINABLE 111 +#define TLS1_AD_UNRECOGNIZED_NAME 112 +#define TLS1_AD_BAD_CERTIFICATE_STATUS_RESPONSE 113 +#define TLS1_AD_BAD_CERTIFICATE_HASH_VALUE 114 +#define TLS1_AD_UNKNOWN_PSK_IDENTITY 115 /* fatal */ + +/* ExtensionType values from RFC3546 / RFC4366 / RFC6066 */ +#define TLSEXT_TYPE_server_name 0 +#define TLSEXT_TYPE_max_fragment_length 1 +#define TLSEXT_TYPE_client_certificate_url 2 +#define TLSEXT_TYPE_trusted_ca_keys 3 +#define TLSEXT_TYPE_truncated_hmac 4 +#define TLSEXT_TYPE_status_request 5 +/* ExtensionType values from RFC4681 */ +#define TLSEXT_TYPE_user_mapping 6 + +/* ExtensionType values from RFC5878 */ +#define TLSEXT_TYPE_client_authz 7 +#define TLSEXT_TYPE_server_authz 8 + +/* ExtensionType values from RFC6091 */ +#define TLSEXT_TYPE_cert_type 9 + +/* ExtensionType values from RFC4492 */ +#define TLSEXT_TYPE_elliptic_curves 10 +#define TLSEXT_TYPE_ec_point_formats 11 + +/* ExtensionType value from RFC5054 */ +#define TLSEXT_TYPE_srp 12 + +/* ExtensionType values from RFC5246 */ +#define TLSEXT_TYPE_signature_algorithms 13 + +/* ExtensionType value from RFC5764 */ +#define TLSEXT_TYPE_use_srtp 14 + +/* ExtensionType value from RFC5620 */ +#define TLSEXT_TYPE_heartbeat 15 + +/* ExtensionType value from RFC7301 */ +#define TLSEXT_TYPE_application_layer_protocol_negotiation 16 + +/* ExtensionType value for TLS padding extension. + * http://www.iana.org/assignments/tls-extensiontype-values/tls-extensiontype-values.xhtml + * http://tools.ietf.org/html/draft-agl-tls-padding-03 + */ +#define TLSEXT_TYPE_padding 21 + +/* https://tools.ietf.org/html/draft-ietf-tls-session-hash-01 */ +#define TLSEXT_TYPE_extended_master_secret 23 + +/* ExtensionType value from RFC4507 */ +#define TLSEXT_TYPE_session_ticket 35 + +/* ExtensionType value from RFC5746 */ +#define TLSEXT_TYPE_renegotiate 0xff01 + +/* ExtensionType value from RFC6962 */ +#define TLSEXT_TYPE_certificate_timestamp 18 + +/* This is not an IANA defined extension number */ +#define TLSEXT_TYPE_next_proto_neg 13172 + +/* This is not an IANA defined extension number */ +#define TLSEXT_TYPE_channel_id 30031 +#define TLSEXT_TYPE_channel_id_new 30032 + +/* NameType value from RFC 3546 */ +#define TLSEXT_NAMETYPE_host_name 0 +/* status request value from RFC 3546 */ +#define TLSEXT_STATUSTYPE_ocsp 1 + +/* ECPointFormat values from RFC 4492 */ +#define TLSEXT_ECPOINTFORMAT_uncompressed 0 +#define TLSEXT_ECPOINTFORMAT_ansiX962_compressed_prime 1 +#define TLSEXT_ECPOINTFORMAT_ansiX962_compressed_char2 2 + +/* Signature and hash algorithms from RFC 5246 */ + +#define TLSEXT_signature_anonymous 0 +#define TLSEXT_signature_rsa 1 +#define TLSEXT_signature_dsa 2 +#define TLSEXT_signature_ecdsa 3 + +#define TLSEXT_hash_none 0 +#define TLSEXT_hash_md5 1 +#define TLSEXT_hash_sha1 2 +#define TLSEXT_hash_sha224 3 +#define TLSEXT_hash_sha256 4 +#define TLSEXT_hash_sha384 5 +#define TLSEXT_hash_sha512 6 + +/* Flag set for unrecognised algorithms */ +#define TLSEXT_nid_unknown 0x1000000 + +/* ECC curves */ + +#define TLSEXT_curve_P_256 23 +#define TLSEXT_curve_P_384 24 + + +#define TLSEXT_MAXLEN_host_name 255 + +OPENSSL_EXPORT const char *SSL_get_servername(const SSL *s, const int type); +OPENSSL_EXPORT int SSL_get_servername_type(const SSL *s); + +/* SSL_export_keying_material exports a value derived from the master secret, as + * specified in RFC 5705. It writes |out_len| bytes to |out| given a label and + * optional context. (Since a zero length context is allowed, the |use_context| + * flag controls whether a context is included.) + * + * It returns one on success and zero otherwise. */ +OPENSSL_EXPORT int SSL_export_keying_material( + SSL *s, uint8_t *out, size_t out_len, const char *label, size_t label_len, + const uint8_t *context, size_t context_len, int use_context); + +OPENSSL_EXPORT int SSL_get_sigalgs(SSL *s, int idx, int *psign, int *phash, + int *psignandhash, uint8_t *rsig, + uint8_t *rhash); + +OPENSSL_EXPORT int SSL_get_shared_sigalgs(SSL *s, int idx, int *psign, + int *phash, int *psignandhash, + uint8_t *rsig, uint8_t *rhash); + +/* SSL_set_tlsext_host_name, for a client, configures |ssl| to advertise |name| + * in the server_name extension. It returns one on success and zero on error. */ +OPENSSL_EXPORT int SSL_set_tlsext_host_name(SSL *ssl, const char *name); + +/* SSL_CTX_set_tlsext_servername_callback configures |callback| to be called on + * the server after ClientHello extensions have been parsed and returns one. + * |callback| may use |SSL_get_servername| to examine the server_name extension + * and return a |SSL_TLSEXT_ERR_*| value. If it returns |SSL_TLSEXT_ERR_NOACK|, + * the server_name extension is not acknowledged in the ServerHello. If the + * return value signals an alert, |callback| should set |*out_alert| to the + * alert to send. */ +OPENSSL_EXPORT int SSL_CTX_set_tlsext_servername_callback( + SSL_CTX *ctx, int (*callback)(SSL *ssl, int *out_alert, void *arg)); + +#define SSL_TLSEXT_ERR_OK 0 +#define SSL_TLSEXT_ERR_ALERT_WARNING 1 +#define SSL_TLSEXT_ERR_ALERT_FATAL 2 +#define SSL_TLSEXT_ERR_NOACK 3 + +/* SSL_CTX_set_tlsext_servername_arg sets the argument to the servername + * callback and returns one. See |SSL_CTX_set_tlsext_servername_callback|. */ +OPENSSL_EXPORT int SSL_CTX_set_tlsext_servername_arg(SSL_CTX *ctx, void *arg); + +#define SSL_CTX_get_tlsext_ticket_keys(ctx, keys, keylen) \ + SSL_CTX_ctrl((ctx), SSL_CTRL_GET_TLSEXT_TICKET_KEYS, (keylen), (keys)) +#define SSL_CTX_set_tlsext_ticket_keys(ctx, keys, keylen) \ + SSL_CTX_ctrl((ctx), SSL_CTRL_SET_TLSEXT_TICKET_KEYS, (keylen), (keys)) + +/* SSL_CTX_set_tlsext_ticket_key_cb sets the ticket callback to |callback| and + * returns one. |callback| will be called when encrypting a new ticket and when + * decrypting a ticket from the client. + * + * In both modes, |ctx| and |hmac_ctx| will already have been initialized with + * |EVP_CIPHER_CTX_init| and |HMAC_CTX_init|, respectively. |callback| + * configures |hmac_ctx| with an HMAC digest and key, and configures |ctx| + * for encryption or decryption, based on the mode. + * + * When encrypting a new ticket, |encrypt| will be one. It writes a public + * 16-byte key name to |key_name| and a fresh IV to |iv|. The output IV length + * must match |EVP_CIPHER_CTX_iv_length| of the cipher selected. In this mode, + * |callback| returns 1 on success and -1 on error. + * + * When decrypting a ticket, |encrypt| will be zero. |key_name| will point to a + * 16-byte key name and |iv| points to an IV. The length of the IV consumed must + * match |EVP_CIPHER_CTX_iv_length| of the cipher selected. In this mode, + * |callback| returns -1 to abort the handshake, 0 if decrypting the ticket + * failed, and 1 or 2 on success. If it returns 2, the ticket will be renewed. + * This may be used to re-key the ticket. + * + * WARNING: |callback| wildly breaks the usual return value convention and is + * called in two different modes. */ +OPENSSL_EXPORT int SSL_CTX_set_tlsext_ticket_key_cb( + SSL_CTX *ctx, int (*callback)(SSL *ssl, uint8_t *key_name, uint8_t *iv, + EVP_CIPHER_CTX *ctx, HMAC_CTX *hmac_ctx, + int encrypt)); + +/* PSK ciphersuites from 4279 */ +#define TLS1_CK_PSK_WITH_RC4_128_SHA 0x0300008A +#define TLS1_CK_PSK_WITH_3DES_EDE_CBC_SHA 0x0300008B +#define TLS1_CK_PSK_WITH_AES_128_CBC_SHA 0x0300008C +#define TLS1_CK_PSK_WITH_AES_256_CBC_SHA 0x0300008D + +/* PSK ciphersuites from RFC 5489 */ +#define TLS1_CK_ECDHE_PSK_WITH_AES_128_CBC_SHA 0x0300C035 +#define TLS1_CK_ECDHE_PSK_WITH_AES_256_CBC_SHA 0x0300C036 + +/* Additional TLS ciphersuites from expired Internet Draft + * draft-ietf-tls-56-bit-ciphersuites-01.txt + * (available if TLS1_ALLOW_EXPERIMENTAL_CIPHERSUITES is defined, see + * s3_lib.c). We actually treat them like SSL 3.0 ciphers, which we probably + * shouldn't. Note that the first two are actually not in the IDs. */ +#define TLS1_CK_RSA_EXPORT1024_WITH_RC4_56_MD5 0x03000060 /* not in ID */ +#define TLS1_CK_RSA_EXPORT1024_WITH_RC2_CBC_56_MD5 0x03000061 /* not in ID */ +#define TLS1_CK_RSA_EXPORT1024_WITH_DES_CBC_SHA 0x03000062 +#define TLS1_CK_DHE_DSS_EXPORT1024_WITH_DES_CBC_SHA 0x03000063 +#define TLS1_CK_RSA_EXPORT1024_WITH_RC4_56_SHA 0x03000064 +#define TLS1_CK_DHE_DSS_EXPORT1024_WITH_RC4_56_SHA 0x03000065 +#define TLS1_CK_DHE_DSS_WITH_RC4_128_SHA 0x03000066 + +/* AES ciphersuites from RFC3268 */ + +#define TLS1_CK_RSA_WITH_AES_128_SHA 0x0300002F +#define TLS1_CK_DH_DSS_WITH_AES_128_SHA 0x03000030 +#define TLS1_CK_DH_RSA_WITH_AES_128_SHA 0x03000031 +#define TLS1_CK_DHE_DSS_WITH_AES_128_SHA 0x03000032 +#define TLS1_CK_DHE_RSA_WITH_AES_128_SHA 0x03000033 +#define TLS1_CK_ADH_WITH_AES_128_SHA 0x03000034 + +#define TLS1_CK_RSA_WITH_AES_256_SHA 0x03000035 +#define TLS1_CK_DH_DSS_WITH_AES_256_SHA 0x03000036 +#define TLS1_CK_DH_RSA_WITH_AES_256_SHA 0x03000037 +#define TLS1_CK_DHE_DSS_WITH_AES_256_SHA 0x03000038 +#define TLS1_CK_DHE_RSA_WITH_AES_256_SHA 0x03000039 +#define TLS1_CK_ADH_WITH_AES_256_SHA 0x0300003A + +/* TLS v1.2 ciphersuites */ +#define TLS1_CK_RSA_WITH_NULL_SHA256 0x0300003B +#define TLS1_CK_RSA_WITH_AES_128_SHA256 0x0300003C +#define TLS1_CK_RSA_WITH_AES_256_SHA256 0x0300003D +#define TLS1_CK_DH_DSS_WITH_AES_128_SHA256 0x0300003E +#define TLS1_CK_DH_RSA_WITH_AES_128_SHA256 0x0300003F +#define TLS1_CK_DHE_DSS_WITH_AES_128_SHA256 0x03000040 + +/* Camellia ciphersuites from RFC4132 */ +#define TLS1_CK_RSA_WITH_CAMELLIA_128_CBC_SHA 0x03000041 +#define TLS1_CK_DH_DSS_WITH_CAMELLIA_128_CBC_SHA 0x03000042 +#define TLS1_CK_DH_RSA_WITH_CAMELLIA_128_CBC_SHA 0x03000043 +#define TLS1_CK_DHE_DSS_WITH_CAMELLIA_128_CBC_SHA 0x03000044 +#define TLS1_CK_DHE_RSA_WITH_CAMELLIA_128_CBC_SHA 0x03000045 +#define TLS1_CK_ADH_WITH_CAMELLIA_128_CBC_SHA 0x03000046 + +/* TLS v1.2 ciphersuites */ +#define TLS1_CK_DHE_RSA_WITH_AES_128_SHA256 0x03000067 +#define TLS1_CK_DH_DSS_WITH_AES_256_SHA256 0x03000068 +#define TLS1_CK_DH_RSA_WITH_AES_256_SHA256 0x03000069 +#define TLS1_CK_DHE_DSS_WITH_AES_256_SHA256 0x0300006A +#define TLS1_CK_DHE_RSA_WITH_AES_256_SHA256 0x0300006B +#define TLS1_CK_ADH_WITH_AES_128_SHA256 0x0300006C +#define TLS1_CK_ADH_WITH_AES_256_SHA256 0x0300006D + +/* Camellia ciphersuites from RFC4132 */ +#define TLS1_CK_RSA_WITH_CAMELLIA_256_CBC_SHA 0x03000084 +#define TLS1_CK_DH_DSS_WITH_CAMELLIA_256_CBC_SHA 0x03000085 +#define TLS1_CK_DH_RSA_WITH_CAMELLIA_256_CBC_SHA 0x03000086 +#define TLS1_CK_DHE_DSS_WITH_CAMELLIA_256_CBC_SHA 0x03000087 +#define TLS1_CK_DHE_RSA_WITH_CAMELLIA_256_CBC_SHA 0x03000088 +#define TLS1_CK_ADH_WITH_CAMELLIA_256_CBC_SHA 0x03000089 + +/* SEED ciphersuites from RFC4162 */ +#define TLS1_CK_RSA_WITH_SEED_SHA 0x03000096 +#define TLS1_CK_DH_DSS_WITH_SEED_SHA 0x03000097 +#define TLS1_CK_DH_RSA_WITH_SEED_SHA 0x03000098 +#define TLS1_CK_DHE_DSS_WITH_SEED_SHA 0x03000099 +#define TLS1_CK_DHE_RSA_WITH_SEED_SHA 0x0300009A +#define TLS1_CK_ADH_WITH_SEED_SHA 0x0300009B + +/* TLS v1.2 GCM ciphersuites from RFC5288 */ +#define TLS1_CK_RSA_WITH_AES_128_GCM_SHA256 0x0300009C +#define TLS1_CK_RSA_WITH_AES_256_GCM_SHA384 0x0300009D +#define TLS1_CK_DHE_RSA_WITH_AES_128_GCM_SHA256 0x0300009E +#define TLS1_CK_DHE_RSA_WITH_AES_256_GCM_SHA384 0x0300009F +#define TLS1_CK_DH_RSA_WITH_AES_128_GCM_SHA256 0x030000A0 +#define TLS1_CK_DH_RSA_WITH_AES_256_GCM_SHA384 0x030000A1 +#define TLS1_CK_DHE_DSS_WITH_AES_128_GCM_SHA256 0x030000A2 +#define TLS1_CK_DHE_DSS_WITH_AES_256_GCM_SHA384 0x030000A3 +#define TLS1_CK_DH_DSS_WITH_AES_128_GCM_SHA256 0x030000A4 +#define TLS1_CK_DH_DSS_WITH_AES_256_GCM_SHA384 0x030000A5 +#define TLS1_CK_ADH_WITH_AES_128_GCM_SHA256 0x030000A6 +#define TLS1_CK_ADH_WITH_AES_256_GCM_SHA384 0x030000A7 + +/* ECC ciphersuites from RFC4492 */ +#define TLS1_CK_ECDH_ECDSA_WITH_NULL_SHA 0x0300C001 +#define TLS1_CK_ECDH_ECDSA_WITH_RC4_128_SHA 0x0300C002 +#define TLS1_CK_ECDH_ECDSA_WITH_DES_192_CBC3_SHA 0x0300C003 +#define TLS1_CK_ECDH_ECDSA_WITH_AES_128_CBC_SHA 0x0300C004 +#define TLS1_CK_ECDH_ECDSA_WITH_AES_256_CBC_SHA 0x0300C005 + +#define TLS1_CK_ECDHE_ECDSA_WITH_NULL_SHA 0x0300C006 +#define TLS1_CK_ECDHE_ECDSA_WITH_RC4_128_SHA 0x0300C007 +#define TLS1_CK_ECDHE_ECDSA_WITH_DES_192_CBC3_SHA 0x0300C008 +#define TLS1_CK_ECDHE_ECDSA_WITH_AES_128_CBC_SHA 0x0300C009 +#define TLS1_CK_ECDHE_ECDSA_WITH_AES_256_CBC_SHA 0x0300C00A + +#define TLS1_CK_ECDH_RSA_WITH_NULL_SHA 0x0300C00B +#define TLS1_CK_ECDH_RSA_WITH_RC4_128_SHA 0x0300C00C +#define TLS1_CK_ECDH_RSA_WITH_DES_192_CBC3_SHA 0x0300C00D +#define TLS1_CK_ECDH_RSA_WITH_AES_128_CBC_SHA 0x0300C00E +#define TLS1_CK_ECDH_RSA_WITH_AES_256_CBC_SHA 0x0300C00F + +#define TLS1_CK_ECDHE_RSA_WITH_NULL_SHA 0x0300C010 +#define TLS1_CK_ECDHE_RSA_WITH_RC4_128_SHA 0x0300C011 +#define TLS1_CK_ECDHE_RSA_WITH_DES_192_CBC3_SHA 0x0300C012 +#define TLS1_CK_ECDHE_RSA_WITH_AES_128_CBC_SHA 0x0300C013 +#define TLS1_CK_ECDHE_RSA_WITH_AES_256_CBC_SHA 0x0300C014 + +#define TLS1_CK_ECDH_anon_WITH_NULL_SHA 0x0300C015 +#define TLS1_CK_ECDH_anon_WITH_RC4_128_SHA 0x0300C016 +#define TLS1_CK_ECDH_anon_WITH_DES_192_CBC3_SHA 0x0300C017 +#define TLS1_CK_ECDH_anon_WITH_AES_128_CBC_SHA 0x0300C018 +#define TLS1_CK_ECDH_anon_WITH_AES_256_CBC_SHA 0x0300C019 + +/* SRP ciphersuites from RFC 5054 */ +#define TLS1_CK_SRP_SHA_WITH_3DES_EDE_CBC_SHA 0x0300C01A +#define TLS1_CK_SRP_SHA_RSA_WITH_3DES_EDE_CBC_SHA 0x0300C01B +#define TLS1_CK_SRP_SHA_DSS_WITH_3DES_EDE_CBC_SHA 0x0300C01C +#define TLS1_CK_SRP_SHA_WITH_AES_128_CBC_SHA 0x0300C01D +#define TLS1_CK_SRP_SHA_RSA_WITH_AES_128_CBC_SHA 0x0300C01E +#define TLS1_CK_SRP_SHA_DSS_WITH_AES_128_CBC_SHA 0x0300C01F +#define TLS1_CK_SRP_SHA_WITH_AES_256_CBC_SHA 0x0300C020 +#define TLS1_CK_SRP_SHA_RSA_WITH_AES_256_CBC_SHA 0x0300C021 +#define TLS1_CK_SRP_SHA_DSS_WITH_AES_256_CBC_SHA 0x0300C022 + +/* ECDH HMAC based ciphersuites from RFC5289 */ + +#define TLS1_CK_ECDHE_ECDSA_WITH_AES_128_SHA256 0x0300C023 +#define TLS1_CK_ECDHE_ECDSA_WITH_AES_256_SHA384 0x0300C024 +#define TLS1_CK_ECDH_ECDSA_WITH_AES_128_SHA256 0x0300C025 +#define TLS1_CK_ECDH_ECDSA_WITH_AES_256_SHA384 0x0300C026 +#define TLS1_CK_ECDHE_RSA_WITH_AES_128_SHA256 0x0300C027 +#define TLS1_CK_ECDHE_RSA_WITH_AES_256_SHA384 0x0300C028 +#define TLS1_CK_ECDH_RSA_WITH_AES_128_SHA256 0x0300C029 +#define TLS1_CK_ECDH_RSA_WITH_AES_256_SHA384 0x0300C02A + +/* ECDH GCM based ciphersuites from RFC5289 */ +#define TLS1_CK_ECDHE_ECDSA_WITH_AES_128_GCM_SHA256 0x0300C02B +#define TLS1_CK_ECDHE_ECDSA_WITH_AES_256_GCM_SHA384 0x0300C02C +#define TLS1_CK_ECDH_ECDSA_WITH_AES_128_GCM_SHA256 0x0300C02D +#define TLS1_CK_ECDH_ECDSA_WITH_AES_256_GCM_SHA384 0x0300C02E +#define TLS1_CK_ECDHE_RSA_WITH_AES_128_GCM_SHA256 0x0300C02F +#define TLS1_CK_ECDHE_RSA_WITH_AES_256_GCM_SHA384 0x0300C030 +#define TLS1_CK_ECDH_RSA_WITH_AES_128_GCM_SHA256 0x0300C031 +#define TLS1_CK_ECDH_RSA_WITH_AES_256_GCM_SHA384 0x0300C032 + +#define TLS1_CK_ECDHE_RSA_CHACHA20_POLY1305 0x0300CC13 +#define TLS1_CK_ECDHE_ECDSA_CHACHA20_POLY1305 0x0300CC14 +#define TLS1_CK_DHE_RSA_CHACHA20_POLY1305 0x0300CC15 + +/* XXX + * Inconsistency alert: + * The OpenSSL names of ciphers with ephemeral DH here include the string + * "DHE", while elsewhere it has always been "EDH". + * (The alias for the list of all such ciphers also is "EDH".) + * The specifications speak of "EDH"; maybe we should allow both forms + * for everything. */ +#define TLS1_TXT_RSA_EXPORT1024_WITH_RC4_56_MD5 "EXP1024-RC4-MD5" +#define TLS1_TXT_RSA_EXPORT1024_WITH_RC2_CBC_56_MD5 "EXP1024-RC2-CBC-MD5" +#define TLS1_TXT_RSA_EXPORT1024_WITH_DES_CBC_SHA "EXP1024-DES-CBC-SHA" +#define TLS1_TXT_DHE_DSS_EXPORT1024_WITH_DES_CBC_SHA \ + "EXP1024-DHE-DSS-DES-CBC-SHA" +#define TLS1_TXT_RSA_EXPORT1024_WITH_RC4_56_SHA "EXP1024-RC4-SHA" +#define TLS1_TXT_DHE_DSS_EXPORT1024_WITH_RC4_56_SHA "EXP1024-DHE-DSS-RC4-SHA" +#define TLS1_TXT_DHE_DSS_WITH_RC4_128_SHA "DHE-DSS-RC4-SHA" + +/* AES ciphersuites from RFC3268 */ +#define TLS1_TXT_RSA_WITH_AES_128_SHA "AES128-SHA" +#define TLS1_TXT_DH_DSS_WITH_AES_128_SHA "DH-DSS-AES128-SHA" +#define TLS1_TXT_DH_RSA_WITH_AES_128_SHA "DH-RSA-AES128-SHA" +#define TLS1_TXT_DHE_DSS_WITH_AES_128_SHA "DHE-DSS-AES128-SHA" +#define TLS1_TXT_DHE_RSA_WITH_AES_128_SHA "DHE-RSA-AES128-SHA" +#define TLS1_TXT_ADH_WITH_AES_128_SHA "ADH-AES128-SHA" + +#define TLS1_TXT_RSA_WITH_AES_256_SHA "AES256-SHA" +#define TLS1_TXT_DH_DSS_WITH_AES_256_SHA "DH-DSS-AES256-SHA" +#define TLS1_TXT_DH_RSA_WITH_AES_256_SHA "DH-RSA-AES256-SHA" +#define TLS1_TXT_DHE_DSS_WITH_AES_256_SHA "DHE-DSS-AES256-SHA" +#define TLS1_TXT_DHE_RSA_WITH_AES_256_SHA "DHE-RSA-AES256-SHA" +#define TLS1_TXT_ADH_WITH_AES_256_SHA "ADH-AES256-SHA" + +/* ECC ciphersuites from RFC4492 */ +#define TLS1_TXT_ECDH_ECDSA_WITH_NULL_SHA "ECDH-ECDSA-NULL-SHA" +#define TLS1_TXT_ECDH_ECDSA_WITH_RC4_128_SHA "ECDH-ECDSA-RC4-SHA" +#define TLS1_TXT_ECDH_ECDSA_WITH_DES_192_CBC3_SHA "ECDH-ECDSA-DES-CBC3-SHA" +#define TLS1_TXT_ECDH_ECDSA_WITH_AES_128_CBC_SHA "ECDH-ECDSA-AES128-SHA" +#define TLS1_TXT_ECDH_ECDSA_WITH_AES_256_CBC_SHA "ECDH-ECDSA-AES256-SHA" + +#define TLS1_TXT_ECDHE_ECDSA_WITH_NULL_SHA "ECDHE-ECDSA-NULL-SHA" +#define TLS1_TXT_ECDHE_ECDSA_WITH_RC4_128_SHA "ECDHE-ECDSA-RC4-SHA" +#define TLS1_TXT_ECDHE_ECDSA_WITH_DES_192_CBC3_SHA "ECDHE-ECDSA-DES-CBC3-SHA" +#define TLS1_TXT_ECDHE_ECDSA_WITH_AES_128_CBC_SHA "ECDHE-ECDSA-AES128-SHA" +#define TLS1_TXT_ECDHE_ECDSA_WITH_AES_256_CBC_SHA "ECDHE-ECDSA-AES256-SHA" + +#define TLS1_TXT_ECDH_RSA_WITH_NULL_SHA "ECDH-RSA-NULL-SHA" +#define TLS1_TXT_ECDH_RSA_WITH_RC4_128_SHA "ECDH-RSA-RC4-SHA" +#define TLS1_TXT_ECDH_RSA_WITH_DES_192_CBC3_SHA "ECDH-RSA-DES-CBC3-SHA" +#define TLS1_TXT_ECDH_RSA_WITH_AES_128_CBC_SHA "ECDH-RSA-AES128-SHA" +#define TLS1_TXT_ECDH_RSA_WITH_AES_256_CBC_SHA "ECDH-RSA-AES256-SHA" + +#define TLS1_TXT_ECDHE_RSA_WITH_NULL_SHA "ECDHE-RSA-NULL-SHA" +#define TLS1_TXT_ECDHE_RSA_WITH_RC4_128_SHA "ECDHE-RSA-RC4-SHA" +#define TLS1_TXT_ECDHE_RSA_WITH_DES_192_CBC3_SHA "ECDHE-RSA-DES-CBC3-SHA" +#define TLS1_TXT_ECDHE_RSA_WITH_AES_128_CBC_SHA "ECDHE-RSA-AES128-SHA" +#define TLS1_TXT_ECDHE_RSA_WITH_AES_256_CBC_SHA "ECDHE-RSA-AES256-SHA" + +#define TLS1_TXT_ECDH_anon_WITH_NULL_SHA "AECDH-NULL-SHA" +#define TLS1_TXT_ECDH_anon_WITH_RC4_128_SHA "AECDH-RC4-SHA" +#define TLS1_TXT_ECDH_anon_WITH_DES_192_CBC3_SHA "AECDH-DES-CBC3-SHA" +#define TLS1_TXT_ECDH_anon_WITH_AES_128_CBC_SHA "AECDH-AES128-SHA" +#define TLS1_TXT_ECDH_anon_WITH_AES_256_CBC_SHA "AECDH-AES256-SHA" + +/* PSK ciphersuites from RFC 4279 */ +#define TLS1_TXT_PSK_WITH_RC4_128_SHA "PSK-RC4-SHA" +#define TLS1_TXT_PSK_WITH_3DES_EDE_CBC_SHA "PSK-3DES-EDE-CBC-SHA" +#define TLS1_TXT_PSK_WITH_AES_128_CBC_SHA "PSK-AES128-CBC-SHA" +#define TLS1_TXT_PSK_WITH_AES_256_CBC_SHA "PSK-AES256-CBC-SHA" + +/* PSK ciphersuites from RFC 5489 */ +#define TLS1_TXT_ECDHE_PSK_WITH_AES_128_CBC_SHA "ECDHE-PSK-AES128-CBC-SHA" +#define TLS1_TXT_ECDHE_PSK_WITH_AES_256_CBC_SHA "ECDHE-PSK-AES256-CBC-SHA" + +/* SRP ciphersuite from RFC 5054 */ +#define TLS1_TXT_SRP_SHA_WITH_3DES_EDE_CBC_SHA "SRP-3DES-EDE-CBC-SHA" +#define TLS1_TXT_SRP_SHA_RSA_WITH_3DES_EDE_CBC_SHA "SRP-RSA-3DES-EDE-CBC-SHA" +#define TLS1_TXT_SRP_SHA_DSS_WITH_3DES_EDE_CBC_SHA "SRP-DSS-3DES-EDE-CBC-SHA" +#define TLS1_TXT_SRP_SHA_WITH_AES_128_CBC_SHA "SRP-AES-128-CBC-SHA" +#define TLS1_TXT_SRP_SHA_RSA_WITH_AES_128_CBC_SHA "SRP-RSA-AES-128-CBC-SHA" +#define TLS1_TXT_SRP_SHA_DSS_WITH_AES_128_CBC_SHA "SRP-DSS-AES-128-CBC-SHA" +#define TLS1_TXT_SRP_SHA_WITH_AES_256_CBC_SHA "SRP-AES-256-CBC-SHA" +#define TLS1_TXT_SRP_SHA_RSA_WITH_AES_256_CBC_SHA "SRP-RSA-AES-256-CBC-SHA" +#define TLS1_TXT_SRP_SHA_DSS_WITH_AES_256_CBC_SHA "SRP-DSS-AES-256-CBC-SHA" + +/* Camellia ciphersuites from RFC4132 */ +#define TLS1_TXT_RSA_WITH_CAMELLIA_128_CBC_SHA "CAMELLIA128-SHA" +#define TLS1_TXT_DH_DSS_WITH_CAMELLIA_128_CBC_SHA "DH-DSS-CAMELLIA128-SHA" +#define TLS1_TXT_DH_RSA_WITH_CAMELLIA_128_CBC_SHA "DH-RSA-CAMELLIA128-SHA" +#define TLS1_TXT_DHE_DSS_WITH_CAMELLIA_128_CBC_SHA "DHE-DSS-CAMELLIA128-SHA" +#define TLS1_TXT_DHE_RSA_WITH_CAMELLIA_128_CBC_SHA "DHE-RSA-CAMELLIA128-SHA" +#define TLS1_TXT_ADH_WITH_CAMELLIA_128_CBC_SHA "ADH-CAMELLIA128-SHA" + +#define TLS1_TXT_RSA_WITH_CAMELLIA_256_CBC_SHA "CAMELLIA256-SHA" +#define TLS1_TXT_DH_DSS_WITH_CAMELLIA_256_CBC_SHA "DH-DSS-CAMELLIA256-SHA" +#define TLS1_TXT_DH_RSA_WITH_CAMELLIA_256_CBC_SHA "DH-RSA-CAMELLIA256-SHA" +#define TLS1_TXT_DHE_DSS_WITH_CAMELLIA_256_CBC_SHA "DHE-DSS-CAMELLIA256-SHA" +#define TLS1_TXT_DHE_RSA_WITH_CAMELLIA_256_CBC_SHA "DHE-RSA-CAMELLIA256-SHA" +#define TLS1_TXT_ADH_WITH_CAMELLIA_256_CBC_SHA "ADH-CAMELLIA256-SHA" + +/* SEED ciphersuites from RFC4162 */ +#define TLS1_TXT_RSA_WITH_SEED_SHA "SEED-SHA" +#define TLS1_TXT_DH_DSS_WITH_SEED_SHA "DH-DSS-SEED-SHA" +#define TLS1_TXT_DH_RSA_WITH_SEED_SHA "DH-RSA-SEED-SHA" +#define TLS1_TXT_DHE_DSS_WITH_SEED_SHA "DHE-DSS-SEED-SHA" +#define TLS1_TXT_DHE_RSA_WITH_SEED_SHA "DHE-RSA-SEED-SHA" +#define TLS1_TXT_ADH_WITH_SEED_SHA "ADH-SEED-SHA" + +/* TLS v1.2 ciphersuites */ +#define TLS1_TXT_RSA_WITH_NULL_SHA256 "NULL-SHA256" +#define TLS1_TXT_RSA_WITH_AES_128_SHA256 "AES128-SHA256" +#define TLS1_TXT_RSA_WITH_AES_256_SHA256 "AES256-SHA256" +#define TLS1_TXT_DH_DSS_WITH_AES_128_SHA256 "DH-DSS-AES128-SHA256" +#define TLS1_TXT_DH_RSA_WITH_AES_128_SHA256 "DH-RSA-AES128-SHA256" +#define TLS1_TXT_DHE_DSS_WITH_AES_128_SHA256 "DHE-DSS-AES128-SHA256" +#define TLS1_TXT_DHE_RSA_WITH_AES_128_SHA256 "DHE-RSA-AES128-SHA256" +#define TLS1_TXT_DH_DSS_WITH_AES_256_SHA256 "DH-DSS-AES256-SHA256" +#define TLS1_TXT_DH_RSA_WITH_AES_256_SHA256 "DH-RSA-AES256-SHA256" +#define TLS1_TXT_DHE_DSS_WITH_AES_256_SHA256 "DHE-DSS-AES256-SHA256" +#define TLS1_TXT_DHE_RSA_WITH_AES_256_SHA256 "DHE-RSA-AES256-SHA256" +#define TLS1_TXT_ADH_WITH_AES_128_SHA256 "ADH-AES128-SHA256" +#define TLS1_TXT_ADH_WITH_AES_256_SHA256 "ADH-AES256-SHA256" + +/* TLS v1.2 GCM ciphersuites from RFC5288 */ +#define TLS1_TXT_RSA_WITH_AES_128_GCM_SHA256 "AES128-GCM-SHA256" +#define TLS1_TXT_RSA_WITH_AES_256_GCM_SHA384 "AES256-GCM-SHA384" +#define TLS1_TXT_DHE_RSA_WITH_AES_128_GCM_SHA256 "DHE-RSA-AES128-GCM-SHA256" +#define TLS1_TXT_DHE_RSA_WITH_AES_256_GCM_SHA384 "DHE-RSA-AES256-GCM-SHA384" +#define TLS1_TXT_DH_RSA_WITH_AES_128_GCM_SHA256 "DH-RSA-AES128-GCM-SHA256" +#define TLS1_TXT_DH_RSA_WITH_AES_256_GCM_SHA384 "DH-RSA-AES256-GCM-SHA384" +#define TLS1_TXT_DHE_DSS_WITH_AES_128_GCM_SHA256 "DHE-DSS-AES128-GCM-SHA256" +#define TLS1_TXT_DHE_DSS_WITH_AES_256_GCM_SHA384 "DHE-DSS-AES256-GCM-SHA384" +#define TLS1_TXT_DH_DSS_WITH_AES_128_GCM_SHA256 "DH-DSS-AES128-GCM-SHA256" +#define TLS1_TXT_DH_DSS_WITH_AES_256_GCM_SHA384 "DH-DSS-AES256-GCM-SHA384" +#define TLS1_TXT_ADH_WITH_AES_128_GCM_SHA256 "ADH-AES128-GCM-SHA256" +#define TLS1_TXT_ADH_WITH_AES_256_GCM_SHA384 "ADH-AES256-GCM-SHA384" + +/* ECDH HMAC based ciphersuites from RFC5289 */ + +#define TLS1_TXT_ECDHE_ECDSA_WITH_AES_128_SHA256 "ECDHE-ECDSA-AES128-SHA256" +#define TLS1_TXT_ECDHE_ECDSA_WITH_AES_256_SHA384 "ECDHE-ECDSA-AES256-SHA384" +#define TLS1_TXT_ECDH_ECDSA_WITH_AES_128_SHA256 "ECDH-ECDSA-AES128-SHA256" +#define TLS1_TXT_ECDH_ECDSA_WITH_AES_256_SHA384 "ECDH-ECDSA-AES256-SHA384" +#define TLS1_TXT_ECDHE_RSA_WITH_AES_128_SHA256 "ECDHE-RSA-AES128-SHA256" +#define TLS1_TXT_ECDHE_RSA_WITH_AES_256_SHA384 "ECDHE-RSA-AES256-SHA384" +#define TLS1_TXT_ECDH_RSA_WITH_AES_128_SHA256 "ECDH-RSA-AES128-SHA256" +#define TLS1_TXT_ECDH_RSA_WITH_AES_256_SHA384 "ECDH-RSA-AES256-SHA384" + +/* ECDH GCM based ciphersuites from RFC5289 */ +#define TLS1_TXT_ECDHE_ECDSA_WITH_AES_128_GCM_SHA256 \ + "ECDHE-ECDSA-AES128-GCM-SHA256" +#define TLS1_TXT_ECDHE_ECDSA_WITH_AES_256_GCM_SHA384 \ + "ECDHE-ECDSA-AES256-GCM-SHA384" +#define TLS1_TXT_ECDH_ECDSA_WITH_AES_128_GCM_SHA256 \ + "ECDH-ECDSA-AES128-GCM-SHA256" +#define TLS1_TXT_ECDH_ECDSA_WITH_AES_256_GCM_SHA384 \ + "ECDH-ECDSA-AES256-GCM-SHA384" +#define TLS1_TXT_ECDHE_RSA_WITH_AES_128_GCM_SHA256 "ECDHE-RSA-AES128-GCM-SHA256" +#define TLS1_TXT_ECDHE_RSA_WITH_AES_256_GCM_SHA384 "ECDHE-RSA-AES256-GCM-SHA384" +#define TLS1_TXT_ECDH_RSA_WITH_AES_128_GCM_SHA256 "ECDH-RSA-AES128-GCM-SHA256" +#define TLS1_TXT_ECDH_RSA_WITH_AES_256_GCM_SHA384 "ECDH-RSA-AES256-GCM-SHA384" + +#define TLS1_TXT_ECDHE_RSA_WITH_CHACHA20_POLY1305 "ECDHE-RSA-CHACHA20-POLY1305" +#define TLS1_TXT_ECDHE_ECDSA_WITH_CHACHA20_POLY1305 \ + "ECDHE-ECDSA-CHACHA20-POLY1305" +#define TLS1_TXT_DHE_RSA_WITH_CHACHA20_POLY1305 "DHE-RSA-CHACHA20-POLY1305" + +#define TLS_CT_RSA_SIGN 1 +#define TLS_CT_DSS_SIGN 2 +#define TLS_CT_RSA_FIXED_DH 3 +#define TLS_CT_DSS_FIXED_DH 4 +#define TLS_CT_ECDSA_SIGN 64 +#define TLS_CT_RSA_FIXED_ECDH 65 +#define TLS_CT_ECDSA_FIXED_ECDH 66 + +#define TLS_MD_MAX_CONST_SIZE 20 +#define TLS_MD_CLIENT_FINISH_CONST "client finished" +#define TLS_MD_CLIENT_FINISH_CONST_SIZE 15 +#define TLS_MD_SERVER_FINISH_CONST "server finished" +#define TLS_MD_SERVER_FINISH_CONST_SIZE 15 +#define TLS_MD_KEY_EXPANSION_CONST "key expansion" +#define TLS_MD_KEY_EXPANSION_CONST_SIZE 13 +#define TLS_MD_CLIENT_WRITE_KEY_CONST "client write key" +#define TLS_MD_CLIENT_WRITE_KEY_CONST_SIZE 16 +#define TLS_MD_SERVER_WRITE_KEY_CONST "server write key" +#define TLS_MD_SERVER_WRITE_KEY_CONST_SIZE 16 +#define TLS_MD_IV_BLOCK_CONST "IV block" +#define TLS_MD_IV_BLOCK_CONST_SIZE 8 +#define TLS_MD_MASTER_SECRET_CONST "master secret" +#define TLS_MD_MASTER_SECRET_CONST_SIZE 13 +#define TLS_MD_EXTENDED_MASTER_SECRET_CONST "extended master secret" +#define TLS_MD_EXTENDED_MASTER_SECRET_CONST_SIZE 22 + + +#ifdef __cplusplus +} +#endif +#endif diff --git a/phonelibs/boringssl/include/openssl/type_check.h b/phonelibs/boringssl/include/openssl/type_check.h new file mode 100644 index 00000000000000..674913a354a04c --- /dev/null +++ b/phonelibs/boringssl/include/openssl/type_check.h @@ -0,0 +1,91 @@ +/* Copyright (C) 1995-1998 Eric Young (eay@cryptsoft.com) + * All rights reserved. + * + * This package is an SSL implementation written + * by Eric Young (eay@cryptsoft.com). + * The implementation was written so as to conform with Netscapes SSL. + * + * This library is free for commercial and non-commercial use as long as + * the following conditions are aheared to. The following conditions + * apply to all code found in this distribution, be it the RC4, RSA, + * lhash, DES, etc., code; not just the SSL code. The SSL documentation + * included with this distribution is covered by the same copyright terms + * except that the holder is Tim Hudson (tjh@cryptsoft.com). + * + * Copyright remains Eric Young's, and as such any Copyright notices in + * the code are not to be removed. + * If this package is used in a product, Eric Young should be given attribution + * as the author of the parts of the library used. + * This can be in the form of a textual message at program startup or + * in documentation (online or textual) provided with the package. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must 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. All advertising materials mentioning features or use of this software + * must display the following acknowledgement: + * "This product includes cryptographic software written by + * Eric Young (eay@cryptsoft.com)" + * The word 'cryptographic' can be left out if the rouines from the library + * being used are not cryptographic related :-). + * 4. If you include any Windows specific code (or a derivative thereof) from + * the apps directory (application code) you must include an acknowledgement: + * "This product includes software written by Tim Hudson (tjh@cryptsoft.com)" + * + * THIS SOFTWARE IS PROVIDED BY ERIC YOUNG ``AS IS'' AND + * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHOR OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (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 licence and distribution terms for any publically available version or + * derivative of this code cannot be changed. i.e. this code cannot simply be + * copied and put under another distribution licence + * [including the GNU Public Licence.] */ + +#ifndef OPENSSL_HEADER_TYPE_CHECK_H +#define OPENSSL_HEADER_TYPE_CHECK_H + +#include + +#if defined(__cplusplus) +extern "C" { +#endif + + +/* This header file contains some common macros for enforcing type checking. + * Several, common OpenSSL structures (i.e. stack and lhash) operate on void + * pointers, but we wish to have type checking when they are used with a + * specific type. */ + +/* CHECKED_CAST casts |p| from type |from| to type |to|. */ +#define CHECKED_CAST(to, from, p) ((to) (1 ? (p) : (from)0)) + +/* CHECKED_PTR_OF casts a given pointer to void* and statically checks that it + * was a pointer to |type|. */ +#define CHECKED_PTR_OF(type, p) CHECKED_CAST(void*, type*, (p)) + +#if defined(__STDC_VERSION__) && __STDC_VERSION__ >= 201112L +#define OPENSSL_COMPILE_ASSERT(cond, msg) _Static_assert(cond, #msg) +#else +#define OPENSSL_COMPILE_ASSERT(cond, msg) \ + typedef char OPENSSL_COMPILE_ASSERT_##msg[((cond) ? 1 : -1)] +#endif + + +#if defined(__cplusplus) +} /* extern C */ +#endif + +#endif /* OPENSSL_HEADER_TYPE_CHECK_H */ diff --git a/phonelibs/boringssl/include/openssl/x509.h b/phonelibs/boringssl/include/openssl/x509.h new file mode 100644 index 00000000000000..69c7da64e840d7 --- /dev/null +++ b/phonelibs/boringssl/include/openssl/x509.h @@ -0,0 +1,1317 @@ +/* crypto/x509/x509.h */ +/* Copyright (C) 1995-1998 Eric Young (eay@cryptsoft.com) + * All rights reserved. + * + * This package is an SSL implementation written + * by Eric Young (eay@cryptsoft.com). + * The implementation was written so as to conform with Netscapes SSL. + * + * This library is free for commercial and non-commercial use as long as + * the following conditions are aheared to. The following conditions + * apply to all code found in this distribution, be it the RC4, RSA, + * lhash, DES, etc., code; not just the SSL code. The SSL documentation + * included with this distribution is covered by the same copyright terms + * except that the holder is Tim Hudson (tjh@cryptsoft.com). + * + * Copyright remains Eric Young's, and as such any Copyright notices in + * the code are not to be removed. + * If this package is used in a product, Eric Young should be given attribution + * as the author of the parts of the library used. + * This can be in the form of a textual message at program startup or + * in documentation (online or textual) provided with the package. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must 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. All advertising materials mentioning features or use of this software + * must display the following acknowledgement: + * "This product includes cryptographic software written by + * Eric Young (eay@cryptsoft.com)" + * The word 'cryptographic' can be left out if the rouines from the library + * being used are not cryptographic related :-). + * 4. If you include any Windows specific code (or a derivative thereof) from + * the apps directory (application code) you must include an acknowledgement: + * "This product includes software written by Tim Hudson (tjh@cryptsoft.com)" + * + * THIS SOFTWARE IS PROVIDED BY ERIC YOUNG ``AS IS'' AND + * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHOR OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (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 licence and distribution terms for any publically available version or + * derivative of this code cannot be changed. i.e. this code cannot simply be + * copied and put under another distribution licence + * [including the GNU Public Licence.] + */ +/* ==================================================================== + * Copyright 2002 Sun Microsystems, Inc. ALL RIGHTS RESERVED. + * ECDH support in OpenSSL originally developed by + * SUN MICROSYSTEMS, INC., and contributed to the OpenSSL project. + */ + +#ifndef HEADER_X509_H +#define HEADER_X509_H + +#include + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#ifdef __cplusplus +extern "C" { +#endif + + +#define X509_FILETYPE_PEM 1 +#define X509_FILETYPE_ASN1 2 +#define X509_FILETYPE_DEFAULT 3 + +#define X509v3_KU_DIGITAL_SIGNATURE 0x0080 +#define X509v3_KU_NON_REPUDIATION 0x0040 +#define X509v3_KU_KEY_ENCIPHERMENT 0x0020 +#define X509v3_KU_DATA_ENCIPHERMENT 0x0010 +#define X509v3_KU_KEY_AGREEMENT 0x0008 +#define X509v3_KU_KEY_CERT_SIGN 0x0004 +#define X509v3_KU_CRL_SIGN 0x0002 +#define X509v3_KU_ENCIPHER_ONLY 0x0001 +#define X509v3_KU_DECIPHER_ONLY 0x8000 +#define X509v3_KU_UNDEF 0xffff + +typedef struct X509_objects_st + { + int nid; + int (*a2i)(void); + int (*i2a)(void); + } X509_OBJECTS; + +DECLARE_ASN1_SET_OF(X509_ALGOR) + +typedef STACK_OF(X509_ALGOR) X509_ALGORS; + +typedef struct X509_val_st + { + ASN1_TIME *notBefore; + ASN1_TIME *notAfter; + } X509_VAL; + +struct X509_pubkey_st + { + X509_ALGOR *algor; + ASN1_BIT_STRING *public_key; + EVP_PKEY *pkey; + }; + +typedef struct X509_sig_st + { + X509_ALGOR *algor; + ASN1_OCTET_STRING *digest; + } X509_SIG; + +typedef struct X509_name_entry_st + { + ASN1_OBJECT *object; + ASN1_STRING *value; + int set; + int size; /* temp variable */ + } X509_NAME_ENTRY; + +DECLARE_STACK_OF(X509_NAME_ENTRY) +DECLARE_ASN1_SET_OF(X509_NAME_ENTRY) + +/* we always keep X509_NAMEs in 2 forms. */ +typedef struct X509_name_st + { + STACK_OF(X509_NAME_ENTRY) *entries; + int modified; /* true if 'bytes' needs to be built */ +#ifndef OPENSSL_NO_BUFFER + BUF_MEM *bytes; +#else + char *bytes; +#endif +/* unsigned long hash; Keep the hash around for lookups */ + unsigned char *canon_enc; + int canon_enclen; + } X509_NAME; + +DECLARE_STACK_OF(X509_NAME) + +#define X509_EX_V_NETSCAPE_HACK 0x8000 +#define X509_EX_V_INIT 0x0001 +typedef struct X509_extension_st + { + ASN1_OBJECT *object; + ASN1_BOOLEAN critical; + ASN1_OCTET_STRING *value; + } X509_EXTENSION; + +typedef STACK_OF(X509_EXTENSION) X509_EXTENSIONS; + +DECLARE_STACK_OF(X509_EXTENSION) +DECLARE_ASN1_SET_OF(X509_EXTENSION) + +/* a sequence of these are used */ +typedef struct x509_attributes_st + { + ASN1_OBJECT *object; + int single; /* 0 for a set, 1 for a single item (which is wrong) */ + union { + char *ptr; +/* 0 */ STACK_OF(ASN1_TYPE) *set; +/* 1 */ ASN1_TYPE *single; + } value; + } X509_ATTRIBUTE; + +DECLARE_STACK_OF(X509_ATTRIBUTE) +DECLARE_ASN1_SET_OF(X509_ATTRIBUTE) + + +typedef struct X509_req_info_st + { + ASN1_ENCODING enc; + ASN1_INTEGER *version; + X509_NAME *subject; + X509_PUBKEY *pubkey; + /* d=2 hl=2 l= 0 cons: cont: 00 */ + STACK_OF(X509_ATTRIBUTE) *attributes; /* [ 0 ] */ + } X509_REQ_INFO; + +typedef struct X509_req_st + { + X509_REQ_INFO *req_info; + X509_ALGOR *sig_alg; + ASN1_BIT_STRING *signature; + CRYPTO_refcount_t references; + } X509_REQ; + +typedef struct x509_cinf_st + { + ASN1_INTEGER *version; /* [ 0 ] default of v1 */ + ASN1_INTEGER *serialNumber; + X509_ALGOR *signature; + X509_NAME *issuer; + X509_VAL *validity; + X509_NAME *subject; + X509_PUBKEY *key; + ASN1_BIT_STRING *issuerUID; /* [ 1 ] optional in v2 */ + ASN1_BIT_STRING *subjectUID; /* [ 2 ] optional in v2 */ + STACK_OF(X509_EXTENSION) *extensions; /* [ 3 ] optional in v3 */ + ASN1_ENCODING enc; + } X509_CINF; + +/* This stuff is certificate "auxiliary info" + * it contains details which are useful in certificate + * stores and databases. When used this is tagged onto + * the end of the certificate itself + */ + +typedef struct x509_cert_aux_st + { + STACK_OF(ASN1_OBJECT) *trust; /* trusted uses */ + STACK_OF(ASN1_OBJECT) *reject; /* rejected uses */ + ASN1_UTF8STRING *alias; /* "friendly name" */ + ASN1_OCTET_STRING *keyid; /* key id of private key */ + STACK_OF(X509_ALGOR) *other; /* other unspecified info */ + } X509_CERT_AUX; + +struct x509_st + { + X509_CINF *cert_info; + X509_ALGOR *sig_alg; + ASN1_BIT_STRING *signature; + int valid; + CRYPTO_refcount_t references; + char *name; + CRYPTO_EX_DATA ex_data; + /* These contain copies of various extension values */ + long ex_pathlen; + long ex_pcpathlen; + unsigned long ex_flags; + unsigned long ex_kusage; + unsigned long ex_xkusage; + unsigned long ex_nscert; + ASN1_OCTET_STRING *skid; + AUTHORITY_KEYID *akid; + X509_POLICY_CACHE *policy_cache; + STACK_OF(DIST_POINT) *crldp; + STACK_OF(GENERAL_NAME) *altname; + NAME_CONSTRAINTS *nc; + unsigned char sha1_hash[SHA_DIGEST_LENGTH]; + X509_CERT_AUX *aux; + } /* X509 */; + +DECLARE_STACK_OF(X509) +DECLARE_ASN1_SET_OF(X509) + +/* This is used for a table of trust checking functions */ + +typedef struct x509_trust_st { + int trust; + int flags; + int (*check_trust)(struct x509_trust_st *, X509 *, int); + char *name; + int arg1; + void *arg2; +} X509_TRUST; + +DECLARE_STACK_OF(X509_TRUST) + +typedef struct x509_cert_pair_st { + X509 *forward; + X509 *reverse; +} X509_CERT_PAIR; + +/* standard trust ids */ + +#define X509_TRUST_DEFAULT -1 /* Only valid in purpose settings */ + +#define X509_TRUST_COMPAT 1 +#define X509_TRUST_SSL_CLIENT 2 +#define X509_TRUST_SSL_SERVER 3 +#define X509_TRUST_EMAIL 4 +#define X509_TRUST_OBJECT_SIGN 5 +#define X509_TRUST_OCSP_SIGN 6 +#define X509_TRUST_OCSP_REQUEST 7 +#define X509_TRUST_TSA 8 + +/* Keep these up to date! */ +#define X509_TRUST_MIN 1 +#define X509_TRUST_MAX 8 + + +/* trust_flags values */ +#define X509_TRUST_DYNAMIC 1 +#define X509_TRUST_DYNAMIC_NAME 2 + +/* check_trust return codes */ + +#define X509_TRUST_TRUSTED 1 +#define X509_TRUST_REJECTED 2 +#define X509_TRUST_UNTRUSTED 3 + +/* Flags for X509_print_ex() */ + +#define X509_FLAG_COMPAT 0 +#define X509_FLAG_NO_HEADER 1L +#define X509_FLAG_NO_VERSION (1L << 1) +#define X509_FLAG_NO_SERIAL (1L << 2) +#define X509_FLAG_NO_SIGNAME (1L << 3) +#define X509_FLAG_NO_ISSUER (1L << 4) +#define X509_FLAG_NO_VALIDITY (1L << 5) +#define X509_FLAG_NO_SUBJECT (1L << 6) +#define X509_FLAG_NO_PUBKEY (1L << 7) +#define X509_FLAG_NO_EXTENSIONS (1L << 8) +#define X509_FLAG_NO_SIGDUMP (1L << 9) +#define X509_FLAG_NO_AUX (1L << 10) +#define X509_FLAG_NO_ATTRIBUTES (1L << 11) +#define X509_FLAG_NO_IDS (1L << 12) + +/* Flags specific to X509_NAME_print_ex() */ + +/* The field separator information */ + +#define XN_FLAG_SEP_MASK (0xf << 16) + +#define XN_FLAG_COMPAT 0 /* Traditional SSLeay: use old X509_NAME_print */ +#define XN_FLAG_SEP_COMMA_PLUS (1 << 16) /* RFC2253 ,+ */ +#define XN_FLAG_SEP_CPLUS_SPC (2 << 16) /* ,+ spaced: more readable */ +#define XN_FLAG_SEP_SPLUS_SPC (3 << 16) /* ;+ spaced */ +#define XN_FLAG_SEP_MULTILINE (4 << 16) /* One line per field */ + +#define XN_FLAG_DN_REV (1 << 20) /* Reverse DN order */ + +/* How the field name is shown */ + +#define XN_FLAG_FN_MASK (0x3 << 21) + +#define XN_FLAG_FN_SN 0 /* Object short name */ +#define XN_FLAG_FN_LN (1 << 21) /* Object long name */ +#define XN_FLAG_FN_OID (2 << 21) /* Always use OIDs */ +#define XN_FLAG_FN_NONE (3 << 21) /* No field names */ + +#define XN_FLAG_SPC_EQ (1 << 23) /* Put spaces round '=' */ + +/* This determines if we dump fields we don't recognise: + * RFC2253 requires this. + */ + +#define XN_FLAG_DUMP_UNKNOWN_FIELDS (1 << 24) + +#define XN_FLAG_FN_ALIGN (1 << 25) /* Align field names to 20 characters */ + +/* Complete set of RFC2253 flags */ + +#define XN_FLAG_RFC2253 (ASN1_STRFLGS_RFC2253 | \ + XN_FLAG_SEP_COMMA_PLUS | \ + XN_FLAG_DN_REV | \ + XN_FLAG_FN_SN | \ + XN_FLAG_DUMP_UNKNOWN_FIELDS) + +/* readable oneline form */ + +#define XN_FLAG_ONELINE (ASN1_STRFLGS_RFC2253 | \ + ASN1_STRFLGS_ESC_QUOTE | \ + XN_FLAG_SEP_CPLUS_SPC | \ + XN_FLAG_SPC_EQ | \ + XN_FLAG_FN_SN) + +/* readable multiline form */ + +#define XN_FLAG_MULTILINE (ASN1_STRFLGS_ESC_CTRL | \ + ASN1_STRFLGS_ESC_MSB | \ + XN_FLAG_SEP_MULTILINE | \ + XN_FLAG_SPC_EQ | \ + XN_FLAG_FN_LN | \ + XN_FLAG_FN_ALIGN) + +struct x509_revoked_st + { + ASN1_INTEGER *serialNumber; + ASN1_TIME *revocationDate; + STACK_OF(X509_EXTENSION) /* optional */ *extensions; + /* Set up if indirect CRL */ + STACK_OF(GENERAL_NAME) *issuer; + /* Revocation reason */ + int reason; + int sequence; /* load sequence */ + }; + +DECLARE_STACK_OF(X509_REVOKED) +DECLARE_ASN1_SET_OF(X509_REVOKED) + +typedef struct X509_crl_info_st + { + ASN1_INTEGER *version; + X509_ALGOR *sig_alg; + X509_NAME *issuer; + ASN1_TIME *lastUpdate; + ASN1_TIME *nextUpdate; + STACK_OF(X509_REVOKED) *revoked; + STACK_OF(X509_EXTENSION) /* [0] */ *extensions; + ASN1_ENCODING enc; + } X509_CRL_INFO; + +struct X509_crl_st + { + /* actual signature */ + X509_CRL_INFO *crl; + X509_ALGOR *sig_alg; + ASN1_BIT_STRING *signature; + CRYPTO_refcount_t references; + int flags; + /* Copies of various extensions */ + AUTHORITY_KEYID *akid; + ISSUING_DIST_POINT *idp; + /* Convenient breakdown of IDP */ + int idp_flags; + int idp_reasons; + /* CRL and base CRL numbers for delta processing */ + ASN1_INTEGER *crl_number; + ASN1_INTEGER *base_crl_number; + unsigned char sha1_hash[SHA_DIGEST_LENGTH]; + STACK_OF(GENERAL_NAMES) *issuers; + const X509_CRL_METHOD *meth; + void *meth_data; + } /* X509_CRL */; + +DECLARE_STACK_OF(X509_CRL) +DECLARE_ASN1_SET_OF(X509_CRL) + +typedef struct private_key_st + { + int version; + /* The PKCS#8 data types */ + X509_ALGOR *enc_algor; + ASN1_OCTET_STRING *enc_pkey; /* encrypted pub key */ + + /* When decrypted, the following will not be NULL */ + EVP_PKEY *dec_pkey; + + /* used to encrypt and decrypt */ + int key_length; + char *key_data; + int key_free; /* true if we should auto free key_data */ + + /* expanded version of 'enc_algor' */ + EVP_CIPHER_INFO cipher; + } X509_PKEY; + +#ifndef OPENSSL_NO_EVP +typedef struct X509_info_st + { + X509 *x509; + X509_CRL *crl; + X509_PKEY *x_pkey; + + EVP_CIPHER_INFO enc_cipher; + int enc_len; + char *enc_data; + + } X509_INFO; + +DECLARE_STACK_OF(X509_INFO) +#endif + +/* The next 2 structures and their 8 routines were sent to me by + * Pat Richard and are used to manipulate + * Netscapes spki structures - useful if you are writing a CA web page + */ +typedef struct Netscape_spkac_st + { + X509_PUBKEY *pubkey; + ASN1_IA5STRING *challenge; /* challenge sent in atlas >= PR2 */ + } NETSCAPE_SPKAC; + +typedef struct Netscape_spki_st + { + NETSCAPE_SPKAC *spkac; /* signed public key and challenge */ + X509_ALGOR *sig_algor; + ASN1_BIT_STRING *signature; + } NETSCAPE_SPKI; + +/* Netscape certificate sequence structure */ +typedef struct Netscape_certificate_sequence + { + ASN1_OBJECT *type; + STACK_OF(X509) *certs; + } NETSCAPE_CERT_SEQUENCE; + +/* Unused (and iv length is wrong) +typedef struct CBCParameter_st + { + unsigned char iv[8]; + } CBC_PARAM; +*/ + +/* Password based encryption structure */ + +typedef struct PBEPARAM_st { +ASN1_OCTET_STRING *salt; +ASN1_INTEGER *iter; +} PBEPARAM; + +/* Password based encryption V2 structures */ + +typedef struct PBE2PARAM_st { +X509_ALGOR *keyfunc; +X509_ALGOR *encryption; +} PBE2PARAM; + +typedef struct PBKDF2PARAM_st { +ASN1_TYPE *salt; /* Usually OCTET STRING but could be anything */ +ASN1_INTEGER *iter; +ASN1_INTEGER *keylength; +X509_ALGOR *prf; +} PBKDF2PARAM; + + +/* PKCS#8 private key info structure */ + +struct pkcs8_priv_key_info_st + { + int broken; /* Flag for various broken formats */ +#define PKCS8_OK 0 +#define PKCS8_NO_OCTET 1 +#define PKCS8_EMBEDDED_PARAM 2 +#define PKCS8_NS_DB 3 +#define PKCS8_NEG_PRIVKEY 4 + ASN1_INTEGER *version; + X509_ALGOR *pkeyalg; + ASN1_TYPE *pkey; /* Should be OCTET STRING but some are broken */ + STACK_OF(X509_ATTRIBUTE) *attributes; + }; + +#ifdef __cplusplus +} +#endif + +#include + +#ifdef __cplusplus +extern "C" { +#endif + +#define X509_EXT_PACK_UNKNOWN 1 +#define X509_EXT_PACK_STRING 2 + +#define X509_get_version(x) ASN1_INTEGER_get((x)->cert_info->version) +/* #define X509_get_serialNumber(x) ((x)->cert_info->serialNumber) */ +#define X509_get_notBefore(x) ((x)->cert_info->validity->notBefore) +#define X509_get_notAfter(x) ((x)->cert_info->validity->notAfter) +#define X509_get_cert_info(x) ((x)->cert_info) +#define X509_extract_key(x) X509_get_pubkey(x) /*****/ +#define X509_REQ_get_version(x) ASN1_INTEGER_get((x)->req_info->version) +#define X509_REQ_get_subject_name(x) ((x)->req_info->subject) +#define X509_REQ_extract_key(a) X509_REQ_get_pubkey(a) +#define X509_name_cmp(a,b) X509_NAME_cmp((a),(b)) +#define X509_get_signature_type(x) EVP_PKEY_type(OBJ_obj2nid((x)->sig_alg->algorithm)) + +#define X509_CRL_get_version(x) ASN1_INTEGER_get((x)->crl->version) +#define X509_CRL_get_lastUpdate(x) ((x)->crl->lastUpdate) +#define X509_CRL_get_nextUpdate(x) ((x)->crl->nextUpdate) +#define X509_CRL_get_issuer(x) ((x)->crl->issuer) +#define X509_CRL_get_REVOKED(x) ((x)->crl->revoked) + +#define X509_CINF_set_modified(c) ((c)->enc.modified = 1) +#define X509_CINF_get_issuer(c) (&(c)->issuer) +#define X509_CINF_get_extensions(c) ((c)->extensions) +#define X509_CINF_get_signature(c) ((c)->signature) + +OPENSSL_EXPORT void X509_CRL_set_default_method(const X509_CRL_METHOD *meth); +OPENSSL_EXPORT X509_CRL_METHOD *X509_CRL_METHOD_new( + int (*crl_init)(X509_CRL *crl), + int (*crl_free)(X509_CRL *crl), + int (*crl_lookup)(X509_CRL *crl, X509_REVOKED **ret, + ASN1_INTEGER *ser, X509_NAME *issuer), + int (*crl_verify)(X509_CRL *crl, EVP_PKEY *pk)); +OPENSSL_EXPORT void X509_CRL_METHOD_free(X509_CRL_METHOD *m); + +OPENSSL_EXPORT void X509_CRL_set_meth_data(X509_CRL *crl, void *dat); +OPENSSL_EXPORT void *X509_CRL_get_meth_data(X509_CRL *crl); + +/* This one is only used so that a binary form can output, as in + * i2d_X509_NAME(X509_get_X509_PUBKEY(x),&buf) */ +#define X509_get_X509_PUBKEY(x) ((x)->cert_info->key) + + +OPENSSL_EXPORT const char *X509_verify_cert_error_string(long n); + +#ifndef OPENSSL_NO_EVP +OPENSSL_EXPORT int X509_verify(X509 *a, EVP_PKEY *r); + +OPENSSL_EXPORT int X509_REQ_verify(X509_REQ *a, EVP_PKEY *r); +OPENSSL_EXPORT int X509_CRL_verify(X509_CRL *a, EVP_PKEY *r); +OPENSSL_EXPORT int NETSCAPE_SPKI_verify(NETSCAPE_SPKI *a, EVP_PKEY *r); + +OPENSSL_EXPORT NETSCAPE_SPKI * NETSCAPE_SPKI_b64_decode(const char *str, int len); +OPENSSL_EXPORT char * NETSCAPE_SPKI_b64_encode(NETSCAPE_SPKI *x); +OPENSSL_EXPORT EVP_PKEY *NETSCAPE_SPKI_get_pubkey(NETSCAPE_SPKI *x); +OPENSSL_EXPORT int NETSCAPE_SPKI_set_pubkey(NETSCAPE_SPKI *x, EVP_PKEY *pkey); + +OPENSSL_EXPORT int NETSCAPE_SPKI_print(BIO *out, NETSCAPE_SPKI *spki); + +OPENSSL_EXPORT int X509_signature_dump(BIO *bp,const ASN1_STRING *sig, int indent); +OPENSSL_EXPORT int X509_signature_print(BIO *bp,X509_ALGOR *alg, ASN1_STRING *sig); + +OPENSSL_EXPORT int X509_sign(X509 *x, EVP_PKEY *pkey, const EVP_MD *md); +OPENSSL_EXPORT int X509_sign_ctx(X509 *x, EVP_MD_CTX *ctx); +/* int X509_http_nbio(OCSP_REQ_CTX *rctx, X509 **pcert); */ +OPENSSL_EXPORT int X509_REQ_sign(X509_REQ *x, EVP_PKEY *pkey, const EVP_MD *md); +OPENSSL_EXPORT int X509_REQ_sign_ctx(X509_REQ *x, EVP_MD_CTX *ctx); +OPENSSL_EXPORT int X509_CRL_sign(X509_CRL *x, EVP_PKEY *pkey, const EVP_MD *md); +OPENSSL_EXPORT int X509_CRL_sign_ctx(X509_CRL *x, EVP_MD_CTX *ctx); +/* int X509_CRL_http_nbio(OCSP_REQ_CTX *rctx, X509_CRL **pcrl); */ +OPENSSL_EXPORT int NETSCAPE_SPKI_sign(NETSCAPE_SPKI *x, EVP_PKEY *pkey, const EVP_MD *md); + +OPENSSL_EXPORT int X509_pubkey_digest(const X509 *data,const EVP_MD *type, + unsigned char *md, unsigned int *len); +OPENSSL_EXPORT int X509_digest(const X509 *data,const EVP_MD *type, + unsigned char *md, unsigned int *len); +OPENSSL_EXPORT int X509_CRL_digest(const X509_CRL *data,const EVP_MD *type, + unsigned char *md, unsigned int *len); +OPENSSL_EXPORT int X509_REQ_digest(const X509_REQ *data,const EVP_MD *type, + unsigned char *md, unsigned int *len); +OPENSSL_EXPORT int X509_NAME_digest(const X509_NAME *data,const EVP_MD *type, + unsigned char *md, unsigned int *len); +#endif + +#ifndef OPENSSL_NO_FP_API +OPENSSL_EXPORT X509 *d2i_X509_fp(FILE *fp, X509 **x509); +OPENSSL_EXPORT int i2d_X509_fp(FILE *fp,X509 *x509); +OPENSSL_EXPORT X509_CRL *d2i_X509_CRL_fp(FILE *fp,X509_CRL **crl); +OPENSSL_EXPORT int i2d_X509_CRL_fp(FILE *fp,X509_CRL *crl); +OPENSSL_EXPORT X509_REQ *d2i_X509_REQ_fp(FILE *fp,X509_REQ **req); +OPENSSL_EXPORT int i2d_X509_REQ_fp(FILE *fp,X509_REQ *req); +OPENSSL_EXPORT RSA *d2i_RSAPrivateKey_fp(FILE *fp,RSA **rsa); +OPENSSL_EXPORT int i2d_RSAPrivateKey_fp(FILE *fp,RSA *rsa); +OPENSSL_EXPORT RSA *d2i_RSAPublicKey_fp(FILE *fp,RSA **rsa); +OPENSSL_EXPORT int i2d_RSAPublicKey_fp(FILE *fp,RSA *rsa); +OPENSSL_EXPORT RSA *d2i_RSA_PUBKEY_fp(FILE *fp,RSA **rsa); +OPENSSL_EXPORT int i2d_RSA_PUBKEY_fp(FILE *fp,RSA *rsa); +#ifndef OPENSSL_NO_DSA +OPENSSL_EXPORT DSA *d2i_DSA_PUBKEY_fp(FILE *fp, DSA **dsa); +OPENSSL_EXPORT int i2d_DSA_PUBKEY_fp(FILE *fp, DSA *dsa); +OPENSSL_EXPORT DSA *d2i_DSAPrivateKey_fp(FILE *fp, DSA **dsa); +OPENSSL_EXPORT int i2d_DSAPrivateKey_fp(FILE *fp, DSA *dsa); +#endif +OPENSSL_EXPORT EC_KEY *d2i_EC_PUBKEY_fp(FILE *fp, EC_KEY **eckey); +OPENSSL_EXPORT int i2d_EC_PUBKEY_fp(FILE *fp, EC_KEY *eckey); +OPENSSL_EXPORT EC_KEY *d2i_ECPrivateKey_fp(FILE *fp, EC_KEY **eckey); +OPENSSL_EXPORT int i2d_ECPrivateKey_fp(FILE *fp, EC_KEY *eckey); +OPENSSL_EXPORT X509_SIG *d2i_PKCS8_fp(FILE *fp,X509_SIG **p8); +OPENSSL_EXPORT int i2d_PKCS8_fp(FILE *fp,X509_SIG *p8); +OPENSSL_EXPORT PKCS8_PRIV_KEY_INFO *d2i_PKCS8_PRIV_KEY_INFO_fp(FILE *fp, + PKCS8_PRIV_KEY_INFO **p8inf); +OPENSSL_EXPORT int i2d_PKCS8_PRIV_KEY_INFO_fp(FILE *fp,PKCS8_PRIV_KEY_INFO *p8inf); +OPENSSL_EXPORT int i2d_PKCS8PrivateKeyInfo_fp(FILE *fp, EVP_PKEY *key); +OPENSSL_EXPORT int i2d_PrivateKey_fp(FILE *fp, EVP_PKEY *pkey); +OPENSSL_EXPORT EVP_PKEY *d2i_PrivateKey_fp(FILE *fp, EVP_PKEY **a); +OPENSSL_EXPORT int i2d_PUBKEY_fp(FILE *fp, EVP_PKEY *pkey); +OPENSSL_EXPORT EVP_PKEY *d2i_PUBKEY_fp(FILE *fp, EVP_PKEY **a); +#endif + +OPENSSL_EXPORT X509 *d2i_X509_bio(BIO *bp,X509 **x509); +OPENSSL_EXPORT int i2d_X509_bio(BIO *bp,X509 *x509); +OPENSSL_EXPORT X509_CRL *d2i_X509_CRL_bio(BIO *bp,X509_CRL **crl); +OPENSSL_EXPORT int i2d_X509_CRL_bio(BIO *bp,X509_CRL *crl); +OPENSSL_EXPORT X509_REQ *d2i_X509_REQ_bio(BIO *bp,X509_REQ **req); +OPENSSL_EXPORT int i2d_X509_REQ_bio(BIO *bp,X509_REQ *req); +OPENSSL_EXPORT RSA *d2i_RSAPrivateKey_bio(BIO *bp,RSA **rsa); +OPENSSL_EXPORT int i2d_RSAPrivateKey_bio(BIO *bp,RSA *rsa); +OPENSSL_EXPORT RSA *d2i_RSAPublicKey_bio(BIO *bp,RSA **rsa); +OPENSSL_EXPORT int i2d_RSAPublicKey_bio(BIO *bp,RSA *rsa); +OPENSSL_EXPORT RSA *d2i_RSA_PUBKEY_bio(BIO *bp,RSA **rsa); +OPENSSL_EXPORT int i2d_RSA_PUBKEY_bio(BIO *bp,RSA *rsa); +#ifndef OPENSSL_NO_DSA +OPENSSL_EXPORT DSA *d2i_DSA_PUBKEY_bio(BIO *bp, DSA **dsa); +OPENSSL_EXPORT int i2d_DSA_PUBKEY_bio(BIO *bp, DSA *dsa); +OPENSSL_EXPORT DSA *d2i_DSAPrivateKey_bio(BIO *bp, DSA **dsa); +OPENSSL_EXPORT int i2d_DSAPrivateKey_bio(BIO *bp, DSA *dsa); +#endif +OPENSSL_EXPORT EC_KEY *d2i_EC_PUBKEY_bio(BIO *bp, EC_KEY **eckey); +OPENSSL_EXPORT int i2d_EC_PUBKEY_bio(BIO *bp, EC_KEY *eckey); +OPENSSL_EXPORT EC_KEY *d2i_ECPrivateKey_bio(BIO *bp, EC_KEY **eckey); +OPENSSL_EXPORT int i2d_ECPrivateKey_bio(BIO *bp, EC_KEY *eckey); +OPENSSL_EXPORT X509_SIG *d2i_PKCS8_bio(BIO *bp,X509_SIG **p8); +OPENSSL_EXPORT int i2d_PKCS8_bio(BIO *bp,X509_SIG *p8); +OPENSSL_EXPORT PKCS8_PRIV_KEY_INFO *d2i_PKCS8_PRIV_KEY_INFO_bio(BIO *bp, + PKCS8_PRIV_KEY_INFO **p8inf); +OPENSSL_EXPORT int i2d_PKCS8_PRIV_KEY_INFO_bio(BIO *bp,PKCS8_PRIV_KEY_INFO *p8inf); +OPENSSL_EXPORT int i2d_PKCS8PrivateKeyInfo_bio(BIO *bp, EVP_PKEY *key); +OPENSSL_EXPORT int i2d_PrivateKey_bio(BIO *bp, EVP_PKEY *pkey); +OPENSSL_EXPORT EVP_PKEY *d2i_PrivateKey_bio(BIO *bp, EVP_PKEY **a); +OPENSSL_EXPORT int i2d_PUBKEY_bio(BIO *bp, EVP_PKEY *pkey); +OPENSSL_EXPORT EVP_PKEY *d2i_PUBKEY_bio(BIO *bp, EVP_PKEY **a); + +OPENSSL_EXPORT X509 *X509_dup(X509 *x509); +OPENSSL_EXPORT X509_ATTRIBUTE *X509_ATTRIBUTE_dup(X509_ATTRIBUTE *xa); +OPENSSL_EXPORT X509_EXTENSION *X509_EXTENSION_dup(X509_EXTENSION *ex); +OPENSSL_EXPORT X509_CRL *X509_CRL_dup(X509_CRL *crl); +OPENSSL_EXPORT X509_REVOKED *X509_REVOKED_dup(X509_REVOKED *rev); +OPENSSL_EXPORT X509_REQ *X509_REQ_dup(X509_REQ *req); +OPENSSL_EXPORT X509_ALGOR *X509_ALGOR_dup(X509_ALGOR *xn); +OPENSSL_EXPORT int X509_ALGOR_set0(X509_ALGOR *alg, const ASN1_OBJECT *aobj, int ptype, void *pval); +OPENSSL_EXPORT void X509_ALGOR_get0(ASN1_OBJECT **paobj, int *pptype, void **ppval, + X509_ALGOR *algor); +OPENSSL_EXPORT void X509_ALGOR_set_md(X509_ALGOR *alg, const EVP_MD *md); +OPENSSL_EXPORT int X509_ALGOR_cmp(const X509_ALGOR *a, const X509_ALGOR *b); + +OPENSSL_EXPORT X509_NAME *X509_NAME_dup(X509_NAME *xn); +OPENSSL_EXPORT X509_NAME_ENTRY *X509_NAME_ENTRY_dup(X509_NAME_ENTRY *ne); + +OPENSSL_EXPORT int X509_cmp_time(const ASN1_TIME *s, time_t *t); +OPENSSL_EXPORT int X509_cmp_current_time(const ASN1_TIME *s); +OPENSSL_EXPORT ASN1_TIME * X509_time_adj(ASN1_TIME *s, long adj, time_t *t); +OPENSSL_EXPORT ASN1_TIME * X509_time_adj_ex(ASN1_TIME *s, int offset_day, long offset_sec, time_t *t); +OPENSSL_EXPORT ASN1_TIME * X509_gmtime_adj(ASN1_TIME *s, long adj); + +OPENSSL_EXPORT const char * X509_get_default_cert_area(void ); +OPENSSL_EXPORT const char * X509_get_default_cert_dir(void ); +OPENSSL_EXPORT const char * X509_get_default_cert_file(void ); +OPENSSL_EXPORT const char * X509_get_default_cert_dir_env(void ); +OPENSSL_EXPORT const char * X509_get_default_cert_file_env(void ); +OPENSSL_EXPORT const char * X509_get_default_private_dir(void ); + +OPENSSL_EXPORT X509_REQ * X509_to_X509_REQ(X509 *x, EVP_PKEY *pkey, const EVP_MD *md); +OPENSSL_EXPORT X509 * X509_REQ_to_X509(X509_REQ *r, int days,EVP_PKEY *pkey); + +DECLARE_ASN1_ENCODE_FUNCTIONS(X509_ALGORS, X509_ALGORS, X509_ALGORS) +DECLARE_ASN1_FUNCTIONS(X509_VAL) + +DECLARE_ASN1_FUNCTIONS(X509_PUBKEY) + +OPENSSL_EXPORT int X509_PUBKEY_set(X509_PUBKEY **x, EVP_PKEY *pkey); +OPENSSL_EXPORT EVP_PKEY * X509_PUBKEY_get(X509_PUBKEY *key); +OPENSSL_EXPORT int i2d_PUBKEY(const EVP_PKEY *a,unsigned char **pp); +OPENSSL_EXPORT EVP_PKEY * d2i_PUBKEY(EVP_PKEY **a,const unsigned char **pp, + long length); +OPENSSL_EXPORT int i2d_RSA_PUBKEY(const RSA *a,unsigned char **pp); +OPENSSL_EXPORT RSA * d2i_RSA_PUBKEY(RSA **a,const unsigned char **pp, + long length); +#ifndef OPENSSL_NO_DSA +OPENSSL_EXPORT int i2d_DSA_PUBKEY(const DSA *a,unsigned char **pp); +OPENSSL_EXPORT DSA * d2i_DSA_PUBKEY(DSA **a,const unsigned char **pp, + long length); +#endif +OPENSSL_EXPORT int i2d_EC_PUBKEY(const EC_KEY *a, unsigned char **pp); +OPENSSL_EXPORT EC_KEY *d2i_EC_PUBKEY(EC_KEY **a, const unsigned char **pp, + long length); + +DECLARE_ASN1_FUNCTIONS(X509_SIG) +DECLARE_ASN1_FUNCTIONS(X509_REQ_INFO) +DECLARE_ASN1_FUNCTIONS(X509_REQ) + +DECLARE_ASN1_FUNCTIONS(X509_ATTRIBUTE) +OPENSSL_EXPORT X509_ATTRIBUTE *X509_ATTRIBUTE_create(int nid, int atrtype, void *value); + +DECLARE_ASN1_FUNCTIONS(X509_EXTENSION) +DECLARE_ASN1_ENCODE_FUNCTIONS(X509_EXTENSIONS, X509_EXTENSIONS, X509_EXTENSIONS) + +DECLARE_ASN1_FUNCTIONS(X509_NAME_ENTRY) + +DECLARE_ASN1_FUNCTIONS(X509_NAME) + +OPENSSL_EXPORT int X509_NAME_set(X509_NAME **xn, X509_NAME *name); + +DECLARE_ASN1_FUNCTIONS(X509_CINF) + +DECLARE_ASN1_FUNCTIONS(X509) +DECLARE_ASN1_FUNCTIONS(X509_CERT_AUX) + +DECLARE_ASN1_FUNCTIONS(X509_CERT_PAIR) + +/* X509_up_ref adds one to the reference count of |x| and returns + * |x|. */ +OPENSSL_EXPORT X509 *X509_up_ref(X509 *x); + +OPENSSL_EXPORT int X509_get_ex_new_index(long argl, void *argp, CRYPTO_EX_new *new_func, + CRYPTO_EX_dup *dup_func, CRYPTO_EX_free *free_func); +OPENSSL_EXPORT int X509_set_ex_data(X509 *r, int idx, void *arg); +OPENSSL_EXPORT void *X509_get_ex_data(X509 *r, int idx); +OPENSSL_EXPORT int i2d_X509_AUX(X509 *a,unsigned char **pp); +OPENSSL_EXPORT X509 * d2i_X509_AUX(X509 **a,const unsigned char **pp,long length); + +OPENSSL_EXPORT void X509_get0_signature(ASN1_BIT_STRING **psig, X509_ALGOR **palg, + const X509 *x); +OPENSSL_EXPORT int X509_get_signature_nid(const X509 *x); + +OPENSSL_EXPORT int X509_alias_set1(X509 *x, unsigned char *name, int len); +OPENSSL_EXPORT int X509_keyid_set1(X509 *x, unsigned char *id, int len); +OPENSSL_EXPORT unsigned char * X509_alias_get0(X509 *x, int *len); +OPENSSL_EXPORT unsigned char * X509_keyid_get0(X509 *x, int *len); +OPENSSL_EXPORT int (*X509_TRUST_set_default(int (*trust)(int , X509 *, int)))(int, X509 *, int); +OPENSSL_EXPORT int X509_TRUST_set(int *t, int trust); +OPENSSL_EXPORT int X509_add1_trust_object(X509 *x, ASN1_OBJECT *obj); +OPENSSL_EXPORT int X509_add1_reject_object(X509 *x, ASN1_OBJECT *obj); +OPENSSL_EXPORT void X509_trust_clear(X509 *x); +OPENSSL_EXPORT void X509_reject_clear(X509 *x); + +DECLARE_ASN1_FUNCTIONS(X509_REVOKED) +DECLARE_ASN1_FUNCTIONS(X509_CRL_INFO) +DECLARE_ASN1_FUNCTIONS(X509_CRL) + +OPENSSL_EXPORT int X509_CRL_add0_revoked(X509_CRL *crl, X509_REVOKED *rev); +OPENSSL_EXPORT int X509_CRL_get0_by_serial(X509_CRL *crl, + X509_REVOKED **ret, ASN1_INTEGER *serial); +OPENSSL_EXPORT int X509_CRL_get0_by_cert(X509_CRL *crl, X509_REVOKED **ret, X509 *x); + +OPENSSL_EXPORT X509_PKEY * X509_PKEY_new(void ); +OPENSSL_EXPORT void X509_PKEY_free(X509_PKEY *a); + +DECLARE_ASN1_FUNCTIONS(NETSCAPE_SPKI) +DECLARE_ASN1_FUNCTIONS(NETSCAPE_SPKAC) +DECLARE_ASN1_FUNCTIONS(NETSCAPE_CERT_SEQUENCE) + +#ifndef OPENSSL_NO_EVP +OPENSSL_EXPORT X509_INFO * X509_INFO_new(void); +OPENSSL_EXPORT void X509_INFO_free(X509_INFO *a); +OPENSSL_EXPORT char * X509_NAME_oneline(X509_NAME *a,char *buf,int size); + +OPENSSL_EXPORT int ASN1_digest(i2d_of_void *i2d,const EVP_MD *type,char *data, + unsigned char *md,unsigned int *len); + +OPENSSL_EXPORT int ASN1_item_digest(const ASN1_ITEM *it,const EVP_MD *type,void *data, + unsigned char *md,unsigned int *len); + +OPENSSL_EXPORT int ASN1_item_verify(const ASN1_ITEM *it, X509_ALGOR *algor1, + ASN1_BIT_STRING *signature,void *data,EVP_PKEY *pkey); + +OPENSSL_EXPORT int ASN1_item_sign(const ASN1_ITEM *it, X509_ALGOR *algor1, X509_ALGOR *algor2, + ASN1_BIT_STRING *signature, + void *data, EVP_PKEY *pkey, const EVP_MD *type); +OPENSSL_EXPORT int ASN1_item_sign_ctx(const ASN1_ITEM *it, + X509_ALGOR *algor1, X509_ALGOR *algor2, + ASN1_BIT_STRING *signature, void *asn, EVP_MD_CTX *ctx); +#endif + +OPENSSL_EXPORT int X509_set_version(X509 *x,long version); +OPENSSL_EXPORT int X509_set_serialNumber(X509 *x, ASN1_INTEGER *serial); +OPENSSL_EXPORT ASN1_INTEGER * X509_get_serialNumber(X509 *x); +OPENSSL_EXPORT int X509_set_issuer_name(X509 *x, X509_NAME *name); +OPENSSL_EXPORT X509_NAME * X509_get_issuer_name(X509 *a); +OPENSSL_EXPORT int X509_set_subject_name(X509 *x, X509_NAME *name); +OPENSSL_EXPORT X509_NAME * X509_get_subject_name(X509 *a); +OPENSSL_EXPORT int X509_set_notBefore(X509 *x, const ASN1_TIME *tm); +OPENSSL_EXPORT int X509_set_notAfter(X509 *x, const ASN1_TIME *tm); +OPENSSL_EXPORT int X509_set_pubkey(X509 *x, EVP_PKEY *pkey); +OPENSSL_EXPORT EVP_PKEY * X509_get_pubkey(X509 *x); +OPENSSL_EXPORT ASN1_BIT_STRING * X509_get0_pubkey_bitstr(const X509 *x); +OPENSSL_EXPORT int X509_certificate_type(X509 *x,EVP_PKEY *pubkey /* optional */); + +OPENSSL_EXPORT int X509_REQ_set_version(X509_REQ *x,long version); +OPENSSL_EXPORT int X509_REQ_set_subject_name(X509_REQ *req,X509_NAME *name); +OPENSSL_EXPORT int X509_REQ_set_pubkey(X509_REQ *x, EVP_PKEY *pkey); +OPENSSL_EXPORT EVP_PKEY * X509_REQ_get_pubkey(X509_REQ *req); +OPENSSL_EXPORT int X509_REQ_extension_nid(int nid); +OPENSSL_EXPORT const int * X509_REQ_get_extension_nids(void); +OPENSSL_EXPORT void X509_REQ_set_extension_nids(const int *nids); +OPENSSL_EXPORT STACK_OF(X509_EXTENSION) *X509_REQ_get_extensions(X509_REQ *req); +OPENSSL_EXPORT int X509_REQ_add_extensions_nid(X509_REQ *req, STACK_OF(X509_EXTENSION) *exts, + int nid); +OPENSSL_EXPORT int X509_REQ_add_extensions(X509_REQ *req, STACK_OF(X509_EXTENSION) *exts); +OPENSSL_EXPORT int X509_REQ_get_attr_count(const X509_REQ *req); +OPENSSL_EXPORT int X509_REQ_get_attr_by_NID(const X509_REQ *req, int nid, + int lastpos); +OPENSSL_EXPORT int X509_REQ_get_attr_by_OBJ(const X509_REQ *req, ASN1_OBJECT *obj, + int lastpos); +OPENSSL_EXPORT X509_ATTRIBUTE *X509_REQ_get_attr(const X509_REQ *req, int loc); +OPENSSL_EXPORT X509_ATTRIBUTE *X509_REQ_delete_attr(X509_REQ *req, int loc); +OPENSSL_EXPORT int X509_REQ_add1_attr(X509_REQ *req, X509_ATTRIBUTE *attr); +OPENSSL_EXPORT int X509_REQ_add1_attr_by_OBJ(X509_REQ *req, + const ASN1_OBJECT *obj, int type, + const unsigned char *bytes, int len); +OPENSSL_EXPORT int X509_REQ_add1_attr_by_NID(X509_REQ *req, + int nid, int type, + const unsigned char *bytes, int len); +OPENSSL_EXPORT int X509_REQ_add1_attr_by_txt(X509_REQ *req, + const char *attrname, int type, + const unsigned char *bytes, int len); + +OPENSSL_EXPORT int X509_CRL_set_version(X509_CRL *x, long version); +OPENSSL_EXPORT int X509_CRL_set_issuer_name(X509_CRL *x, X509_NAME *name); +OPENSSL_EXPORT int X509_CRL_set_lastUpdate(X509_CRL *x, const ASN1_TIME *tm); +OPENSSL_EXPORT int X509_CRL_set_nextUpdate(X509_CRL *x, const ASN1_TIME *tm); +OPENSSL_EXPORT int X509_CRL_sort(X509_CRL *crl); + +OPENSSL_EXPORT int X509_REVOKED_set_serialNumber(X509_REVOKED *x, ASN1_INTEGER *serial); +OPENSSL_EXPORT int X509_REVOKED_set_revocationDate(X509_REVOKED *r, ASN1_TIME *tm); + +OPENSSL_EXPORT X509_CRL *X509_CRL_diff(X509_CRL *base, X509_CRL *newer, + EVP_PKEY *skey, const EVP_MD *md, unsigned int flags); + +OPENSSL_EXPORT int X509_REQ_check_private_key(X509_REQ *x509,EVP_PKEY *pkey); + +OPENSSL_EXPORT int X509_check_private_key(X509 *x509,EVP_PKEY *pkey); +OPENSSL_EXPORT int X509_chain_check_suiteb(int *perror_depth, + X509 *x, STACK_OF(X509) *chain, + unsigned long flags); +OPENSSL_EXPORT int X509_CRL_check_suiteb(X509_CRL *crl, EVP_PKEY *pk, + unsigned long flags); +OPENSSL_EXPORT STACK_OF(X509) *X509_chain_up_ref(STACK_OF(X509) *chain); + +OPENSSL_EXPORT int X509_issuer_and_serial_cmp(const X509 *a, const X509 *b); +OPENSSL_EXPORT unsigned long X509_issuer_and_serial_hash(X509 *a); + +OPENSSL_EXPORT int X509_issuer_name_cmp(const X509 *a, const X509 *b); +OPENSSL_EXPORT unsigned long X509_issuer_name_hash(X509 *a); + +OPENSSL_EXPORT int X509_subject_name_cmp(const X509 *a, const X509 *b); +OPENSSL_EXPORT unsigned long X509_subject_name_hash(X509 *x); + +OPENSSL_EXPORT unsigned long X509_issuer_name_hash_old(X509 *a); +OPENSSL_EXPORT unsigned long X509_subject_name_hash_old(X509 *x); + +OPENSSL_EXPORT int X509_cmp(const X509 *a, const X509 *b); +OPENSSL_EXPORT int X509_NAME_cmp(const X509_NAME *a, const X509_NAME *b); +OPENSSL_EXPORT unsigned long X509_NAME_hash(X509_NAME *x); +OPENSSL_EXPORT unsigned long X509_NAME_hash_old(X509_NAME *x); + +OPENSSL_EXPORT int X509_CRL_cmp(const X509_CRL *a, const X509_CRL *b); +OPENSSL_EXPORT int X509_CRL_match(const X509_CRL *a, const X509_CRL *b); +#ifndef OPENSSL_NO_FP_API +OPENSSL_EXPORT int X509_print_ex_fp(FILE *bp,X509 *x, unsigned long nmflag, unsigned long cflag); +OPENSSL_EXPORT int X509_print_fp(FILE *bp,X509 *x); +OPENSSL_EXPORT int X509_CRL_print_fp(FILE *bp,X509_CRL *x); +OPENSSL_EXPORT int X509_REQ_print_fp(FILE *bp,X509_REQ *req); +OPENSSL_EXPORT int X509_NAME_print_ex_fp(FILE *fp, X509_NAME *nm, int indent, unsigned long flags); +#endif + +OPENSSL_EXPORT int X509_NAME_print(BIO *bp, X509_NAME *name, int obase); +OPENSSL_EXPORT int X509_NAME_print_ex(BIO *out, X509_NAME *nm, int indent, unsigned long flags); +OPENSSL_EXPORT int X509_print_ex(BIO *bp,X509 *x, unsigned long nmflag, unsigned long cflag); +OPENSSL_EXPORT int X509_print(BIO *bp,X509 *x); +OPENSSL_EXPORT int X509_ocspid_print(BIO *bp,X509 *x); +OPENSSL_EXPORT int X509_CERT_AUX_print(BIO *bp,X509_CERT_AUX *x, int indent); +OPENSSL_EXPORT int X509_CRL_print(BIO *bp,X509_CRL *x); +OPENSSL_EXPORT int X509_REQ_print_ex(BIO *bp, X509_REQ *x, unsigned long nmflag, unsigned long cflag); +OPENSSL_EXPORT int X509_REQ_print(BIO *bp,X509_REQ *req); + +OPENSSL_EXPORT int X509_NAME_entry_count(X509_NAME *name); +OPENSSL_EXPORT int X509_NAME_get_text_by_NID(X509_NAME *name, int nid, + char *buf,int len); +OPENSSL_EXPORT int X509_NAME_get_text_by_OBJ(X509_NAME *name, const ASN1_OBJECT *obj, + char *buf,int len); + +/* NOTE: you should be passsing -1, not 0 as lastpos. The functions that use + * lastpos, search after that position on. */ +OPENSSL_EXPORT int X509_NAME_get_index_by_NID(X509_NAME *name,int nid,int lastpos); +OPENSSL_EXPORT int X509_NAME_get_index_by_OBJ(X509_NAME *name, const ASN1_OBJECT *obj, + int lastpos); +OPENSSL_EXPORT X509_NAME_ENTRY *X509_NAME_get_entry(X509_NAME *name, int loc); +OPENSSL_EXPORT X509_NAME_ENTRY *X509_NAME_delete_entry(X509_NAME *name, int loc); +OPENSSL_EXPORT int X509_NAME_add_entry(X509_NAME *name,X509_NAME_ENTRY *ne, + int loc, int set); +OPENSSL_EXPORT int X509_NAME_add_entry_by_OBJ(X509_NAME *name, ASN1_OBJECT *obj, int type, + unsigned char *bytes, int len, int loc, int set); +OPENSSL_EXPORT int X509_NAME_add_entry_by_NID(X509_NAME *name, int nid, int type, + unsigned char *bytes, int len, int loc, int set); +OPENSSL_EXPORT X509_NAME_ENTRY *X509_NAME_ENTRY_create_by_txt(X509_NAME_ENTRY **ne, + const char *field, int type, const unsigned char *bytes, int len); +OPENSSL_EXPORT X509_NAME_ENTRY *X509_NAME_ENTRY_create_by_NID(X509_NAME_ENTRY **ne, int nid, + int type,unsigned char *bytes, int len); +OPENSSL_EXPORT int X509_NAME_add_entry_by_txt(X509_NAME *name, const char *field, int type, + const unsigned char *bytes, int len, int loc, int set); +OPENSSL_EXPORT X509_NAME_ENTRY *X509_NAME_ENTRY_create_by_OBJ(X509_NAME_ENTRY **ne, + const ASN1_OBJECT *obj, int type,const unsigned char *bytes, + int len); +OPENSSL_EXPORT int X509_NAME_ENTRY_set_object(X509_NAME_ENTRY *ne, + const ASN1_OBJECT *obj); +OPENSSL_EXPORT int X509_NAME_ENTRY_set_data(X509_NAME_ENTRY *ne, int type, + const unsigned char *bytes, int len); +OPENSSL_EXPORT ASN1_OBJECT * X509_NAME_ENTRY_get_object(X509_NAME_ENTRY *ne); +OPENSSL_EXPORT ASN1_STRING * X509_NAME_ENTRY_get_data(X509_NAME_ENTRY *ne); + +OPENSSL_EXPORT int X509v3_get_ext_count(const STACK_OF(X509_EXTENSION) *x); +OPENSSL_EXPORT int X509v3_get_ext_by_NID(const STACK_OF(X509_EXTENSION) *x, + int nid, int lastpos); +OPENSSL_EXPORT int X509v3_get_ext_by_OBJ(const STACK_OF(X509_EXTENSION) *x, + const ASN1_OBJECT *obj,int lastpos); +OPENSSL_EXPORT int X509v3_get_ext_by_critical(const STACK_OF(X509_EXTENSION) *x, + int crit, int lastpos); +OPENSSL_EXPORT X509_EXTENSION *X509v3_get_ext(const STACK_OF(X509_EXTENSION) *x, int loc); +OPENSSL_EXPORT X509_EXTENSION *X509v3_delete_ext(STACK_OF(X509_EXTENSION) *x, int loc); +OPENSSL_EXPORT STACK_OF(X509_EXTENSION) *X509v3_add_ext(STACK_OF(X509_EXTENSION) **x, + X509_EXTENSION *ex, int loc); + +OPENSSL_EXPORT int X509_get_ext_count(X509 *x); +OPENSSL_EXPORT int X509_get_ext_by_NID(X509 *x, int nid, int lastpos); +OPENSSL_EXPORT int X509_get_ext_by_OBJ(X509 *x,ASN1_OBJECT *obj,int lastpos); +OPENSSL_EXPORT int X509_get_ext_by_critical(X509 *x, int crit, int lastpos); +OPENSSL_EXPORT X509_EXTENSION *X509_get_ext(X509 *x, int loc); +OPENSSL_EXPORT X509_EXTENSION *X509_delete_ext(X509 *x, int loc); +OPENSSL_EXPORT int X509_add_ext(X509 *x, X509_EXTENSION *ex, int loc); +OPENSSL_EXPORT void * X509_get_ext_d2i(X509 *x, int nid, int *crit, int *idx); +OPENSSL_EXPORT int X509_add1_ext_i2d(X509 *x, int nid, void *value, int crit, + unsigned long flags); + +OPENSSL_EXPORT int X509_CRL_get_ext_count(X509_CRL *x); +OPENSSL_EXPORT int X509_CRL_get_ext_by_NID(X509_CRL *x, int nid, int lastpos); +OPENSSL_EXPORT int X509_CRL_get_ext_by_OBJ(X509_CRL *x,ASN1_OBJECT *obj,int lastpos); +OPENSSL_EXPORT int X509_CRL_get_ext_by_critical(X509_CRL *x, int crit, int lastpos); +OPENSSL_EXPORT X509_EXTENSION *X509_CRL_get_ext(X509_CRL *x, int loc); +OPENSSL_EXPORT X509_EXTENSION *X509_CRL_delete_ext(X509_CRL *x, int loc); +OPENSSL_EXPORT int X509_CRL_add_ext(X509_CRL *x, X509_EXTENSION *ex, int loc); +OPENSSL_EXPORT void * X509_CRL_get_ext_d2i(X509_CRL *x, int nid, int *crit, int *idx); +OPENSSL_EXPORT int X509_CRL_add1_ext_i2d(X509_CRL *x, int nid, void *value, int crit, + unsigned long flags); + +OPENSSL_EXPORT int X509_REVOKED_get_ext_count(X509_REVOKED *x); +OPENSSL_EXPORT int X509_REVOKED_get_ext_by_NID(X509_REVOKED *x, int nid, int lastpos); +OPENSSL_EXPORT int X509_REVOKED_get_ext_by_OBJ(X509_REVOKED *x,ASN1_OBJECT *obj,int lastpos); +OPENSSL_EXPORT int X509_REVOKED_get_ext_by_critical(X509_REVOKED *x, int crit, int lastpos); +OPENSSL_EXPORT X509_EXTENSION *X509_REVOKED_get_ext(X509_REVOKED *x, int loc); +OPENSSL_EXPORT X509_EXTENSION *X509_REVOKED_delete_ext(X509_REVOKED *x, int loc); +OPENSSL_EXPORT int X509_REVOKED_add_ext(X509_REVOKED *x, X509_EXTENSION *ex, int loc); +OPENSSL_EXPORT void * X509_REVOKED_get_ext_d2i(X509_REVOKED *x, int nid, int *crit, int *idx); +OPENSSL_EXPORT int X509_REVOKED_add1_ext_i2d(X509_REVOKED *x, int nid, void *value, int crit, + unsigned long flags); + +OPENSSL_EXPORT X509_EXTENSION *X509_EXTENSION_create_by_NID(X509_EXTENSION **ex, + int nid, int crit, ASN1_OCTET_STRING *data); +OPENSSL_EXPORT X509_EXTENSION *X509_EXTENSION_create_by_OBJ(X509_EXTENSION **ex, + const ASN1_OBJECT *obj,int crit,ASN1_OCTET_STRING *data); +OPENSSL_EXPORT int X509_EXTENSION_set_object(X509_EXTENSION *ex,const ASN1_OBJECT *obj); +OPENSSL_EXPORT int X509_EXTENSION_set_critical(X509_EXTENSION *ex, int crit); +OPENSSL_EXPORT int X509_EXTENSION_set_data(X509_EXTENSION *ex, + ASN1_OCTET_STRING *data); +OPENSSL_EXPORT ASN1_OBJECT * X509_EXTENSION_get_object(X509_EXTENSION *ex); +OPENSSL_EXPORT ASN1_OCTET_STRING *X509_EXTENSION_get_data(X509_EXTENSION *ne); +OPENSSL_EXPORT int X509_EXTENSION_get_critical(X509_EXTENSION *ex); + +OPENSSL_EXPORT int X509at_get_attr_count(const STACK_OF(X509_ATTRIBUTE) *x); +OPENSSL_EXPORT int X509at_get_attr_by_NID(const STACK_OF(X509_ATTRIBUTE) *x, int nid, + int lastpos); +OPENSSL_EXPORT int X509at_get_attr_by_OBJ(const STACK_OF(X509_ATTRIBUTE) *sk, const ASN1_OBJECT *obj, + int lastpos); +OPENSSL_EXPORT X509_ATTRIBUTE *X509at_get_attr(const STACK_OF(X509_ATTRIBUTE) *x, int loc); +OPENSSL_EXPORT X509_ATTRIBUTE *X509at_delete_attr(STACK_OF(X509_ATTRIBUTE) *x, int loc); +OPENSSL_EXPORT STACK_OF(X509_ATTRIBUTE) *X509at_add1_attr(STACK_OF(X509_ATTRIBUTE) **x, + X509_ATTRIBUTE *attr); +OPENSSL_EXPORT STACK_OF(X509_ATTRIBUTE) *X509at_add1_attr_by_OBJ(STACK_OF(X509_ATTRIBUTE) **x, + const ASN1_OBJECT *obj, int type, + const unsigned char *bytes, int len); +OPENSSL_EXPORT STACK_OF(X509_ATTRIBUTE) *X509at_add1_attr_by_NID(STACK_OF(X509_ATTRIBUTE) **x, + int nid, int type, + const unsigned char *bytes, int len); +OPENSSL_EXPORT STACK_OF(X509_ATTRIBUTE) *X509at_add1_attr_by_txt(STACK_OF(X509_ATTRIBUTE) **x, + const char *attrname, int type, + const unsigned char *bytes, int len); +OPENSSL_EXPORT void *X509at_get0_data_by_OBJ(STACK_OF(X509_ATTRIBUTE) *x, + ASN1_OBJECT *obj, int lastpos, int type); +OPENSSL_EXPORT X509_ATTRIBUTE *X509_ATTRIBUTE_create_by_NID(X509_ATTRIBUTE **attr, int nid, + int atrtype, const void *data, int len); +OPENSSL_EXPORT X509_ATTRIBUTE *X509_ATTRIBUTE_create_by_OBJ(X509_ATTRIBUTE **attr, + const ASN1_OBJECT *obj, int atrtype, const void *data, int len); +OPENSSL_EXPORT X509_ATTRIBUTE *X509_ATTRIBUTE_create_by_txt(X509_ATTRIBUTE **attr, + const char *atrname, int type, const unsigned char *bytes, int len); +OPENSSL_EXPORT int X509_ATTRIBUTE_set1_object(X509_ATTRIBUTE *attr, const ASN1_OBJECT *obj); +OPENSSL_EXPORT int X509_ATTRIBUTE_set1_data(X509_ATTRIBUTE *attr, int attrtype, const void *data, int len); +OPENSSL_EXPORT void *X509_ATTRIBUTE_get0_data(X509_ATTRIBUTE *attr, int idx, + int atrtype, void *data); +OPENSSL_EXPORT int X509_ATTRIBUTE_count(X509_ATTRIBUTE *attr); +OPENSSL_EXPORT ASN1_OBJECT *X509_ATTRIBUTE_get0_object(X509_ATTRIBUTE *attr); +OPENSSL_EXPORT ASN1_TYPE *X509_ATTRIBUTE_get0_type(X509_ATTRIBUTE *attr, int idx); + +OPENSSL_EXPORT int EVP_PKEY_get_attr_count(const EVP_PKEY *key); +OPENSSL_EXPORT int EVP_PKEY_get_attr_by_NID(const EVP_PKEY *key, int nid, + int lastpos); +OPENSSL_EXPORT int EVP_PKEY_get_attr_by_OBJ(const EVP_PKEY *key, ASN1_OBJECT *obj, + int lastpos); +OPENSSL_EXPORT X509_ATTRIBUTE *EVP_PKEY_get_attr(const EVP_PKEY *key, int loc); +OPENSSL_EXPORT X509_ATTRIBUTE *EVP_PKEY_delete_attr(EVP_PKEY *key, int loc); +OPENSSL_EXPORT int EVP_PKEY_add1_attr(EVP_PKEY *key, X509_ATTRIBUTE *attr); +OPENSSL_EXPORT int EVP_PKEY_add1_attr_by_OBJ(EVP_PKEY *key, + const ASN1_OBJECT *obj, int type, + const unsigned char *bytes, int len); +OPENSSL_EXPORT int EVP_PKEY_add1_attr_by_NID(EVP_PKEY *key, + int nid, int type, + const unsigned char *bytes, int len); +OPENSSL_EXPORT int EVP_PKEY_add1_attr_by_txt(EVP_PKEY *key, + const char *attrname, int type, + const unsigned char *bytes, int len); + +OPENSSL_EXPORT int X509_verify_cert(X509_STORE_CTX *ctx); + +/* lookup a cert from a X509 STACK */ +OPENSSL_EXPORT X509 *X509_find_by_issuer_and_serial(STACK_OF(X509) *sk,X509_NAME *name, + ASN1_INTEGER *serial); +OPENSSL_EXPORT X509 *X509_find_by_subject(STACK_OF(X509) *sk,X509_NAME *name); + +DECLARE_ASN1_FUNCTIONS(PBEPARAM) +DECLARE_ASN1_FUNCTIONS(PBE2PARAM) +DECLARE_ASN1_FUNCTIONS(PBKDF2PARAM) + +OPENSSL_EXPORT int PKCS5_pbe_set0_algor(X509_ALGOR *algor, int alg, int iter, + const unsigned char *salt, int saltlen); + +OPENSSL_EXPORT X509_ALGOR *PKCS5_pbe_set(int alg, int iter, + const unsigned char *salt, int saltlen); +OPENSSL_EXPORT X509_ALGOR *PKCS5_pbe2_set(const EVP_CIPHER *cipher, int iter, + unsigned char *salt, int saltlen); +OPENSSL_EXPORT X509_ALGOR *PKCS5_pbe2_set_iv(const EVP_CIPHER *cipher, int iter, + unsigned char *salt, int saltlen, + unsigned char *aiv, int prf_nid); + +OPENSSL_EXPORT X509_ALGOR *PKCS5_pbkdf2_set(int iter, unsigned char *salt, int saltlen, + int prf_nid, int keylen); + +/* PKCS#8 utilities */ + +DECLARE_ASN1_FUNCTIONS(PKCS8_PRIV_KEY_INFO) + +OPENSSL_EXPORT EVP_PKEY *EVP_PKCS82PKEY(PKCS8_PRIV_KEY_INFO *p8); +OPENSSL_EXPORT PKCS8_PRIV_KEY_INFO *EVP_PKEY2PKCS8(EVP_PKEY *pkey); +OPENSSL_EXPORT PKCS8_PRIV_KEY_INFO *EVP_PKEY2PKCS8_broken(EVP_PKEY *pkey, int broken); +OPENSSL_EXPORT PKCS8_PRIV_KEY_INFO *PKCS8_set_broken(PKCS8_PRIV_KEY_INFO *p8, int broken); + +OPENSSL_EXPORT int PKCS8_pkey_set0(PKCS8_PRIV_KEY_INFO *priv, ASN1_OBJECT *aobj, + int version, int ptype, void *pval, + unsigned char *penc, int penclen); +OPENSSL_EXPORT int PKCS8_pkey_get0(ASN1_OBJECT **ppkalg, + const unsigned char **pk, int *ppklen, + X509_ALGOR **pa, + PKCS8_PRIV_KEY_INFO *p8); + +OPENSSL_EXPORT int X509_PUBKEY_set0_param(X509_PUBKEY *pub, const ASN1_OBJECT *aobj, + int ptype, void *pval, + unsigned char *penc, int penclen); +OPENSSL_EXPORT int X509_PUBKEY_get0_param(ASN1_OBJECT **ppkalg, + const unsigned char **pk, int *ppklen, + X509_ALGOR **pa, + X509_PUBKEY *pub); + +OPENSSL_EXPORT int X509_check_trust(X509 *x, int id, int flags); +OPENSSL_EXPORT int X509_TRUST_get_count(void); +OPENSSL_EXPORT X509_TRUST * X509_TRUST_get0(int idx); +OPENSSL_EXPORT int X509_TRUST_get_by_id(int id); +OPENSSL_EXPORT int X509_TRUST_add(int id, int flags, int (*ck)(X509_TRUST *, X509 *, int), + char *name, int arg1, void *arg2); +OPENSSL_EXPORT void X509_TRUST_cleanup(void); +OPENSSL_EXPORT int X509_TRUST_get_flags(X509_TRUST *xp); +OPENSSL_EXPORT char *X509_TRUST_get0_name(X509_TRUST *xp); +OPENSSL_EXPORT int X509_TRUST_get_trust(X509_TRUST *xp); + +/* PKCS7_get_certificates parses a PKCS#7, SignedData structure from |cbs| and + * appends the included certificates to |out_certs|. It returns one on success + * and zero on error. */ +OPENSSL_EXPORT int PKCS7_get_certificates(STACK_OF(X509) *out_certs, CBS *cbs); + +/* PKCS7_bundle_certificates appends a PKCS#7, SignedData structure containing + * |certs| to |out|. It returns one on success and zero on error. */ +OPENSSL_EXPORT int PKCS7_bundle_certificates( + CBB *out, const STACK_OF(X509) *certs); + +/* PKCS7_get_CRLs parses a PKCS#7, SignedData structure from |cbs| and appends + * the included CRLs to |out_crls|. It returns one on success and zero on + * error. */ +OPENSSL_EXPORT int PKCS7_get_CRLs(STACK_OF(X509_CRL) *out_crls, CBS *cbs); + +/* PKCS7_bundle_CRLs appends a PKCS#7, SignedData structure containing + * |crls| to |out|. It returns one on success and zero on error. */ +OPENSSL_EXPORT int PKCS7_bundle_CRLs(CBB *out, const STACK_OF(X509_CRL) *crls); + +/* PKCS7_get_PEM_certificates reads a PEM-encoded, PKCS#7, SignedData structure + * from |pem_bio| and appends the included certificates to |out_certs|. It + * returns one on success and zero on error. */ +OPENSSL_EXPORT int PKCS7_get_PEM_certificates(STACK_OF(X509) *out_certs, + BIO *pem_bio); + +/* PKCS7_get_PEM_CRLs reads a PEM-encoded, PKCS#7, SignedData structure from + * |pem_bio| and appends the included CRLs to |out_crls|. It returns one on + * success and zero on error. */ +OPENSSL_EXPORT int PKCS7_get_PEM_CRLs(STACK_OF(X509_CRL) *out_crls, + BIO *pem_bio); + +/* EVP_PK values indicate the algorithm of the public key in a certificate. */ + +#define EVP_PK_RSA 0x0001 +#define EVP_PK_DSA 0x0002 +#define EVP_PK_DH 0x0004 +#define EVP_PK_EC 0x0008 + +/* EVP_PKS values indicate the algorithm used to sign a certificate. */ + +#define EVP_PKS_RSA 0x0100 +#define EVP_PKS_DSA 0x0200 +#define EVP_PKS_EC 0x0400 + +/* EVP_PKT values are flags that define what public-key operations can be + * performed with the public key from a certificate. */ + +/* EVP_PKT_SIGN indicates that the public key can be used for signing. */ +#define EVP_PKT_SIGN 0x0010 +/* EVP_PKT_ENC indicates that a session key can be encrypted to the public + * key. */ +#define EVP_PKT_ENC 0x0020 +/* EVP_PKT_EXCH indicates that key-agreement can be performed. */ +#define EVP_PKT_EXCH 0x0040 +/* EVP_PKT_EXP indicates that key is weak (i.e. "export"). */ +#define EVP_PKT_EXP 0x1000 + + +#ifdef __cplusplus +} +#endif + +#define X509_F_ASN1_digest 100 +#define X509_F_ASN1_item_sign_ctx 101 +#define X509_F_ASN1_item_verify 102 +#define X509_F_NETSCAPE_SPKI_b64_decode 103 +#define X509_F_NETSCAPE_SPKI_b64_encode 104 +#define X509_F_PKCS7_get_certificates 105 +#define X509_F_X509_ATTRIBUTE_create_by_NID 106 +#define X509_F_X509_ATTRIBUTE_create_by_OBJ 107 +#define X509_F_X509_ATTRIBUTE_create_by_txt 108 +#define X509_F_X509_ATTRIBUTE_get0_data 109 +#define X509_F_X509_ATTRIBUTE_set1_data 110 +#define X509_F_X509_CRL_add0_revoked 111 +#define X509_F_X509_CRL_diff 112 +#define X509_F_X509_CRL_print_fp 113 +#define X509_F_X509_EXTENSION_create_by_NID 114 +#define X509_F_X509_EXTENSION_create_by_OBJ 115 +#define X509_F_X509_INFO_new 116 +#define X509_F_X509_NAME_ENTRY_create_by_NID 117 +#define X509_F_X509_NAME_ENTRY_create_by_txt 118 +#define X509_F_X509_NAME_ENTRY_set_object 119 +#define X509_F_X509_NAME_add_entry 120 +#define X509_F_X509_NAME_oneline 121 +#define X509_F_X509_NAME_print 122 +#define X509_F_X509_PKEY_new 123 +#define X509_F_X509_PUBKEY_get 124 +#define X509_F_X509_PUBKEY_set 125 +#define X509_F_X509_REQ_check_private_key 126 +#define X509_F_X509_REQ_to_X509 127 +#define X509_F_X509_STORE_CTX_get1_issuer 128 +#define X509_F_X509_STORE_CTX_init 129 +#define X509_F_X509_STORE_CTX_new 130 +#define X509_F_X509_STORE_CTX_purpose_inherit 131 +#define X509_F_X509_STORE_add_cert 132 +#define X509_F_X509_STORE_add_crl 133 +#define X509_F_X509_TRUST_add 134 +#define X509_F_X509_TRUST_set 135 +#define X509_F_X509_check_private_key 136 +#define X509_F_X509_get_pubkey_parameters 137 +#define X509_F_X509_load_cert_crl_file 138 +#define X509_F_X509_load_cert_file 139 +#define X509_F_X509_load_crl_file 140 +#define X509_F_X509_print_ex_fp 141 +#define X509_F_X509_to_X509_REQ 142 +#define X509_F_X509_verify_cert 143 +#define X509_F_X509at_add1_attr 144 +#define X509_F_X509v3_add_ext 145 +#define X509_F_add_cert_dir 146 +#define X509_F_by_file_ctrl 147 +#define X509_F_check_policy 148 +#define X509_F_dir_ctrl 149 +#define X509_F_get_cert_by_subject 150 +#define X509_F_i2d_DSA_PUBKEY 151 +#define X509_F_i2d_EC_PUBKEY 152 +#define X509_F_i2d_RSA_PUBKEY 153 +#define X509_F_x509_name_encode 154 +#define X509_F_x509_name_ex_d2i 155 +#define X509_F_x509_name_ex_new 156 +#define X509_F_pkcs7_parse_header 157 +#define X509_F_PKCS7_get_CRLs 158 +#define X509_R_AKID_MISMATCH 100 +#define X509_R_BAD_PKCS7_VERSION 101 +#define X509_R_BAD_X509_FILETYPE 102 +#define X509_R_BASE64_DECODE_ERROR 103 +#define X509_R_CANT_CHECK_DH_KEY 104 +#define X509_R_CERT_ALREADY_IN_HASH_TABLE 105 +#define X509_R_CRL_ALREADY_DELTA 106 +#define X509_R_CRL_VERIFY_FAILURE 107 +#define X509_R_IDP_MISMATCH 108 +#define X509_R_INVALID_BIT_STRING_BITS_LEFT 109 +#define X509_R_INVALID_DIRECTORY 110 +#define X509_R_INVALID_FIELD_NAME 111 +#define X509_R_INVALID_TRUST 112 +#define X509_R_ISSUER_MISMATCH 113 +#define X509_R_KEY_TYPE_MISMATCH 114 +#define X509_R_KEY_VALUES_MISMATCH 115 +#define X509_R_LOADING_CERT_DIR 116 +#define X509_R_LOADING_DEFAULTS 117 +#define X509_R_METHOD_NOT_SUPPORTED 118 +#define X509_R_NEWER_CRL_NOT_NEWER 119 +#define X509_R_NOT_PKCS7_SIGNED_DATA 120 +#define X509_R_NO_CERTIFICATES_INCLUDED 121 +#define X509_R_NO_CERT_SET_FOR_US_TO_VERIFY 122 +#define X509_R_NO_CRL_NUMBER 123 +#define X509_R_PUBLIC_KEY_DECODE_ERROR 124 +#define X509_R_PUBLIC_KEY_ENCODE_ERROR 125 +#define X509_R_SHOULD_RETRY 126 +#define X509_R_UNABLE_TO_FIND_PARAMETERS_IN_CHAIN 127 +#define X509_R_UNABLE_TO_GET_CERTS_PUBLIC_KEY 128 +#define X509_R_UNKNOWN_KEY_TYPE 129 +#define X509_R_UNKNOWN_NID 130 +#define X509_R_UNKNOWN_PURPOSE_ID 131 +#define X509_R_UNKNOWN_TRUST_ID 132 +#define X509_R_UNSUPPORTED_ALGORITHM 133 +#define X509_R_WRONG_LOOKUP_TYPE 134 +#define X509_R_WRONG_TYPE 135 +#define X509_R_NO_CRLS_INCLUDED 136 + +#endif diff --git a/phonelibs/boringssl/include/openssl/x509_vfy.h b/phonelibs/boringssl/include/openssl/x509_vfy.h new file mode 100644 index 00000000000000..146e047a6d7d4d --- /dev/null +++ b/phonelibs/boringssl/include/openssl/x509_vfy.h @@ -0,0 +1,612 @@ +/* crypto/x509/x509_vfy.h */ +/* Copyright (C) 1995-1998 Eric Young (eay@cryptsoft.com) + * All rights reserved. + * + * This package is an SSL implementation written + * by Eric Young (eay@cryptsoft.com). + * The implementation was written so as to conform with Netscapes SSL. + * + * This library is free for commercial and non-commercial use as long as + * the following conditions are aheared to. The following conditions + * apply to all code found in this distribution, be it the RC4, RSA, + * lhash, DES, etc., code; not just the SSL code. The SSL documentation + * included with this distribution is covered by the same copyright terms + * except that the holder is Tim Hudson (tjh@cryptsoft.com). + * + * Copyright remains Eric Young's, and as such any Copyright notices in + * the code are not to be removed. + * If this package is used in a product, Eric Young should be given attribution + * as the author of the parts of the library used. + * This can be in the form of a textual message at program startup or + * in documentation (online or textual) provided with the package. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must 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. All advertising materials mentioning features or use of this software + * must display the following acknowledgement: + * "This product includes cryptographic software written by + * Eric Young (eay@cryptsoft.com)" + * The word 'cryptographic' can be left out if the rouines from the library + * being used are not cryptographic related :-). + * 4. If you include any Windows specific code (or a derivative thereof) from + * the apps directory (application code) you must include an acknowledgement: + * "This product includes software written by Tim Hudson (tjh@cryptsoft.com)" + * + * THIS SOFTWARE IS PROVIDED BY ERIC YOUNG ``AS IS'' AND + * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHOR OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (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 licence and distribution terms for any publically available version or + * derivative of this code cannot be changed. i.e. this code cannot simply be + * copied and put under another distribution licence + * [including the GNU Public Licence.] + */ + +#ifndef HEADER_X509_H +#include +/* openssl/x509.h ends up #include-ing this file at about the only + * appropriate moment. */ +#endif + +#ifndef HEADER_X509_VFY_H +#define HEADER_X509_VFY_H + +#include +#include +#include + +#ifdef __cplusplus +extern "C" { +#endif + +#if 0 +/* Outer object */ +typedef struct x509_hash_dir_st + { + int num_dirs; + char **dirs; + int *dirs_type; + int num_dirs_alloced; + } X509_HASH_DIR_CTX; +#endif + +typedef struct x509_file_st + { + int num_paths; /* number of paths to files or directories */ + int num_alloced; + char **paths; /* the list of paths or directories */ + int *path_type; + } X509_CERT_FILE_CTX; + +/*******************************/ +/* +SSL_CTX -> X509_STORE + -> X509_LOOKUP + ->X509_LOOKUP_METHOD + -> X509_LOOKUP + ->X509_LOOKUP_METHOD + +SSL -> X509_STORE_CTX + ->X509_STORE + +The X509_STORE holds the tables etc for verification stuff. +A X509_STORE_CTX is used while validating a single certificate. +The X509_STORE has X509_LOOKUPs for looking up certs. +The X509_STORE then calls a function to actually verify the +certificate chain. +*/ + +#define X509_LU_RETRY -1 +#define X509_LU_FAIL 0 +#define X509_LU_X509 1 +#define X509_LU_CRL 2 +#define X509_LU_PKEY 3 + +typedef struct x509_object_st + { + /* one of the above types */ + int type; + union { + char *ptr; + X509 *x509; + X509_CRL *crl; + EVP_PKEY *pkey; + } data; + } X509_OBJECT; + +typedef struct x509_lookup_st X509_LOOKUP; + +DECLARE_STACK_OF(X509_LOOKUP) +DECLARE_STACK_OF(X509_OBJECT) + +/* This is a static that defines the function interface */ +typedef struct x509_lookup_method_st + { + const char *name; + int (*new_item)(X509_LOOKUP *ctx); + void (*free)(X509_LOOKUP *ctx); + int (*init)(X509_LOOKUP *ctx); + int (*shutdown)(X509_LOOKUP *ctx); + int (*ctrl)(X509_LOOKUP *ctx,int cmd,const char *argc,long argl, + char **ret); + int (*get_by_subject)(X509_LOOKUP *ctx,int type,X509_NAME *name, + X509_OBJECT *ret); + int (*get_by_issuer_serial)(X509_LOOKUP *ctx,int type,X509_NAME *name, + ASN1_INTEGER *serial,X509_OBJECT *ret); + int (*get_by_fingerprint)(X509_LOOKUP *ctx,int type, + unsigned char *bytes,int len, + X509_OBJECT *ret); + int (*get_by_alias)(X509_LOOKUP *ctx,int type,char *str,int len, + X509_OBJECT *ret); + } X509_LOOKUP_METHOD; + +typedef struct X509_VERIFY_PARAM_ID_st X509_VERIFY_PARAM_ID; + +/* This structure hold all parameters associated with a verify operation + * by including an X509_VERIFY_PARAM structure in related structures the + * parameters used can be customized + */ + +typedef struct X509_VERIFY_PARAM_st + { + char *name; + time_t check_time; /* Time to use */ + unsigned long inh_flags; /* Inheritance flags */ + unsigned long flags; /* Various verify flags */ + int purpose; /* purpose to check untrusted certificates */ + int trust; /* trust setting to check */ + int depth; /* Verify depth */ + STACK_OF(ASN1_OBJECT) *policies; /* Permissible policies */ + X509_VERIFY_PARAM_ID *id; /* opaque ID data */ + } X509_VERIFY_PARAM; + +DECLARE_STACK_OF(X509_VERIFY_PARAM) + +/* This is used to hold everything. It is used for all certificate + * validation. Once we have a certificate chain, the 'verify' + * function is then called to actually check the cert chain. */ +struct x509_store_st + { + /* The following is a cache of trusted certs */ + int cache; /* if true, stash any hits */ + STACK_OF(X509_OBJECT) *objs; /* Cache of all objects */ + CRYPTO_MUTEX objs_lock; + + /* These are external lookup methods */ + STACK_OF(X509_LOOKUP) *get_cert_methods; + + X509_VERIFY_PARAM *param; + + /* Callbacks for various operations */ + int (*verify)(X509_STORE_CTX *ctx); /* called to verify a certificate */ + int (*verify_cb)(int ok,X509_STORE_CTX *ctx); /* error callback */ + int (*get_issuer)(X509 **issuer, X509_STORE_CTX *ctx, X509 *x); /* get issuers cert from ctx */ + int (*check_issued)(X509_STORE_CTX *ctx, X509 *x, X509 *issuer); /* check issued */ + int (*check_revocation)(X509_STORE_CTX *ctx); /* Check revocation status of chain */ + int (*get_crl)(X509_STORE_CTX *ctx, X509_CRL **crl, X509 *x); /* retrieve CRL */ + int (*check_crl)(X509_STORE_CTX *ctx, X509_CRL *crl); /* Check CRL validity */ + int (*cert_crl)(X509_STORE_CTX *ctx, X509_CRL *crl, X509 *x); /* Check certificate against CRL */ + STACK_OF(X509) * (*lookup_certs)(X509_STORE_CTX *ctx, X509_NAME *nm); + STACK_OF(X509_CRL) * (*lookup_crls)(X509_STORE_CTX *ctx, X509_NAME *nm); + int (*cleanup)(X509_STORE_CTX *ctx); + + CRYPTO_refcount_t references; + } /* X509_STORE */; + +OPENSSL_EXPORT int X509_STORE_set_depth(X509_STORE *store, int depth); + +#define X509_STORE_set_verify_cb_func(ctx,func) ((ctx)->verify_cb=(func)) +#define X509_STORE_set_verify_func(ctx,func) ((ctx)->verify=(func)) + +/* This is the functions plus an instance of the local variables. */ +struct x509_lookup_st + { + int init; /* have we been started */ + int skip; /* don't use us. */ + X509_LOOKUP_METHOD *method; /* the functions */ + char *method_data; /* method data */ + + X509_STORE *store_ctx; /* who owns us */ + } /* X509_LOOKUP */; + +/* This is a used when verifying cert chains. Since the + * gathering of the cert chain can take some time (and have to be + * 'retried', this needs to be kept and passed around. */ +struct x509_store_ctx_st /* X509_STORE_CTX */ + { + X509_STORE *ctx; + int current_method; /* used when looking up certs */ + + /* The following are set by the caller */ + X509 *cert; /* The cert to check */ + STACK_OF(X509) *untrusted; /* chain of X509s - untrusted - passed in */ + STACK_OF(X509_CRL) *crls; /* set of CRLs passed in */ + + X509_VERIFY_PARAM *param; + void *other_ctx; /* Other info for use with get_issuer() */ + + /* Callbacks for various operations */ + int (*verify)(X509_STORE_CTX *ctx); /* called to verify a certificate */ + int (*verify_cb)(int ok,X509_STORE_CTX *ctx); /* error callback */ + int (*get_issuer)(X509 **issuer, X509_STORE_CTX *ctx, X509 *x); /* get issuers cert from ctx */ + int (*check_issued)(X509_STORE_CTX *ctx, X509 *x, X509 *issuer); /* check issued */ + int (*check_revocation)(X509_STORE_CTX *ctx); /* Check revocation status of chain */ + int (*get_crl)(X509_STORE_CTX *ctx, X509_CRL **crl, X509 *x); /* retrieve CRL */ + int (*check_crl)(X509_STORE_CTX *ctx, X509_CRL *crl); /* Check CRL validity */ + int (*cert_crl)(X509_STORE_CTX *ctx, X509_CRL *crl, X509 *x); /* Check certificate against CRL */ + int (*check_policy)(X509_STORE_CTX *ctx); + STACK_OF(X509) * (*lookup_certs)(X509_STORE_CTX *ctx, X509_NAME *nm); + STACK_OF(X509_CRL) * (*lookup_crls)(X509_STORE_CTX *ctx, X509_NAME *nm); + int (*cleanup)(X509_STORE_CTX *ctx); + + /* The following is built up */ + int valid; /* if 0, rebuild chain */ + int last_untrusted; /* index of last untrusted cert */ + STACK_OF(X509) *chain; /* chain of X509s - built up and trusted */ + X509_POLICY_TREE *tree; /* Valid policy tree */ + + int explicit_policy; /* Require explicit policy value */ + + /* When something goes wrong, this is why */ + int error_depth; + int error; + X509 *current_cert; + X509 *current_issuer; /* cert currently being tested as valid issuer */ + X509_CRL *current_crl; /* current CRL */ + + int current_crl_score; /* score of current CRL */ + unsigned int current_reasons; /* Reason mask */ + + X509_STORE_CTX *parent; /* For CRL path validation: parent context */ + + CRYPTO_EX_DATA ex_data; + } /* X509_STORE_CTX */; + +OPENSSL_EXPORT void X509_STORE_CTX_set_depth(X509_STORE_CTX *ctx, int depth); + +#define X509_STORE_CTX_set_app_data(ctx,data) \ + X509_STORE_CTX_set_ex_data(ctx,0,data) +#define X509_STORE_CTX_get_app_data(ctx) \ + X509_STORE_CTX_get_ex_data(ctx,0) + +#define X509_L_FILE_LOAD 1 +#define X509_L_ADD_DIR 2 + +#define X509_LOOKUP_load_file(x,name,type) \ + X509_LOOKUP_ctrl((x),X509_L_FILE_LOAD,(name),(long)(type),NULL) + +#define X509_LOOKUP_add_dir(x,name,type) \ + X509_LOOKUP_ctrl((x),X509_L_ADD_DIR,(name),(long)(type),NULL) + +#define X509_V_OK 0 +/* illegal error (for uninitialized values, to avoid X509_V_OK): 1 */ + +#define X509_V_ERR_UNABLE_TO_GET_ISSUER_CERT 2 +#define X509_V_ERR_UNABLE_TO_GET_CRL 3 +#define X509_V_ERR_UNABLE_TO_DECRYPT_CERT_SIGNATURE 4 +#define X509_V_ERR_UNABLE_TO_DECRYPT_CRL_SIGNATURE 5 +#define X509_V_ERR_UNABLE_TO_DECODE_ISSUER_PUBLIC_KEY 6 +#define X509_V_ERR_CERT_SIGNATURE_FAILURE 7 +#define X509_V_ERR_CRL_SIGNATURE_FAILURE 8 +#define X509_V_ERR_CERT_NOT_YET_VALID 9 +#define X509_V_ERR_CERT_HAS_EXPIRED 10 +#define X509_V_ERR_CRL_NOT_YET_VALID 11 +#define X509_V_ERR_CRL_HAS_EXPIRED 12 +#define X509_V_ERR_ERROR_IN_CERT_NOT_BEFORE_FIELD 13 +#define X509_V_ERR_ERROR_IN_CERT_NOT_AFTER_FIELD 14 +#define X509_V_ERR_ERROR_IN_CRL_LAST_UPDATE_FIELD 15 +#define X509_V_ERR_ERROR_IN_CRL_NEXT_UPDATE_FIELD 16 +#define X509_V_ERR_OUT_OF_MEM 17 +#define X509_V_ERR_DEPTH_ZERO_SELF_SIGNED_CERT 18 +#define X509_V_ERR_SELF_SIGNED_CERT_IN_CHAIN 19 +#define X509_V_ERR_UNABLE_TO_GET_ISSUER_CERT_LOCALLY 20 +#define X509_V_ERR_UNABLE_TO_VERIFY_LEAF_SIGNATURE 21 +#define X509_V_ERR_CERT_CHAIN_TOO_LONG 22 +#define X509_V_ERR_CERT_REVOKED 23 +#define X509_V_ERR_INVALID_CA 24 +#define X509_V_ERR_PATH_LENGTH_EXCEEDED 25 +#define X509_V_ERR_INVALID_PURPOSE 26 +#define X509_V_ERR_CERT_UNTRUSTED 27 +#define X509_V_ERR_CERT_REJECTED 28 +/* These are 'informational' when looking for issuer cert */ +#define X509_V_ERR_SUBJECT_ISSUER_MISMATCH 29 +#define X509_V_ERR_AKID_SKID_MISMATCH 30 +#define X509_V_ERR_AKID_ISSUER_SERIAL_MISMATCH 31 +#define X509_V_ERR_KEYUSAGE_NO_CERTSIGN 32 + +#define X509_V_ERR_UNABLE_TO_GET_CRL_ISSUER 33 +#define X509_V_ERR_UNHANDLED_CRITICAL_EXTENSION 34 +#define X509_V_ERR_KEYUSAGE_NO_CRL_SIGN 35 +#define X509_V_ERR_UNHANDLED_CRITICAL_CRL_EXTENSION 36 +#define X509_V_ERR_INVALID_NON_CA 37 +#define X509_V_ERR_PROXY_PATH_LENGTH_EXCEEDED 38 +#define X509_V_ERR_KEYUSAGE_NO_DIGITAL_SIGNATURE 39 +#define X509_V_ERR_PROXY_CERTIFICATES_NOT_ALLOWED 40 + +#define X509_V_ERR_INVALID_EXTENSION 41 +#define X509_V_ERR_INVALID_POLICY_EXTENSION 42 +#define X509_V_ERR_NO_EXPLICIT_POLICY 43 +#define X509_V_ERR_DIFFERENT_CRL_SCOPE 44 +#define X509_V_ERR_UNSUPPORTED_EXTENSION_FEATURE 45 + +#define X509_V_ERR_UNNESTED_RESOURCE 46 + +#define X509_V_ERR_PERMITTED_VIOLATION 47 +#define X509_V_ERR_EXCLUDED_VIOLATION 48 +#define X509_V_ERR_SUBTREE_MINMAX 49 +#define X509_V_ERR_UNSUPPORTED_CONSTRAINT_TYPE 51 +#define X509_V_ERR_UNSUPPORTED_CONSTRAINT_SYNTAX 52 +#define X509_V_ERR_UNSUPPORTED_NAME_SYNTAX 53 +#define X509_V_ERR_CRL_PATH_VALIDATION_ERROR 54 + +/* Suite B mode algorithm violation */ +#define X509_V_ERR_SUITE_B_INVALID_VERSION 56 +#define X509_V_ERR_SUITE_B_INVALID_ALGORITHM 57 +#define X509_V_ERR_SUITE_B_INVALID_CURVE 58 +#define X509_V_ERR_SUITE_B_INVALID_SIGNATURE_ALGORITHM 59 +#define X509_V_ERR_SUITE_B_LOS_NOT_ALLOWED 60 +#define X509_V_ERR_SUITE_B_CANNOT_SIGN_P_384_WITH_P_256 61 + +/* Host, email and IP check errors */ +#define X509_V_ERR_HOSTNAME_MISMATCH 62 +#define X509_V_ERR_EMAIL_MISMATCH 63 +#define X509_V_ERR_IP_ADDRESS_MISMATCH 64 + +/* The application is not happy */ +#define X509_V_ERR_APPLICATION_VERIFICATION 50 + +/* Certificate verify flags */ + +/* Send issuer+subject checks to verify_cb */ +#define X509_V_FLAG_CB_ISSUER_CHECK 0x1 +/* Use check time instead of current time */ +#define X509_V_FLAG_USE_CHECK_TIME 0x2 +/* Lookup CRLs */ +#define X509_V_FLAG_CRL_CHECK 0x4 +/* Lookup CRLs for whole chain */ +#define X509_V_FLAG_CRL_CHECK_ALL 0x8 +/* Ignore unhandled critical extensions */ +#define X509_V_FLAG_IGNORE_CRITICAL 0x10 +/* Disable workarounds for broken certificates */ +#define X509_V_FLAG_X509_STRICT 0x20 +/* Enable proxy certificate validation */ +#define X509_V_FLAG_ALLOW_PROXY_CERTS 0x40 +/* Enable policy checking */ +#define X509_V_FLAG_POLICY_CHECK 0x80 +/* Policy variable require-explicit-policy */ +#define X509_V_FLAG_EXPLICIT_POLICY 0x100 +/* Policy variable inhibit-any-policy */ +#define X509_V_FLAG_INHIBIT_ANY 0x200 +/* Policy variable inhibit-policy-mapping */ +#define X509_V_FLAG_INHIBIT_MAP 0x400 +/* Notify callback that policy is OK */ +#define X509_V_FLAG_NOTIFY_POLICY 0x800 +/* Extended CRL features such as indirect CRLs, alternate CRL signing keys */ +#define X509_V_FLAG_EXTENDED_CRL_SUPPORT 0x1000 +/* Delta CRL support */ +#define X509_V_FLAG_USE_DELTAS 0x2000 +/* Check selfsigned CA signature */ +#define X509_V_FLAG_CHECK_SS_SIGNATURE 0x4000 +/* Use trusted store first */ +#define X509_V_FLAG_TRUSTED_FIRST 0x8000 +/* Suite B 128 bit only mode: not normally used */ +#define X509_V_FLAG_SUITEB_128_LOS_ONLY 0x10000 +/* Suite B 192 bit only mode */ +#define X509_V_FLAG_SUITEB_192_LOS 0x20000 +/* Suite B 128 bit mode allowing 192 bit algorithms */ +#define X509_V_FLAG_SUITEB_128_LOS 0x30000 + +/* Allow partial chains if at least one certificate is in trusted store */ +#define X509_V_FLAG_PARTIAL_CHAIN 0x80000 + +#define X509_VP_FLAG_DEFAULT 0x1 +#define X509_VP_FLAG_OVERWRITE 0x2 +#define X509_VP_FLAG_RESET_FLAGS 0x4 +#define X509_VP_FLAG_LOCKED 0x8 +#define X509_VP_FLAG_ONCE 0x10 + +/* Internal use: mask of policy related options */ +#define X509_V_FLAG_POLICY_MASK (X509_V_FLAG_POLICY_CHECK \ + | X509_V_FLAG_EXPLICIT_POLICY \ + | X509_V_FLAG_INHIBIT_ANY \ + | X509_V_FLAG_INHIBIT_MAP) + +OPENSSL_EXPORT int X509_OBJECT_idx_by_subject(STACK_OF(X509_OBJECT) *h, int type, + X509_NAME *name); +OPENSSL_EXPORT X509_OBJECT *X509_OBJECT_retrieve_by_subject(STACK_OF(X509_OBJECT) *h,int type,X509_NAME *name); +OPENSSL_EXPORT X509_OBJECT *X509_OBJECT_retrieve_match(STACK_OF(X509_OBJECT) *h, X509_OBJECT *x); +OPENSSL_EXPORT void X509_OBJECT_up_ref_count(X509_OBJECT *a); +OPENSSL_EXPORT void X509_OBJECT_free_contents(X509_OBJECT *a); +OPENSSL_EXPORT X509_STORE *X509_STORE_new(void ); +OPENSSL_EXPORT void X509_STORE_free(X509_STORE *v); + +OPENSSL_EXPORT STACK_OF(X509)* X509_STORE_get1_certs(X509_STORE_CTX *st, X509_NAME *nm); +OPENSSL_EXPORT STACK_OF(X509_CRL)* X509_STORE_get1_crls(X509_STORE_CTX *st, X509_NAME *nm); +OPENSSL_EXPORT int X509_STORE_set_flags(X509_STORE *ctx, unsigned long flags); +OPENSSL_EXPORT int X509_STORE_set_purpose(X509_STORE *ctx, int purpose); +OPENSSL_EXPORT int X509_STORE_set_trust(X509_STORE *ctx, int trust); +OPENSSL_EXPORT int X509_STORE_set1_param(X509_STORE *ctx, X509_VERIFY_PARAM *pm); + +OPENSSL_EXPORT void X509_STORE_set_verify_cb(X509_STORE *ctx, + int (*verify_cb)(int, X509_STORE_CTX *)); + +OPENSSL_EXPORT void X509_STORE_set_lookup_crls_cb(X509_STORE *ctx, + STACK_OF(X509_CRL)* (*cb)(X509_STORE_CTX *ctx, X509_NAME *nm)); + +OPENSSL_EXPORT X509_STORE_CTX *X509_STORE_CTX_new(void); + +OPENSSL_EXPORT int X509_STORE_CTX_get1_issuer(X509 **issuer, X509_STORE_CTX *ctx, X509 *x); + +OPENSSL_EXPORT void X509_STORE_CTX_free(X509_STORE_CTX *ctx); +OPENSSL_EXPORT int X509_STORE_CTX_init(X509_STORE_CTX *ctx, X509_STORE *store, + X509 *x509, STACK_OF(X509) *chain); +OPENSSL_EXPORT void X509_STORE_CTX_trusted_stack(X509_STORE_CTX *ctx, STACK_OF(X509) *sk); +OPENSSL_EXPORT void X509_STORE_CTX_cleanup(X509_STORE_CTX *ctx); + +OPENSSL_EXPORT X509_STORE *X509_STORE_CTX_get0_store(X509_STORE_CTX *ctx); + +OPENSSL_EXPORT X509_LOOKUP *X509_STORE_add_lookup(X509_STORE *v, X509_LOOKUP_METHOD *m); + +OPENSSL_EXPORT X509_LOOKUP_METHOD *X509_LOOKUP_hash_dir(void); +OPENSSL_EXPORT X509_LOOKUP_METHOD *X509_LOOKUP_file(void); + +OPENSSL_EXPORT int X509_STORE_add_cert(X509_STORE *ctx, X509 *x); +OPENSSL_EXPORT int X509_STORE_add_crl(X509_STORE *ctx, X509_CRL *x); + +OPENSSL_EXPORT int X509_STORE_get_by_subject(X509_STORE_CTX *vs,int type,X509_NAME *name, + X509_OBJECT *ret); + +OPENSSL_EXPORT int X509_LOOKUP_ctrl(X509_LOOKUP *ctx, int cmd, const char *argc, + long argl, char **ret); + +#ifndef OPENSSL_NO_STDIO +OPENSSL_EXPORT int X509_load_cert_file(X509_LOOKUP *ctx, const char *file, int type); +OPENSSL_EXPORT int X509_load_crl_file(X509_LOOKUP *ctx, const char *file, int type); +OPENSSL_EXPORT int X509_load_cert_crl_file(X509_LOOKUP *ctx, const char *file, int type); +#endif + + +OPENSSL_EXPORT X509_LOOKUP *X509_LOOKUP_new(X509_LOOKUP_METHOD *method); +OPENSSL_EXPORT void X509_LOOKUP_free(X509_LOOKUP *ctx); +OPENSSL_EXPORT int X509_LOOKUP_init(X509_LOOKUP *ctx); +OPENSSL_EXPORT int X509_LOOKUP_by_subject(X509_LOOKUP *ctx, int type, X509_NAME *name, + X509_OBJECT *ret); +OPENSSL_EXPORT int X509_LOOKUP_by_issuer_serial(X509_LOOKUP *ctx, int type, X509_NAME *name, + ASN1_INTEGER *serial, X509_OBJECT *ret); +OPENSSL_EXPORT int X509_LOOKUP_by_fingerprint(X509_LOOKUP *ctx, int type, + unsigned char *bytes, int len, X509_OBJECT *ret); +OPENSSL_EXPORT int X509_LOOKUP_by_alias(X509_LOOKUP *ctx, int type, char *str, + int len, X509_OBJECT *ret); +OPENSSL_EXPORT int X509_LOOKUP_shutdown(X509_LOOKUP *ctx); + +#ifndef OPENSSL_NO_STDIO +OPENSSL_EXPORT int X509_STORE_load_locations (X509_STORE *ctx, + const char *file, const char *dir); +OPENSSL_EXPORT int X509_STORE_set_default_paths(X509_STORE *ctx); +#endif + +OPENSSL_EXPORT int X509_STORE_CTX_get_ex_new_index(long argl, void *argp, CRYPTO_EX_new *new_func, + CRYPTO_EX_dup *dup_func, CRYPTO_EX_free *free_func); +OPENSSL_EXPORT int X509_STORE_CTX_set_ex_data(X509_STORE_CTX *ctx,int idx,void *data); +OPENSSL_EXPORT void * X509_STORE_CTX_get_ex_data(X509_STORE_CTX *ctx,int idx); +OPENSSL_EXPORT int X509_STORE_CTX_get_error(X509_STORE_CTX *ctx); +OPENSSL_EXPORT void X509_STORE_CTX_set_error(X509_STORE_CTX *ctx,int s); +OPENSSL_EXPORT int X509_STORE_CTX_get_error_depth(X509_STORE_CTX *ctx); +OPENSSL_EXPORT X509 * X509_STORE_CTX_get_current_cert(X509_STORE_CTX *ctx); +OPENSSL_EXPORT X509 *X509_STORE_CTX_get0_current_issuer(X509_STORE_CTX *ctx); +OPENSSL_EXPORT X509_CRL *X509_STORE_CTX_get0_current_crl(X509_STORE_CTX *ctx); +OPENSSL_EXPORT X509_STORE_CTX *X509_STORE_CTX_get0_parent_ctx(X509_STORE_CTX *ctx); +OPENSSL_EXPORT STACK_OF(X509) *X509_STORE_CTX_get_chain(X509_STORE_CTX *ctx); +OPENSSL_EXPORT STACK_OF(X509) *X509_STORE_CTX_get1_chain(X509_STORE_CTX *ctx); +OPENSSL_EXPORT void X509_STORE_CTX_set_cert(X509_STORE_CTX *c,X509 *x); +OPENSSL_EXPORT void X509_STORE_CTX_set_chain(X509_STORE_CTX *c,STACK_OF(X509) *sk); +OPENSSL_EXPORT void X509_STORE_CTX_set0_crls(X509_STORE_CTX *c,STACK_OF(X509_CRL) *sk); +OPENSSL_EXPORT int X509_STORE_CTX_set_purpose(X509_STORE_CTX *ctx, int purpose); +OPENSSL_EXPORT int X509_STORE_CTX_set_trust(X509_STORE_CTX *ctx, int trust); +OPENSSL_EXPORT int X509_STORE_CTX_purpose_inherit(X509_STORE_CTX *ctx, int def_purpose, + int purpose, int trust); +OPENSSL_EXPORT void X509_STORE_CTX_set_flags(X509_STORE_CTX *ctx, unsigned long flags); +OPENSSL_EXPORT void X509_STORE_CTX_set_time(X509_STORE_CTX *ctx, unsigned long flags, + time_t t); +OPENSSL_EXPORT void X509_STORE_CTX_set_verify_cb(X509_STORE_CTX *ctx, + int (*verify_cb)(int, X509_STORE_CTX *)); + +OPENSSL_EXPORT X509_POLICY_TREE *X509_STORE_CTX_get0_policy_tree(X509_STORE_CTX *ctx); +OPENSSL_EXPORT int X509_STORE_CTX_get_explicit_policy(X509_STORE_CTX *ctx); + +OPENSSL_EXPORT X509_VERIFY_PARAM *X509_STORE_CTX_get0_param(X509_STORE_CTX *ctx); +OPENSSL_EXPORT void X509_STORE_CTX_set0_param(X509_STORE_CTX *ctx, X509_VERIFY_PARAM *param); +OPENSSL_EXPORT int X509_STORE_CTX_set_default(X509_STORE_CTX *ctx, const char *name); + +/* X509_VERIFY_PARAM functions */ + +OPENSSL_EXPORT X509_VERIFY_PARAM *X509_VERIFY_PARAM_new(void); +OPENSSL_EXPORT void X509_VERIFY_PARAM_free(X509_VERIFY_PARAM *param); +OPENSSL_EXPORT int X509_VERIFY_PARAM_inherit(X509_VERIFY_PARAM *to, + const X509_VERIFY_PARAM *from); +OPENSSL_EXPORT int X509_VERIFY_PARAM_set1(X509_VERIFY_PARAM *to, + const X509_VERIFY_PARAM *from); +OPENSSL_EXPORT int X509_VERIFY_PARAM_set1_name(X509_VERIFY_PARAM *param, const char *name); +OPENSSL_EXPORT int X509_VERIFY_PARAM_set_flags(X509_VERIFY_PARAM *param, unsigned long flags); +OPENSSL_EXPORT int X509_VERIFY_PARAM_clear_flags(X509_VERIFY_PARAM *param, + unsigned long flags); +OPENSSL_EXPORT unsigned long X509_VERIFY_PARAM_get_flags(X509_VERIFY_PARAM *param); +OPENSSL_EXPORT int X509_VERIFY_PARAM_set_purpose(X509_VERIFY_PARAM *param, int purpose); +OPENSSL_EXPORT int X509_VERIFY_PARAM_set_trust(X509_VERIFY_PARAM *param, int trust); +OPENSSL_EXPORT void X509_VERIFY_PARAM_set_depth(X509_VERIFY_PARAM *param, int depth); +OPENSSL_EXPORT void X509_VERIFY_PARAM_set_time(X509_VERIFY_PARAM *param, time_t t); +OPENSSL_EXPORT int X509_VERIFY_PARAM_add0_policy(X509_VERIFY_PARAM *param, + ASN1_OBJECT *policy); +OPENSSL_EXPORT int X509_VERIFY_PARAM_set1_policies(X509_VERIFY_PARAM *param, + STACK_OF(ASN1_OBJECT) *policies); + +OPENSSL_EXPORT int X509_VERIFY_PARAM_set1_host(X509_VERIFY_PARAM *param, + const char *name, size_t namelen); +OPENSSL_EXPORT int X509_VERIFY_PARAM_add1_host(X509_VERIFY_PARAM *param, + const char *name, + size_t namelen); +OPENSSL_EXPORT void X509_VERIFY_PARAM_set_hostflags(X509_VERIFY_PARAM *param, + unsigned int flags); +OPENSSL_EXPORT char *X509_VERIFY_PARAM_get0_peername(X509_VERIFY_PARAM *); +OPENSSL_EXPORT int X509_VERIFY_PARAM_set1_email(X509_VERIFY_PARAM *param, + const char *email, size_t emaillen); +OPENSSL_EXPORT int X509_VERIFY_PARAM_set1_ip(X509_VERIFY_PARAM *param, + const unsigned char *ip, size_t iplen); +OPENSSL_EXPORT int X509_VERIFY_PARAM_set1_ip_asc(X509_VERIFY_PARAM *param, const char *ipasc); + +OPENSSL_EXPORT int X509_VERIFY_PARAM_get_depth(const X509_VERIFY_PARAM *param); +OPENSSL_EXPORT const char *X509_VERIFY_PARAM_get0_name(const X509_VERIFY_PARAM *param); + +OPENSSL_EXPORT int X509_VERIFY_PARAM_add0_table(X509_VERIFY_PARAM *param); +OPENSSL_EXPORT int X509_VERIFY_PARAM_get_count(void); +OPENSSL_EXPORT const X509_VERIFY_PARAM *X509_VERIFY_PARAM_get0(int id); +OPENSSL_EXPORT const X509_VERIFY_PARAM *X509_VERIFY_PARAM_lookup(const char *name); +OPENSSL_EXPORT void X509_VERIFY_PARAM_table_cleanup(void); + +OPENSSL_EXPORT int X509_policy_check(X509_POLICY_TREE **ptree, int *pexplicit_policy, + STACK_OF(X509) *certs, + STACK_OF(ASN1_OBJECT) *policy_oids, + unsigned int flags); + +OPENSSL_EXPORT void X509_policy_tree_free(X509_POLICY_TREE *tree); + +OPENSSL_EXPORT int X509_policy_tree_level_count(const X509_POLICY_TREE *tree); +OPENSSL_EXPORT X509_POLICY_LEVEL * + X509_policy_tree_get0_level(const X509_POLICY_TREE *tree, int i); + +OPENSSL_EXPORT STACK_OF(X509_POLICY_NODE) * + X509_policy_tree_get0_policies(const X509_POLICY_TREE *tree); + +OPENSSL_EXPORT STACK_OF(X509_POLICY_NODE) * + X509_policy_tree_get0_user_policies(const X509_POLICY_TREE *tree); + +OPENSSL_EXPORT int X509_policy_level_node_count(X509_POLICY_LEVEL *level); + +OPENSSL_EXPORT X509_POLICY_NODE *X509_policy_level_get0_node(X509_POLICY_LEVEL *level, int i); + +OPENSSL_EXPORT const ASN1_OBJECT *X509_policy_node_get0_policy(const X509_POLICY_NODE *node); + +OPENSSL_EXPORT STACK_OF(POLICYQUALINFO) * + X509_policy_node_get0_qualifiers(const X509_POLICY_NODE *node); +OPENSSL_EXPORT const X509_POLICY_NODE * + X509_policy_node_get0_parent(const X509_POLICY_NODE *node); + +#ifdef __cplusplus +} +#endif +#endif + diff --git a/phonelibs/boringssl/include/openssl/x509v3.h b/phonelibs/boringssl/include/openssl/x509v3.h new file mode 100644 index 00000000000000..5caa5c1f4e348b --- /dev/null +++ b/phonelibs/boringssl/include/openssl/x509v3.h @@ -0,0 +1,855 @@ +/* Written by Dr Stephen N Henson (steve@openssl.org) for the OpenSSL + * project 1999. */ +/* ==================================================================== + * Copyright (c) 1999-2004 The OpenSSL Project. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * + * 3. All advertising materials mentioning features or use of this + * software must display the following acknowledgment: + * "This product includes software developed by the OpenSSL Project + * for use in the OpenSSL Toolkit. (http://www.OpenSSL.org/)" + * + * 4. The names "OpenSSL Toolkit" and "OpenSSL Project" must not be used to + * endorse or promote products derived from this software without + * prior written permission. For written permission, please contact + * licensing@OpenSSL.org. + * + * 5. Products derived from this software may not be called "OpenSSL" + * nor may "OpenSSL" appear in their names without prior written + * permission of the OpenSSL Project. + * + * 6. Redistributions of any form whatsoever must retain the following + * acknowledgment: + * "This product includes software developed by the OpenSSL Project + * for use in the OpenSSL Toolkit (http://www.OpenSSL.org/)" + * + * THIS SOFTWARE IS PROVIDED BY THE OpenSSL PROJECT ``AS IS'' AND ANY + * EXPRESSED OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR + * PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE OpenSSL PROJECT OR + * ITS CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, + * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT + * NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + * STRICT LIABILITY, OR TORT (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 product includes cryptographic software written by Eric Young + * (eay@cryptsoft.com). This product includes software written by Tim + * Hudson (tjh@cryptsoft.com). */ + +#ifndef HEADER_X509V3_H +#define HEADER_X509V3_H + +#include +#include +#include + +#ifdef __cplusplus +extern "C" { +#endif + +/* Forward reference */ +struct v3_ext_method; +struct v3_ext_ctx; + +/* Useful typedefs */ + +typedef void * (*X509V3_EXT_NEW)(void); +typedef void (*X509V3_EXT_FREE)(void *); +typedef void * (*X509V3_EXT_D2I)(void *, const unsigned char ** , long); +typedef int (*X509V3_EXT_I2D)(void *, unsigned char **); +typedef STACK_OF(CONF_VALUE) * + (*X509V3_EXT_I2V)(const struct v3_ext_method *method, void *ext, + STACK_OF(CONF_VALUE) *extlist); +typedef void * (*X509V3_EXT_V2I)(const struct v3_ext_method *method, + struct v3_ext_ctx *ctx, + STACK_OF(CONF_VALUE) *values); +typedef char * (*X509V3_EXT_I2S)(const struct v3_ext_method *method, void *ext); +typedef void * (*X509V3_EXT_S2I)(const struct v3_ext_method *method, + struct v3_ext_ctx *ctx, const char *str); +typedef int (*X509V3_EXT_I2R)(const struct v3_ext_method *method, void *ext, + BIO *out, int indent); +typedef void * (*X509V3_EXT_R2I)(const struct v3_ext_method *method, + struct v3_ext_ctx *ctx, const char *str); + +/* V3 extension structure */ + +struct v3_ext_method { +int ext_nid; +int ext_flags; +/* If this is set the following four fields are ignored */ +ASN1_ITEM_EXP *it; +/* Old style ASN1 calls */ +X509V3_EXT_NEW ext_new; +X509V3_EXT_FREE ext_free; +X509V3_EXT_D2I d2i; +X509V3_EXT_I2D i2d; + +/* The following pair is used for string extensions */ +X509V3_EXT_I2S i2s; +X509V3_EXT_S2I s2i; + +/* The following pair is used for multi-valued extensions */ +X509V3_EXT_I2V i2v; +X509V3_EXT_V2I v2i; + +/* The following are used for raw extensions */ +X509V3_EXT_I2R i2r; +X509V3_EXT_R2I r2i; + +void *usr_data; /* Any extension specific data */ +}; + +typedef struct X509V3_CONF_METHOD_st { +char * (*get_string)(void *db, char *section, char *value); +STACK_OF(CONF_VALUE) * (*get_section)(void *db, char *section); +void (*free_string)(void *db, char * string); +void (*free_section)(void *db, STACK_OF(CONF_VALUE) *section); +} X509V3_CONF_METHOD; + +/* Context specific info */ +struct v3_ext_ctx { +#define CTX_TEST 0x1 +int flags; +X509 *issuer_cert; +X509 *subject_cert; +X509_REQ *subject_req; +X509_CRL *crl; +const X509V3_CONF_METHOD *db_meth; +void *db; +/* Maybe more here */ +}; + +typedef struct v3_ext_method X509V3_EXT_METHOD; + +DECLARE_STACK_OF(X509V3_EXT_METHOD) + +/* ext_flags values */ +#define X509V3_EXT_DYNAMIC 0x1 +#define X509V3_EXT_CTX_DEP 0x2 +#define X509V3_EXT_MULTILINE 0x4 + +typedef BIT_STRING_BITNAME ENUMERATED_NAMES; + +typedef struct BASIC_CONSTRAINTS_st { +int ca; +ASN1_INTEGER *pathlen; +} BASIC_CONSTRAINTS; + + +typedef struct PKEY_USAGE_PERIOD_st { +ASN1_GENERALIZEDTIME *notBefore; +ASN1_GENERALIZEDTIME *notAfter; +} PKEY_USAGE_PERIOD; + +typedef struct otherName_st { +ASN1_OBJECT *type_id; +ASN1_TYPE *value; +} OTHERNAME; + +typedef struct EDIPartyName_st { + ASN1_STRING *nameAssigner; + ASN1_STRING *partyName; +} EDIPARTYNAME; + +typedef struct GENERAL_NAME_st { + +#define GEN_OTHERNAME 0 +#define GEN_EMAIL 1 +#define GEN_DNS 2 +#define GEN_X400 3 +#define GEN_DIRNAME 4 +#define GEN_EDIPARTY 5 +#define GEN_URI 6 +#define GEN_IPADD 7 +#define GEN_RID 8 + +int type; +union { + char *ptr; + OTHERNAME *otherName; /* otherName */ + ASN1_IA5STRING *rfc822Name; + ASN1_IA5STRING *dNSName; + ASN1_TYPE *x400Address; + X509_NAME *directoryName; + EDIPARTYNAME *ediPartyName; + ASN1_IA5STRING *uniformResourceIdentifier; + ASN1_OCTET_STRING *iPAddress; + ASN1_OBJECT *registeredID; + + /* Old names */ + ASN1_OCTET_STRING *ip; /* iPAddress */ + X509_NAME *dirn; /* dirn */ + ASN1_IA5STRING *ia5;/* rfc822Name, dNSName, uniformResourceIdentifier */ + ASN1_OBJECT *rid; /* registeredID */ + ASN1_TYPE *other; /* x400Address */ +} d; +} GENERAL_NAME; + +typedef STACK_OF(GENERAL_NAME) GENERAL_NAMES; + +typedef struct ACCESS_DESCRIPTION_st { + ASN1_OBJECT *method; + GENERAL_NAME *location; +} ACCESS_DESCRIPTION; + +typedef STACK_OF(ACCESS_DESCRIPTION) AUTHORITY_INFO_ACCESS; + +typedef STACK_OF(ASN1_OBJECT) EXTENDED_KEY_USAGE; + +DECLARE_STACK_OF(GENERAL_NAME) +DECLARE_ASN1_SET_OF(GENERAL_NAME) + +DECLARE_STACK_OF(ACCESS_DESCRIPTION) +DECLARE_ASN1_SET_OF(ACCESS_DESCRIPTION) + +typedef struct DIST_POINT_NAME_st { +int type; +union { + GENERAL_NAMES *fullname; + STACK_OF(X509_NAME_ENTRY) *relativename; +} name; +/* If relativename then this contains the full distribution point name */ +X509_NAME *dpname; +} DIST_POINT_NAME; +/* All existing reasons */ +#define CRLDP_ALL_REASONS 0x807f + +#define CRL_REASON_NONE -1 +#define CRL_REASON_UNSPECIFIED 0 +#define CRL_REASON_KEY_COMPROMISE 1 +#define CRL_REASON_CA_COMPROMISE 2 +#define CRL_REASON_AFFILIATION_CHANGED 3 +#define CRL_REASON_SUPERSEDED 4 +#define CRL_REASON_CESSATION_OF_OPERATION 5 +#define CRL_REASON_CERTIFICATE_HOLD 6 +#define CRL_REASON_REMOVE_FROM_CRL 8 +#define CRL_REASON_PRIVILEGE_WITHDRAWN 9 +#define CRL_REASON_AA_COMPROMISE 10 + +struct DIST_POINT_st { +DIST_POINT_NAME *distpoint; +ASN1_BIT_STRING *reasons; +GENERAL_NAMES *CRLissuer; +int dp_reasons; +}; + +typedef STACK_OF(DIST_POINT) CRL_DIST_POINTS; + +DECLARE_STACK_OF(DIST_POINT) +DECLARE_ASN1_SET_OF(DIST_POINT) + +struct AUTHORITY_KEYID_st { +ASN1_OCTET_STRING *keyid; +GENERAL_NAMES *issuer; +ASN1_INTEGER *serial; +}; + +/* Strong extranet structures */ + +typedef struct SXNET_ID_st { + ASN1_INTEGER *zone; + ASN1_OCTET_STRING *user; +} SXNETID; + +DECLARE_STACK_OF(SXNETID) +DECLARE_ASN1_SET_OF(SXNETID) + +typedef struct SXNET_st { + ASN1_INTEGER *version; + STACK_OF(SXNETID) *ids; +} SXNET; + +typedef struct NOTICEREF_st { + ASN1_STRING *organization; + STACK_OF(ASN1_INTEGER) *noticenos; +} NOTICEREF; + +typedef struct USERNOTICE_st { + NOTICEREF *noticeref; + ASN1_STRING *exptext; +} USERNOTICE; + +typedef struct POLICYQUALINFO_st { + ASN1_OBJECT *pqualid; + union { + ASN1_IA5STRING *cpsuri; + USERNOTICE *usernotice; + ASN1_TYPE *other; + } d; +} POLICYQUALINFO; + +DECLARE_STACK_OF(POLICYQUALINFO) +DECLARE_ASN1_SET_OF(POLICYQUALINFO) + +typedef struct POLICYINFO_st { + ASN1_OBJECT *policyid; + STACK_OF(POLICYQUALINFO) *qualifiers; +} POLICYINFO; + +typedef STACK_OF(POLICYINFO) CERTIFICATEPOLICIES; + +DECLARE_STACK_OF(POLICYINFO) +DECLARE_ASN1_SET_OF(POLICYINFO) + +typedef struct POLICY_MAPPING_st { + ASN1_OBJECT *issuerDomainPolicy; + ASN1_OBJECT *subjectDomainPolicy; +} POLICY_MAPPING; + +DECLARE_STACK_OF(POLICY_MAPPING) + +typedef STACK_OF(POLICY_MAPPING) POLICY_MAPPINGS; + +typedef struct GENERAL_SUBTREE_st { + GENERAL_NAME *base; + ASN1_INTEGER *minimum; + ASN1_INTEGER *maximum; +} GENERAL_SUBTREE; + +DECLARE_STACK_OF(GENERAL_SUBTREE) + +struct NAME_CONSTRAINTS_st { + STACK_OF(GENERAL_SUBTREE) *permittedSubtrees; + STACK_OF(GENERAL_SUBTREE) *excludedSubtrees; +}; + +typedef struct POLICY_CONSTRAINTS_st { + ASN1_INTEGER *requireExplicitPolicy; + ASN1_INTEGER *inhibitPolicyMapping; +} POLICY_CONSTRAINTS; + +/* Proxy certificate structures, see RFC 3820 */ +typedef struct PROXY_POLICY_st + { + ASN1_OBJECT *policyLanguage; + ASN1_OCTET_STRING *policy; + } PROXY_POLICY; + +typedef struct PROXY_CERT_INFO_EXTENSION_st + { + ASN1_INTEGER *pcPathLengthConstraint; + PROXY_POLICY *proxyPolicy; + } PROXY_CERT_INFO_EXTENSION; + +DECLARE_ASN1_FUNCTIONS(PROXY_POLICY) +DECLARE_ASN1_FUNCTIONS(PROXY_CERT_INFO_EXTENSION) + +struct ISSUING_DIST_POINT_st + { + DIST_POINT_NAME *distpoint; + int onlyuser; + int onlyCA; + ASN1_BIT_STRING *onlysomereasons; + int indirectCRL; + int onlyattr; + }; + +/* Values in idp_flags field */ +/* IDP present */ +#define IDP_PRESENT 0x1 +/* IDP values inconsistent */ +#define IDP_INVALID 0x2 +/* onlyuser true */ +#define IDP_ONLYUSER 0x4 +/* onlyCA true */ +#define IDP_ONLYCA 0x8 +/* onlyattr true */ +#define IDP_ONLYATTR 0x10 +/* indirectCRL true */ +#define IDP_INDIRECT 0x20 +/* onlysomereasons present */ +#define IDP_REASONS 0x40 + +#define X509V3_conf_err(val) ERR_add_error_data(6, "section:", val->section, \ +",name:", val->name, ",value:", val->value); + +#define X509V3_set_ctx_test(ctx) \ + X509V3_set_ctx(ctx, NULL, NULL, NULL, NULL, CTX_TEST) +#define X509V3_set_ctx_nodb(ctx) (ctx)->db = NULL; + +#define EXT_BITSTRING(nid, table) { nid, 0, ASN1_ITEM_ref(ASN1_BIT_STRING), \ + 0,0,0,0, \ + 0,0, \ + (X509V3_EXT_I2V)i2v_ASN1_BIT_STRING, \ + (X509V3_EXT_V2I)v2i_ASN1_BIT_STRING, \ + NULL, NULL, \ + (void *)table} + +#define EXT_IA5STRING(nid) { nid, 0, ASN1_ITEM_ref(ASN1_IA5STRING), \ + 0,0,0,0, \ + (X509V3_EXT_I2S)i2s_ASN1_IA5STRING, \ + (X509V3_EXT_S2I)s2i_ASN1_IA5STRING, \ + 0,0,0,0, \ + NULL} + +#define EXT_END { -1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} + + +/* X509_PURPOSE stuff */ + +#define EXFLAG_BCONS 0x1 +#define EXFLAG_KUSAGE 0x2 +#define EXFLAG_XKUSAGE 0x4 +#define EXFLAG_NSCERT 0x8 + +#define EXFLAG_CA 0x10 +/* Really self issued not necessarily self signed */ +#define EXFLAG_SI 0x20 +#define EXFLAG_V1 0x40 +#define EXFLAG_INVALID 0x80 +#define EXFLAG_SET 0x100 +#define EXFLAG_CRITICAL 0x200 +#define EXFLAG_PROXY 0x400 + +#define EXFLAG_INVALID_POLICY 0x800 +#define EXFLAG_FRESHEST 0x1000 +/* Self signed */ +#define EXFLAG_SS 0x2000 + +#define KU_DIGITAL_SIGNATURE 0x0080 +#define KU_NON_REPUDIATION 0x0040 +#define KU_KEY_ENCIPHERMENT 0x0020 +#define KU_DATA_ENCIPHERMENT 0x0010 +#define KU_KEY_AGREEMENT 0x0008 +#define KU_KEY_CERT_SIGN 0x0004 +#define KU_CRL_SIGN 0x0002 +#define KU_ENCIPHER_ONLY 0x0001 +#define KU_DECIPHER_ONLY 0x8000 + +#define NS_SSL_CLIENT 0x80 +#define NS_SSL_SERVER 0x40 +#define NS_SMIME 0x20 +#define NS_OBJSIGN 0x10 +#define NS_SSL_CA 0x04 +#define NS_SMIME_CA 0x02 +#define NS_OBJSIGN_CA 0x01 +#define NS_ANY_CA (NS_SSL_CA|NS_SMIME_CA|NS_OBJSIGN_CA) + +#define XKU_SSL_SERVER 0x1 +#define XKU_SSL_CLIENT 0x2 +#define XKU_SMIME 0x4 +#define XKU_CODE_SIGN 0x8 +#define XKU_SGC 0x10 +#define XKU_OCSP_SIGN 0x20 +#define XKU_TIMESTAMP 0x40 +#define XKU_DVCS 0x80 +#define XKU_ANYEKU 0x100 + +#define X509_PURPOSE_DYNAMIC 0x1 +#define X509_PURPOSE_DYNAMIC_NAME 0x2 + +typedef struct x509_purpose_st { + int purpose; + int trust; /* Default trust ID */ + int flags; + int (*check_purpose)(const struct x509_purpose_st *, + const X509 *, int); + char *name; + char *sname; + void *usr_data; +} X509_PURPOSE; + +#define X509_PURPOSE_SSL_CLIENT 1 +#define X509_PURPOSE_SSL_SERVER 2 +#define X509_PURPOSE_NS_SSL_SERVER 3 +#define X509_PURPOSE_SMIME_SIGN 4 +#define X509_PURPOSE_SMIME_ENCRYPT 5 +#define X509_PURPOSE_CRL_SIGN 6 +#define X509_PURPOSE_ANY 7 +#define X509_PURPOSE_OCSP_HELPER 8 +#define X509_PURPOSE_TIMESTAMP_SIGN 9 + +#define X509_PURPOSE_MIN 1 +#define X509_PURPOSE_MAX 9 + +/* Flags for X509V3_EXT_print() */ + +#define X509V3_EXT_UNKNOWN_MASK (0xfL << 16) +/* Return error for unknown extensions */ +#define X509V3_EXT_DEFAULT 0 +/* Print error for unknown extensions */ +#define X509V3_EXT_ERROR_UNKNOWN (1L << 16) +/* ASN1 parse unknown extensions */ +#define X509V3_EXT_PARSE_UNKNOWN (2L << 16) +/* BIO_dump unknown extensions */ +#define X509V3_EXT_DUMP_UNKNOWN (3L << 16) + +/* Flags for X509V3_add1_i2d */ + +#define X509V3_ADD_OP_MASK 0xfL +#define X509V3_ADD_DEFAULT 0L +#define X509V3_ADD_APPEND 1L +#define X509V3_ADD_REPLACE 2L +#define X509V3_ADD_REPLACE_EXISTING 3L +#define X509V3_ADD_KEEP_EXISTING 4L +#define X509V3_ADD_DELETE 5L +#define X509V3_ADD_SILENT 0x10 + +DECLARE_STACK_OF(X509_PURPOSE) + +DECLARE_ASN1_FUNCTIONS(BASIC_CONSTRAINTS) + +DECLARE_ASN1_FUNCTIONS(SXNET) +DECLARE_ASN1_FUNCTIONS(SXNETID) + +int SXNET_add_id_asc(SXNET **psx, char *zone, char *user, int userlen); +int SXNET_add_id_ulong(SXNET **psx, unsigned long lzone, char *user, int userlen); +int SXNET_add_id_INTEGER(SXNET **psx, ASN1_INTEGER *izone, char *user, int userlen); + +ASN1_OCTET_STRING *SXNET_get_id_asc(SXNET *sx, char *zone); +ASN1_OCTET_STRING *SXNET_get_id_ulong(SXNET *sx, unsigned long lzone); +ASN1_OCTET_STRING *SXNET_get_id_INTEGER(SXNET *sx, ASN1_INTEGER *zone); + +DECLARE_ASN1_FUNCTIONS(AUTHORITY_KEYID) + +DECLARE_ASN1_FUNCTIONS(PKEY_USAGE_PERIOD) + +DECLARE_ASN1_FUNCTIONS(GENERAL_NAME) +OPENSSL_EXPORT GENERAL_NAME *GENERAL_NAME_dup(GENERAL_NAME *a); +OPENSSL_EXPORT int GENERAL_NAME_cmp(GENERAL_NAME *a, GENERAL_NAME *b); + + + +OPENSSL_EXPORT ASN1_BIT_STRING *v2i_ASN1_BIT_STRING(X509V3_EXT_METHOD *method, + X509V3_CTX *ctx, STACK_OF(CONF_VALUE) *nval); +OPENSSL_EXPORT STACK_OF(CONF_VALUE) *i2v_ASN1_BIT_STRING(X509V3_EXT_METHOD *method, + ASN1_BIT_STRING *bits, + STACK_OF(CONF_VALUE) *extlist); + +OPENSSL_EXPORT STACK_OF(CONF_VALUE) *i2v_GENERAL_NAME(X509V3_EXT_METHOD *method, GENERAL_NAME *gen, STACK_OF(CONF_VALUE) *ret); +OPENSSL_EXPORT int GENERAL_NAME_print(BIO *out, GENERAL_NAME *gen); + +DECLARE_ASN1_FUNCTIONS(GENERAL_NAMES) + +OPENSSL_EXPORT STACK_OF(CONF_VALUE) *i2v_GENERAL_NAMES(X509V3_EXT_METHOD *method, + GENERAL_NAMES *gen, STACK_OF(CONF_VALUE) *extlist); +OPENSSL_EXPORT GENERAL_NAMES *v2i_GENERAL_NAMES(const X509V3_EXT_METHOD *method, + X509V3_CTX *ctx, STACK_OF(CONF_VALUE) *nval); + +DECLARE_ASN1_FUNCTIONS(OTHERNAME) +DECLARE_ASN1_FUNCTIONS(EDIPARTYNAME) +OPENSSL_EXPORT int OTHERNAME_cmp(OTHERNAME *a, OTHERNAME *b); +OPENSSL_EXPORT void GENERAL_NAME_set0_value(GENERAL_NAME *a, int type, void *value); +OPENSSL_EXPORT void *GENERAL_NAME_get0_value(GENERAL_NAME *a, int *ptype); +OPENSSL_EXPORT int GENERAL_NAME_set0_othername(GENERAL_NAME *gen, + ASN1_OBJECT *oid, ASN1_TYPE *value); +OPENSSL_EXPORT int GENERAL_NAME_get0_otherName(GENERAL_NAME *gen, + ASN1_OBJECT **poid, ASN1_TYPE **pvalue); + +OPENSSL_EXPORT char *i2s_ASN1_OCTET_STRING(X509V3_EXT_METHOD *method, ASN1_OCTET_STRING *ia5); +OPENSSL_EXPORT ASN1_OCTET_STRING *s2i_ASN1_OCTET_STRING(X509V3_EXT_METHOD *method, X509V3_CTX *ctx, char *str); + +DECLARE_ASN1_FUNCTIONS(EXTENDED_KEY_USAGE) +OPENSSL_EXPORT int i2a_ACCESS_DESCRIPTION(BIO *bp, ACCESS_DESCRIPTION* a); + +DECLARE_ASN1_FUNCTIONS(CERTIFICATEPOLICIES) +DECLARE_ASN1_FUNCTIONS(POLICYINFO) +DECLARE_ASN1_FUNCTIONS(POLICYQUALINFO) +DECLARE_ASN1_FUNCTIONS(USERNOTICE) +DECLARE_ASN1_FUNCTIONS(NOTICEREF) + +DECLARE_ASN1_FUNCTIONS(CRL_DIST_POINTS) +DECLARE_ASN1_FUNCTIONS(DIST_POINT) +DECLARE_ASN1_FUNCTIONS(DIST_POINT_NAME) +DECLARE_ASN1_FUNCTIONS(ISSUING_DIST_POINT) + +OPENSSL_EXPORT int DIST_POINT_set_dpname(DIST_POINT_NAME *dpn, X509_NAME *iname); + +OPENSSL_EXPORT int NAME_CONSTRAINTS_check(X509 *x, NAME_CONSTRAINTS *nc); + +DECLARE_ASN1_FUNCTIONS(ACCESS_DESCRIPTION) +DECLARE_ASN1_FUNCTIONS(AUTHORITY_INFO_ACCESS) + +DECLARE_ASN1_ITEM(POLICY_MAPPING) +DECLARE_ASN1_ALLOC_FUNCTIONS(POLICY_MAPPING) +DECLARE_ASN1_ITEM(POLICY_MAPPINGS) + +DECLARE_ASN1_ITEM(GENERAL_SUBTREE) +DECLARE_ASN1_ALLOC_FUNCTIONS(GENERAL_SUBTREE) + +DECLARE_ASN1_ITEM(NAME_CONSTRAINTS) +DECLARE_ASN1_ALLOC_FUNCTIONS(NAME_CONSTRAINTS) + +DECLARE_ASN1_ALLOC_FUNCTIONS(POLICY_CONSTRAINTS) +DECLARE_ASN1_ITEM(POLICY_CONSTRAINTS) + +OPENSSL_EXPORT GENERAL_NAME *a2i_GENERAL_NAME(GENERAL_NAME *out, + const X509V3_EXT_METHOD *method, X509V3_CTX *ctx, + int gen_type, char *value, int is_nc); + +OPENSSL_EXPORT GENERAL_NAME *v2i_GENERAL_NAME(const X509V3_EXT_METHOD *method, X509V3_CTX *ctx, + CONF_VALUE *cnf); +OPENSSL_EXPORT GENERAL_NAME *v2i_GENERAL_NAME_ex(GENERAL_NAME *out, + const X509V3_EXT_METHOD *method, + X509V3_CTX *ctx, CONF_VALUE *cnf, int is_nc); +OPENSSL_EXPORT void X509V3_conf_free(CONF_VALUE *val); + +OPENSSL_EXPORT X509_EXTENSION *X509V3_EXT_nconf_nid(CONF *conf, X509V3_CTX *ctx, int ext_nid, char *value); +OPENSSL_EXPORT X509_EXTENSION *X509V3_EXT_nconf(CONF *conf, X509V3_CTX *ctx, char *name, char *value); +OPENSSL_EXPORT int X509V3_EXT_add_nconf_sk(CONF *conf, X509V3_CTX *ctx, char *section, STACK_OF(X509_EXTENSION) **sk); +OPENSSL_EXPORT int X509V3_EXT_add_nconf(CONF *conf, X509V3_CTX *ctx, char *section, X509 *cert); +OPENSSL_EXPORT int X509V3_EXT_REQ_add_nconf(CONF *conf, X509V3_CTX *ctx, char *section, X509_REQ *req); +OPENSSL_EXPORT int X509V3_EXT_CRL_add_nconf(CONF *conf, X509V3_CTX *ctx, char *section, X509_CRL *crl); + +OPENSSL_EXPORT int X509V3_EXT_CRL_add_conf(LHASH_OF(CONF_VALUE) *conf, X509V3_CTX *ctx, + char *section, X509_CRL *crl); + +OPENSSL_EXPORT int X509V3_add_value_bool_nf(char *name, int asn1_bool, + STACK_OF(CONF_VALUE) **extlist); +OPENSSL_EXPORT int X509V3_get_value_bool(CONF_VALUE *value, int *asn1_bool); +OPENSSL_EXPORT int X509V3_get_value_int(CONF_VALUE *value, ASN1_INTEGER **aint); +OPENSSL_EXPORT void X509V3_set_nconf(X509V3_CTX *ctx, CONF *conf); + +OPENSSL_EXPORT char * X509V3_get_string(X509V3_CTX *ctx, char *name, char *section); +OPENSSL_EXPORT STACK_OF(CONF_VALUE) * X509V3_get_section(X509V3_CTX *ctx, char *section); +OPENSSL_EXPORT void X509V3_string_free(X509V3_CTX *ctx, char *str); +OPENSSL_EXPORT void X509V3_section_free( X509V3_CTX *ctx, STACK_OF(CONF_VALUE) *section); +OPENSSL_EXPORT void X509V3_set_ctx(X509V3_CTX *ctx, X509 *issuer, X509 *subject, + X509_REQ *req, X509_CRL *crl, int flags); + +OPENSSL_EXPORT int X509V3_add_value(const char *name, const char *value, + STACK_OF(CONF_VALUE) **extlist); +OPENSSL_EXPORT int X509V3_add_value_uchar(const char *name, const unsigned char *value, + STACK_OF(CONF_VALUE) **extlist); +OPENSSL_EXPORT int X509V3_add_value_bool(const char *name, int asn1_bool, + STACK_OF(CONF_VALUE) **extlist); +OPENSSL_EXPORT int X509V3_add_value_int(const char *name, ASN1_INTEGER *aint, + STACK_OF(CONF_VALUE) **extlist); +OPENSSL_EXPORT char * i2s_ASN1_INTEGER(X509V3_EXT_METHOD *meth, ASN1_INTEGER *aint); +OPENSSL_EXPORT ASN1_INTEGER * s2i_ASN1_INTEGER(X509V3_EXT_METHOD *meth, char *value); +OPENSSL_EXPORT char * i2s_ASN1_ENUMERATED(X509V3_EXT_METHOD *meth, ASN1_ENUMERATED *aint); +OPENSSL_EXPORT char * i2s_ASN1_ENUMERATED_TABLE(X509V3_EXT_METHOD *meth, ASN1_ENUMERATED *aint); +OPENSSL_EXPORT int X509V3_EXT_add(X509V3_EXT_METHOD *ext); +OPENSSL_EXPORT int X509V3_EXT_add_list(X509V3_EXT_METHOD *extlist); +OPENSSL_EXPORT int X509V3_EXT_add_alias(int nid_to, int nid_from); +OPENSSL_EXPORT void X509V3_EXT_cleanup(void); + +OPENSSL_EXPORT const X509V3_EXT_METHOD *X509V3_EXT_get(X509_EXTENSION *ext); +OPENSSL_EXPORT const X509V3_EXT_METHOD *X509V3_EXT_get_nid(int nid); +OPENSSL_EXPORT int X509V3_add_standard_extensions(void); +OPENSSL_EXPORT STACK_OF(CONF_VALUE) *X509V3_parse_list(const char *line); +OPENSSL_EXPORT void *X509V3_EXT_d2i(X509_EXTENSION *ext); +OPENSSL_EXPORT void *X509V3_get_d2i(STACK_OF(X509_EXTENSION) *x, int nid, int *crit, int *idx); + + +OPENSSL_EXPORT X509_EXTENSION *X509V3_EXT_i2d(int ext_nid, int crit, void *ext_struc); +OPENSSL_EXPORT int X509V3_add1_i2d(STACK_OF(X509_EXTENSION) **x, int nid, void *value, int crit, unsigned long flags); + +char *hex_to_string(const unsigned char *buffer, long len); +unsigned char *string_to_hex(const char *str, long *len); +int name_cmp(const char *name, const char *cmp); + +OPENSSL_EXPORT void X509V3_EXT_val_prn(BIO *out, STACK_OF(CONF_VALUE) *val, int indent, + int ml); +OPENSSL_EXPORT int X509V3_EXT_print(BIO *out, X509_EXTENSION *ext, unsigned long flag, int indent); +OPENSSL_EXPORT int X509V3_EXT_print_fp(FILE *out, X509_EXTENSION *ext, int flag, int indent); + +OPENSSL_EXPORT int X509V3_extensions_print(BIO *out, const char *title, STACK_OF(X509_EXTENSION) *exts, unsigned long flag, int indent); + +OPENSSL_EXPORT int X509_check_ca(X509 *x); +OPENSSL_EXPORT int X509_check_purpose(X509 *x, int id, int ca); +OPENSSL_EXPORT int X509_supported_extension(X509_EXTENSION *ex); +OPENSSL_EXPORT int X509_PURPOSE_set(int *p, int purpose); +OPENSSL_EXPORT int X509_check_issued(X509 *issuer, X509 *subject); +OPENSSL_EXPORT int X509_check_akid(X509 *issuer, AUTHORITY_KEYID *akid); +OPENSSL_EXPORT int X509_PURPOSE_get_count(void); +OPENSSL_EXPORT X509_PURPOSE * X509_PURPOSE_get0(int idx); +OPENSSL_EXPORT int X509_PURPOSE_get_by_sname(char *sname); +OPENSSL_EXPORT int X509_PURPOSE_get_by_id(int id); +OPENSSL_EXPORT int X509_PURPOSE_add(int id, int trust, int flags, + int (*ck)(const X509_PURPOSE *, const X509 *, int), + char *name, char *sname, void *arg); +OPENSSL_EXPORT char *X509_PURPOSE_get0_name(X509_PURPOSE *xp); +OPENSSL_EXPORT char *X509_PURPOSE_get0_sname(X509_PURPOSE *xp); +OPENSSL_EXPORT int X509_PURPOSE_get_trust(X509_PURPOSE *xp); +OPENSSL_EXPORT void X509_PURPOSE_cleanup(void); +OPENSSL_EXPORT int X509_PURPOSE_get_id(X509_PURPOSE *); + +OPENSSL_EXPORT STACK_OF(OPENSSL_STRING) *X509_get1_email(X509 *x); +OPENSSL_EXPORT STACK_OF(OPENSSL_STRING) *X509_REQ_get1_email(X509_REQ *x); +OPENSSL_EXPORT void X509_email_free(STACK_OF(OPENSSL_STRING) *sk); +OPENSSL_EXPORT STACK_OF(OPENSSL_STRING) *X509_get1_ocsp(X509 *x); +/* Flags for X509_check_* functions */ + +/* Always check subject name for host match even if subject alt names present */ +#define X509_CHECK_FLAG_ALWAYS_CHECK_SUBJECT 0x1 +/* Disable wildcard matching for dnsName fields and common name. */ +#define X509_CHECK_FLAG_NO_WILDCARDS 0x2 +/* Wildcards must not match a partial label. */ +#define X509_CHECK_FLAG_NO_PARTIAL_WILDCARDS 0x4 +/* Allow (non-partial) wildcards to match multiple labels. */ +#define X509_CHECK_FLAG_MULTI_LABEL_WILDCARDS 0x8 +/* Constraint verifier subdomain patterns to match a single labels. */ +#define X509_CHECK_FLAG_SINGLE_LABEL_SUBDOMAINS 0x10 +/* + * Match reference identifiers starting with "." to any sub-domain. + * This is a non-public flag, turned on implicitly when the subject + * reference identity is a DNS name. + */ +#define _X509_CHECK_FLAG_DOT_SUBDOMAINS 0x8000 + +OPENSSL_EXPORT int X509_check_host(X509 *x, const char *chk, size_t chklen, + unsigned int flags, char **peername); +OPENSSL_EXPORT int X509_check_email(X509 *x, const char *chk, size_t chklen, + unsigned int flags); +OPENSSL_EXPORT int X509_check_ip(X509 *x, const unsigned char *chk, size_t chklen, + unsigned int flags); +OPENSSL_EXPORT int X509_check_ip_asc(X509 *x, const char *ipasc, unsigned int flags); + +OPENSSL_EXPORT ASN1_OCTET_STRING *a2i_IPADDRESS(const char *ipasc); +OPENSSL_EXPORT ASN1_OCTET_STRING *a2i_IPADDRESS_NC(const char *ipasc); +OPENSSL_EXPORT int a2i_ipadd(unsigned char *ipout, const char *ipasc); +OPENSSL_EXPORT int X509V3_NAME_from_section(X509_NAME *nm, STACK_OF(CONF_VALUE)*dn_sk, + unsigned long chtype); + +OPENSSL_EXPORT void X509_POLICY_NODE_print(BIO *out, X509_POLICY_NODE *node, int indent); +DECLARE_STACK_OF(X509_POLICY_NODE) + +/* BEGIN ERROR CODES */ +/* The following lines are auto generated by the script mkerr.pl. Any changes + * made after this point may be overwritten when the script is next run. + */ +void ERR_load_X509V3_strings(void); + + +#ifdef __cplusplus +} +#endif +#define X509V3_F_SXNET_add_id_INTEGER 100 +#define X509V3_F_SXNET_add_id_asc 101 +#define X509V3_F_SXNET_add_id_ulong 102 +#define X509V3_F_SXNET_get_id_asc 103 +#define X509V3_F_SXNET_get_id_ulong 104 +#define X509V3_F_X509V3_EXT_add 105 +#define X509V3_F_X509V3_EXT_add_alias 106 +#define X509V3_F_X509V3_EXT_free 107 +#define X509V3_F_X509V3_EXT_i2d 108 +#define X509V3_F_X509V3_EXT_nconf 109 +#define X509V3_F_X509V3_add1_i2d 110 +#define X509V3_F_X509V3_add_value 111 +#define X509V3_F_X509V3_get_section 112 +#define X509V3_F_X509V3_get_string 113 +#define X509V3_F_X509V3_get_value_bool 114 +#define X509V3_F_X509V3_parse_list 115 +#define X509V3_F_X509_PURPOSE_add 116 +#define X509V3_F_X509_PURPOSE_set 117 +#define X509V3_F_a2i_GENERAL_NAME 118 +#define X509V3_F_copy_email 119 +#define X509V3_F_copy_issuer 120 +#define X509V3_F_do_dirname 121 +#define X509V3_F_do_ext_i2d 122 +#define X509V3_F_do_ext_nconf 123 +#define X509V3_F_gnames_from_sectname 124 +#define X509V3_F_hex_to_string 125 +#define X509V3_F_i2s_ASN1_ENUMERATED 126 +#define X509V3_F_i2s_ASN1_IA5STRING 127 +#define X509V3_F_i2s_ASN1_INTEGER 128 +#define X509V3_F_i2v_AUTHORITY_INFO_ACCESS 129 +#define X509V3_F_notice_section 130 +#define X509V3_F_nref_nos 131 +#define X509V3_F_policy_section 132 +#define X509V3_F_process_pci_value 133 +#define X509V3_F_r2i_certpol 134 +#define X509V3_F_r2i_pci 135 +#define X509V3_F_s2i_ASN1_IA5STRING 136 +#define X509V3_F_s2i_ASN1_INTEGER 137 +#define X509V3_F_s2i_ASN1_OCTET_STRING 138 +#define X509V3_F_s2i_skey_id 139 +#define X509V3_F_set_dist_point_name 140 +#define X509V3_F_string_to_hex 141 +#define X509V3_F_v2i_ASN1_BIT_STRING 142 +#define X509V3_F_v2i_AUTHORITY_INFO_ACCESS 143 +#define X509V3_F_v2i_AUTHORITY_KEYID 144 +#define X509V3_F_v2i_BASIC_CONSTRAINTS 145 +#define X509V3_F_v2i_EXTENDED_KEY_USAGE 146 +#define X509V3_F_v2i_GENERAL_NAMES 147 +#define X509V3_F_v2i_GENERAL_NAME_ex 148 +#define X509V3_F_v2i_NAME_CONSTRAINTS 149 +#define X509V3_F_v2i_POLICY_CONSTRAINTS 150 +#define X509V3_F_v2i_POLICY_MAPPINGS 151 +#define X509V3_F_v2i_crld 152 +#define X509V3_F_v2i_idp 153 +#define X509V3_F_v2i_issuer_alt 154 +#define X509V3_F_v2i_subject_alt 155 +#define X509V3_F_v3_generic_extension 156 +#define X509V3_R_BAD_IP_ADDRESS 100 +#define X509V3_R_BAD_OBJECT 101 +#define X509V3_R_BN_DEC2BN_ERROR 102 +#define X509V3_R_BN_TO_ASN1_INTEGER_ERROR 103 +#define X509V3_R_CANNOT_FIND_FREE_FUNCTION 104 +#define X509V3_R_DIRNAME_ERROR 105 +#define X509V3_R_DISTPOINT_ALREADY_SET 106 +#define X509V3_R_DUPLICATE_ZONE_ID 107 +#define X509V3_R_ERROR_CONVERTING_ZONE 108 +#define X509V3_R_ERROR_CREATING_EXTENSION 109 +#define X509V3_R_ERROR_IN_EXTENSION 110 +#define X509V3_R_EXPECTED_A_SECTION_NAME 111 +#define X509V3_R_EXTENSION_EXISTS 112 +#define X509V3_R_EXTENSION_NAME_ERROR 113 +#define X509V3_R_EXTENSION_NOT_FOUND 114 +#define X509V3_R_EXTENSION_SETTING_NOT_SUPPORTED 115 +#define X509V3_R_EXTENSION_VALUE_ERROR 116 +#define X509V3_R_ILLEGAL_EMPTY_EXTENSION 117 +#define X509V3_R_ILLEGAL_HEX_DIGIT 118 +#define X509V3_R_INCORRECT_POLICY_SYNTAX_TAG 119 +#define X509V3_R_INVALID_BOOLEAN_STRING 120 +#define X509V3_R_INVALID_EXTENSION_STRING 121 +#define X509V3_R_INVALID_MULTIPLE_RDNS 122 +#define X509V3_R_INVALID_NAME 123 +#define X509V3_R_INVALID_NULL_ARGUMENT 124 +#define X509V3_R_INVALID_NULL_NAME 125 +#define X509V3_R_INVALID_NULL_VALUE 126 +#define X509V3_R_INVALID_NUMBER 127 +#define X509V3_R_INVALID_NUMBERS 128 +#define X509V3_R_INVALID_OBJECT_IDENTIFIER 129 +#define X509V3_R_INVALID_OPTION 130 +#define X509V3_R_INVALID_POLICY_IDENTIFIER 131 +#define X509V3_R_INVALID_PROXY_POLICY_SETTING 132 +#define X509V3_R_INVALID_PURPOSE 133 +#define X509V3_R_INVALID_SECTION 134 +#define X509V3_R_INVALID_SYNTAX 135 +#define X509V3_R_ISSUER_DECODE_ERROR 136 +#define X509V3_R_MISSING_VALUE 137 +#define X509V3_R_NEED_ORGANIZATION_AND_NUMBERS 138 +#define X509V3_R_NO_CONFIG_DATABASE 139 +#define X509V3_R_NO_ISSUER_CERTIFICATE 140 +#define X509V3_R_NO_ISSUER_DETAILS 141 +#define X509V3_R_NO_POLICY_IDENTIFIER 142 +#define X509V3_R_NO_PROXY_CERT_POLICY_LANGUAGE_DEFINED 143 +#define X509V3_R_NO_PUBLIC_KEY 144 +#define X509V3_R_NO_SUBJECT_DETAILS 145 +#define X509V3_R_ODD_NUMBER_OF_DIGITS 146 +#define X509V3_R_OPERATION_NOT_DEFINED 147 +#define X509V3_R_OTHERNAME_ERROR 148 +#define X509V3_R_POLICY_LANGUAGE_ALREADY_DEFINED 149 +#define X509V3_R_POLICY_PATH_LENGTH 150 +#define X509V3_R_POLICY_PATH_LENGTH_ALREADY_DEFINED 151 +#define X509V3_R_POLICY_WHEN_PROXY_LANGUAGE_REQUIRES_NO_POLICY 152 +#define X509V3_R_SECTION_NOT_FOUND 153 +#define X509V3_R_UNABLE_TO_GET_ISSUER_DETAILS 154 +#define X509V3_R_UNABLE_TO_GET_ISSUER_KEYID 155 +#define X509V3_R_UNKNOWN_BIT_STRING_ARGUMENT 156 +#define X509V3_R_UNKNOWN_EXTENSION 157 +#define X509V3_R_UNKNOWN_EXTENSION_NAME 158 +#define X509V3_R_UNKNOWN_OPTION 159 +#define X509V3_R_UNSUPPORTED_OPTION 160 +#define X509V3_R_UNSUPPORTED_TYPE 161 +#define X509V3_R_USER_TOO_LONG 162 + +#endif diff --git a/phonelibs/boringssl/lib/libcrypto_static.a b/phonelibs/boringssl/lib/libcrypto_static.a new file mode 100644 index 00000000000000..f683cb11d42ead Binary files /dev/null and b/phonelibs/boringssl/lib/libcrypto_static.a differ diff --git a/phonelibs/boringssl/lib/libssl_static.a b/phonelibs/boringssl/lib/libssl_static.a new file mode 100644 index 00000000000000..b6c52d03a04e8c Binary files /dev/null and b/phonelibs/boringssl/lib/libssl_static.a differ diff --git a/phonelibs/capnp-c/include/capnp_c.h b/phonelibs/capnp-c/include/capnp_c.h new file mode 100644 index 00000000000000..9fa2718f7f0cf1 --- /dev/null +++ b/phonelibs/capnp-c/include/capnp_c.h @@ -0,0 +1,426 @@ +/* vim: set sw=8 ts=8 sts=8 noet: */ +/* capnp_c.h + * + * Copyright (C) 2013 James McKaskill + * Copyright (C) 2014 Steve Dee + * + * This software may be modified and distributed under the terms + * of the MIT license. See the LICENSE file for details. + */ + +#ifndef CAPNP_C_H +#define CAPNP_C_H + +#include +#include +#if defined(unix) && !defined(__APPLE__) +#include +#endif + +// ssize_t is not defined in stdint.h in MSVC. +#ifdef _MSC_VER +typedef intmax_t ssize_t; +#endif + +#ifdef __cplusplus +extern "C" { +#endif + +#if defined(__cplusplus) || (defined(__STDC_VERSION__) && __STDC_VERSION__ >= 199901L) +#define CAPN_INLINE static inline +#else +#define CAPN_INLINE static +#endif + +#define CAPN_VERSION 1 + +/* struct capn is a common structure shared between segments in the same + * session/context so that far pointers between segments will be created. + * + * lookup is used to lookup segments by id when derefencing a far pointer + * + * create is used to create or lookup an alternate segment that has at least + * sz available (ie returned seg->len + sz <= seg->cap) + * + * create_local is used to create a segment for the copy tree and should be + * allocated in the local memory space. + * + * Allocated segments must be zero initialized. + * + * create and lookup can be NULL if you don't need multiple segments and don't + * want to support copying + * + * seglist and copylist are linked lists which can be used to free up segments + * on cleanup, but should not be modified by the user. + * + * lookup, create, create_local, and user can be set by the user. Other values + * should be zero initialized. + */ +struct capn { + /* user settable */ + struct capn_segment *(*lookup)(void* /*user*/, uint32_t /*id */); + struct capn_segment *(*create)(void* /*user*/, uint32_t /*id */, int /*sz*/); + struct capn_segment *(*create_local)(void* /*user*/, int /*sz*/); + void *user; + /* zero initialized, user should not modify */ + uint32_t segnum; + struct capn_tree *copy; + struct capn_tree *segtree; + struct capn_segment *seglist, *lastseg; + struct capn_segment *copylist; +}; + +/* struct capn_tree is a rb tree header used internally for the segment id + * lookup and copy tree */ +struct capn_tree { + struct capn_tree *parent, *link[2]; + unsigned int red : 1; +}; + +struct capn_tree *capn_tree_insert(struct capn_tree *root, struct capn_tree *n); + +/* struct capn_segment contains the information about a single segment. + * + * capn points to a struct capn that is shared between segments in the + * same session + * + * id specifies the segment id, used for far pointers + * + * data specifies the segment data. This should not move after creation. + * + * len specifies the current segment length. This is 0 for a blank + * segment. + * + * cap specifies the segment capacity. + * + * When creating new structures len will be incremented until it reaces cap, + * at which point a new segment will be requested via capn->create. The + * create callback can either create a new segment or expand an existing + * one by incrementing cap and returning the expanded segment. + * + * data, len, and cap must all by 8 byte aligned + * + * data, len, cap, and user should all set by the user. Other values + * should be zero initialized. + */ +#ifdef _MSC_VER +__declspec(align(64)) +#endif +struct capn_segment { + struct capn_tree hdr; + struct capn_segment *next; + struct capn *capn; + uint32_t id; + /* user settable */ + char *data; + size_t len, cap; + void *user; +}; + +enum CAPN_TYPE { + CAPN_NULL = 0, + CAPN_STRUCT = 1, + CAPN_LIST = 2, + CAPN_PTR_LIST = 3, + CAPN_BIT_LIST = 4, + CAPN_FAR_POINTER = 5, +}; + +struct capn_ptr { + unsigned int type : 4; + unsigned int has_ptr_tag : 1; + unsigned int is_list_member : 1; + unsigned int is_composite_list : 1; + unsigned int datasz : 19; + unsigned int ptrs : 16; + int len; + char *data; + struct capn_segment *seg; +}; + +struct capn_text { + int len; + const char *str; + struct capn_segment *seg; +}; + +typedef struct capn_ptr capn_ptr; +typedef struct capn_text capn_text; +typedef struct {capn_ptr p;} capn_data; +typedef struct {capn_ptr p;} capn_list1; +typedef struct {capn_ptr p;} capn_list8; +typedef struct {capn_ptr p;} capn_list16; +typedef struct {capn_ptr p;} capn_list32; +typedef struct {capn_ptr p;} capn_list64; + +struct capn_msg { + struct capn_segment *seg; + uint64_t iface; + uint16_t method; + capn_ptr args; +}; + +/* capn_append_segment appends a segment to a session */ +void capn_append_segment(struct capn*, struct capn_segment*); + +capn_ptr capn_root(struct capn *c); +void capn_resolve(capn_ptr *p); + +#define capn_len(list) ((list).p.type == CAPN_FAR_POINTER ? (capn_resolve(&(list).p), (list).p.len) : (list).p.len) + +/* capn_getp|setp functions get/set ptrs in list/structs + * off is the list index or pointer index in a struct + * capn_setp will copy the data, create far pointers, etc if the target + * is in a different segment/context. + * Both of these will use/return inner pointers for composite lists. + */ +capn_ptr capn_getp(capn_ptr p, int off, int resolve); +int capn_setp(capn_ptr p, int off, capn_ptr tgt); + +capn_text capn_get_text(capn_ptr p, int off, capn_text def); +capn_data capn_get_data(capn_ptr p, int off); +int capn_set_text(capn_ptr p, int off, capn_text tgt); + +/* capn_get* functions get data from a list + * The length of the list is given by p->size + * off specifies how far into the list to start + * sz indicates the number of elements to get + * The function returns the number of elements read or -1 on an error. + * off must be byte aligned for capn_getv1 + */ +int capn_get1(capn_list1 p, int off); +uint8_t capn_get8(capn_list8 p, int off); +uint16_t capn_get16(capn_list16 p, int off); +uint32_t capn_get32(capn_list32 p, int off); +uint64_t capn_get64(capn_list64 p, int off); +int capn_getv1(capn_list1 p, int off, uint8_t *data, int sz); +int capn_getv8(capn_list8 p, int off, uint8_t *data, int sz); +int capn_getv16(capn_list16 p, int off, uint16_t *data, int sz); +int capn_getv32(capn_list32 p, int off, uint32_t *data, int sz); +int capn_getv64(capn_list64 p, int off, uint64_t *data, int sz); + +/* capn_set* functions set data in a list + * off specifies how far into the list to start + * sz indicates the number of elements to write + * The function returns the number of elemnts written or -1 on an error. + * off must be byte aligned for capn_setv1 + */ +int capn_set1(capn_list1 p, int off, int v); +int capn_set8(capn_list8 p, int off, uint8_t v); +int capn_set16(capn_list16 p, int off, uint16_t v); +int capn_set32(capn_list32 p, int off, uint32_t v); +int capn_set64(capn_list64 p, int off, uint64_t v); +int capn_setv1(capn_list1 p, int off, const uint8_t *data, int sz); +int capn_setv8(capn_list8 p, int off, const uint8_t *data, int sz); +int capn_setv16(capn_list16 p, int off, const uint16_t *data, int sz); +int capn_setv32(capn_list32 p, int off, const uint32_t *data, int sz); +int capn_setv64(capn_list64 p, int off, const uint64_t *data, int sz); + +/* capn_new_* functions create a new object + * datasz is in bytes, ptrs is # of pointers, sz is # of elements in the list + * On an error a CAPN_NULL pointer is returned + */ +capn_ptr capn_new_string(struct capn_segment *seg, const char *str, ssize_t sz); +capn_ptr capn_new_struct(struct capn_segment *seg, int datasz, int ptrs); +capn_ptr capn_new_interface(struct capn_segment *seg, int datasz, int ptrs); +capn_ptr capn_new_ptr_list(struct capn_segment *seg, int sz); +capn_ptr capn_new_list(struct capn_segment *seg, int sz, int datasz, int ptrs); +capn_list1 capn_new_list1(struct capn_segment *seg, int sz); +capn_list8 capn_new_list8(struct capn_segment *seg, int sz); +capn_list16 capn_new_list16(struct capn_segment *seg, int sz); +capn_list32 capn_new_list32(struct capn_segment *seg, int sz); +capn_list64 capn_new_list64(struct capn_segment *seg, int sz); + +/* capn_read|write* functions read/write struct values + * off is the offset into the structure in bytes + * Rarely should these be called directly, instead use the generated code. + * Data must be xored with the default value + * These are inlined + */ +CAPN_INLINE uint8_t capn_read8(capn_ptr p, int off); +CAPN_INLINE uint16_t capn_read16(capn_ptr p, int off); +CAPN_INLINE uint32_t capn_read32(capn_ptr p, int off); +CAPN_INLINE uint64_t capn_read64(capn_ptr p, int off); +CAPN_INLINE int capn_write1(capn_ptr p, int off, int val); +CAPN_INLINE int capn_write8(capn_ptr p, int off, uint8_t val); +CAPN_INLINE int capn_write16(capn_ptr p, int off, uint16_t val); +CAPN_INLINE int capn_write32(capn_ptr p, int off, uint32_t val); +CAPN_INLINE int capn_write64(capn_ptr p, int off, uint64_t val); + +/* capn_init_malloc inits the capn struct with a create function which + * allocates segments on the heap using malloc + * + * capn_init_(fp|mem) inits by reading segments in from the file/memory buffer + * in serialized form (optionally packed). It will then setup the create + * function ala capn_init_malloc so that further segments can be created. + * + * capn_free frees all the segment headers and data created by the create + * function setup by capn_init_* + */ +void capn_init_malloc(struct capn *c); +int capn_init_fp(struct capn *c, FILE *f, int packed); +int capn_init_mem(struct capn *c, const uint8_t *p, size_t sz, int packed); + +/* capn_write_(fp|mem) writes segments to the file/memory buffer in + * serialized form and returns the number of bytes written. + */ +/* TODO */ +/*int capn_write_fp(struct capn *c, FILE *f, int packed);*/ +int capn_write_fd(struct capn *c, ssize_t (*write_fd)(int fd, void *p, size_t count), int fd, int packed); +int capn_write_mem(struct capn *c, uint8_t *p, size_t sz, int packed); + +void capn_free(struct capn *c); +void capn_reset_copy(struct capn *c); + +/* Inline functions */ + + +CAPN_INLINE uint8_t capn_flip8(uint8_t v) { + return v; +} +CAPN_INLINE uint16_t capn_flip16(uint16_t v) { +#if defined(__BYTE_ORDER) && (__BYTE_ORDER == __LITTLE_ENDIAN) + return v; +#elif defined(__BYTE_ORDER) && (__BYTE_ORDER == __BIG_ENDIAN) && \ + defined(__GNUC__) && __GNUC__ >= 4 && __GNUC_MINOR__ >= 8 + return __builtin_bswap16(v); +#else + union { uint16_t u; uint8_t v[2]; } s; + s.v[0] = (uint8_t)v; + s.v[1] = (uint8_t)(v>>8); + return s.u; +#endif +} +CAPN_INLINE uint32_t capn_flip32(uint32_t v) { +#if defined(__BYTE_ORDER) && (__BYTE_ORDER == __LITTLE_ENDIAN) + return v; +#elif defined(__BYTE_ORDER) && (__BYTE_ORDER == __BIG_ENDIAN) && \ + defined(__GNUC__) && __GNUC__ >= 4 && __GNUC_MINOR__ >= 8 + return __builtin_bswap32(v); +#else + union { uint32_t u; uint8_t v[4]; } s; + s.v[0] = (uint8_t)v; + s.v[1] = (uint8_t)(v>>8); + s.v[2] = (uint8_t)(v>>16); + s.v[3] = (uint8_t)(v>>24); + return s.u; +#endif +} +CAPN_INLINE uint64_t capn_flip64(uint64_t v) { +#if defined(__BYTE_ORDER) && (__BYTE_ORDER == __LITTLE_ENDIAN) + return v; +#elif defined(__BYTE_ORDER) && (__BYTE_ORDER == __BIG_ENDIAN) && \ + defined(__GNUC__) && __GNUC__ >= 4 && __GNUC_MINOR__ >= 8 + return __builtin_bswap64(v); +#else + union { uint64_t u; uint8_t v[8]; } s; + s.v[0] = (uint8_t)v; + s.v[1] = (uint8_t)(v>>8); + s.v[2] = (uint8_t)(v>>16); + s.v[3] = (uint8_t)(v>>24); + s.v[4] = (uint8_t)(v>>32); + s.v[5] = (uint8_t)(v>>40); + s.v[6] = (uint8_t)(v>>48); + s.v[7] = (uint8_t)(v>>56); + return s.u; +#endif +} + +CAPN_INLINE int capn_write1(capn_ptr p, int off, int val) { + if (off >= p.datasz*8) { + return -1; + } else if (val) { + uint8_t tmp = (uint8_t)(1 << (off & 7)); + ((uint8_t*) p.data)[off >> 3] |= tmp; + return 0; + } else { + uint8_t tmp = (uint8_t)(~(1 << (off & 7))); + ((uint8_t*) p.data)[off >> 3] &= tmp; + return 0; + } +} + +CAPN_INLINE uint8_t capn_read8(capn_ptr p, int off) { + return off+1 <= p.datasz ? capn_flip8(*(uint8_t*) (p.data+off)) : 0; +} +CAPN_INLINE int capn_write8(capn_ptr p, int off, uint8_t val) { + if (off+1 <= p.datasz) { + *(uint8_t*) (p.data+off) = capn_flip8(val); + return 0; + } else { + return -1; + } +} + +CAPN_INLINE uint16_t capn_read16(capn_ptr p, int off) { + return off+2 <= p.datasz ? capn_flip16(*(uint16_t*) (p.data+off)) : 0; +} +CAPN_INLINE int capn_write16(capn_ptr p, int off, uint16_t val) { + if (off+2 <= p.datasz) { + *(uint16_t*) (p.data+off) = capn_flip16(val); + return 0; + } else { + return -1; + } +} + +CAPN_INLINE uint32_t capn_read32(capn_ptr p, int off) { + return off+4 <= p.datasz ? capn_flip32(*(uint32_t*) (p.data+off)) : 0; +} +CAPN_INLINE int capn_write32(capn_ptr p, int off, uint32_t val) { + if (off+4 <= p.datasz) { + *(uint32_t*) (p.data+off) = capn_flip32(val); + return 0; + } else { + return -1; + } +} + +CAPN_INLINE uint64_t capn_read64(capn_ptr p, int off) { + return off+8 <= p.datasz ? capn_flip64(*(uint64_t*) (p.data+off)) : 0; +} +CAPN_INLINE int capn_write64(capn_ptr p, int off, uint64_t val) { + if (off+8 <= p.datasz) { + *(uint64_t*) (p.data+off) = capn_flip64(val); + return 0; + } else { + return -1; + } +} + +union capn_conv_f32 { + uint32_t u; + float f; +}; + +union capn_conv_f64 { + uint64_t u; + double f; +}; + +CAPN_INLINE float capn_to_f32(uint32_t v) { + union capn_conv_f32 u; + u.u = v; + return u.f; +} +CAPN_INLINE double capn_to_f64(uint64_t v) { + union capn_conv_f64 u; + u.u = v; + return u.f; +} +CAPN_INLINE uint32_t capn_from_f32(float v) { + union capn_conv_f32 u; + u.f = v; + return u.u; +} +CAPN_INLINE uint64_t capn_from_f64(double v) { + union capn_conv_f64 u; + u.f = v; + return u.u; +} + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/capnp-cpp/aarch64/bin/capnp b/phonelibs/capnp-cpp/aarch64/bin/capnp new file mode 100755 index 00000000000000..e60fe7fe3c1ba0 Binary files /dev/null and b/phonelibs/capnp-cpp/aarch64/bin/capnp differ diff --git a/phonelibs/capnp-cpp/aarch64/bin/capnpc b/phonelibs/capnp-cpp/aarch64/bin/capnpc new file mode 120000 index 00000000000000..5668473f09dafe --- /dev/null +++ b/phonelibs/capnp-cpp/aarch64/bin/capnpc @@ -0,0 +1 @@ +capnp \ No newline at end of file diff --git a/phonelibs/capnp-cpp/aarch64/bin/capnpc-c++ b/phonelibs/capnp-cpp/aarch64/bin/capnpc-c++ new file mode 100755 index 00000000000000..d3090911446257 Binary files /dev/null and b/phonelibs/capnp-cpp/aarch64/bin/capnpc-c++ differ diff --git a/phonelibs/capnp-cpp/aarch64/bin/capnpc-capnp b/phonelibs/capnp-cpp/aarch64/bin/capnpc-capnp new file mode 100755 index 00000000000000..b1c7a9a9b818b6 Binary files /dev/null and b/phonelibs/capnp-cpp/aarch64/bin/capnpc-capnp differ diff --git a/phonelibs/capnp-cpp/aarch64/lib/libcapnp.a b/phonelibs/capnp-cpp/aarch64/lib/libcapnp.a new file mode 100644 index 00000000000000..a997023caa4e1b Binary files /dev/null and b/phonelibs/capnp-cpp/aarch64/lib/libcapnp.a differ diff --git a/phonelibs/capnp-cpp/aarch64/lib/libcapnpc.a b/phonelibs/capnp-cpp/aarch64/lib/libcapnpc.a new file mode 100644 index 00000000000000..2ede39fb910a33 Binary files /dev/null and b/phonelibs/capnp-cpp/aarch64/lib/libcapnpc.a differ diff --git a/phonelibs/capnp-cpp/aarch64/lib/libkj.a b/phonelibs/capnp-cpp/aarch64/lib/libkj.a new file mode 100644 index 00000000000000..58cf096637f027 Binary files /dev/null and b/phonelibs/capnp-cpp/aarch64/lib/libkj.a differ diff --git a/phonelibs/capnp-cpp/include/capnp/any.h b/phonelibs/capnp-cpp/include/capnp/any.h new file mode 100644 index 00000000000000..6df9dc8dc2dcea --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/any.h @@ -0,0 +1,1073 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef CAPNP_ANY_H_ +#define CAPNP_ANY_H_ + +#if defined(__GNUC__) && !defined(CAPNP_HEADER_WARNINGS) +#pragma GCC system_header +#endif + +#include "layout.h" +#include "pointer-helpers.h" +#include "orphan.h" +#include "list.h" + +namespace capnp { + +class StructSchema; +class ListSchema; +class InterfaceSchema; +class Orphanage; +class ClientHook; +class PipelineHook; +struct PipelineOp; +struct AnyPointer; + +struct AnyList { + AnyList() = delete; + + class Reader; + class Builder; +}; + +struct AnyStruct { + AnyStruct() = delete; + + class Reader; + class Builder; + class Pipeline; +}; + +template<> +struct List { + List() = delete; + + class Reader; + class Builder; +}; + +namespace _ { // private +template <> struct Kind_ { static constexpr Kind kind = Kind::OTHER; }; +template <> struct Kind_ { static constexpr Kind kind = Kind::OTHER; }; +template <> struct Kind_ { static constexpr Kind kind = Kind::OTHER; }; +} // namespace _ (private) + +// ======================================================================================= +// AnyPointer! + +enum class Equality { + NOT_EQUAL, + EQUAL, + UNKNOWN_CONTAINS_CAPS +}; + +kj::StringPtr KJ_STRINGIFY(Equality res); + +struct AnyPointer { + // Reader/Builder for the `AnyPointer` field type, i.e. a pointer that can point to an arbitrary + // object. + + AnyPointer() = delete; + + class Reader { + public: + typedef AnyPointer Reads; + + Reader() = default; + inline Reader(_::PointerReader reader): reader(reader) {} + + inline MessageSize targetSize() const; + // Get the total size of the target object and all its children. + + inline PointerType getPointerType() const; + + inline bool isNull() const { return getPointerType() == PointerType::NULL_; } + inline bool isStruct() const { return getPointerType() == PointerType::STRUCT; } + inline bool isList() const { return getPointerType() == PointerType::LIST; } + inline bool isCapability() const { return getPointerType() == PointerType::CAPABILITY; } + + Equality equals(AnyPointer::Reader right); + bool operator==(AnyPointer::Reader right); + inline bool operator!=(AnyPointer::Reader right) { + return !(*this == right); + } + + template + inline ReaderFor getAs() const; + // Valid for T = any generated struct type, interface type, List, Text, or Data. + + template + inline ReaderFor getAs(StructSchema schema) const; + // Only valid for T = DynamicStruct. Requires `#include `. + + template + inline ReaderFor getAs(ListSchema schema) const; + // Only valid for T = DynamicList. Requires `#include `. + + template + inline ReaderFor getAs(InterfaceSchema schema) const; + // Only valid for T = DynamicCapability. Requires `#include `. + +#if !CAPNP_LITE + kj::Own getPipelinedCap(kj::ArrayPtr ops) const; + // Used by RPC system to implement pipelining. Applications generally shouldn't use this + // directly. +#endif // !CAPNP_LITE + + private: + _::PointerReader reader; + friend struct AnyPointer; + friend class Orphanage; + friend class CapReaderContext; + friend struct _::PointerHelpers; + }; + + class Builder { + public: + typedef AnyPointer Builds; + + Builder() = delete; + inline Builder(decltype(nullptr)) {} + inline Builder(_::PointerBuilder builder): builder(builder) {} + + inline MessageSize targetSize() const; + // Get the total size of the target object and all its children. + + inline PointerType getPointerType(); + + inline bool isNull() { return getPointerType() == PointerType::NULL_; } + inline bool isStruct() { return getPointerType() == PointerType::STRUCT; } + inline bool isList() { return getPointerType() == PointerType::LIST; } + inline bool isCapability() { return getPointerType() == PointerType::CAPABILITY; } + + inline Equality equals(AnyPointer::Reader right) { + return asReader().equals(right); + } + inline bool operator==(AnyPointer::Reader right) { + return asReader() == right; + } + inline bool operator!=(AnyPointer::Reader right) { + return !(*this == right); + } + + inline void clear(); + // Set to null. + + template + inline BuilderFor getAs(); + // Valid for T = any generated struct type, List, Text, or Data. + + template + inline BuilderFor getAs(StructSchema schema); + // Only valid for T = DynamicStruct. Requires `#include `. + + template + inline BuilderFor getAs(ListSchema schema); + // Only valid for T = DynamicList. Requires `#include `. + + template + inline BuilderFor getAs(InterfaceSchema schema); + // Only valid for T = DynamicCapability. Requires `#include `. + + template + inline BuilderFor initAs(); + // Valid for T = any generated struct type. + + template + inline BuilderFor initAs(uint elementCount); + // Valid for T = List, Text, or Data. + + template + inline BuilderFor initAs(StructSchema schema); + // Only valid for T = DynamicStruct. Requires `#include `. + + template + inline BuilderFor initAs(ListSchema schema, uint elementCount); + // Only valid for T = DynamicList. Requires `#include `. + + inline AnyList::Builder initAsAnyList(ElementSize elementSize, uint elementCount); + // Note: Does not accept INLINE_COMPOSITE for elementSize. + + inline List::Builder initAsListOfAnyStruct( + uint16_t dataWordCount, uint16_t pointerCount, uint elementCount); + + inline AnyStruct::Builder initAsAnyStruct(uint16_t dataWordCount, uint16_t pointerCount); + + template + inline void setAs(ReaderFor value); + // Valid for ReaderType = T::Reader for T = any generated struct type, List, Text, Data, + // DynamicStruct, or DynamicList (the dynamic types require `#include `). + + template + inline void setAs(std::initializer_list>> list); + // Valid for T = List. + + template + inline void setCanonicalAs(ReaderFor value); + + inline void set(Reader value) { builder.copyFrom(value.reader); } + // Set to a copy of another AnyPointer. + + inline void setCanonical(Reader value) { builder.copyFrom(value.reader, true); } + + template + inline void adopt(Orphan&& orphan); + // Valid for T = any generated struct type, List, Text, Data, DynamicList, DynamicStruct, + // or DynamicValue (the dynamic types require `#include `). + + template + inline Orphan disownAs(); + // Valid for T = any generated struct type, List, Text, Data. + + template + inline Orphan disownAs(StructSchema schema); + // Only valid for T = DynamicStruct. Requires `#include `. + + template + inline Orphan disownAs(ListSchema schema); + // Only valid for T = DynamicList. Requires `#include `. + + template + inline Orphan disownAs(InterfaceSchema schema); + // Only valid for T = DynamicCapability. Requires `#include `. + + inline Orphan disown(); + // Disown without a type. + + inline Reader asReader() const { return Reader(builder.asReader()); } + inline operator Reader() const { return Reader(builder.asReader()); } + + private: + _::PointerBuilder builder; + friend class Orphanage; + friend class CapBuilderContext; + friend struct _::PointerHelpers; + }; + +#if !CAPNP_LITE + class Pipeline { + public: + typedef AnyPointer Pipelines; + + inline Pipeline(decltype(nullptr)) {} + inline explicit Pipeline(kj::Own&& hook): hook(kj::mv(hook)) {} + + Pipeline noop(); + // Just make a copy. + + Pipeline getPointerField(uint16_t pointerIndex); + // Deprecated. In the future, we should use .asAnyStruct.getPointerField. + + inline AnyStruct::Pipeline asAnyStruct(); + + kj::Own asCap(); + // Expect that the result is a capability and construct a pipelined version of it now. + + inline kj::Own releasePipelineHook() { return kj::mv(hook); } + // For use by RPC implementations. + + template ) == Kind::INTERFACE>> + inline operator T() { return T(asCap()); } + + private: + kj::Own hook; + kj::Array ops; + + inline Pipeline(kj::Own&& hook, kj::Array&& ops) + : hook(kj::mv(hook)), ops(kj::mv(ops)) {} + + friend class LocalClient; + friend class PipelineHook; + friend class AnyStruct::Pipeline; + }; +#endif // !CAPNP_LITE +}; + +template <> +class Orphan { + // An orphaned object of unknown type. + +public: + Orphan() = default; + KJ_DISALLOW_COPY(Orphan); + Orphan(Orphan&&) = default; + inline Orphan(_::OrphanBuilder&& builder) + : builder(kj::mv(builder)) {} + + Orphan& operator=(Orphan&&) = default; + + template + inline Orphan(Orphan&& other): builder(kj::mv(other.builder)) {} + template + inline Orphan& operator=(Orphan&& other) { builder = kj::mv(other.builder); return *this; } + // Cast from typed orphan. + + // It's not possible to get an AnyPointer::{Reader,Builder} directly since there is no + // underlying pointer (the pointer would normally live in the parent, but this object is + // orphaned). It is possible, however, to request typed readers/builders. + + template + inline BuilderFor getAs(); + template + inline BuilderFor getAs(StructSchema schema); + template + inline BuilderFor getAs(ListSchema schema); + template + inline typename T::Client getAs(InterfaceSchema schema); + template + inline ReaderFor getAsReader() const; + template + inline ReaderFor getAsReader(StructSchema schema) const; + template + inline ReaderFor getAsReader(ListSchema schema) const; + template + inline typename T::Client getAsReader(InterfaceSchema schema) const; + + template + inline Orphan releaseAs(); + template + inline Orphan releaseAs(StructSchema schema); + template + inline Orphan releaseAs(ListSchema schema); + template + inline Orphan releaseAs(InterfaceSchema schema); + // Down-cast the orphan to a specific type. + + inline bool operator==(decltype(nullptr)) const { return builder == nullptr; } + inline bool operator!=(decltype(nullptr)) const { return builder != nullptr; } + +private: + _::OrphanBuilder builder; + + template + friend struct _::PointerHelpers; + friend class Orphanage; + template + friend class Orphan; + friend class AnyPointer::Builder; +}; + +template struct AnyTypeFor_; +template <> struct AnyTypeFor_ { typedef AnyStruct Type; }; +template <> struct AnyTypeFor_ { typedef AnyList Type; }; + +template +using AnyTypeFor = typename AnyTypeFor_::Type; + +template +inline ReaderFor>> toAny(T&& value) { + return ReaderFor>>( + _::PointerHelpers>::getInternalReader(value)); +} +template +inline BuilderFor>> toAny(T&& value) { + return BuilderFor>>( + _::PointerHelpers>::getInternalBuilder(kj::mv(value))); +} + +template <> +struct List { + // Note: This cannot be used for a list of structs, since such lists are not encoded as pointer + // lists! Use List. + + List() = delete; + + class Reader { + public: + typedef List Reads; + + inline Reader(): reader(ElementSize::POINTER) {} + inline explicit Reader(_::ListReader reader): reader(reader) {} + + inline uint size() const { return unbound(reader.size() / ELEMENTS); } + inline AnyPointer::Reader operator[](uint index) const { + KJ_IREQUIRE(index < size()); + return AnyPointer::Reader(reader.getPointerElement(bounded(index) * ELEMENTS)); + } + + typedef _::IndexingIterator Iterator; + inline Iterator begin() const { return Iterator(this, 0); } + inline Iterator end() const { return Iterator(this, size()); } + + private: + _::ListReader reader; + template + friend struct _::PointerHelpers; + template + friend struct List; + friend class Orphanage; + template + friend struct ToDynamic_; + }; + + class Builder { + public: + typedef List Builds; + + Builder() = delete; + inline Builder(decltype(nullptr)): builder(ElementSize::POINTER) {} + inline explicit Builder(_::ListBuilder builder): builder(builder) {} + + inline operator Reader() const { return Reader(builder.asReader()); } + inline Reader asReader() const { return Reader(builder.asReader()); } + + inline uint size() const { return unbound(builder.size() / ELEMENTS); } + inline AnyPointer::Builder operator[](uint index) { + KJ_IREQUIRE(index < size()); + return AnyPointer::Builder(builder.getPointerElement(bounded(index) * ELEMENTS)); + } + + typedef _::IndexingIterator Iterator; + inline Iterator begin() { return Iterator(this, 0); } + inline Iterator end() { return Iterator(this, size()); } + + private: + _::ListBuilder builder; + template + friend struct _::PointerHelpers; + friend class Orphanage; + template + friend struct ToDynamic_; + }; +}; + +class AnyStruct::Reader { +public: + typedef AnyStruct Reads; + + Reader() = default; + inline Reader(_::StructReader reader): _reader(reader) {} + + template ) == Kind::STRUCT>> + inline Reader(T&& value) + : _reader(_::PointerHelpers>::getInternalReader(kj::fwd(value))) {} + + kj::ArrayPtr getDataSection() { + return _reader.getDataSectionAsBlob(); + } + List::Reader getPointerSection() { + return List::Reader(_reader.getPointerSectionAsList()); + } + + kj::Array canonicalize() { + return _reader.canonicalize(); + } + + Equality equals(AnyStruct::Reader right); + bool operator==(AnyStruct::Reader right); + inline bool operator!=(AnyStruct::Reader right) { + return !(*this == right); + } + + template + ReaderFor as() const { + // T must be a struct type. + return typename T::Reader(_reader); + } +private: + _::StructReader _reader; + + template + friend struct _::PointerHelpers; + friend class Orphanage; +}; + +class AnyStruct::Builder { +public: + typedef AnyStruct Builds; + + inline Builder(decltype(nullptr)) {} + inline Builder(_::StructBuilder builder): _builder(builder) {} + +#if !_MSC_VER // TODO(msvc): MSVC ICEs on this. Try restoring when compiler improves. + template ) == Kind::STRUCT>> + inline Builder(T&& value) + : _builder(_::PointerHelpers>::getInternalBuilder(kj::fwd(value))) {} +#endif + + inline kj::ArrayPtr getDataSection() { + return _builder.getDataSectionAsBlob(); + } + List::Builder getPointerSection() { + return List::Builder(_builder.getPointerSectionAsList()); + } + + inline Equality equals(AnyStruct::Reader right) { + return asReader().equals(right); + } + inline bool operator==(AnyStruct::Reader right) { + return asReader() == right; + } + inline bool operator!=(AnyStruct::Reader right) { + return !(*this == right); + } + + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return Reader(_builder.asReader()); } + + template + BuilderFor as() { + // T must be a struct type. + return typename T::Builder(_builder); + } +private: + _::StructBuilder _builder; + friend class Orphanage; + friend class CapBuilderContext; +}; + +#if !CAPNP_LITE +class AnyStruct::Pipeline { +public: + inline Pipeline(decltype(nullptr)): typeless(nullptr) {} + inline explicit Pipeline(AnyPointer::Pipeline&& typeless) + : typeless(kj::mv(typeless)) {} + + inline AnyPointer::Pipeline getPointerField(uint16_t pointerIndex) { + // Return a new Promise representing a sub-object of the result. `pointerIndex` is the index + // of the sub-object within the pointer section of the result (the result must be a struct). + // + // TODO(perf): On GCC 4.8 / Clang 3.3, use rvalue qualifiers to avoid the need for copies. + // Also make `ops` into a Vector to optimize this. + return typeless.getPointerField(pointerIndex); + } + +private: + AnyPointer::Pipeline typeless; +}; +#endif // !CAPNP_LITE + +class List::Reader { +public: + typedef List Reads; + + inline Reader(): reader(ElementSize::INLINE_COMPOSITE) {} + inline explicit Reader(_::ListReader reader): reader(reader) {} + + inline uint size() const { return unbound(reader.size() / ELEMENTS); } + inline AnyStruct::Reader operator[](uint index) const { + KJ_IREQUIRE(index < size()); + return AnyStruct::Reader(reader.getStructElement(bounded(index) * ELEMENTS)); + } + + typedef _::IndexingIterator Iterator; + inline Iterator begin() const { return Iterator(this, 0); } + inline Iterator end() const { return Iterator(this, size()); } + +private: + _::ListReader reader; + template + friend struct _::PointerHelpers; + template + friend struct List; + friend class Orphanage; + template + friend struct ToDynamic_; +}; + +class List::Builder { +public: + typedef List Builds; + + Builder() = delete; + inline Builder(decltype(nullptr)): builder(ElementSize::INLINE_COMPOSITE) {} + inline explicit Builder(_::ListBuilder builder): builder(builder) {} + + inline operator Reader() const { return Reader(builder.asReader()); } + inline Reader asReader() const { return Reader(builder.asReader()); } + + inline uint size() const { return unbound(builder.size() / ELEMENTS); } + inline AnyStruct::Builder operator[](uint index) { + KJ_IREQUIRE(index < size()); + return AnyStruct::Builder(builder.getStructElement(bounded(index) * ELEMENTS)); + } + + typedef _::IndexingIterator Iterator; + inline Iterator begin() { return Iterator(this, 0); } + inline Iterator end() { return Iterator(this, size()); } + +private: + _::ListBuilder builder; + template + friend struct _::PointerHelpers; + friend class Orphanage; + template + friend struct ToDynamic_; +}; + +class AnyList::Reader { +public: + typedef AnyList Reads; + + inline Reader(): _reader(ElementSize::VOID) {} + inline Reader(_::ListReader reader): _reader(reader) {} + +#if !_MSC_VER // TODO(msvc): MSVC ICEs on this. Try restoring when compiler improves. + template ) == Kind::LIST>> + inline Reader(T&& value) + : _reader(_::PointerHelpers>::getInternalReader(kj::fwd(value))) {} +#endif + + inline ElementSize getElementSize() { return _reader.getElementSize(); } + inline uint size() { return unbound(_reader.size() / ELEMENTS); } + + inline kj::ArrayPtr getRawBytes() { return _reader.asRawBytes(); } + + Equality equals(AnyList::Reader right); + bool operator==(AnyList::Reader right); + inline bool operator!=(AnyList::Reader right) { + return !(*this == right); + } + + template ReaderFor as() { + // T must be List. + return ReaderFor(_reader); + } +private: + _::ListReader _reader; + + template + friend struct _::PointerHelpers; + friend class Orphanage; +}; + +class AnyList::Builder { +public: + typedef AnyList Builds; + + inline Builder(decltype(nullptr)): _builder(ElementSize::VOID) {} + inline Builder(_::ListBuilder builder): _builder(builder) {} + +#if !_MSC_VER // TODO(msvc): MSVC ICEs on this. Try restoring when compiler improves. + template ) == Kind::LIST>> + inline Builder(T&& value) + : _builder(_::PointerHelpers>::getInternalBuilder(kj::fwd(value))) {} +#endif + + inline ElementSize getElementSize() { return _builder.getElementSize(); } + inline uint size() { return unbound(_builder.size() / ELEMENTS); } + + Equality equals(AnyList::Reader right); + inline bool operator==(AnyList::Reader right) { + return asReader() == right; + } + inline bool operator!=(AnyList::Reader right) { + return !(*this == right); + } + + template BuilderFor as() { + // T must be List. + return BuilderFor(_builder); + } + + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return Reader(_builder.asReader()); } + +private: + _::ListBuilder _builder; + + friend class Orphanage; +}; + +// ======================================================================================= +// Pipeline helpers +// +// These relate to capabilities, but we don't declare them in capability.h because generated code +// for structs needs to know about these, even in files that contain no interfaces. + +#if !CAPNP_LITE + +struct PipelineOp { + // Corresponds to rpc.capnp's PromisedAnswer.Op. + + enum Type { + NOOP, // for convenience + + GET_POINTER_FIELD + + // There may be other types in the future... + }; + + Type type; + union { + uint16_t pointerIndex; // for GET_POINTER_FIELD + }; +}; + +class PipelineHook { + // Represents a currently-running call, and implements pipelined requests on its result. + +public: + virtual kj::Own addRef() = 0; + // Increment this object's reference count. + + virtual kj::Own getPipelinedCap(kj::ArrayPtr ops) = 0; + // Extract a promised Capability from the results. + + virtual kj::Own getPipelinedCap(kj::Array&& ops); + // Version of getPipelinedCap() passing the array by move. May avoid a copy in some cases. + // Default implementation just calls the other version. + + template > + static inline kj::Own from(Pipeline&& pipeline); + +private: + template struct FromImpl; +}; + +#endif // !CAPNP_LITE + +// ======================================================================================= +// Inline implementation details + +inline MessageSize AnyPointer::Reader::targetSize() const { + return reader.targetSize().asPublic(); +} + +inline PointerType AnyPointer::Reader::getPointerType() const { + return reader.getPointerType(); +} + +template +inline ReaderFor AnyPointer::Reader::getAs() const { + return _::PointerHelpers::get(reader); +} + +inline MessageSize AnyPointer::Builder::targetSize() const { + return asReader().targetSize(); +} + +inline PointerType AnyPointer::Builder::getPointerType() { + return builder.getPointerType(); +} + +inline void AnyPointer::Builder::clear() { + return builder.clear(); +} + +template +inline BuilderFor AnyPointer::Builder::getAs() { + return _::PointerHelpers::get(builder); +} + +template +inline BuilderFor AnyPointer::Builder::initAs() { + return _::PointerHelpers::init(builder); +} + +template +inline BuilderFor AnyPointer::Builder::initAs(uint elementCount) { + return _::PointerHelpers::init(builder, elementCount); +} + +inline AnyList::Builder AnyPointer::Builder::initAsAnyList( + ElementSize elementSize, uint elementCount) { + return AnyList::Builder(builder.initList(elementSize, bounded(elementCount) * ELEMENTS)); +} + +inline List::Builder AnyPointer::Builder::initAsListOfAnyStruct( + uint16_t dataWordCount, uint16_t pointerCount, uint elementCount) { + return List::Builder(builder.initStructList(bounded(elementCount) * ELEMENTS, + _::StructSize(bounded(dataWordCount) * WORDS, + bounded(pointerCount) * POINTERS))); +} + +inline AnyStruct::Builder AnyPointer::Builder::initAsAnyStruct( + uint16_t dataWordCount, uint16_t pointerCount) { + return AnyStruct::Builder(builder.initStruct( + _::StructSize(bounded(dataWordCount) * WORDS, + bounded(pointerCount) * POINTERS))); +} + +template +inline void AnyPointer::Builder::setAs(ReaderFor value) { + return _::PointerHelpers::set(builder, value); +} + +template +inline void AnyPointer::Builder::setCanonicalAs(ReaderFor value) { + return _::PointerHelpers::setCanonical(builder, value); +} + +template +inline void AnyPointer::Builder::setAs( + std::initializer_list>> list) { + return _::PointerHelpers::set(builder, list); +} + +template +inline void AnyPointer::Builder::adopt(Orphan&& orphan) { + _::PointerHelpers::adopt(builder, kj::mv(orphan)); +} + +template +inline Orphan AnyPointer::Builder::disownAs() { + return _::PointerHelpers::disown(builder); +} + +inline Orphan AnyPointer::Builder::disown() { + return Orphan(builder.disown()); +} + +template <> struct ReaderFor_ { typedef AnyPointer::Reader Type; }; +template <> struct BuilderFor_ { typedef AnyPointer::Builder Type; }; +template <> struct ReaderFor_ { typedef AnyStruct::Reader Type; }; +template <> struct BuilderFor_ { typedef AnyStruct::Builder Type; }; + +template <> +struct Orphanage::GetInnerReader { + static inline _::PointerReader apply(const AnyPointer::Reader& t) { + return t.reader; + } +}; + +template <> +struct Orphanage::GetInnerBuilder { + static inline _::PointerBuilder apply(AnyPointer::Builder& t) { + return t.builder; + } +}; + +template <> +struct Orphanage::GetInnerReader { + static inline _::StructReader apply(const AnyStruct::Reader& t) { + return t._reader; + } +}; + +template <> +struct Orphanage::GetInnerBuilder { + static inline _::StructBuilder apply(AnyStruct::Builder& t) { + return t._builder; + } +}; + +template <> +struct Orphanage::GetInnerReader { + static inline _::ListReader apply(const AnyList::Reader& t) { + return t._reader; + } +}; + +template <> +struct Orphanage::GetInnerBuilder { + static inline _::ListBuilder apply(AnyList::Builder& t) { + return t._builder; + } +}; + +template +inline BuilderFor Orphan::getAs() { + return _::OrphanGetImpl::apply(builder); +} +template +inline ReaderFor Orphan::getAsReader() const { + return _::OrphanGetImpl::applyReader(builder); +} +template +inline Orphan Orphan::releaseAs() { + return Orphan(kj::mv(builder)); +} + +// Using AnyPointer as the template type should work... + +template <> +inline typename AnyPointer::Reader AnyPointer::Reader::getAs() const { + return *this; +} +template <> +inline typename AnyPointer::Builder AnyPointer::Builder::getAs() { + return *this; +} +template <> +inline typename AnyPointer::Builder AnyPointer::Builder::initAs() { + clear(); + return *this; +} +template <> +inline void AnyPointer::Builder::setAs(AnyPointer::Reader value) { + return builder.copyFrom(value.reader); +} +template <> +inline void AnyPointer::Builder::adopt(Orphan&& orphan) { + builder.adopt(kj::mv(orphan.builder)); +} +template <> +inline Orphan AnyPointer::Builder::disownAs() { + return Orphan(builder.disown()); +} +template <> +inline Orphan Orphan::releaseAs() { + return kj::mv(*this); +} + +namespace _ { // private + +// Specialize PointerHelpers for AnyPointer. + +template <> +struct PointerHelpers { + static inline AnyPointer::Reader get(PointerReader reader, + const void* defaultValue = nullptr, + uint defaultBytes = 0) { + return AnyPointer::Reader(reader); + } + static inline AnyPointer::Builder get(PointerBuilder builder, + const void* defaultValue = nullptr, + uint defaultBytes = 0) { + return AnyPointer::Builder(builder); + } + static inline void set(PointerBuilder builder, AnyPointer::Reader value) { + AnyPointer::Builder(builder).set(value); + } + static inline void adopt(PointerBuilder builder, Orphan&& value) { + builder.adopt(kj::mv(value.builder)); + } + static inline Orphan disown(PointerBuilder builder) { + return Orphan(builder.disown()); + } + static inline _::PointerReader getInternalReader(const AnyPointer::Reader& reader) { + return reader.reader; + } + static inline _::PointerBuilder getInternalBuilder(AnyPointer::Builder&& builder) { + return builder.builder; + } +}; + +template <> +struct PointerHelpers { + static inline AnyStruct::Reader get( + PointerReader reader, const word* defaultValue = nullptr) { + return AnyStruct::Reader(reader.getStruct(defaultValue)); + } + static inline AnyStruct::Builder get( + PointerBuilder builder, const word* defaultValue = nullptr) { + // TODO(someday): Allow specifying the size somehow? + return AnyStruct::Builder(builder.getStruct( + _::StructSize(ZERO * WORDS, ZERO * POINTERS), defaultValue)); + } + static inline void set(PointerBuilder builder, AnyStruct::Reader value) { + builder.setStruct(value._reader); + } + static inline AnyStruct::Builder init( + PointerBuilder builder, uint16_t dataWordCount, uint16_t pointerCount) { + return AnyStruct::Builder(builder.initStruct( + StructSize(bounded(dataWordCount) * WORDS, + bounded(pointerCount) * POINTERS))); + } + + static void adopt(PointerBuilder builder, Orphan&& value) { + builder.adopt(kj::mv(value.builder)); + } + static Orphan disown(PointerBuilder builder) { + return Orphan(builder.disown()); + } +}; + +template <> +struct PointerHelpers { + static inline AnyList::Reader get( + PointerReader reader, const word* defaultValue = nullptr) { + return AnyList::Reader(reader.getListAnySize(defaultValue)); + } + static inline AnyList::Builder get( + PointerBuilder builder, const word* defaultValue = nullptr) { + return AnyList::Builder(builder.getListAnySize(defaultValue)); + } + static inline void set(PointerBuilder builder, AnyList::Reader value) { + builder.setList(value._reader); + } + static inline AnyList::Builder init( + PointerBuilder builder, ElementSize elementSize, uint elementCount) { + return AnyList::Builder(builder.initList( + elementSize, bounded(elementCount) * ELEMENTS)); + } + static inline AnyList::Builder init( + PointerBuilder builder, uint16_t dataWordCount, uint16_t pointerCount, uint elementCount) { + return AnyList::Builder(builder.initStructList( + bounded(elementCount) * ELEMENTS, + StructSize(bounded(dataWordCount) * WORDS, + bounded(pointerCount) * POINTERS))); + } + + static void adopt(PointerBuilder builder, Orphan&& value) { + builder.adopt(kj::mv(value.builder)); + } + static Orphan disown(PointerBuilder builder) { + return Orphan(builder.disown()); + } +}; + +template <> +struct OrphanGetImpl { + static inline AnyStruct::Builder apply(_::OrphanBuilder& builder) { + return AnyStruct::Builder(builder.asStruct(_::StructSize(ZERO * WORDS, ZERO * POINTERS))); + } + static inline AnyStruct::Reader applyReader(const _::OrphanBuilder& builder) { + return AnyStruct::Reader(builder.asStructReader(_::StructSize(ZERO * WORDS, ZERO * POINTERS))); + } + static inline void truncateListOf(_::OrphanBuilder& builder, ElementCount size) { + builder.truncate(size, _::StructSize(ZERO * WORDS, ZERO * POINTERS)); + } +}; + +template <> +struct OrphanGetImpl { + static inline AnyList::Builder apply(_::OrphanBuilder& builder) { + return AnyList::Builder(builder.asListAnySize()); + } + static inline AnyList::Reader applyReader(const _::OrphanBuilder& builder) { + return AnyList::Reader(builder.asListReaderAnySize()); + } + static inline void truncateListOf(_::OrphanBuilder& builder, ElementCount size) { + builder.truncate(size, ElementSize::POINTER); + } +}; + +} // namespace _ (private) + +#if !CAPNP_LITE + +template +struct PipelineHook::FromImpl { + static inline kj::Own apply(typename T::Pipeline&& pipeline) { + return from(kj::mv(pipeline._typeless)); + } +}; + +template <> +struct PipelineHook::FromImpl { + static inline kj::Own apply(AnyPointer::Pipeline&& pipeline) { + return kj::mv(pipeline.hook); + } +}; + +template +inline kj::Own PipelineHook::from(Pipeline&& pipeline) { + return FromImpl::apply(kj::fwd(pipeline)); +} + +#endif // !CAPNP_LITE + +} // namespace capnp + +#endif // CAPNP_ANY_H_ diff --git a/phonelibs/capnp-cpp/include/capnp/blob.h b/phonelibs/capnp-cpp/include/capnp/blob.h new file mode 100644 index 00000000000000..d11f101a5ad378 --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/blob.h @@ -0,0 +1,220 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef CAPNP_BLOB_H_ +#define CAPNP_BLOB_H_ + +#if defined(__GNUC__) && !defined(CAPNP_HEADER_WARNINGS) +#pragma GCC system_header +#endif + +#include +#include +#include "common.h" +#include + +namespace capnp { + +struct Data { + Data() = delete; + class Reader; + class Builder; + class Pipeline {}; +}; + +struct Text { + Text() = delete; + class Reader; + class Builder; + class Pipeline {}; +}; + +class Data::Reader: public kj::ArrayPtr { + // Points to a blob of bytes. The usual Reader rules apply -- Data::Reader behaves like a simple + // pointer which does not own its target, can be passed by value, etc. + +public: + typedef Data Reads; + + Reader() = default; + inline Reader(decltype(nullptr)): ArrayPtr(nullptr) {} + inline Reader(const byte* value, size_t size): ArrayPtr(value, size) {} + inline Reader(const kj::Array& value): ArrayPtr(value) {} + inline Reader(const ArrayPtr& value): ArrayPtr(value) {} + inline Reader(const kj::Array& value): ArrayPtr(value) {} + inline Reader(const ArrayPtr& value): ArrayPtr(value) {} +}; + +class Text::Reader: public kj::StringPtr { + // Like Data::Reader, but points at NUL-terminated UTF-8 text. The NUL terminator is not counted + // in the size but must be present immediately after the last byte. + // + // Text::Reader's interface contract is that its data MUST be NUL-terminated. The producer of + // the Text::Reader must guarantee this, so that the consumer need not check. The data SHOULD + // also be valid UTF-8, but this is NOT guaranteed -- the consumer must verify if it cares. + +public: + typedef Text Reads; + + Reader() = default; + inline Reader(decltype(nullptr)): StringPtr(nullptr) {} + inline Reader(const char* value): StringPtr(value) {} + inline Reader(const char* value, size_t size): StringPtr(value, size) {} + inline Reader(const kj::String& value): StringPtr(value) {} + inline Reader(const StringPtr& value): StringPtr(value) {} + +#if KJ_COMPILER_SUPPORTS_STL_STRING_INTEROP + template ().c_str())> + inline Reader(const T& t): StringPtr(t) {} + // Allow implicit conversion from any class that has a c_str() method (namely, std::string). + // We use a template trick to detect std::string in order to avoid including the header for + // those who don't want it. +#endif +}; + +class Data::Builder: public kj::ArrayPtr { + // Like Data::Reader except the pointers aren't const. + +public: + typedef Data Builds; + + Builder() = default; + inline Builder(decltype(nullptr)): ArrayPtr(nullptr) {} + inline Builder(byte* value, size_t size): ArrayPtr(value, size) {} + inline Builder(kj::Array& value): ArrayPtr(value) {} + inline Builder(ArrayPtr value): ArrayPtr(value) {} + + inline Data::Reader asReader() const { return Data::Reader(*this); } + inline operator Reader() const { return asReader(); } +}; + +class Text::Builder: public kj::DisallowConstCopy { + // Basically identical to kj::StringPtr, except that the contents are non-const. + +public: + inline Builder(): content(nulstr, 1) {} + inline Builder(decltype(nullptr)): content(nulstr, 1) {} + inline Builder(char* value): content(value, strlen(value) + 1) {} + inline Builder(char* value, size_t size): content(value, size + 1) { + KJ_IREQUIRE(value[size] == '\0', "StringPtr must be NUL-terminated."); + } + + inline Reader asReader() const { return Reader(content.begin(), content.size() - 1); } + inline operator Reader() const { return asReader(); } + + inline operator kj::ArrayPtr(); + inline kj::ArrayPtr asArray(); + inline operator kj::ArrayPtr() const; + inline kj::ArrayPtr asArray() const; + inline kj::ArrayPtr asBytes() { return asArray().asBytes(); } + inline kj::ArrayPtr asBytes() const { return asArray().asBytes(); } + // Result does not include NUL terminator. + + inline operator kj::StringPtr() const; + inline kj::StringPtr asString() const; + + inline const char* cStr() const { return content.begin(); } + // Returns NUL-terminated string. + + inline size_t size() const { return content.size() - 1; } + // Result does not include NUL terminator. + + inline char operator[](size_t index) const { return content[index]; } + inline char& operator[](size_t index) { return content[index]; } + + inline char* begin() { return content.begin(); } + inline char* end() { return content.end() - 1; } + inline const char* begin() const { return content.begin(); } + inline const char* end() const { return content.end() - 1; } + + inline bool operator==(decltype(nullptr)) const { return content.size() <= 1; } + inline bool operator!=(decltype(nullptr)) const { return content.size() > 1; } + + inline bool operator==(Builder other) const { return asString() == other.asString(); } + inline bool operator!=(Builder other) const { return asString() != other.asString(); } + inline bool operator< (Builder other) const { return asString() < other.asString(); } + inline bool operator> (Builder other) const { return asString() > other.asString(); } + inline bool operator<=(Builder other) const { return asString() <= other.asString(); } + inline bool operator>=(Builder other) const { return asString() >= other.asString(); } + + inline kj::StringPtr slice(size_t start) const; + inline kj::ArrayPtr slice(size_t start, size_t end) const; + inline Builder slice(size_t start); + inline kj::ArrayPtr slice(size_t start, size_t end); + // A string slice is only NUL-terminated if it is a suffix, so slice() has a one-parameter + // version that assumes end = size(). + +private: + inline explicit Builder(kj::ArrayPtr content): content(content) {} + + kj::ArrayPtr content; + + static char nulstr[1]; +}; + +inline kj::StringPtr KJ_STRINGIFY(Text::Builder builder) { + return builder.asString(); +} + +inline bool operator==(const char* a, const Text::Builder& b) { return a == b.asString(); } +inline bool operator!=(const char* a, const Text::Builder& b) { return a != b.asString(); } + +inline Text::Builder::operator kj::StringPtr() const { + return kj::StringPtr(content.begin(), content.size() - 1); +} + +inline kj::StringPtr Text::Builder::asString() const { + return kj::StringPtr(content.begin(), content.size() - 1); +} + +inline Text::Builder::operator kj::ArrayPtr() { + return content.slice(0, content.size() - 1); +} + +inline kj::ArrayPtr Text::Builder::asArray() { + return content.slice(0, content.size() - 1); +} + +inline Text::Builder::operator kj::ArrayPtr() const { + return content.slice(0, content.size() - 1); +} + +inline kj::ArrayPtr Text::Builder::asArray() const { + return content.slice(0, content.size() - 1); +} + +inline kj::StringPtr Text::Builder::slice(size_t start) const { + return asReader().slice(start); +} +inline kj::ArrayPtr Text::Builder::slice(size_t start, size_t end) const { + return content.slice(start, end); +} + +inline Text::Builder Text::Builder::slice(size_t start) { + return Text::Builder(content.slice(start, content.size())); +} +inline kj::ArrayPtr Text::Builder::slice(size_t start, size_t end) { + return content.slice(start, end); +} + +} // namespace capnp + +#endif // CAPNP_BLOB_H_ diff --git a/phonelibs/capnp-cpp/include/capnp/c++.capnp b/phonelibs/capnp-cpp/include/capnp/c++.capnp new file mode 100644 index 00000000000000..2bda54717920ab --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/c++.capnp @@ -0,0 +1,26 @@ +# Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +# Licensed under the MIT License: +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in +# all copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +# THE SOFTWARE. + +@0xbdf87d7bb8304e81; +$namespace("capnp::annotations"); + +annotation namespace(file): Text; +annotation name(field, enumerant, struct, enum, interface, method, param, group, union): Text; diff --git a/phonelibs/capnp-cpp/include/capnp/c++.capnp.h b/phonelibs/capnp-cpp/include/capnp/c++.capnp.h new file mode 100644 index 00000000000000..6d9817fbded116 --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/c++.capnp.h @@ -0,0 +1,33 @@ +// Generated by Cap'n Proto compiler, DO NOT EDIT +// source: c++.capnp + +#ifndef CAPNP_INCLUDED_bdf87d7bb8304e81_ +#define CAPNP_INCLUDED_bdf87d7bb8304e81_ + +#include + +#if CAPNP_VERSION != 6001 +#error "Version mismatch between generated code and library headers. You must use the same version of the Cap'n Proto compiler and library." +#endif + + +namespace capnp { +namespace schemas { + +CAPNP_DECLARE_SCHEMA(b9c6f99ebf805f2c); +CAPNP_DECLARE_SCHEMA(f264a779fef191ce); + +} // namespace schemas +} // namespace capnp + +namespace capnp { +namespace annotations { + +// ======================================================================================= + +// ======================================================================================= + +} // namespace +} // namespace + +#endif // CAPNP_INCLUDED_bdf87d7bb8304e81_ diff --git a/phonelibs/capnp-cpp/include/capnp/c.capnp b/phonelibs/capnp-cpp/include/capnp/c.capnp new file mode 100644 index 00000000000000..5de7e7363afcc0 --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/c.capnp @@ -0,0 +1,37 @@ +# Copyright (c) 2016 NetDEF, Inc. and contributors +# Licensed under the MIT License: +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in +# all copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +# THE SOFTWARE. + +@0xc0183dd65ffef0f3; + +annotation nameinfix @0x85a8d86d736ba637 (file): Text; +# add an infix (middle insert) for output file names +# +# "make" generally has implicit rules for compiling "foo.c" => "foo". This +# is very annoying with capnp since the rule will be "foo" => "foo.c", leading +# to a loop. $nameinfix (recommended parameter: "-gen") inserts its parameter +# before the ".c", so the filename becomes "foo-gen.c" +# +# ("foo" is really "foo.capnp", so it's foo.capnp-gen.c) + +annotation fieldgetset @0xf72bc690355d66de (file): Void; +# generate getter & setter functions for accessing fields +# +# allows grabbing/putting values without de-/encoding the entire struct. diff --git a/phonelibs/capnp-cpp/include/capnp/capability.h b/phonelibs/capnp-cpp/include/capnp/capability.h new file mode 100644 index 00000000000000..56a5e6f6de2d38 --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/capability.h @@ -0,0 +1,884 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef CAPNP_CAPABILITY_H_ +#define CAPNP_CAPABILITY_H_ + +#if defined(__GNUC__) && !defined(CAPNP_HEADER_WARNINGS) +#pragma GCC system_header +#endif + +#if CAPNP_LITE +#error "RPC APIs, including this header, are not available in lite mode." +#endif + +#include +#include +#include "raw-schema.h" +#include "any.h" +#include "pointer-helpers.h" + +namespace capnp { + +template +class Response; + +template +class RemotePromise: public kj::Promise>, public T::Pipeline { + // A Promise which supports pipelined calls. T is typically a struct type. T must declare + // an inner "mix-in" type "Pipeline" which implements pipelining; RemotePromise simply + // multiply-inherits that type along with Promise>. T::Pipeline must be movable, + // but does not need to be copyable (i.e. just like Promise). + // + // The promise is for an owned pointer so that the RPC system can allocate the MessageReader + // itself. + +public: + inline RemotePromise(kj::Promise>&& promise, typename T::Pipeline&& pipeline) + : kj::Promise>(kj::mv(promise)), + T::Pipeline(kj::mv(pipeline)) {} + inline RemotePromise(decltype(nullptr)) + : kj::Promise>(nullptr), + T::Pipeline(nullptr) {} + KJ_DISALLOW_COPY(RemotePromise); + RemotePromise(RemotePromise&& other) = default; + RemotePromise& operator=(RemotePromise&& other) = default; +}; + +class LocalClient; +namespace _ { // private +extern const RawSchema NULL_INTERFACE_SCHEMA; // defined in schema.c++ +class CapabilityServerSetBase; +} // namespace _ (private) + +struct Capability { + // A capability without type-safe methods. Typed capability clients wrap `Client` and typed + // capability servers subclass `Server` to dispatch to the regular, typed methods. + + class Client; + class Server; + + struct _capnpPrivate { + struct IsInterface; + static constexpr uint64_t typeId = 0x3; + static constexpr Kind kind = Kind::INTERFACE; + static constexpr _::RawSchema const* schema = &_::NULL_INTERFACE_SCHEMA; + + static const _::RawBrandedSchema* brand() { + return &_::NULL_INTERFACE_SCHEMA.defaultBrand; + } + }; +}; + +// ======================================================================================= +// Capability clients + +class RequestHook; +class ResponseHook; +class PipelineHook; +class ClientHook; + +template +class Request: public Params::Builder { + // A call that hasn't been sent yet. This class extends a Builder for the call's "Params" + // structure with a method send() that actually sends it. + // + // Given a Cap'n Proto method `foo(a :A, b :B): C`, the generated client interface will have + // a method `Request fooRequest()` (as well as a convenience method + // `RemotePromise foo(A::Reader a, B::Reader b)`). + +public: + inline Request(typename Params::Builder builder, kj::Own&& hook) + : Params::Builder(builder), hook(kj::mv(hook)) {} + inline Request(decltype(nullptr)): Params::Builder(nullptr) {} + + RemotePromise send() KJ_WARN_UNUSED_RESULT; + // Send the call and return a promise for the results. + +private: + kj::Own hook; + + friend class Capability::Client; + friend struct DynamicCapability; + template + friend class CallContext; + friend class RequestHook; +}; + +template +class Response: public Results::Reader { + // A completed call. This class extends a Reader for the call's answer structure. The Response + // is move-only -- once it goes out-of-scope, the underlying message will be freed. + +public: + inline Response(typename Results::Reader reader, kj::Own&& hook) + : Results::Reader(reader), hook(kj::mv(hook)) {} + +private: + kj::Own hook; + + template + friend class Request; + friend class ResponseHook; +}; + +class Capability::Client { + // Base type for capability clients. + +public: + typedef Capability Reads; + typedef Capability Calls; + + Client(decltype(nullptr)); + // If you need to declare a Client before you have anything to assign to it (perhaps because + // the assignment is going to occur in an if/else scope), you can start by initializing it to + // `nullptr`. The resulting client is not meant to be called and throws exceptions from all + // methods. + + template ()>> + Client(kj::Own&& server); + // Make a client capability that wraps the given server capability. The server's methods will + // only be executed in the given EventLoop, regardless of what thread calls the client's methods. + + template ()>> + Client(kj::Promise&& promise); + // Make a client from a promise for a future client. The resulting client queues calls until the + // promise resolves. + + Client(kj::Exception&& exception); + // Make a broken client that throws the given exception from all calls. + + Client(Client& other); + Client& operator=(Client& other); + // Copies by reference counting. Warning: This refcounting is not thread-safe. All copies of + // the client must remain in one thread. + + Client(Client&&) = default; + Client& operator=(Client&&) = default; + // Move constructor avoids reference counting. + + explicit Client(kj::Own&& hook); + // For use by the RPC implementation: Wrap a ClientHook. + + template + typename T::Client castAs(); + // Reinterpret the capability as implementing the given interface. Note that no error will occur + // here if the capability does not actually implement this interface, but later method calls will + // fail. It's up to the application to decide how indicate that additional interfaces are + // supported. + // + // TODO(perf): GCC 4.8 / Clang 3.3: rvalue-qualified version for better performance. + + template + typename T::Client castAs(InterfaceSchema schema); + // Dynamic version. `T` must be `DynamicCapability`, and you must `#include `. + + kj::Promise whenResolved(); + // If the capability is actually only a promise, the returned promise resolves once the + // capability itself has resolved to its final destination (or propagates the exception if + // the capability promise is rejected). This is mainly useful for error-checking in the case + // where no calls are being made. There is no reason to wait for this before making calls; if + // the capability does not resolve, the call results will propagate the error. + + Request typelessRequest( + uint64_t interfaceId, uint16_t methodId, + kj::Maybe sizeHint); + // Make a request without knowing the types of the params or results. You specify the type ID + // and method number manually. + + // TODO(someday): method(s) for Join + +protected: + Client() = default; + + template + Request newCall(uint64_t interfaceId, uint16_t methodId, + kj::Maybe sizeHint); + +private: + kj::Own hook; + + static kj::Own makeLocalClient(kj::Own&& server); + + template + friend struct _::PointerHelpers; + friend struct DynamicCapability; + friend class Orphanage; + friend struct DynamicStruct; + friend struct DynamicList; + template + friend struct List; + friend class _::CapabilityServerSetBase; + friend class ClientHook; +}; + +// ======================================================================================= +// Capability servers + +class CallContextHook; + +template +class CallContext: public kj::DisallowConstCopy { + // Wrapper around CallContextHook with a specific return type. + // + // Methods of this class may only be called from within the server's event loop, not from other + // threads. + // + // The CallContext becomes invalid as soon as the call reports completion. + +public: + explicit CallContext(CallContextHook& hook); + + typename Params::Reader getParams(); + // Get the params payload. + + void releaseParams(); + // Release the params payload. getParams() will throw an exception after this is called. + // Releasing the params may allow the RPC system to free up buffer space to handle other + // requests. Long-running asynchronous methods should try to call this as early as is + // convenient. + + typename Results::Builder getResults(kj::Maybe sizeHint = nullptr); + typename Results::Builder initResults(kj::Maybe sizeHint = nullptr); + void setResults(typename Results::Reader value); + void adoptResults(Orphan&& value); + Orphanage getResultsOrphanage(kj::Maybe sizeHint = nullptr); + // Manipulate the results payload. The "Return" message (part of the RPC protocol) will + // typically be allocated the first time one of these is called. Some RPC systems may + // allocate these messages in a limited space (such as a shared memory segment), therefore the + // application should delay calling these as long as is convenient to do so (but don't delay + // if doing so would require extra copies later). + // + // `sizeHint` indicates a guess at the message size. This will usually be used to decide how + // much space to allocate for the first message segment (don't worry: only space that is actually + // used will be sent on the wire). If omitted, the system decides. The message root pointer + // should not be included in the size. So, if you are simply going to copy some existing message + // directly into the results, just call `.totalSize()` and pass that in. + + template + kj::Promise tailCall(Request&& tailRequest); + // Resolve the call by making a tail call. `tailRequest` is a request that has been filled in + // but not yet sent. The context will send the call, then fill in the results with the result + // of the call. If tailCall() is used, {get,init,set,adopt}Results (above) *must not* be called. + // + // The RPC implementation may be able to optimize a tail call to another machine such that the + // results never actually pass through this machine. Even if no such optimization is possible, + // `tailCall()` may allow pipelined calls to be forwarded optimistically to the new call site. + // + // In general, this should be the last thing a method implementation calls, and the promise + // returned from `tailCall()` should then be returned by the method implementation. + + void allowCancellation(); + // Indicate that it is OK for the RPC system to discard its Promise for this call's result if + // the caller cancels the call, thereby transitively canceling any asynchronous operations the + // call implementation was performing. This is not done by default because it could represent a + // security risk: applications must be carefully written to ensure that they do not end up in + // a bad state if an operation is canceled at an arbitrary point. However, for long-running + // method calls that hold significant resources, prompt cancellation is often useful. + // + // Keep in mind that asynchronous cancellation cannot occur while the method is synchronously + // executing on a local thread. The method must perform an asynchronous operation or call + // `EventLoop::current().evalLater()` to yield control. + // + // Note: You might think that we should offer `onCancel()` and/or `isCanceled()` methods that + // provide notification when the caller cancels the request without forcefully killing off the + // promise chain. Unfortunately, this composes poorly with promise forking: the canceled + // path may be just one branch of a fork of the result promise. The other branches still want + // the call to continue. Promise forking is used within the Cap'n Proto implementation -- in + // particular each pipelined call forks the result promise. So, if a caller made a pipelined + // call and then dropped the original object, the call should not be canceled, but it would be + // excessively complicated for the framework to avoid notififying of cancellation as long as + // pipelined calls still exist. + +private: + CallContextHook* hook; + + friend class Capability::Server; + friend struct DynamicCapability; +}; + +class Capability::Server { + // Objects implementing a Cap'n Proto interface must subclass this. Typically, such objects + // will instead subclass a typed Server interface which will take care of implementing + // dispatchCall(). + +public: + typedef Capability Serves; + + virtual kj::Promise dispatchCall(uint64_t interfaceId, uint16_t methodId, + CallContext context) = 0; + // Call the given method. `params` is the input struct, and should be released as soon as it + // is no longer needed. `context` may be used to allocate the output struct and deal with + // cancellation. + + // TODO(someday): Method which can optionally be overridden to implement Join when the object is + // a proxy. + +protected: + inline Capability::Client thisCap(); + // Get a capability pointing to this object, much like the `this` keyword. + // + // The effect of this method is undefined if: + // - No capability client has been created pointing to this object. (This is always the case in + // the server's constructor.) + // - The capability client pointing at this object has been destroyed. (This is always the case + // in the server's destructor.) + // - Multiple capability clients have been created around the same server (possible if the server + // is refcounted, which is not recommended since the client itself provides refcounting). + + template + CallContext internalGetTypedContext( + CallContext typeless); + kj::Promise internalUnimplemented(const char* actualInterfaceName, + uint64_t requestedTypeId); + kj::Promise internalUnimplemented(const char* interfaceName, + uint64_t typeId, uint16_t methodId); + kj::Promise internalUnimplemented(const char* interfaceName, const char* methodName, + uint64_t typeId, uint16_t methodId); + +private: + ClientHook* thisHook = nullptr; + friend class LocalClient; +}; + +// ======================================================================================= + +class ReaderCapabilityTable: private _::CapTableReader { + // Class which imbues Readers with the ability to read capabilities. + // + // In Cap'n Proto format, the encoding of a capability pointer is simply an integer index into + // an external table. Since these pointers fundamentally point outside the message, a + // MessageReader by default has no idea what they point at, and therefore reading capabilities + // from such a reader will throw exceptions. + // + // In order to be able to read capabilities, you must first attach a capability table, using + // this class. By "imbuing" a Reader, you get a new Reader which will interpret capability + // pointers by treating them as indexes into the ReaderCapabilityTable. + // + // Note that when using Cap'n Proto's RPC system, this is handled automatically. + +public: + explicit ReaderCapabilityTable(kj::Array>> table); + KJ_DISALLOW_COPY(ReaderCapabilityTable); + + template + T imbue(T reader); + // Return a reader equivalent to `reader` except that when reading capability-valued fields, + // the capabilities are looked up in this table. + +private: + kj::Array>> table; + + kj::Maybe> extractCap(uint index) override; +}; + +class BuilderCapabilityTable: private _::CapTableBuilder { + // Class which imbues Builders with the ability to read and write capabilities. + // + // This is much like ReaderCapabilityTable, except for builders. The table starts out empty, + // but capabilities can be added to it over time. + +public: + BuilderCapabilityTable(); + KJ_DISALLOW_COPY(BuilderCapabilityTable); + + inline kj::ArrayPtr>> getTable() { return table; } + + template + T imbue(T builder); + // Return a builder equivalent to `builder` except that when reading capability-valued fields, + // the capabilities are looked up in this table. + +private: + kj::Vector>> table; + + kj::Maybe> extractCap(uint index) override; + uint injectCap(kj::Own&& cap) override; + void dropCap(uint index) override; +}; + +// ======================================================================================= + +namespace _ { // private + +class CapabilityServerSetBase { +public: + Capability::Client addInternal(kj::Own&& server, void* ptr); + kj::Promise getLocalServerInternal(Capability::Client& client); +}; + +} // namespace _ (private) + +template +class CapabilityServerSet: private _::CapabilityServerSetBase { + // Allows a server to recognize its own capabilities when passed back to it, and obtain the + // underlying Server objects associated with them. + // + // All objects in the set must have the same interface type T. The objects may implement various + // interfaces derived from T (and in fact T can be `capnp::Capability` to accept all objects), + // but note that if you compile with RTTI disabled then you will not be able to down-cast through + // virtual inheritance, and all inheritance between server interfaces is virtual. So, with RTTI + // disabled, you will likely need to set T to be the most-derived Cap'n Proto interface type, + // and you server class will need to be directly derived from that, so that you can use + // static_cast (or kj::downcast) to cast to it after calling getLocalServer(). (If you compile + // with RTTI, then you can freely dynamic_cast and ignore this issue!) + +public: + CapabilityServerSet() = default; + KJ_DISALLOW_COPY(CapabilityServerSet); + + typename T::Client add(kj::Own&& server); + // Create a new capability Client for the given Server and also add this server to the set. + + kj::Promise> getLocalServer(typename T::Client& client); + // Given a Client pointing to a server previously passed to add(), return the corresponding + // Server. This returns a promise because if the input client is itself a promise, this must + // wait for it to resolve. Keep in mind that the server will be deleted when all clients are + // gone, so the caller should make sure to keep the client alive (hence why this method only + // accepts an lvalue input). +}; + +// ======================================================================================= +// Hook interfaces which must be implemented by the RPC system. Applications never call these +// directly; the RPC system implements them and the types defined earlier in this file wrap them. + +class RequestHook { + // Hook interface implemented by RPC system representing a request being built. + +public: + virtual RemotePromise send() = 0; + // Send the call and return a promise for the result. + + virtual const void* getBrand() = 0; + // Returns a void* that identifies who made this request. This can be used by an RPC adapter to + // discover when tail call is going to be sent over its own connection and therefore can be + // optimized into a remote tail call. + + template + inline static kj::Own from(Request&& request) { + return kj::mv(request.hook); + } +}; + +class ResponseHook { + // Hook interface implemented by RPC system representing a response. + // + // At present this class has no methods. It exists only for garbage collection -- when the + // ResponseHook is destroyed, the results can be freed. + +public: + virtual ~ResponseHook() noexcept(false); + // Just here to make sure the type is dynamic. + + template + inline static kj::Own from(Response&& response) { + return kj::mv(response.hook); + } +}; + +// class PipelineHook is declared in any.h because it is needed there. + +class ClientHook { +public: + ClientHook(); + + virtual Request newCall( + uint64_t interfaceId, uint16_t methodId, kj::Maybe sizeHint) = 0; + // Start a new call, allowing the client to allocate request/response objects as it sees fit. + // This version is used when calls are made from application code in the local process. + + struct VoidPromiseAndPipeline { + kj::Promise promise; + kj::Own pipeline; + }; + + virtual VoidPromiseAndPipeline call(uint64_t interfaceId, uint16_t methodId, + kj::Own&& context) = 0; + // Call the object, but the caller controls allocation of the request/response objects. If the + // callee insists on allocating these objects itself, it must make a copy. This version is used + // when calls come in over the network via an RPC system. Note that even if the returned + // `Promise` is discarded, the call may continue executing if any pipelined calls are + // waiting for it. + // + // Since the caller of this method chooses the CallContext implementation, it is the caller's + // responsibility to ensure that the returned promise is not canceled unless allowed via + // the context's `allowCancellation()`. + // + // The call must not begin synchronously; the callee must arrange for the call to begin in a + // later turn of the event loop. Otherwise, application code may call back and affect the + // callee's state in an unexpected way. + + virtual kj::Maybe getResolved() = 0; + // If this ClientHook is a promise that has already resolved, returns the inner, resolved version + // of the capability. The caller may permanently replace this client with the resolved one if + // desired. Returns null if the client isn't a promise or hasn't resolved yet -- use + // `whenMoreResolved()` to distinguish between them. + + virtual kj::Maybe>> whenMoreResolved() = 0; + // If this client is a settled reference (not a promise), return nullptr. Otherwise, return a + // promise that eventually resolves to a new client that is closer to being the final, settled + // client (i.e. the value eventually returned by `getResolved()`). Calling this repeatedly + // should eventually produce a settled client. + + kj::Promise whenResolved(); + // Repeatedly calls whenMoreResolved() until it returns nullptr. + + virtual kj::Own addRef() = 0; + // Return a new reference to the same capability. + + virtual const void* getBrand() = 0; + // Returns a void* that identifies who made this client. This can be used by an RPC adapter to + // discover when a capability it needs to marshal is one that it created in the first place, and + // therefore it can transfer the capability without proxying. + + static const uint NULL_CAPABILITY_BRAND; + // Value is irrelevant; used for pointer. + + inline bool isNull() { return getBrand() == &NULL_CAPABILITY_BRAND; } + // Returns true if the capability was created as a result of assigning a Client to null or by + // reading a null pointer out of a Cap'n Proto message. + + virtual void* getLocalServer(_::CapabilityServerSetBase& capServerSet); + // If this is a local capability created through `capServerSet`, return the underlying Server. + // Otherwise, return nullptr. Default implementation (which everyone except LocalClient should + // use) always returns nullptr. + + static kj::Own from(Capability::Client client) { return kj::mv(client.hook); } +}; + +class CallContextHook { + // Hook interface implemented by RPC system to manage a call on the server side. See + // CallContext. + +public: + virtual AnyPointer::Reader getParams() = 0; + virtual void releaseParams() = 0; + virtual AnyPointer::Builder getResults(kj::Maybe sizeHint) = 0; + virtual kj::Promise tailCall(kj::Own&& request) = 0; + virtual void allowCancellation() = 0; + + virtual kj::Promise onTailCall() = 0; + // If `tailCall()` is called, resolves to the PipelineHook from the tail call. An + // implementation of `ClientHook::call()` is allowed to call this at most once. + + virtual ClientHook::VoidPromiseAndPipeline directTailCall(kj::Own&& request) = 0; + // Call this when you would otherwise call onTailCall() immediately followed by tailCall(). + // Implementations of tailCall() should typically call directTailCall() and then fulfill the + // promise fulfiller for onTailCall() with the returned pipeline. + + virtual kj::Own addRef() = 0; +}; + +kj::Own newLocalPromiseClient(kj::Promise>&& promise); +// Returns a ClientHook that queues up calls until `promise` resolves, then forwards them to +// the new client. This hook's `getResolved()` and `whenMoreResolved()` methods will reflect the +// redirection to the eventual replacement client. + +kj::Own newLocalPromisePipeline(kj::Promise>&& promise); +// Returns a PipelineHook that queues up calls until `promise` resolves, then forwards them to +// the new pipeline. + +kj::Own newBrokenCap(kj::StringPtr reason); +kj::Own newBrokenCap(kj::Exception&& reason); +// Helper function that creates a capability which simply throws exceptions when called. + +kj::Own newBrokenPipeline(kj::Exception&& reason); +// Helper function that creates a pipeline which simply throws exceptions when called. + +Request newBrokenRequest( + kj::Exception&& reason, kj::Maybe sizeHint); +// Helper function that creates a Request object that simply throws exceptions when sent. + +// ======================================================================================= +// Extend PointerHelpers for interfaces + +namespace _ { // private + +template +struct PointerHelpers { + static inline typename T::Client get(PointerReader reader) { + return typename T::Client(reader.getCapability()); + } + static inline typename T::Client get(PointerBuilder builder) { + return typename T::Client(builder.getCapability()); + } + static inline void set(PointerBuilder builder, typename T::Client&& value) { + builder.setCapability(kj::mv(value.Capability::Client::hook)); + } + static inline void set(PointerBuilder builder, typename T::Client& value) { + builder.setCapability(value.Capability::Client::hook->addRef()); + } + static inline void adopt(PointerBuilder builder, Orphan&& value) { + builder.adopt(kj::mv(value.builder)); + } + static inline Orphan disown(PointerBuilder builder) { + return Orphan(builder.disown()); + } +}; + +} // namespace _ (private) + +// ======================================================================================= +// Extend List for interfaces + +template +struct List { + List() = delete; + + class Reader { + public: + typedef List Reads; + + Reader() = default; + inline explicit Reader(_::ListReader reader): reader(reader) {} + + inline uint size() const { return unbound(reader.size() / ELEMENTS); } + inline typename T::Client operator[](uint index) const { + KJ_IREQUIRE(index < size()); + return typename T::Client(reader.getPointerElement( + bounded(index) * ELEMENTS).getCapability()); + } + + typedef _::IndexingIterator Iterator; + inline Iterator begin() const { return Iterator(this, 0); } + inline Iterator end() const { return Iterator(this, size()); } + + private: + _::ListReader reader; + template + friend struct _::PointerHelpers; + template + friend struct List; + friend class Orphanage; + template + friend struct ToDynamic_; + }; + + class Builder { + public: + typedef List Builds; + + Builder() = delete; + inline Builder(decltype(nullptr)) {} + inline explicit Builder(_::ListBuilder builder): builder(builder) {} + + inline operator Reader() const { return Reader(builder.asReader()); } + inline Reader asReader() const { return Reader(builder.asReader()); } + + inline uint size() const { return unbound(builder.size() / ELEMENTS); } + inline typename T::Client operator[](uint index) { + KJ_IREQUIRE(index < size()); + return typename T::Client(builder.getPointerElement( + bounded(index) * ELEMENTS).getCapability()); + } + inline void set(uint index, typename T::Client value) { + KJ_IREQUIRE(index < size()); + builder.getPointerElement(bounded(index) * ELEMENTS).setCapability(kj::mv(value.hook)); + } + inline void adopt(uint index, Orphan&& value) { + KJ_IREQUIRE(index < size()); + builder.getPointerElement(bounded(index) * ELEMENTS).adopt(kj::mv(value)); + } + inline Orphan disown(uint index) { + KJ_IREQUIRE(index < size()); + return Orphan(builder.getPointerElement(bounded(index) * ELEMENTS).disown()); + } + + typedef _::IndexingIterator Iterator; + inline Iterator begin() { return Iterator(this, 0); } + inline Iterator end() { return Iterator(this, size()); } + + private: + _::ListBuilder builder; + friend class Orphanage; + template + friend struct ToDynamic_; + }; + +private: + inline static _::ListBuilder initPointer(_::PointerBuilder builder, uint size) { + return builder.initList(ElementSize::POINTER, bounded(size) * ELEMENTS); + } + inline static _::ListBuilder getFromPointer(_::PointerBuilder builder, const word* defaultValue) { + return builder.getList(ElementSize::POINTER, defaultValue); + } + inline static _::ListReader getFromPointer( + const _::PointerReader& reader, const word* defaultValue) { + return reader.getList(ElementSize::POINTER, defaultValue); + } + + template + friend struct List; + template + friend struct _::PointerHelpers; +}; + +// ======================================================================================= +// Inline implementation details + +template +RemotePromise Request::send() { + auto typelessPromise = hook->send(); + hook = nullptr; // prevent reuse + + // Convert the Promise to return the correct response type. + // Explicitly upcast to kj::Promise to make clear that calling .then() doesn't invalidate the + // Pipeline part of the RemotePromise. + auto typedPromise = kj::implicitCast>&>(typelessPromise) + .then([](Response&& response) -> Response { + return Response(response.getAs(), kj::mv(response.hook)); + }); + + // Wrap the typeless pipeline in a typed wrapper. + typename Results::Pipeline typedPipeline( + kj::mv(kj::implicitCast(typelessPromise))); + + return RemotePromise(kj::mv(typedPromise), kj::mv(typedPipeline)); +} + +inline Capability::Client::Client(kj::Own&& hook): hook(kj::mv(hook)) {} +template +inline Capability::Client::Client(kj::Own&& server) + : hook(makeLocalClient(kj::mv(server))) {} +template +inline Capability::Client::Client(kj::Promise&& promise) + : hook(newLocalPromiseClient(promise.then([](T&& t) { return kj::mv(t.hook); }))) {} +inline Capability::Client::Client(Client& other): hook(other.hook->addRef()) {} +inline Capability::Client& Capability::Client::operator=(Client& other) { + hook = other.hook->addRef(); + return *this; +} +template +inline typename T::Client Capability::Client::castAs() { + return typename T::Client(hook->addRef()); +} +inline kj::Promise Capability::Client::whenResolved() { + return hook->whenResolved(); +} +inline Request Capability::Client::typelessRequest( + uint64_t interfaceId, uint16_t methodId, + kj::Maybe sizeHint) { + return newCall(interfaceId, methodId, sizeHint); +} +template +inline Request Capability::Client::newCall( + uint64_t interfaceId, uint16_t methodId, kj::Maybe sizeHint) { + auto typeless = hook->newCall(interfaceId, methodId, sizeHint); + return Request(typeless.template getAs(), kj::mv(typeless.hook)); +} + +template +inline CallContext::CallContext(CallContextHook& hook): hook(&hook) {} +template +inline typename Params::Reader CallContext::getParams() { + return hook->getParams().template getAs(); +} +template +inline void CallContext::releaseParams() { + hook->releaseParams(); +} +template +inline typename Results::Builder CallContext::getResults( + kj::Maybe sizeHint) { + // `template` keyword needed due to: http://llvm.org/bugs/show_bug.cgi?id=17401 + return hook->getResults(sizeHint).template getAs(); +} +template +inline typename Results::Builder CallContext::initResults( + kj::Maybe sizeHint) { + // `template` keyword needed due to: http://llvm.org/bugs/show_bug.cgi?id=17401 + return hook->getResults(sizeHint).template initAs(); +} +template +inline void CallContext::setResults(typename Results::Reader value) { + hook->getResults(value.totalSize()).template setAs(value); +} +template +inline void CallContext::adoptResults(Orphan&& value) { + hook->getResults(nullptr).adopt(kj::mv(value)); +} +template +inline Orphanage CallContext::getResultsOrphanage( + kj::Maybe sizeHint) { + return Orphanage::getForMessageContaining(hook->getResults(sizeHint)); +} +template +template +inline kj::Promise CallContext::tailCall( + Request&& tailRequest) { + return hook->tailCall(kj::mv(tailRequest.hook)); +} +template +inline void CallContext::allowCancellation() { + hook->allowCancellation(); +} + +template +CallContext Capability::Server::internalGetTypedContext( + CallContext typeless) { + return CallContext(*typeless.hook); +} + +Capability::Client Capability::Server::thisCap() { + return Client(thisHook->addRef()); +} + +template +T ReaderCapabilityTable::imbue(T reader) { + return T(_::PointerHelpers>::getInternalReader(reader).imbue(this)); +} + +template +T BuilderCapabilityTable::imbue(T builder) { + return T(_::PointerHelpers>::getInternalBuilder(kj::mv(builder)).imbue(this)); +} + +template +typename T::Client CapabilityServerSet::add(kj::Own&& server) { + void* ptr = reinterpret_cast(server.get()); + // Clang insists that `castAs` is a template-dependent member and therefore we need the + // `template` keyword here, but AFAICT this is wrong: addImpl() is not a template. + return addInternal(kj::mv(server), ptr).template castAs(); +} + +template +kj::Promise> CapabilityServerSet::getLocalServer( + typename T::Client& client) { + return getLocalServerInternal(client) + .then([](void* server) -> kj::Maybe { + if (server == nullptr) { + return nullptr; + } else { + return *reinterpret_cast(server); + } + }); +} + +template +struct Orphanage::GetInnerReader { + static inline kj::Own apply(typename T::Client t) { + return ClientHook::from(kj::mv(t)); + } +}; + +} // namespace capnp + +#endif // CAPNP_CAPABILITY_H_ diff --git a/phonelibs/capnp-cpp/include/capnp/common.h b/phonelibs/capnp-cpp/include/capnp/common.h new file mode 100644 index 00000000000000..3fc7a421124026 --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/common.h @@ -0,0 +1,723 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +// This file contains types which are intended to help detect incorrect usage at compile +// time, but should then be optimized down to basic primitives (usually, integers) by the +// compiler. + +#ifndef CAPNP_COMMON_H_ +#define CAPNP_COMMON_H_ + +#if defined(__GNUC__) && !defined(CAPNP_HEADER_WARNINGS) +#pragma GCC system_header +#endif + +#include +#include +#include + +#if CAPNP_DEBUG_TYPES +#include +#endif + +namespace capnp { + +#define CAPNP_VERSION_MAJOR 0 +#define CAPNP_VERSION_MINOR 6 +#define CAPNP_VERSION_MICRO 1 + +#define CAPNP_VERSION \ + (CAPNP_VERSION_MAJOR * 1000000 + CAPNP_VERSION_MINOR * 1000 + CAPNP_VERSION_MICRO) + +#ifndef CAPNP_LITE +#define CAPNP_LITE 0 +#endif + +typedef unsigned int uint; + +struct Void { + // Type used for Void fields. Using C++'s "void" type creates a bunch of issues since it behaves + // differently from other types. + + inline constexpr bool operator==(Void other) const { return true; } + inline constexpr bool operator!=(Void other) const { return false; } +}; + +static constexpr Void VOID = Void(); +// Constant value for `Void`, which is an empty struct. + +inline kj::StringPtr KJ_STRINGIFY(Void) { return "void"; } + +struct Text; +struct Data; + +enum class Kind: uint8_t { + PRIMITIVE, + BLOB, + ENUM, + STRUCT, + UNION, + INTERFACE, + LIST, + + OTHER + // Some other type which is often a type parameter to Cap'n Proto templates, but which needs + // special handling. This includes types like AnyPointer, Dynamic*, etc. +}; + +enum class Style: uint8_t { + PRIMITIVE, + POINTER, // other than struct + STRUCT, + CAPABILITY +}; + +enum class ElementSize: uint8_t { + // Size of a list element. + + VOID = 0, + BIT = 1, + BYTE = 2, + TWO_BYTES = 3, + FOUR_BYTES = 4, + EIGHT_BYTES = 5, + + POINTER = 6, + + INLINE_COMPOSITE = 7 +}; + +enum class PointerType { + // Various wire types a pointer field can take + + NULL_, + // Should be NULL, but that's #defined in stddef.h + + STRUCT, + LIST, + CAPABILITY +}; + +namespace schemas { + +template +struct EnumInfo; + +} // namespace schemas + +namespace _ { // private + +template struct Kind_; + +template <> struct Kind_ { static constexpr Kind kind = Kind::PRIMITIVE; }; +template <> struct Kind_ { static constexpr Kind kind = Kind::PRIMITIVE; }; +template <> struct Kind_ { static constexpr Kind kind = Kind::PRIMITIVE; }; +template <> struct Kind_ { static constexpr Kind kind = Kind::PRIMITIVE; }; +template <> struct Kind_ { static constexpr Kind kind = Kind::PRIMITIVE; }; +template <> struct Kind_ { static constexpr Kind kind = Kind::PRIMITIVE; }; +template <> struct Kind_ { static constexpr Kind kind = Kind::PRIMITIVE; }; +template <> struct Kind_ { static constexpr Kind kind = Kind::PRIMITIVE; }; +template <> struct Kind_ { static constexpr Kind kind = Kind::PRIMITIVE; }; +template <> struct Kind_ { static constexpr Kind kind = Kind::PRIMITIVE; }; +template <> struct Kind_ { static constexpr Kind kind = Kind::PRIMITIVE; }; +template <> struct Kind_ { static constexpr Kind kind = Kind::PRIMITIVE; }; +template <> struct Kind_ { static constexpr Kind kind = Kind::BLOB; }; +template <> struct Kind_ { static constexpr Kind kind = Kind::BLOB; }; + +template struct Kind_> { + static constexpr Kind kind = Kind::STRUCT; +}; +template struct Kind_> { + static constexpr Kind kind = Kind::INTERFACE; +}; +template struct Kind_::IsEnum>> { + static constexpr Kind kind = Kind::ENUM; +}; + +} // namespace _ (private) + +template ::kind> +inline constexpr Kind kind() { + // This overload of kind() matches types which have a Kind_ specialization. + + return k; +} + +#if _MSC_VER + +#define CAPNP_KIND(T) ::capnp::_::Kind_::kind +// Avoid constexpr methods in MSVC (it remains buggy in many situations). + +#else // _MSC_VER + +#define CAPNP_KIND(T) ::capnp::kind() +// Use this macro rather than kind() in any code which must work in MSVC. + +#endif // _MSC_VER, else + +#if !CAPNP_LITE + +template ()> +inline constexpr Style style() { + return k == Kind::PRIMITIVE || k == Kind::ENUM ? Style::PRIMITIVE + : k == Kind::STRUCT ? Style::STRUCT + : k == Kind::INTERFACE ? Style::CAPABILITY : Style::POINTER; +} + +#endif // !CAPNP_LITE + +template +struct List; + +#if _MSC_VER + +template +struct List {}; +// For some reason, without this declaration, MSVC will error out on some uses of List +// claiming that "T" -- as used in the default initializer for the second template param, "k" -- +// is not defined. I do not understand this error, but adding this empty default declaration fixes +// it. + +#endif + +template struct ListElementType_; +template struct ListElementType_> { typedef T Type; }; +template using ListElementType = typename ListElementType_::Type; + +namespace _ { // private +template struct Kind_> { + static constexpr Kind kind = Kind::LIST; +}; +} // namespace _ (private) + +template struct ReaderFor_ { typedef typename T::Reader Type; }; +template struct ReaderFor_ { typedef T Type; }; +template struct ReaderFor_ { typedef T Type; }; +template struct ReaderFor_ { typedef typename T::Client Type; }; +template using ReaderFor = typename ReaderFor_::Type; +// The type returned by List::Reader::operator[]. + +template struct BuilderFor_ { typedef typename T::Builder Type; }; +template struct BuilderFor_ { typedef T Type; }; +template struct BuilderFor_ { typedef T Type; }; +template struct BuilderFor_ { typedef typename T::Client Type; }; +template using BuilderFor = typename BuilderFor_::Type; +// The type returned by List::Builder::operator[]. + +template struct PipelineFor_ { typedef typename T::Pipeline Type;}; +template struct PipelineFor_ { typedef typename T::Client Type; }; +template using PipelineFor = typename PipelineFor_::Type; + +template struct TypeIfEnum_; +template struct TypeIfEnum_ { typedef T Type; }; + +template +using TypeIfEnum = typename TypeIfEnum_>::Type; + +template +using FromReader = typename kj::Decay::Reads; +// FromReader = MyType (for any Cap'n Proto type). + +template +using FromBuilder = typename kj::Decay::Builds; +// FromBuilder = MyType (for any Cap'n Proto type). + +template +using FromPipeline = typename kj::Decay::Pipelines; +// FromBuilder = MyType (for any Cap'n Proto type). + +template +using FromClient = typename kj::Decay::Calls; +// FromReader = MyType (for any Cap'n Proto interface type). + +template +using FromServer = typename kj::Decay::Serves; +// FromBuilder = MyType (for any Cap'n Proto interface type). + +template +struct FromAny_; + +template +struct FromAny_>> { + using Type = FromReader; +}; + +template +struct FromAny_>> { + using Type = FromBuilder; +}; + +template +struct FromAny_>> { + using Type = FromPipeline; +}; + +// Note that T::Client is covered by FromReader + +template +struct FromAny_, kj::VoidSfinae>> { + using Type = FromServer; +}; + +template +struct FromAny_::kind == Kind::PRIMITIVE || _::Kind_::kind == Kind::ENUM>> { + // TODO(msvc): Ideally the EnableIf condition would be `style() == Style::PRIMITIVE`, but MSVC + // cannot yet use style() in this constexpr context. + + using Type = kj::Decay; +}; + +template +using FromAny = typename FromAny_::Type; +// Given any Cap'n Proto value type as an input, return the Cap'n Proto base type. That is: +// +// Foo::Reader -> Foo +// Foo::Builder -> Foo +// Foo::Pipeline -> Foo +// Foo::Client -> Foo +// Own -> Foo +// uint32_t -> uint32_t + +namespace _ { // private + +template +struct PointerHelpers; + +#if _MSC_VER + +template +struct PointerHelpers {}; +// For some reason, without this declaration, MSVC will error out on some uses of PointerHelpers +// claiming that "T" -- as used in the default initializer for the second template param, "k" -- +// is not defined. I do not understand this error, but adding this empty default declaration fixes +// it. + +#endif + +} // namespace _ (private) + +struct MessageSize { + // Size of a message. Every struct type has a method `.totalSize()` that returns this. + uint64_t wordCount; + uint capCount; +}; + +// ======================================================================================= +// Raw memory types and measures + +using kj::byte; + +class word { uint64_t content KJ_UNUSED_MEMBER; KJ_DISALLOW_COPY(word); public: word() = default; }; +// word is an opaque type with size of 64 bits. This type is useful only to make pointer +// arithmetic clearer. Since the contents are private, the only way to access them is to first +// reinterpret_cast to some other pointer type. +// +// Copying is disallowed because you should always use memcpy(). Otherwise, you may run afoul of +// aliasing rules. +// +// A pointer of type word* should always be word-aligned even if won't actually be dereferenced as +// that type. + +static_assert(sizeof(byte) == 1, "uint8_t is not one byte?"); +static_assert(sizeof(word) == 8, "uint64_t is not 8 bytes?"); + +#if CAPNP_DEBUG_TYPES +// Set CAPNP_DEBUG_TYPES to 1 to use kj::Quantity for "count" types. Otherwise, plain integers are +// used. All the code should still operate exactly the same, we just lose compile-time checking. +// Note that this will also change symbol names, so it's important that the library and any clients +// be compiled with the same setting here. +// +// We disable this by default to reduce symbol name size and avoid any possibility of the compiler +// failing to fully-optimize the types, but anyone modifying Cap'n Proto itself should enable this +// during development and testing. + +namespace _ { class BitLabel; class ElementLabel; struct WirePointer; } + +template +using BitCountN = kj::Quantity(), T>, _::BitLabel>; +template +using ByteCountN = kj::Quantity(), T>, byte>; +template +using WordCountN = kj::Quantity(), T>, word>; +template +using ElementCountN = kj::Quantity(), T>, _::ElementLabel>; +template +using WirePointerCountN = kj::Quantity(), T>, _::WirePointer>; + +typedef BitCountN<8, uint8_t> BitCount8; +typedef BitCountN<16, uint16_t> BitCount16; +typedef BitCountN<32, uint32_t> BitCount32; +typedef BitCountN<64, uint64_t> BitCount64; +typedef BitCountN BitCount; + +typedef ByteCountN<8, uint8_t> ByteCount8; +typedef ByteCountN<16, uint16_t> ByteCount16; +typedef ByteCountN<32, uint32_t> ByteCount32; +typedef ByteCountN<64, uint64_t> ByteCount64; +typedef ByteCountN ByteCount; + +typedef WordCountN<8, uint8_t> WordCount8; +typedef WordCountN<16, uint16_t> WordCount16; +typedef WordCountN<32, uint32_t> WordCount32; +typedef WordCountN<64, uint64_t> WordCount64; +typedef WordCountN WordCount; + +typedef ElementCountN<8, uint8_t> ElementCount8; +typedef ElementCountN<16, uint16_t> ElementCount16; +typedef ElementCountN<32, uint32_t> ElementCount32; +typedef ElementCountN<64, uint64_t> ElementCount64; +typedef ElementCountN ElementCount; + +typedef WirePointerCountN<8, uint8_t> WirePointerCount8; +typedef WirePointerCountN<16, uint16_t> WirePointerCount16; +typedef WirePointerCountN<32, uint32_t> WirePointerCount32; +typedef WirePointerCountN<64, uint64_t> WirePointerCount64; +typedef WirePointerCountN WirePointerCount; + +template +using BitsPerElementN = decltype(BitCountN() / ElementCountN()); +template +using BytesPerElementN = decltype(ByteCountN() / ElementCountN()); +template +using WordsPerElementN = decltype(WordCountN() / ElementCountN()); +template +using PointersPerElementN = decltype(WirePointerCountN() / ElementCountN()); + +using kj::bounded; +using kj::unbound; +using kj::unboundAs; +using kj::unboundMax; +using kj::unboundMaxBits; +using kj::assertMax; +using kj::assertMaxBits; +using kj::upgradeBound; +using kj::ThrowOverflow; +using kj::assumeBits; +using kj::assumeMax; +using kj::subtractChecked; +using kj::trySubtract; + +template +inline constexpr U* operator+(U* ptr, kj::Quantity offset) { + return ptr + unbound(offset / kj::unit>()); +} +template +inline constexpr const U* operator+(const U* ptr, kj::Quantity offset) { + return ptr + unbound(offset / kj::unit>()); +} +template +inline constexpr U* operator+=(U*& ptr, kj::Quantity offset) { + return ptr = ptr + unbound(offset / kj::unit>()); +} +template +inline constexpr const U* operator+=(const U*& ptr, kj::Quantity offset) { + return ptr = ptr + unbound(offset / kj::unit>()); +} + +template +inline constexpr U* operator-(U* ptr, kj::Quantity offset) { + return ptr - unbound(offset / kj::unit>()); +} +template +inline constexpr const U* operator-(const U* ptr, kj::Quantity offset) { + return ptr - unbound(offset / kj::unit>()); +} +template +inline constexpr U* operator-=(U*& ptr, kj::Quantity offset) { + return ptr = ptr - unbound(offset / kj::unit>()); +} +template +inline constexpr const U* operator-=(const U*& ptr, kj::Quantity offset) { + return ptr = ptr - unbound(offset / kj::unit>()); +} + +constexpr auto BITS = kj::unit>(); +constexpr auto BYTES = kj::unit>(); +constexpr auto WORDS = kj::unit>(); +constexpr auto ELEMENTS = kj::unit>(); +constexpr auto POINTERS = kj::unit>(); + +constexpr auto ZERO = kj::bounded<0>(); +constexpr auto ONE = kj::bounded<1>(); + +// GCC 4.7 actually gives unused warnings on these constants in opt mode... +constexpr auto BITS_PER_BYTE KJ_UNUSED = bounded<8>() * BITS / BYTES; +constexpr auto BITS_PER_WORD KJ_UNUSED = bounded<64>() * BITS / WORDS; +constexpr auto BYTES_PER_WORD KJ_UNUSED = bounded<8>() * BYTES / WORDS; + +constexpr auto BITS_PER_POINTER KJ_UNUSED = bounded<64>() * BITS / POINTERS; +constexpr auto BYTES_PER_POINTER KJ_UNUSED = bounded<8>() * BYTES / POINTERS; +constexpr auto WORDS_PER_POINTER KJ_UNUSED = ONE * WORDS / POINTERS; + +constexpr auto POINTER_SIZE_IN_WORDS = ONE * POINTERS * WORDS_PER_POINTER; + +constexpr uint SEGMENT_WORD_COUNT_BITS = 29; // Number of words in a segment. +constexpr uint LIST_ELEMENT_COUNT_BITS = 29; // Number of elements in a list. +constexpr uint STRUCT_DATA_WORD_COUNT_BITS = 16; // Number of words in a Struct data section. +constexpr uint STRUCT_POINTER_COUNT_BITS = 16; // Number of pointers in a Struct pointer section. +constexpr uint BLOB_SIZE_BITS = 29; // Number of bytes in a blob. + +typedef WordCountN SegmentWordCount; +typedef ElementCountN ListElementCount; +typedef WordCountN StructDataWordCount; +typedef WirePointerCountN StructPointerCount; +typedef ByteCountN BlobSize; + +constexpr auto MAX_SEGMENT_WORDS = + bounded()>() * WORDS; +constexpr auto MAX_LIST_ELEMENTS = + bounded()>() * ELEMENTS; +constexpr auto MAX_STUCT_DATA_WORDS = + bounded()>() * WORDS; +constexpr auto MAX_STRUCT_POINTER_COUNT = + bounded()>() * POINTERS; + +using StructDataBitCount = decltype(WordCountN() * BITS_PER_WORD); +// Number of bits in a Struct data segment (should come out to BitCountN<22>). + +using StructDataOffset = decltype(StructDataBitCount() * (ONE * ELEMENTS / BITS)); +using StructPointerOffset = StructPointerCount; +// Type of a field offset. + +inline StructDataOffset assumeDataOffset(uint32_t offset) { + return assumeMax(MAX_STUCT_DATA_WORDS * BITS_PER_WORD * (ONE * ELEMENTS / BITS), + bounded(offset) * ELEMENTS); +} + +inline StructPointerOffset assumePointerOffset(uint32_t offset) { + return assumeMax(MAX_STRUCT_POINTER_COUNT, bounded(offset) * POINTERS); +} + +constexpr uint MAX_TEXT_SIZE = kj::maxValueForBits() - 1; +typedef kj::Quantity, byte> TextSize; +// Not including NUL terminator. + +template +inline KJ_CONSTEXPR() decltype(bounded() * BYTES / ELEMENTS) bytesPerElement() { + return bounded() * BYTES / ELEMENTS; +} + +template +inline KJ_CONSTEXPR() decltype(bounded() * BITS / ELEMENTS) bitsPerElement() { + return bounded() * BITS / ELEMENTS; +} + +template +inline constexpr kj::Quantity, T> +intervalLength(const T* a, const T* b, kj::Quantity, T>) { + return kj::assumeMax(b - a) * kj::unit, T>>(); +} + +template +inline constexpr kj::ArrayPtr arrayPtr(const U* ptr, kj::Quantity size) { + return kj::ArrayPtr(ptr, unbound(size / kj::unit>())); +} +template +inline constexpr kj::ArrayPtr arrayPtr(U* ptr, kj::Quantity size) { + return kj::ArrayPtr(ptr, unbound(size / kj::unit>())); +} + +#else + +template +using BitCountN = T; +template +using ByteCountN = T; +template +using WordCountN = T; +template +using ElementCountN = T; +template +using WirePointerCountN = T; + + +// XXX +typedef BitCountN<8, uint8_t> BitCount8; +typedef BitCountN<16, uint16_t> BitCount16; +typedef BitCountN<32, uint32_t> BitCount32; +typedef BitCountN<64, uint64_t> BitCount64; +typedef BitCountN BitCount; + +typedef ByteCountN<8, uint8_t> ByteCount8; +typedef ByteCountN<16, uint16_t> ByteCount16; +typedef ByteCountN<32, uint32_t> ByteCount32; +typedef ByteCountN<64, uint64_t> ByteCount64; +typedef ByteCountN ByteCount; + +typedef WordCountN<8, uint8_t> WordCount8; +typedef WordCountN<16, uint16_t> WordCount16; +typedef WordCountN<32, uint32_t> WordCount32; +typedef WordCountN<64, uint64_t> WordCount64; +typedef WordCountN WordCount; + +typedef ElementCountN<8, uint8_t> ElementCount8; +typedef ElementCountN<16, uint16_t> ElementCount16; +typedef ElementCountN<32, uint32_t> ElementCount32; +typedef ElementCountN<64, uint64_t> ElementCount64; +typedef ElementCountN ElementCount; + +typedef WirePointerCountN<8, uint8_t> WirePointerCount8; +typedef WirePointerCountN<16, uint16_t> WirePointerCount16; +typedef WirePointerCountN<32, uint32_t> WirePointerCount32; +typedef WirePointerCountN<64, uint64_t> WirePointerCount64; +typedef WirePointerCountN WirePointerCount; + +template +using BitsPerElementN = decltype(BitCountN() / ElementCountN()); +template +using BytesPerElementN = decltype(ByteCountN() / ElementCountN()); +template +using WordsPerElementN = decltype(WordCountN() / ElementCountN()); +template +using PointersPerElementN = decltype(WirePointerCountN() / ElementCountN()); + +using kj::ThrowOverflow; +// YYY + +template inline constexpr uint bounded() { return i; } +template inline constexpr T bounded(T i) { return i; } +template inline constexpr T unbound(T i) { return i; } + +template inline constexpr T unboundAs(U i) { return i; } + +template inline constexpr uint unboundMax(T i) { return i; } +template inline constexpr uint unboundMaxBits(T i) { return i; } + +template +inline T assertMax(T value, ErrorFunc&& func) { + if (KJ_UNLIKELY(value > newMax)) func(); + return value; +} + +template +inline T assertMax(uint newMax, T value, ErrorFunc&& func) { + if (KJ_UNLIKELY(value > newMax)) func(); + return value; +} + +template +inline T assertMaxBits(T value, ErrorFunc&& func = ErrorFunc()) { + if (KJ_UNLIKELY(value > kj::maxValueForBits())) func(); + return value; +} + +template +inline T assertMaxBits(uint bits, T value, ErrorFunc&& func = ErrorFunc()) { + if (KJ_UNLIKELY(value > (1ull << bits) - 1)) func(); + return value; +} + +template inline constexpr T upgradeBound(U i) { return i; } + +template inline constexpr T assumeBits(T i) { return i; } +template inline constexpr T assumeMax(T i) { return i; } + +template +inline auto subtractChecked(T a, U b, ErrorFunc&& errorFunc = ErrorFunc()) + -> decltype(a - b) { + if (b > a) errorFunc(); + return a - b; +} + +template +inline auto trySubtract(T a, U b) -> kj::Maybe { + if (b > a) { + return nullptr; + } else { + return a - b; + } +} + +constexpr uint BITS = 1; +constexpr uint BYTES = 1; +constexpr uint WORDS = 1; +constexpr uint ELEMENTS = 1; +constexpr uint POINTERS = 1; + +constexpr uint ZERO = 0; +constexpr uint ONE = 1; + +// GCC 4.7 actually gives unused warnings on these constants in opt mode... +constexpr uint BITS_PER_BYTE KJ_UNUSED = 8; +constexpr uint BITS_PER_WORD KJ_UNUSED = 64; +constexpr uint BYTES_PER_WORD KJ_UNUSED = 8; + +constexpr uint BITS_PER_POINTER KJ_UNUSED = 64; +constexpr uint BYTES_PER_POINTER KJ_UNUSED = 8; +constexpr uint WORDS_PER_POINTER KJ_UNUSED = 1; + +// XXX +constexpr uint POINTER_SIZE_IN_WORDS = ONE * POINTERS * WORDS_PER_POINTER; + +constexpr uint SEGMENT_WORD_COUNT_BITS = 29; // Number of words in a segment. +constexpr uint LIST_ELEMENT_COUNT_BITS = 29; // Number of elements in a list. +constexpr uint STRUCT_DATA_WORD_COUNT_BITS = 16; // Number of words in a Struct data section. +constexpr uint STRUCT_POINTER_COUNT_BITS = 16; // Number of pointers in a Struct pointer section. +constexpr uint BLOB_SIZE_BITS = 29; // Number of bytes in a blob. + +typedef WordCountN SegmentWordCount; +typedef ElementCountN ListElementCount; +typedef WordCountN StructDataWordCount; +typedef WirePointerCountN StructPointerCount; +typedef ByteCountN BlobSize; +// YYY + +constexpr auto MAX_SEGMENT_WORDS = kj::maxValueForBits(); +constexpr auto MAX_LIST_ELEMENTS = kj::maxValueForBits(); +constexpr auto MAX_STUCT_DATA_WORDS = kj::maxValueForBits(); +constexpr auto MAX_STRUCT_POINTER_COUNT = kj::maxValueForBits(); + +typedef uint StructDataBitCount; +typedef uint StructDataOffset; +typedef uint StructPointerOffset; + +inline StructDataOffset assumeDataOffset(uint32_t offset) { return offset; } +inline StructPointerOffset assumePointerOffset(uint32_t offset) { return offset; } + +constexpr uint MAX_TEXT_SIZE = kj::maxValueForBits() - 1; +typedef uint TextSize; + +template +inline KJ_CONSTEXPR() size_t bytesPerElement() { return sizeof(T); } + +template +inline KJ_CONSTEXPR() size_t bitsPerElement() { return sizeof(T) * 8; } + +template +inline constexpr ptrdiff_t intervalLength(const T* a, const T* b, uint) { + return b - a; +} + +template +inline constexpr kj::ArrayPtr arrayPtr(const U* ptr, T size) { + return kj::arrayPtr(ptr, size); +} +template +inline constexpr kj::ArrayPtr arrayPtr(U* ptr, T size) { + return kj::arrayPtr(ptr, size); +} + +#endif + +} // namespace capnp + +#endif // CAPNP_COMMON_H_ diff --git a/phonelibs/capnp-cpp/include/capnp/compat/json.capnp.h b/phonelibs/capnp-cpp/include/capnp/compat/json.capnp.h new file mode 100644 index 00000000000000..a8877e540b9f2a --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/compat/json.capnp.h @@ -0,0 +1,860 @@ +// Generated by Cap'n Proto compiler, DO NOT EDIT +// source: json.capnp + +#ifndef CAPNP_INCLUDED_8ef99297a43a5e34_ +#define CAPNP_INCLUDED_8ef99297a43a5e34_ + +#include +#if !CAPNP_LITE +#include +#endif // !CAPNP_LITE + +#if CAPNP_VERSION != 6001 +#error "Version mismatch between generated code and library headers. You must use the same version of the Cap'n Proto compiler and library." +#endif + + +namespace capnp { +namespace schemas { + +CAPNP_DECLARE_SCHEMA(8825ffaa852cda72); +CAPNP_DECLARE_SCHEMA(c27855d853a937cc); +CAPNP_DECLARE_SCHEMA(9bbf84153dd4bb60); + +} // namespace schemas +} // namespace capnp + +namespace capnp { + +struct JsonValue { + JsonValue() = delete; + + class Reader; + class Builder; + class Pipeline; + enum Which: uint16_t { + NULL_, + BOOLEAN, + NUMBER, + STRING, + ARRAY, + OBJECT, + CALL, + }; + struct Field; + struct Call; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(8825ffaa852cda72, 2, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct JsonValue::Field { + Field() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(c27855d853a937cc, 0, 2) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct JsonValue::Call { + Call() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(9bbf84153dd4bb60, 0, 2) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +// ======================================================================================= + +class JsonValue::Reader { +public: + typedef JsonValue Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline Which which() const; + inline bool isNull() const; + inline ::capnp::Void getNull() const; + + inline bool isBoolean() const; + inline bool getBoolean() const; + + inline bool isNumber() const; + inline double getNumber() const; + + inline bool isString() const; + inline bool hasString() const; + inline ::capnp::Text::Reader getString() const; + + inline bool isArray() const; + inline bool hasArray() const; + inline ::capnp::List< ::capnp::JsonValue>::Reader getArray() const; + + inline bool isObject() const; + inline bool hasObject() const; + inline ::capnp::List< ::capnp::JsonValue::Field>::Reader getObject() const; + + inline bool isCall() const; + inline bool hasCall() const; + inline ::capnp::JsonValue::Call::Reader getCall() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class JsonValue::Builder { +public: + typedef JsonValue Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline Which which(); + inline bool isNull(); + inline ::capnp::Void getNull(); + inline void setNull( ::capnp::Void value = ::capnp::VOID); + + inline bool isBoolean(); + inline bool getBoolean(); + inline void setBoolean(bool value); + + inline bool isNumber(); + inline double getNumber(); + inline void setNumber(double value); + + inline bool isString(); + inline bool hasString(); + inline ::capnp::Text::Builder getString(); + inline void setString( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initString(unsigned int size); + inline void adoptString(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownString(); + + inline bool isArray(); + inline bool hasArray(); + inline ::capnp::List< ::capnp::JsonValue>::Builder getArray(); + inline void setArray( ::capnp::List< ::capnp::JsonValue>::Reader value); + inline ::capnp::List< ::capnp::JsonValue>::Builder initArray(unsigned int size); + inline void adoptArray(::capnp::Orphan< ::capnp::List< ::capnp::JsonValue>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::capnp::JsonValue>> disownArray(); + + inline bool isObject(); + inline bool hasObject(); + inline ::capnp::List< ::capnp::JsonValue::Field>::Builder getObject(); + inline void setObject( ::capnp::List< ::capnp::JsonValue::Field>::Reader value); + inline ::capnp::List< ::capnp::JsonValue::Field>::Builder initObject(unsigned int size); + inline void adoptObject(::capnp::Orphan< ::capnp::List< ::capnp::JsonValue::Field>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::capnp::JsonValue::Field>> disownObject(); + + inline bool isCall(); + inline bool hasCall(); + inline ::capnp::JsonValue::Call::Builder getCall(); + inline void setCall( ::capnp::JsonValue::Call::Reader value); + inline ::capnp::JsonValue::Call::Builder initCall(); + inline void adoptCall(::capnp::Orphan< ::capnp::JsonValue::Call>&& value); + inline ::capnp::Orphan< ::capnp::JsonValue::Call> disownCall(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class JsonValue::Pipeline { +public: + typedef JsonValue Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class JsonValue::Field::Reader { +public: + typedef Field Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasName() const; + inline ::capnp::Text::Reader getName() const; + + inline bool hasValue() const; + inline ::capnp::JsonValue::Reader getValue() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class JsonValue::Field::Builder { +public: + typedef Field Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasName(); + inline ::capnp::Text::Builder getName(); + inline void setName( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initName(unsigned int size); + inline void adoptName(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownName(); + + inline bool hasValue(); + inline ::capnp::JsonValue::Builder getValue(); + inline void setValue( ::capnp::JsonValue::Reader value); + inline ::capnp::JsonValue::Builder initValue(); + inline void adoptValue(::capnp::Orphan< ::capnp::JsonValue>&& value); + inline ::capnp::Orphan< ::capnp::JsonValue> disownValue(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class JsonValue::Field::Pipeline { +public: + typedef Field Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::capnp::JsonValue::Pipeline getValue(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class JsonValue::Call::Reader { +public: + typedef Call Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasFunction() const; + inline ::capnp::Text::Reader getFunction() const; + + inline bool hasParams() const; + inline ::capnp::List< ::capnp::JsonValue>::Reader getParams() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class JsonValue::Call::Builder { +public: + typedef Call Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasFunction(); + inline ::capnp::Text::Builder getFunction(); + inline void setFunction( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initFunction(unsigned int size); + inline void adoptFunction(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownFunction(); + + inline bool hasParams(); + inline ::capnp::List< ::capnp::JsonValue>::Builder getParams(); + inline void setParams( ::capnp::List< ::capnp::JsonValue>::Reader value); + inline ::capnp::List< ::capnp::JsonValue>::Builder initParams(unsigned int size); + inline void adoptParams(::capnp::Orphan< ::capnp::List< ::capnp::JsonValue>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::capnp::JsonValue>> disownParams(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class JsonValue::Call::Pipeline { +public: + typedef Call Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +// ======================================================================================= + +inline ::capnp::JsonValue::Which JsonValue::Reader::which() const { + return _reader.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline ::capnp::JsonValue::Which JsonValue::Builder::which() { + return _builder.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline bool JsonValue::Reader::isNull() const { + return which() == JsonValue::NULL_; +} +inline bool JsonValue::Builder::isNull() { + return which() == JsonValue::NULL_; +} +inline ::capnp::Void JsonValue::Reader::getNull() const { + KJ_IREQUIRE((which() == JsonValue::NULL_), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::capnp::Void JsonValue::Builder::getNull() { + KJ_IREQUIRE((which() == JsonValue::NULL_), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void JsonValue::Builder::setNull( ::capnp::Void value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, JsonValue::NULL_); + _builder.setDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool JsonValue::Reader::isBoolean() const { + return which() == JsonValue::BOOLEAN; +} +inline bool JsonValue::Builder::isBoolean() { + return which() == JsonValue::BOOLEAN; +} +inline bool JsonValue::Reader::getBoolean() const { + KJ_IREQUIRE((which() == JsonValue::BOOLEAN), + "Must check which() before get()ing a union member."); + return _reader.getDataField( + ::capnp::bounded<16>() * ::capnp::ELEMENTS); +} + +inline bool JsonValue::Builder::getBoolean() { + KJ_IREQUIRE((which() == JsonValue::BOOLEAN), + "Must check which() before get()ing a union member."); + return _builder.getDataField( + ::capnp::bounded<16>() * ::capnp::ELEMENTS); +} +inline void JsonValue::Builder::setBoolean(bool value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, JsonValue::BOOLEAN); + _builder.setDataField( + ::capnp::bounded<16>() * ::capnp::ELEMENTS, value); +} + +inline bool JsonValue::Reader::isNumber() const { + return which() == JsonValue::NUMBER; +} +inline bool JsonValue::Builder::isNumber() { + return which() == JsonValue::NUMBER; +} +inline double JsonValue::Reader::getNumber() const { + KJ_IREQUIRE((which() == JsonValue::NUMBER), + "Must check which() before get()ing a union member."); + return _reader.getDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline double JsonValue::Builder::getNumber() { + KJ_IREQUIRE((which() == JsonValue::NUMBER), + "Must check which() before get()ing a union member."); + return _builder.getDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void JsonValue::Builder::setNumber(double value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, JsonValue::NUMBER); + _builder.setDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline bool JsonValue::Reader::isString() const { + return which() == JsonValue::STRING; +} +inline bool JsonValue::Builder::isString() { + return which() == JsonValue::STRING; +} +inline bool JsonValue::Reader::hasString() const { + if (which() != JsonValue::STRING) return false; + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool JsonValue::Builder::hasString() { + if (which() != JsonValue::STRING) return false; + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader JsonValue::Reader::getString() const { + KJ_IREQUIRE((which() == JsonValue::STRING), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder JsonValue::Builder::getString() { + KJ_IREQUIRE((which() == JsonValue::STRING), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void JsonValue::Builder::setString( ::capnp::Text::Reader value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, JsonValue::STRING); + ::capnp::_::PointerHelpers< ::capnp::Text>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder JsonValue::Builder::initString(unsigned int size) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, JsonValue::STRING); + return ::capnp::_::PointerHelpers< ::capnp::Text>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), size); +} +inline void JsonValue::Builder::adoptString( + ::capnp::Orphan< ::capnp::Text>&& value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, JsonValue::STRING); + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> JsonValue::Builder::disownString() { + KJ_IREQUIRE((which() == JsonValue::STRING), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool JsonValue::Reader::isArray() const { + return which() == JsonValue::ARRAY; +} +inline bool JsonValue::Builder::isArray() { + return which() == JsonValue::ARRAY; +} +inline bool JsonValue::Reader::hasArray() const { + if (which() != JsonValue::ARRAY) return false; + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool JsonValue::Builder::hasArray() { + if (which() != JsonValue::ARRAY) return false; + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::capnp::JsonValue>::Reader JsonValue::Reader::getArray() const { + KJ_IREQUIRE((which() == JsonValue::ARRAY), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::JsonValue>>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::capnp::JsonValue>::Builder JsonValue::Builder::getArray() { + KJ_IREQUIRE((which() == JsonValue::ARRAY), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::JsonValue>>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void JsonValue::Builder::setArray( ::capnp::List< ::capnp::JsonValue>::Reader value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, JsonValue::ARRAY); + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::JsonValue>>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::capnp::JsonValue>::Builder JsonValue::Builder::initArray(unsigned int size) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, JsonValue::ARRAY); + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::JsonValue>>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), size); +} +inline void JsonValue::Builder::adoptArray( + ::capnp::Orphan< ::capnp::List< ::capnp::JsonValue>>&& value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, JsonValue::ARRAY); + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::JsonValue>>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::capnp::JsonValue>> JsonValue::Builder::disownArray() { + KJ_IREQUIRE((which() == JsonValue::ARRAY), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::JsonValue>>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool JsonValue::Reader::isObject() const { + return which() == JsonValue::OBJECT; +} +inline bool JsonValue::Builder::isObject() { + return which() == JsonValue::OBJECT; +} +inline bool JsonValue::Reader::hasObject() const { + if (which() != JsonValue::OBJECT) return false; + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool JsonValue::Builder::hasObject() { + if (which() != JsonValue::OBJECT) return false; + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::capnp::JsonValue::Field>::Reader JsonValue::Reader::getObject() const { + KJ_IREQUIRE((which() == JsonValue::OBJECT), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::JsonValue::Field>>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::capnp::JsonValue::Field>::Builder JsonValue::Builder::getObject() { + KJ_IREQUIRE((which() == JsonValue::OBJECT), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::JsonValue::Field>>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void JsonValue::Builder::setObject( ::capnp::List< ::capnp::JsonValue::Field>::Reader value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, JsonValue::OBJECT); + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::JsonValue::Field>>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::capnp::JsonValue::Field>::Builder JsonValue::Builder::initObject(unsigned int size) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, JsonValue::OBJECT); + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::JsonValue::Field>>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), size); +} +inline void JsonValue::Builder::adoptObject( + ::capnp::Orphan< ::capnp::List< ::capnp::JsonValue::Field>>&& value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, JsonValue::OBJECT); + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::JsonValue::Field>>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::capnp::JsonValue::Field>> JsonValue::Builder::disownObject() { + KJ_IREQUIRE((which() == JsonValue::OBJECT), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::JsonValue::Field>>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool JsonValue::Reader::isCall() const { + return which() == JsonValue::CALL; +} +inline bool JsonValue::Builder::isCall() { + return which() == JsonValue::CALL; +} +inline bool JsonValue::Reader::hasCall() const { + if (which() != JsonValue::CALL) return false; + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool JsonValue::Builder::hasCall() { + if (which() != JsonValue::CALL) return false; + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::JsonValue::Call::Reader JsonValue::Reader::getCall() const { + KJ_IREQUIRE((which() == JsonValue::CALL), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::JsonValue::Call>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::JsonValue::Call::Builder JsonValue::Builder::getCall() { + KJ_IREQUIRE((which() == JsonValue::CALL), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::JsonValue::Call>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void JsonValue::Builder::setCall( ::capnp::JsonValue::Call::Reader value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, JsonValue::CALL); + ::capnp::_::PointerHelpers< ::capnp::JsonValue::Call>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::JsonValue::Call::Builder JsonValue::Builder::initCall() { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, JsonValue::CALL); + return ::capnp::_::PointerHelpers< ::capnp::JsonValue::Call>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void JsonValue::Builder::adoptCall( + ::capnp::Orphan< ::capnp::JsonValue::Call>&& value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, JsonValue::CALL); + ::capnp::_::PointerHelpers< ::capnp::JsonValue::Call>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::JsonValue::Call> JsonValue::Builder::disownCall() { + KJ_IREQUIRE((which() == JsonValue::CALL), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::JsonValue::Call>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool JsonValue::Field::Reader::hasName() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool JsonValue::Field::Builder::hasName() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader JsonValue::Field::Reader::getName() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder JsonValue::Field::Builder::getName() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void JsonValue::Field::Builder::setName( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder JsonValue::Field::Builder::initName(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), size); +} +inline void JsonValue::Field::Builder::adoptName( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> JsonValue::Field::Builder::disownName() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool JsonValue::Field::Reader::hasValue() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool JsonValue::Field::Builder::hasValue() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::JsonValue::Reader JsonValue::Field::Reader::getValue() const { + return ::capnp::_::PointerHelpers< ::capnp::JsonValue>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::JsonValue::Builder JsonValue::Field::Builder::getValue() { + return ::capnp::_::PointerHelpers< ::capnp::JsonValue>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::capnp::JsonValue::Pipeline JsonValue::Field::Pipeline::getValue() { + return ::capnp::JsonValue::Pipeline(_typeless.getPointerField(1)); +} +#endif // !CAPNP_LITE +inline void JsonValue::Field::Builder::setValue( ::capnp::JsonValue::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::JsonValue>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::JsonValue::Builder JsonValue::Field::Builder::initValue() { + return ::capnp::_::PointerHelpers< ::capnp::JsonValue>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void JsonValue::Field::Builder::adoptValue( + ::capnp::Orphan< ::capnp::JsonValue>&& value) { + ::capnp::_::PointerHelpers< ::capnp::JsonValue>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::JsonValue> JsonValue::Field::Builder::disownValue() { + return ::capnp::_::PointerHelpers< ::capnp::JsonValue>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline bool JsonValue::Call::Reader::hasFunction() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool JsonValue::Call::Builder::hasFunction() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader JsonValue::Call::Reader::getFunction() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder JsonValue::Call::Builder::getFunction() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void JsonValue::Call::Builder::setFunction( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder JsonValue::Call::Builder::initFunction(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), size); +} +inline void JsonValue::Call::Builder::adoptFunction( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> JsonValue::Call::Builder::disownFunction() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool JsonValue::Call::Reader::hasParams() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool JsonValue::Call::Builder::hasParams() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::capnp::JsonValue>::Reader JsonValue::Call::Reader::getParams() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::JsonValue>>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::capnp::JsonValue>::Builder JsonValue::Call::Builder::getParams() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::JsonValue>>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void JsonValue::Call::Builder::setParams( ::capnp::List< ::capnp::JsonValue>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::JsonValue>>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::capnp::JsonValue>::Builder JsonValue::Call::Builder::initParams(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::JsonValue>>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), size); +} +inline void JsonValue::Call::Builder::adoptParams( + ::capnp::Orphan< ::capnp::List< ::capnp::JsonValue>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::JsonValue>>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::capnp::JsonValue>> JsonValue::Call::Builder::disownParams() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::JsonValue>>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +} // namespace + +#endif // CAPNP_INCLUDED_8ef99297a43a5e34_ diff --git a/phonelibs/capnp-cpp/include/capnp/compat/json.h b/phonelibs/capnp-cpp/include/capnp/compat/json.h new file mode 100644 index 00000000000000..7fa815e0998e9e --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/compat/json.h @@ -0,0 +1,462 @@ +// Copyright (c) 2015 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef CAPNP_COMPAT_JSON_H_ +#define CAPNP_COMPAT_JSON_H_ + +#include +#include +#include + +namespace capnp { + +class JsonCodec { + // Flexible class for encoding Cap'n Proto types as JSON, and decoding JSON back to Cap'n Proto. + // + // Typical usage: + // + // JsonCodec json; + // + // // encode + // kj::String encoded = json.encode(someStructReader); + // + // // decode + // json.decode(encoded, someStructBuilder); + // + // Advanced users can do fancy things like override the way certain types or fields are + // represented in JSON by registering handlers. See the unit test for an example. + // + // Notes: + // - When encoding, all primitive fields are always encoded, even if default-valued. Pointer + // fields are only encoded if they are non-null. + // - 64-bit integers are encoded as strings, since JSON "numbers" are double-precision floating + // points which cannot store a 64-bit integer without losing data. + // - NaNs and infinite floating point numbers are not allowed by the JSON spec, and so are encoded + // as null. This matches the behavior of `JSON.stringify` in at least Firefox and Chrome. + // - Data is encoded as an array of numbers in the range [0,255]. You probably want to register + // a handler that does something better, like maybe base64 encoding, but there are a zillion + // different ways people do this. + // - Encoding/decoding capabilities and AnyPointers requires registering a Handler, since there's + // no obvious default behavior. + // - When decoding, unrecognized field names are ignored. Note: This means that JSON is NOT a + // good format for receiving input from a human. Consider `capnp eval` or the SchemaParser + // library for human input. + +public: + JsonCodec(); + ~JsonCodec() noexcept(false); + + // --------------------------------------------------------------------------- + // standard API + + void setPrettyPrint(bool enabled); + // Enable to insert newlines, indentation, and other extra spacing into the output. The default + // is to use minimal whitespace. + + void setMaxNestingDepth(size_t maxNestingDepth); + // Set maximum nesting depth when decoding JSON to prevent highly nested input from overflowing + // the call stack. The default is 64. + + template + kj::String encode(T&& value); + // Encode any Cap'n Proto value to JSON, including primitives and + // Dynamic{Enum,Struct,List,Capability}, but not DynamicValue (see below). + + kj::String encode(DynamicValue::Reader value, Type type) const; + // Encode a DynamicValue to JSON. `type` is needed because `DynamicValue` itself does + // not distinguish between e.g. int32 and int64, which in JSON are handled differently. Most + // of the time, though, you can use the single-argument templated version of `encode()` instead. + + void decode(kj::ArrayPtr input, DynamicStruct::Builder output) const; + // Decode JSON text directly into a struct builder. This only works for structs since lists + // need to be allocated with the correct size in advance. + // + // (Remember that any Cap'n Proto struct reader type can be implicitly cast to + // DynamicStruct::Reader.) + + template + Orphan decode(kj::ArrayPtr input, Orphanage orphanage) const; + // Decode JSON text to any Cap'n Proto object (pointer value), allocated using the given + // orphanage. T must be specified explicitly and cannot be dynamic, e.g.: + // + // Orphan orphan = json.decode(text, orphanage); + + template + ReaderFor decode(kj::ArrayPtr input) const; + // Decode JSON text into a primitive or capability value. T must be specified explicitly and + // cannot be dynamic, e.g.: + // + // uint32_t n = json.decode(text); + + Orphan decode(kj::ArrayPtr input, Type type, Orphanage orphanage) const; + Orphan decode( + kj::ArrayPtr input, ListSchema type, Orphanage orphanage) const; + Orphan decode( + kj::ArrayPtr input, StructSchema type, Orphanage orphanage) const; + DynamicCapability::Client decode(kj::ArrayPtr input, InterfaceSchema type) const; + DynamicEnum decode(kj::ArrayPtr input, EnumSchema type) const; + // Decode to a dynamic value, specifying the type schema. + + // --------------------------------------------------------------------------- + // layered API + // + // You can separate text <-> JsonValue from JsonValue <-> T. These are particularly useful + // for calling from Handler implementations. + + kj::String encodeRaw(JsonValue::Reader value) const; + void decodeRaw(kj::ArrayPtr input, JsonValue::Builder output) const; + // Translate JsonValue <-> text. + + template + void encode(T&& value, JsonValue::Builder output); + void encode(DynamicValue::Reader input, Type type, JsonValue::Builder output) const; + void decode(JsonValue::Reader input, DynamicStruct::Builder output) const; + template + Orphan decode(JsonValue::Reader input, Orphanage orphanage) const; + template + ReaderFor decode(JsonValue::Reader input) const; + + Orphan decode(JsonValue::Reader input, Type type, Orphanage orphanage) const; + Orphan decode(JsonValue::Reader input, ListSchema type, Orphanage orphanage) const; + Orphan decode( + JsonValue::Reader input, StructSchema type, Orphanage orphanage) const; + DynamicCapability::Client decode(JsonValue::Reader input, InterfaceSchema type) const; + DynamicEnum decode(JsonValue::Reader input, EnumSchema type) const; + + // --------------------------------------------------------------------------- + // specializing particular types + + template ()> + class Handler; + // Implement this interface to specify a special encoding for a particular type or field. + // + // The templates are a bit ugly, but subclasses of this type essentially implement two methods, + // one to encode values of this type and one to decode values of this type. `encode()` is simple: + // + // void encode(const JsonCodec& codec, ReaderFor input, JsonValue::Builder output) const; + // + // `decode()` is a bit trickier. When T is a struct (including DynamicStruct), it is: + // + // void decode(const JsonCodec& codec, JsonValue::Reader input, BuilderFor output) const; + // + // However, when T is a primitive, decode() is: + // + // T decode(const JsonCodec& codec, JsonValue::Reader input) const; + // + // Or when T is any non-struct object (list, blob), decode() is: + // + // Orphan decode(const JsonCodec& codec, JsonValue::Reader input, Orphanage orphanage) const; + // + // Or when T is an interface: + // + // T::Client decode(const JsonCodec& codec, JsonValue::Reader input) const; + // + // Additionally, when T is a struct you can *optionally* also implement the orphan-returning form + // of decode(), but it will only be called when the struct would be allocated as an individual + // object, not as part of a list. This allows you to return "nullptr" in these cases to say that + // the pointer value should be null. This does not apply to list elements because struct list + // elements cannot ever be null (since Cap'n Proto encodes struct lists as a flat list rather + // than list-of-pointers). + + template + void addTypeHandler(Handler& handler); + void addTypeHandler(Type type, Handler& handler); + void addTypeHandler(EnumSchema type, Handler& handler); + void addTypeHandler(StructSchema type, Handler& handler); + void addTypeHandler(ListSchema type, Handler& handler); + void addTypeHandler(InterfaceSchema type, Handler& handler); + // Arrange that whenever the type T appears in the message, your handler will be used to + // encode/decode it. + // + // Note that if you register a handler for a capability type, it will also apply to subtypes. + // Thus Handler handles all capabilities. + + template + void addFieldHandler(StructSchema::Field field, Handler& handler); + // Matches only the specific field. T can be a dynamic type. T must match the field's type. + +private: + class HandlerBase; + struct Impl; + + kj::Own impl; + + void encodeField(StructSchema::Field field, DynamicValue::Reader input, + JsonValue::Builder output) const; + void decodeArray(List::Reader input, DynamicList::Builder output) const; + void decodeObject(List::Reader input, DynamicStruct::Builder output) const; + void addTypeHandlerImpl(Type type, HandlerBase& handler); + void addFieldHandlerImpl(StructSchema::Field field, Type type, HandlerBase& handler); +}; + +// ======================================================================================= +// inline implementation details + +template +kj::String JsonCodec::encode(T&& value) { + typedef FromAny> Base; + return encode(DynamicValue::Reader(ReaderFor(kj::fwd(value))), Type::from()); +} + +template +inline Orphan JsonCodec::decode(kj::ArrayPtr input, Orphanage orphanage) const { + return decode(input, Type::from(), orphanage).template releaseAs(); +} + +template +inline ReaderFor JsonCodec::decode(kj::ArrayPtr input) const { + static_assert(style() == Style::PRIMITIVE || style() == Style::CAPABILITY, + "must specify an orphanage to decode an object type"); + return decode(input, Type::from(), Orphanage()).getReader().template as(); +} + +inline Orphan JsonCodec::decode( + kj::ArrayPtr input, ListSchema type, Orphanage orphanage) const { + return decode(input, Type(type), orphanage).releaseAs(); +} +inline Orphan JsonCodec::decode( + kj::ArrayPtr input, StructSchema type, Orphanage orphanage) const { + return decode(input, Type(type), orphanage).releaseAs(); +} +inline DynamicCapability::Client JsonCodec::decode( + kj::ArrayPtr input, InterfaceSchema type) const { + return decode(input, Type(type), Orphanage()).getReader().as(); +} +inline DynamicEnum JsonCodec::decode(kj::ArrayPtr input, EnumSchema type) const { + return decode(input, Type(type), Orphanage()).getReader().as(); +} + +// ----------------------------------------------------------------------------- + +template +void JsonCodec::encode(T&& value, JsonValue::Builder output) { + typedef FromAny> Base; + encode(DynamicValue::Reader(ReaderFor(kj::fwd(value))), Type::from(), output); +} + +template +inline Orphan JsonCodec::decode(JsonValue::Reader input, Orphanage orphanage) const { + return decode(input, Type::from(), orphanage).template releaseAs(); +} + +template +inline ReaderFor JsonCodec::decode(JsonValue::Reader input) const { + static_assert(style() == Style::PRIMITIVE || style() == Style::CAPABILITY, + "must specify an orphanage to decode an object type"); + return decode(input, Type::from(), Orphanage()).getReader().template as(); +} + +inline Orphan JsonCodec::decode( + JsonValue::Reader input, ListSchema type, Orphanage orphanage) const { + return decode(input, Type(type), orphanage).releaseAs(); +} +inline Orphan JsonCodec::decode( + JsonValue::Reader input, StructSchema type, Orphanage orphanage) const { + return decode(input, Type(type), orphanage).releaseAs(); +} +inline DynamicCapability::Client JsonCodec::decode( + JsonValue::Reader input, InterfaceSchema type) const { + return decode(input, Type(type), Orphanage()).getReader().as(); +} +inline DynamicEnum JsonCodec::decode(JsonValue::Reader input, EnumSchema type) const { + return decode(input, Type(type), Orphanage()).getReader().as(); +} + +// ----------------------------------------------------------------------------- + +class JsonCodec::HandlerBase { + // Internal helper; ignore. +public: + virtual void encodeBase(const JsonCodec& codec, DynamicValue::Reader input, + JsonValue::Builder output) const = 0; + virtual Orphan decodeBase(const JsonCodec& codec, JsonValue::Reader input, + Type type, Orphanage orphanage) const; + virtual void decodeStructBase(const JsonCodec& codec, JsonValue::Reader input, + DynamicStruct::Builder output) const; +}; + +template +class JsonCodec::Handler: private JsonCodec::HandlerBase { +public: + virtual void encode(const JsonCodec& codec, ReaderFor input, + JsonValue::Builder output) const = 0; + virtual Orphan decode(const JsonCodec& codec, JsonValue::Reader input, + Orphanage orphanage) const = 0; + +private: + void encodeBase(const JsonCodec& codec, DynamicValue::Reader input, + JsonValue::Builder output) const override final { + encode(codec, input.as(), output); + } + Orphan decodeBase(const JsonCodec& codec, JsonValue::Reader input, + Type type, Orphanage orphanage) const override final { + return decode(codec, input, orphanage); + } + friend class JsonCodec; +}; + +template +class JsonCodec::Handler: private JsonCodec::HandlerBase { +public: + virtual void encode(const JsonCodec& codec, ReaderFor input, + JsonValue::Builder output) const = 0; + virtual void decode(const JsonCodec& codec, JsonValue::Reader input, + BuilderFor output) const = 0; + virtual Orphan decode(const JsonCodec& codec, JsonValue::Reader input, + Orphanage orphanage) const { + // If subclass does not override, fall back to regular version. + auto result = orphanage.newOrphan(); + decode(codec, input, result.get()); + return result; + } + +private: + void encodeBase(const JsonCodec& codec, DynamicValue::Reader input, + JsonValue::Builder output) const override final { + encode(codec, input.as(), output); + } + Orphan decodeBase(const JsonCodec& codec, JsonValue::Reader input, + Type type, Orphanage orphanage) const override final { + return decode(codec, input, orphanage); + } + void decodeStructBase(const JsonCodec& codec, JsonValue::Reader input, + DynamicStruct::Builder output) const override final { + decode(codec, input, output.as()); + } + friend class JsonCodec; +}; + +template <> +class JsonCodec::Handler: private JsonCodec::HandlerBase { + // Almost identical to Style::STRUCT except that we pass the struct type to decode(). + +public: + virtual void encode(const JsonCodec& codec, DynamicStruct::Reader input, + JsonValue::Builder output) const = 0; + virtual void decode(const JsonCodec& codec, JsonValue::Reader input, + DynamicStruct::Builder output) const = 0; + virtual Orphan decode(const JsonCodec& codec, JsonValue::Reader input, + StructSchema type, Orphanage orphanage) const { + // If subclass does not override, fall back to regular version. + auto result = orphanage.newOrphan(type); + decode(codec, input, result.get()); + return result; + } + +private: + void encodeBase(const JsonCodec& codec, DynamicValue::Reader input, + JsonValue::Builder output) const override final { + encode(codec, input.as(), output); + } + Orphan decodeBase(const JsonCodec& codec, JsonValue::Reader input, + Type type, Orphanage orphanage) const override final { + return decode(codec, input, type.asStruct(), orphanage); + } + void decodeStructBase(const JsonCodec& codec, JsonValue::Reader input, + DynamicStruct::Builder output) const override final { + decode(codec, input, output.as()); + } + friend class JsonCodec; +}; + +template +class JsonCodec::Handler: private JsonCodec::HandlerBase { +public: + virtual void encode(const JsonCodec& codec, T input, JsonValue::Builder output) const = 0; + virtual T decode(const JsonCodec& codec, JsonValue::Reader input) const = 0; + +private: + void encodeBase(const JsonCodec& codec, DynamicValue::Reader input, + JsonValue::Builder output) const override final { + encode(codec, input.as(), output); + } + Orphan decodeBase(const JsonCodec& codec, JsonValue::Reader input, + Type type, Orphanage orphanage) const override final { + return decode(codec, input); + } + friend class JsonCodec; +}; + +template +class JsonCodec::Handler: private JsonCodec::HandlerBase { +public: + virtual void encode(const JsonCodec& codec, typename T::Client input, + JsonValue::Builder output) const = 0; + virtual typename T::Client decode(const JsonCodec& codec, JsonValue::Reader input) const = 0; + +private: + void encodeBase(const JsonCodec& codec, DynamicValue::Reader input, + JsonValue::Builder output) const override final { + encode(codec, input.as(), output); + } + Orphan decodeBase(const JsonCodec& codec, JsonValue::Reader input, + Type type, Orphanage orphanage) const override final { + return orphanage.newOrphanCopy(decode(codec, input)); + } + friend class JsonCodec; +}; + +template +inline void JsonCodec::addTypeHandler(Handler& handler) { + addTypeHandlerImpl(Type::from(), handler); +} +inline void JsonCodec::addTypeHandler(Type type, Handler& handler) { + addTypeHandlerImpl(type, handler); +} +inline void JsonCodec::addTypeHandler(EnumSchema type, Handler& handler) { + addTypeHandlerImpl(type, handler); +} +inline void JsonCodec::addTypeHandler(StructSchema type, Handler& handler) { + addTypeHandlerImpl(type, handler); +} +inline void JsonCodec::addTypeHandler(ListSchema type, Handler& handler) { + addTypeHandlerImpl(type, handler); +} +inline void JsonCodec::addTypeHandler(InterfaceSchema type, Handler& handler) { + addTypeHandlerImpl(type, handler); +} + +template +inline void JsonCodec::addFieldHandler(StructSchema::Field field, Handler& handler) { + addFieldHandlerImpl(field, Type::from(), handler); +} + +template <> void JsonCodec::addTypeHandler(Handler& handler) + KJ_UNAVAILABLE("JSON handlers for type sets (e.g. all structs, all lists) not implemented; " + "try specifying a specific type schema as the first parameter"); +template <> void JsonCodec::addTypeHandler(Handler& handler) + KJ_UNAVAILABLE("JSON handlers for type sets (e.g. all structs, all lists) not implemented; " + "try specifying a specific type schema as the first parameter"); +template <> void JsonCodec::addTypeHandler(Handler& handler) + KJ_UNAVAILABLE("JSON handlers for type sets (e.g. all structs, all lists) not implemented; " + "try specifying a specific type schema as the first parameter"); +template <> void JsonCodec::addTypeHandler(Handler& handler) + KJ_UNAVAILABLE("JSON handlers for type sets (e.g. all structs, all lists) not implemented; " + "try specifying a specific type schema as the first parameter"); +template <> void JsonCodec::addTypeHandler(Handler& handler) + KJ_UNAVAILABLE("JSON handlers for type sets (e.g. all structs, all lists) not implemented; " + "try specifying a specific type schema as the first parameter"); +// TODO(someday): Implement support for registering handlers that cover thinsg like "all structs" +// or "all lists". Currently you can only target a specific struct or list type. + +} // namespace capnp + +#endif // CAPNP_COMPAT_JSON_H_ diff --git a/phonelibs/capnp-cpp/include/capnp/dynamic.h b/phonelibs/capnp-cpp/include/capnp/dynamic.h new file mode 100644 index 00000000000000..fcefcc3bf2fee9 --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/dynamic.h @@ -0,0 +1,1643 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +// This file defines classes that can be used to manipulate messages based on schemas that are not +// known until runtime. This is also useful for writing generic code that uses schemas to handle +// arbitrary types in a generic way. +// +// Each of the classes defined here has a to() template method which converts an instance back to a +// native type. This method will throw an exception if the requested type does not match the +// schema. To convert native types to dynamic, use DynamicFactory. +// +// As always, underlying data is validated lazily, so you have to actually traverse the whole +// message if you want to validate all content. + +#ifndef CAPNP_DYNAMIC_H_ +#define CAPNP_DYNAMIC_H_ + +#if defined(__GNUC__) && !defined(CAPNP_HEADER_WARNINGS) +#pragma GCC system_header +#endif + +#include "schema.h" +#include "layout.h" +#include "message.h" +#include "any.h" +#include "capability.h" + +namespace capnp { + +class MessageReader; +class MessageBuilder; + +struct DynamicValue { + DynamicValue() = delete; + + enum Type { + UNKNOWN, + // Means that the value has unknown type and content because it comes from a newer version of + // the schema, or from a newer version of Cap'n Proto that has new features that this version + // doesn't understand. + + VOID, + BOOL, + INT, + UINT, + FLOAT, + TEXT, + DATA, + LIST, + ENUM, + STRUCT, + CAPABILITY, + ANY_POINTER + }; + + class Reader; + class Builder; + class Pipeline; +}; +class DynamicEnum; +struct DynamicStruct { + DynamicStruct() = delete; + class Reader; + class Builder; + class Pipeline; +}; +struct DynamicList { + DynamicList() = delete; + class Reader; + class Builder; +}; +struct DynamicCapability { + DynamicCapability() = delete; + class Client; + class Server; +}; +template <> class Orphan; + +template struct DynamicTypeFor_; +template <> struct DynamicTypeFor_ { typedef DynamicEnum Type; }; +template <> struct DynamicTypeFor_ { typedef DynamicStruct Type; }; +template <> struct DynamicTypeFor_ { typedef DynamicList Type; }; +template <> struct DynamicTypeFor_ { typedef DynamicCapability Type; }; + +template +using DynamicTypeFor = typename DynamicTypeFor_()>::Type; + +template +ReaderFor>> toDynamic(T&& value); +template +BuilderFor>> toDynamic(T&& value); +template +DynamicTypeFor> toDynamic(T&& value); +template +typename DynamicTypeFor>::Client toDynamic(kj::Own&& value); + +namespace _ { // private + +template <> struct Kind_ { static constexpr Kind kind = Kind::OTHER; }; +template <> struct Kind_ { static constexpr Kind kind = Kind::OTHER; }; +template <> struct Kind_ { static constexpr Kind kind = Kind::OTHER; }; +template <> struct Kind_ { static constexpr Kind kind = Kind::OTHER; }; +template <> struct Kind_ { static constexpr Kind kind = Kind::OTHER; }; + +} // namespace _ (private) + +template <> inline constexpr Style style() { return Style::POINTER; } +template <> inline constexpr Style style() { return Style::PRIMITIVE; } +template <> inline constexpr Style style() { return Style::STRUCT; } +template <> inline constexpr Style style() { return Style::POINTER; } +template <> inline constexpr Style style() { return Style::CAPABILITY; } + +// ------------------------------------------------------------------- + +class DynamicEnum { +public: + DynamicEnum() = default; + inline DynamicEnum(EnumSchema::Enumerant enumerant) + : schema(enumerant.getContainingEnum()), value(enumerant.getOrdinal()) {} + inline DynamicEnum(EnumSchema schema, uint16_t value) + : schema(schema), value(value) {} + + template () == Kind::ENUM>> + inline DynamicEnum(T&& value): DynamicEnum(toDynamic(value)) {} + + template + inline T as() const { return static_cast(asImpl(typeId())); } + // Cast to a native enum type. + + inline EnumSchema getSchema() const { return schema; } + + kj::Maybe getEnumerant() const; + // Get which enumerant this enum value represents. Returns nullptr if the numeric value does not + // correspond to any enumerant in the schema -- this can happen if the data was built using a + // newer schema that has more values defined. + + inline uint16_t getRaw() const { return value; } + // Returns the raw underlying enum value. + +private: + EnumSchema schema; + uint16_t value; + + uint16_t asImpl(uint64_t requestedTypeId) const; + + friend struct DynamicStruct; + friend struct DynamicList; + friend struct DynamicValue; + template + friend DynamicTypeFor> toDynamic(T&& value); +}; + +// ------------------------------------------------------------------- + +class DynamicStruct::Reader { +public: + typedef DynamicStruct Reads; + + Reader() = default; + + template >() == Kind::STRUCT>> + inline Reader(T&& value): Reader(toDynamic(value)) {} + + inline MessageSize totalSize() const { return reader.totalSize().asPublic(); } + + template + typename T::Reader as() const; + // Convert the dynamic struct to its compiled-in type. + + inline StructSchema getSchema() const { return schema; } + + DynamicValue::Reader get(StructSchema::Field field) const; + // Read the given field value. + + bool has(StructSchema::Field field) const; + // Tests whether the given field is set to its default value. For pointer values, this does + // not actually traverse the value comparing it with the default, but simply returns true if the + // pointer is non-null. For members of unions, has() returns false if the union member is not + // active, but does not necessarily return true if the member is active (depends on the field's + // value). + + kj::Maybe which() const; + // If the struct contains an (unnamed) union, and the currently-active field within that union + // is known, this returns that field. Otherwise, it returns null. In other words, this returns + // null if there is no union present _or_ if the union's discriminant is set to an unrecognized + // value. This could happen in particular when receiving a message from a sender who has a + // newer version of the protocol and is using a field of the union that you don't know about yet. + + DynamicValue::Reader get(kj::StringPtr name) const; + bool has(kj::StringPtr name) const; + // Shortcuts to access fields by name. These throw exceptions if no such field exists. + +private: + StructSchema schema; + _::StructReader reader; + + inline Reader(StructSchema schema, _::StructReader reader) + : schema(schema), reader(reader) {} + Reader(StructSchema schema, const _::OrphanBuilder& orphan); + + bool isSetInUnion(StructSchema::Field field) const; + void verifySetInUnion(StructSchema::Field field) const; + static DynamicValue::Reader getImpl(_::StructReader reader, StructSchema::Field field); + + template + friend struct _::PointerHelpers; + friend class DynamicStruct::Builder; + friend struct DynamicList; + friend class MessageReader; + friend class MessageBuilder; + template + friend struct ::capnp::ToDynamic_; + friend kj::StringTree _::structString( + _::StructReader reader, const _::RawBrandedSchema& schema); + friend class Orphanage; + friend class Orphan; + friend class Orphan; + friend class Orphan; +}; + +class DynamicStruct::Builder { +public: + typedef DynamicStruct Builds; + + Builder() = default; + inline Builder(decltype(nullptr)) {} + + template >() == Kind::STRUCT>> + inline Builder(T&& value): Builder(toDynamic(value)) {} + + inline MessageSize totalSize() const { return asReader().totalSize(); } + + template + typename T::Builder as(); + // Cast to a particular struct type. + + inline StructSchema getSchema() const { return schema; } + + DynamicValue::Builder get(StructSchema::Field field); + // Read the given field value. + + inline bool has(StructSchema::Field field) { return asReader().has(field); } + // Tests whether the given field is set to its default value. For pointer values, this does + // not actually traverse the value comparing it with the default, but simply returns true if the + // pointer is non-null. For members of unions, has() returns whether the field is currently + // active and the union as a whole is non-default -- so, the only time has() will return false + // for an active union field is if it is the default active field and it has its default value. + + kj::Maybe which(); + // If the struct contains an (unnamed) union, and the currently-active field within that union + // is known, this returns that field. Otherwise, it returns null. In other words, this returns + // null if there is no union present _or_ if the union's discriminant is set to an unrecognized + // value. This could happen in particular when receiving a message from a sender who has a + // newer version of the protocol and is using a field of the union that you don't know about yet. + + void set(StructSchema::Field field, const DynamicValue::Reader& value); + // Set the given field value. + + DynamicValue::Builder init(StructSchema::Field field); + DynamicValue::Builder init(StructSchema::Field field, uint size); + // Init a struct, list, or blob field. + + void adopt(StructSchema::Field field, Orphan&& orphan); + Orphan disown(StructSchema::Field field); + // Adopt/disown. This works even for non-pointer fields: adopt() becomes equivalent to set() + // and disown() becomes like get() followed by clear(). + + void clear(StructSchema::Field field); + // Clear a field, setting it to its default value. For pointer fields, this actually makes the + // field null. + + DynamicValue::Builder get(kj::StringPtr name); + bool has(kj::StringPtr name); + void set(kj::StringPtr name, const DynamicValue::Reader& value); + void set(kj::StringPtr name, std::initializer_list value); + DynamicValue::Builder init(kj::StringPtr name); + DynamicValue::Builder init(kj::StringPtr name, uint size); + void adopt(kj::StringPtr name, Orphan&& orphan); + Orphan disown(kj::StringPtr name); + void clear(kj::StringPtr name); + // Shortcuts to access fields by name. These throw exceptions if no such field exists. + + Reader asReader() const; + +private: + StructSchema schema; + _::StructBuilder builder; + + inline Builder(StructSchema schema, _::StructBuilder builder) + : schema(schema), builder(builder) {} + Builder(StructSchema schema, _::OrphanBuilder& orphan); + + bool isSetInUnion(StructSchema::Field field); + void verifySetInUnion(StructSchema::Field field); + void setInUnion(StructSchema::Field field); + + template + friend struct _::PointerHelpers; + friend struct DynamicList; + friend class MessageReader; + friend class MessageBuilder; + template + friend struct ::capnp::ToDynamic_; + friend class Orphanage; + friend class Orphan; + friend class Orphan; + friend class Orphan; +}; + +class DynamicStruct::Pipeline { +public: + typedef DynamicStruct Pipelines; + + inline Pipeline(decltype(nullptr)): typeless(nullptr) {} + + template + typename T::Pipeline releaseAs(); + // Convert the dynamic pipeline to its compiled-in type. + + inline StructSchema getSchema() { return schema; } + + DynamicValue::Pipeline get(StructSchema::Field field); + // Read the given field value. + + DynamicValue::Pipeline get(kj::StringPtr name); + // Get by string name. + +private: + StructSchema schema; + AnyPointer::Pipeline typeless; + + inline explicit Pipeline(StructSchema schema, AnyPointer::Pipeline&& typeless) + : schema(schema), typeless(kj::mv(typeless)) {} + + friend class Request; +}; + +// ------------------------------------------------------------------- + +class DynamicList::Reader { +public: + typedef DynamicList Reads; + + inline Reader(): reader(ElementSize::VOID) {} + + template >() == Kind::LIST>> + inline Reader(T&& value): Reader(toDynamic(value)) {} + + template + typename T::Reader as() const; + // Try to convert to any List, Data, or Text. Throws an exception if the underlying data + // can't possibly represent the requested type. + + inline ListSchema getSchema() const { return schema; } + + inline uint size() const { return unbound(reader.size() / ELEMENTS); } + DynamicValue::Reader operator[](uint index) const; + + typedef _::IndexingIterator Iterator; + inline Iterator begin() const { return Iterator(this, 0); } + inline Iterator end() const { return Iterator(this, size()); } + +private: + ListSchema schema; + _::ListReader reader; + + Reader(ListSchema schema, _::ListReader reader): schema(schema), reader(reader) {} + Reader(ListSchema schema, const _::OrphanBuilder& orphan); + + template + friend struct _::PointerHelpers; + friend struct DynamicStruct; + friend class DynamicList::Builder; + template + friend struct ::capnp::ToDynamic_; + friend class Orphanage; + friend class Orphan; + friend class Orphan; + friend class Orphan; +}; + +class DynamicList::Builder { +public: + typedef DynamicList Builds; + + inline Builder(): builder(ElementSize::VOID) {} + inline Builder(decltype(nullptr)): builder(ElementSize::VOID) {} + + template >() == Kind::LIST>> + inline Builder(T&& value): Builder(toDynamic(value)) {} + + template + typename T::Builder as(); + // Try to convert to any List, Data, or Text. Throws an exception if the underlying data + // can't possibly represent the requested type. + + inline ListSchema getSchema() const { return schema; } + + inline uint size() const { return unbound(builder.size() / ELEMENTS); } + DynamicValue::Builder operator[](uint index); + void set(uint index, const DynamicValue::Reader& value); + DynamicValue::Builder init(uint index, uint size); + void adopt(uint index, Orphan&& orphan); + Orphan disown(uint index); + + typedef _::IndexingIterator Iterator; + inline Iterator begin() { return Iterator(this, 0); } + inline Iterator end() { return Iterator(this, size()); } + + void copyFrom(std::initializer_list value); + + Reader asReader() const; + +private: + ListSchema schema; + _::ListBuilder builder; + + Builder(ListSchema schema, _::ListBuilder builder): schema(schema), builder(builder) {} + Builder(ListSchema schema, _::OrphanBuilder& orphan); + + template + friend struct _::PointerHelpers; + friend struct DynamicStruct; + template + friend struct ::capnp::ToDynamic_; + friend class Orphanage; + template + friend struct _::OrphanGetImpl; + friend class Orphan; + friend class Orphan; + friend class Orphan; +}; + +// ------------------------------------------------------------------- + +class DynamicCapability::Client: public Capability::Client { +public: + typedef DynamicCapability Calls; + typedef DynamicCapability Reads; + + Client() = default; + + template >() == Kind::INTERFACE>> + inline Client(T&& client); + + template ()>> + inline Client(kj::Own&& server); + + template () == Kind::INTERFACE>> + typename T::Client as(); + template () == Kind::INTERFACE>> + typename T::Client releaseAs(); + // Convert to any client type. + + Client upcast(InterfaceSchema requestedSchema); + // Upcast to a superclass. Throws an exception if `schema` is not a superclass. + + inline InterfaceSchema getSchema() { return schema; } + + Request newRequest( + InterfaceSchema::Method method, kj::Maybe sizeHint = nullptr); + Request newRequest( + kj::StringPtr methodName, kj::Maybe sizeHint = nullptr); + +private: + InterfaceSchema schema; + + Client(InterfaceSchema schema, kj::Own&& hook) + : Capability::Client(kj::mv(hook)), schema(schema) {} + + template + inline Client(InterfaceSchema schema, kj::Own&& server); + + friend struct Capability; + friend struct DynamicStruct; + friend struct DynamicList; + friend struct DynamicValue; + friend class Orphan; + friend class Orphan; + friend class Orphan; + template + friend struct _::PointerHelpers; +}; + +class DynamicCapability::Server: public Capability::Server { +public: + typedef DynamicCapability Serves; + + Server(InterfaceSchema schema): schema(schema) {} + + virtual kj::Promise call(InterfaceSchema::Method method, + CallContext context) = 0; + + kj::Promise dispatchCall(uint64_t interfaceId, uint16_t methodId, + CallContext context) override final; + + inline InterfaceSchema getSchema() const { return schema; } + +private: + InterfaceSchema schema; +}; + +template <> +class Request: public DynamicStruct::Builder { + // Specialization of `Request` for DynamicStruct. + +public: + inline Request(DynamicStruct::Builder builder, kj::Own&& hook, + StructSchema resultSchema) + : DynamicStruct::Builder(builder), hook(kj::mv(hook)), resultSchema(resultSchema) {} + + RemotePromise send(); + // Send the call and return a promise for the results. + +private: + kj::Own hook; + StructSchema resultSchema; + + friend class Capability::Client; + friend struct DynamicCapability; + template + friend class CallContext; + friend class RequestHook; +}; + +template <> +class CallContext: public kj::DisallowConstCopy { + // Wrapper around CallContextHook with a specific return type. + // + // Methods of this class may only be called from within the server's event loop, not from other + // threads. + +public: + explicit CallContext(CallContextHook& hook, StructSchema paramType, StructSchema resultType); + + DynamicStruct::Reader getParams(); + void releaseParams(); + DynamicStruct::Builder getResults(kj::Maybe sizeHint = nullptr); + DynamicStruct::Builder initResults(kj::Maybe sizeHint = nullptr); + void setResults(DynamicStruct::Reader value); + void adoptResults(Orphan&& value); + Orphanage getResultsOrphanage(kj::Maybe sizeHint = nullptr); + template + kj::Promise tailCall(Request&& tailRequest); + void allowCancellation(); + +private: + CallContextHook* hook; + StructSchema paramType; + StructSchema resultType; + + friend class DynamicCapability::Server; +}; + +// ------------------------------------------------------------------- + +// Make sure ReaderFor and BuilderFor work for DynamicEnum, DynamicStruct, and +// DynamicList, so that we can define DynamicValue::as(). + +template <> struct ReaderFor_ { typedef DynamicEnum Type; }; +template <> struct BuilderFor_ { typedef DynamicEnum Type; }; +template <> struct ReaderFor_ { typedef DynamicStruct::Reader Type; }; +template <> struct BuilderFor_ { typedef DynamicStruct::Builder Type; }; +template <> struct ReaderFor_ { typedef DynamicList::Reader Type; }; +template <> struct BuilderFor_ { typedef DynamicList::Builder Type; }; +template <> struct ReaderFor_ { typedef DynamicCapability::Client Type; }; +template <> struct BuilderFor_ { typedef DynamicCapability::Client Type; }; +template <> struct PipelineFor_ { typedef DynamicCapability::Client Type; }; + +class DynamicValue::Reader { +public: + typedef DynamicValue Reads; + + inline Reader(decltype(nullptr) n = nullptr); // UNKNOWN + inline Reader(Void value); + inline Reader(bool value); + inline Reader(char value); + inline Reader(signed char value); + inline Reader(short value); + inline Reader(int value); + inline Reader(long value); + inline Reader(long long value); + inline Reader(unsigned char value); + inline Reader(unsigned short value); + inline Reader(unsigned int value); + inline Reader(unsigned long value); + inline Reader(unsigned long long value); + inline Reader(float value); + inline Reader(double value); + inline Reader(const char* value); // Text + inline Reader(const Text::Reader& value); + inline Reader(const Data::Reader& value); + inline Reader(const DynamicList::Reader& value); + inline Reader(DynamicEnum value); + inline Reader(const DynamicStruct::Reader& value); + inline Reader(const AnyPointer::Reader& value); + inline Reader(DynamicCapability::Client& value); + inline Reader(DynamicCapability::Client&& value); + template ()>> + inline Reader(kj::Own&& value); + Reader(ConstSchema constant); + + template ()))> + inline Reader(T&& value): Reader(toDynamic(kj::mv(value))) {} + + Reader(const Reader& other); + Reader(Reader&& other) noexcept; + ~Reader() noexcept(false); + Reader& operator=(const Reader& other); + Reader& operator=(Reader&& other); + // Unfortunately, we cannot use the implicit definitions of these since DynamicCapability is not + // trivially copyable. + + template + inline ReaderFor as() const { return AsImpl::apply(*this); } + // Use to interpret the value as some Cap'n Proto type. Allowed types are: + // - Void, bool, [u]int{8,16,32,64}_t, float, double, any enum: Returns the raw value. + // - Text, Data, AnyPointer, any struct type: Returns the corresponding Reader. + // - List for any T listed above: Returns List::Reader. + // - DynamicEnum: Returns the corresponding type. + // - DynamicStruct, DynamicList: Returns the corresponding Reader. + // - Any capability type, including DynamicCapability: Returns the corresponding Client. + // - DynamicValue: Returns an identical Reader. Useful to avoid special-casing in generic code. + // (TODO(perf): On GCC 4.8 / Clang 3.3, provide rvalue-qualified version that avoids + // refcounting.) + // + // DynamicValue allows various implicit conversions, mostly just to make the interface friendlier. + // - Any integer can be converted to any other integer type so long as the actual value is within + // the new type's range. + // - Floating-point types can be converted to integers as long as no information would be lost + // in the conversion. + // - Integers can be converted to floating points. This may lose information, but won't throw. + // - Float32/Float64 can be converted between each other. Converting Float64 -> Float32 may lose + // information, but won't throw. + // - Text can be converted to an enum, if the Text matches one of the enumerant names (but not + // vice-versa). + // - Capabilities can be upcast (cast to a supertype), but not downcast. + // + // Any other conversion attempt will throw an exception. + + inline Type getType() const { return type; } + // Get the type of this value. + +private: + Type type; + + union { + Void voidValue; + bool boolValue; + int64_t intValue; + uint64_t uintValue; + double floatValue; + Text::Reader textValue; + Data::Reader dataValue; + DynamicList::Reader listValue; + DynamicEnum enumValue; + DynamicStruct::Reader structValue; + AnyPointer::Reader anyPointerValue; + + mutable DynamicCapability::Client capabilityValue; + // Declared mutable because `Client`s normally cannot be const. + + // Warning: Copy/move constructors assume all these types are trivially copyable except + // Capability. + }; + + template ()> struct AsImpl; + // Implementation backing the as() method. Needs to be a struct to allow partial + // specialization. Has a method apply() which does the work. + + friend class Orphanage; // to speed up newOrphanCopy(DynamicValue::Reader) +}; + +class DynamicValue::Builder { +public: + typedef DynamicValue Builds; + + inline Builder(decltype(nullptr) n = nullptr); // UNKNOWN + inline Builder(Void value); + inline Builder(bool value); + inline Builder(char value); + inline Builder(signed char value); + inline Builder(short value); + inline Builder(int value); + inline Builder(long value); + inline Builder(long long value); + inline Builder(unsigned char value); + inline Builder(unsigned short value); + inline Builder(unsigned int value); + inline Builder(unsigned long value); + inline Builder(unsigned long long value); + inline Builder(float value); + inline Builder(double value); + inline Builder(Text::Builder value); + inline Builder(Data::Builder value); + inline Builder(DynamicList::Builder value); + inline Builder(DynamicEnum value); + inline Builder(DynamicStruct::Builder value); + inline Builder(AnyPointer::Builder value); + inline Builder(DynamicCapability::Client& value); + inline Builder(DynamicCapability::Client&& value); + + template ()))> + inline Builder(T value): Builder(toDynamic(value)) {} + + Builder(Builder& other); + Builder(Builder&& other) noexcept; + ~Builder() noexcept(false); + Builder& operator=(Builder& other); + Builder& operator=(Builder&& other); + // Unfortunately, we cannot use the implicit definitions of these since DynamicCapability is not + // trivially copyable. + + template + inline BuilderFor as() { return AsImpl::apply(*this); } + // See DynamicValue::Reader::as(). + + inline Type getType() { return type; } + // Get the type of this value. + + Reader asReader() const; + +private: + Type type; + + union { + Void voidValue; + bool boolValue; + int64_t intValue; + uint64_t uintValue; + double floatValue; + Text::Builder textValue; + Data::Builder dataValue; + DynamicList::Builder listValue; + DynamicEnum enumValue; + DynamicStruct::Builder structValue; + AnyPointer::Builder anyPointerValue; + + mutable DynamicCapability::Client capabilityValue; + // Declared mutable because `Client`s normally cannot be const. + }; + + template ()> struct AsImpl; + // Implementation backing the as() method. Needs to be a struct to allow partial + // specialization. Has a method apply() which does the work. + + friend class Orphan; +}; + +class DynamicValue::Pipeline { +public: + typedef DynamicValue Pipelines; + + inline Pipeline(decltype(nullptr) n = nullptr); + inline Pipeline(DynamicStruct::Pipeline&& value); + inline Pipeline(DynamicCapability::Client&& value); + + Pipeline(Pipeline&& other) noexcept; + Pipeline& operator=(Pipeline&& other); + ~Pipeline() noexcept(false); + + template + inline PipelineFor releaseAs() { return AsImpl::apply(*this); } + + inline Type getType() { return type; } + // Get the type of this value. + +private: + Type type; + union { + DynamicStruct::Pipeline structValue; + DynamicCapability::Client capabilityValue; + }; + + template ()> struct AsImpl; + // Implementation backing the releaseAs() method. Needs to be a struct to allow partial + // specialization. Has a method apply() which does the work. +}; + +kj::StringTree KJ_STRINGIFY(const DynamicValue::Reader& value); +kj::StringTree KJ_STRINGIFY(const DynamicValue::Builder& value); +kj::StringTree KJ_STRINGIFY(DynamicEnum value); +kj::StringTree KJ_STRINGIFY(const DynamicStruct::Reader& value); +kj::StringTree KJ_STRINGIFY(const DynamicStruct::Builder& value); +kj::StringTree KJ_STRINGIFY(const DynamicList::Reader& value); +kj::StringTree KJ_STRINGIFY(const DynamicList::Builder& value); + +// ------------------------------------------------------------------- +// Orphan <-> Dynamic glue + +template <> +class Orphan { +public: + Orphan() = default; + KJ_DISALLOW_COPY(Orphan); + Orphan(Orphan&&) = default; + Orphan& operator=(Orphan&&) = default; + + template () == Kind::STRUCT>> + inline Orphan(Orphan&& other): schema(Schema::from()), builder(kj::mv(other.builder)) {} + + DynamicStruct::Builder get(); + DynamicStruct::Reader getReader() const; + + template + Orphan releaseAs(); + // Like DynamicStruct::Builder::as(), but coerces the Orphan type. Since Orphans are move-only, + // the original Orphan is no longer valid after this call; ownership is + // transferred to the returned Orphan. + + inline bool operator==(decltype(nullptr)) const { return builder == nullptr; } + inline bool operator!=(decltype(nullptr)) const { return builder != nullptr; } + +private: + StructSchema schema; + _::OrphanBuilder builder; + + inline Orphan(StructSchema schema, _::OrphanBuilder&& builder) + : schema(schema), builder(kj::mv(builder)) {} + + template + friend struct _::PointerHelpers; + friend struct DynamicList; + friend class Orphanage; + friend class Orphan; + friend class Orphan; + friend class MessageBuilder; +}; + +template <> +class Orphan { +public: + Orphan() = default; + KJ_DISALLOW_COPY(Orphan); + Orphan(Orphan&&) = default; + Orphan& operator=(Orphan&&) = default; + + template () == Kind::LIST>> + inline Orphan(Orphan&& other): schema(Schema::from()), builder(kj::mv(other.builder)) {} + + DynamicList::Builder get(); + DynamicList::Reader getReader() const; + + template + Orphan releaseAs(); + // Like DynamicList::Builder::as(), but coerces the Orphan type. Since Orphans are move-only, + // the original Orphan is no longer valid after this call; ownership is + // transferred to the returned Orphan. + + // TODO(someday): Support truncate(). + + inline bool operator==(decltype(nullptr)) const { return builder == nullptr; } + inline bool operator!=(decltype(nullptr)) const { return builder != nullptr; } + +private: + ListSchema schema; + _::OrphanBuilder builder; + + inline Orphan(ListSchema schema, _::OrphanBuilder&& builder) + : schema(schema), builder(kj::mv(builder)) {} + + template + friend struct _::PointerHelpers; + friend struct DynamicList; + friend class Orphanage; + friend class Orphan; + friend class Orphan; +}; + +template <> +class Orphan { +public: + Orphan() = default; + KJ_DISALLOW_COPY(Orphan); + Orphan(Orphan&&) = default; + Orphan& operator=(Orphan&&) = default; + + template () == Kind::INTERFACE>> + inline Orphan(Orphan&& other): schema(Schema::from()), builder(kj::mv(other.builder)) {} + + DynamicCapability::Client get(); + DynamicCapability::Client getReader() const; + + template + Orphan releaseAs(); + // Like DynamicCapability::Client::as(), but coerces the Orphan type. Since Orphans are move-only, + // the original Orphan is no longer valid after this call; ownership is + // transferred to the returned Orphan. + + inline bool operator==(decltype(nullptr)) const { return builder == nullptr; } + inline bool operator!=(decltype(nullptr)) const { return builder != nullptr; } + +private: + InterfaceSchema schema; + _::OrphanBuilder builder; + + inline Orphan(InterfaceSchema schema, _::OrphanBuilder&& builder) + : schema(schema), builder(kj::mv(builder)) {} + + template + friend struct _::PointerHelpers; + friend struct DynamicList; + friend class Orphanage; + friend class Orphan; + friend class Orphan; +}; + +template <> +class Orphan { +public: + inline Orphan(decltype(nullptr) n = nullptr): type(DynamicValue::UNKNOWN) {} + inline Orphan(Void value); + inline Orphan(bool value); + inline Orphan(char value); + inline Orphan(signed char value); + inline Orphan(short value); + inline Orphan(int value); + inline Orphan(long value); + inline Orphan(long long value); + inline Orphan(unsigned char value); + inline Orphan(unsigned short value); + inline Orphan(unsigned int value); + inline Orphan(unsigned long value); + inline Orphan(unsigned long long value); + inline Orphan(float value); + inline Orphan(double value); + inline Orphan(DynamicEnum value); + Orphan(Orphan&&) = default; + template + Orphan(Orphan&&); + Orphan(Orphan&&); + Orphan(void*) = delete; // So Orphan(bool) doesn't accept pointers. + KJ_DISALLOW_COPY(Orphan); + + Orphan& operator=(Orphan&&) = default; + + inline DynamicValue::Type getType() { return type; } + + DynamicValue::Builder get(); + DynamicValue::Reader getReader() const; + + template + Orphan releaseAs(); + // Like DynamicValue::Builder::as(), but coerces the Orphan type. Since Orphans are move-only, + // the original Orphan is no longer valid after this call; ownership is + // transferred to the returned Orphan. + +private: + DynamicValue::Type type; + union { + Void voidValue; + bool boolValue; + int64_t intValue; + uint64_t uintValue; + double floatValue; + DynamicEnum enumValue; + StructSchema structSchema; + ListSchema listSchema; + InterfaceSchema interfaceSchema; + }; + + _::OrphanBuilder builder; + // Only used if `type` is a pointer type. + + Orphan(DynamicValue::Builder value, _::OrphanBuilder&& builder); + Orphan(DynamicValue::Type type, _::OrphanBuilder&& builder) + : type(type), builder(kj::mv(builder)) {} + Orphan(StructSchema structSchema, _::OrphanBuilder&& builder) + : type(DynamicValue::STRUCT), structSchema(structSchema), builder(kj::mv(builder)) {} + Orphan(ListSchema listSchema, _::OrphanBuilder&& builder) + : type(DynamicValue::LIST), listSchema(listSchema), builder(kj::mv(builder)) {} + + template + friend struct _::PointerHelpers; + friend struct DynamicStruct; + friend struct DynamicList; + friend struct AnyPointer; + friend class Orphanage; +}; + +template +inline Orphan::Orphan(Orphan&& other) + : Orphan(other.get(), kj::mv(other.builder)) {} + +inline Orphan::Orphan(Orphan&& other) + : type(DynamicValue::ANY_POINTER), builder(kj::mv(other.builder)) {} + +template +Orphan Orphan::releaseAs() { + get().as(); // type check + return Orphan(kj::mv(builder)); +} + +template +Orphan Orphan::releaseAs() { + get().as(); // type check + return Orphan(kj::mv(builder)); +} + +template +Orphan Orphan::releaseAs() { + get().as(); // type check + return Orphan(kj::mv(builder)); +} + +template +Orphan Orphan::releaseAs() { + get().as(); // type check + type = DynamicValue::UNKNOWN; + return Orphan(kj::mv(builder)); +} + +template <> +Orphan Orphan::releaseAs(); +template <> +Orphan Orphan::releaseAs(); +template <> +Orphan Orphan::releaseAs(); +template <> +Orphan Orphan::releaseAs(); + +template <> +struct Orphanage::GetInnerBuilder { + static inline _::StructBuilder apply(DynamicStruct::Builder& t) { + return t.builder; + } +}; + +template <> +struct Orphanage::GetInnerBuilder { + static inline _::ListBuilder apply(DynamicList::Builder& t) { + return t.builder; + } +}; + +template <> +inline Orphan Orphanage::newOrphanCopy( + DynamicStruct::Reader copyFrom) const { + return Orphan( + copyFrom.getSchema(), _::OrphanBuilder::copy(arena, capTable, copyFrom.reader)); +} + +template <> +inline Orphan Orphanage::newOrphanCopy( + DynamicList::Reader copyFrom) const { + return Orphan(copyFrom.getSchema(), + _::OrphanBuilder::copy(arena, capTable, copyFrom.reader)); +} + +template <> +inline Orphan Orphanage::newOrphanCopy( + DynamicCapability::Client copyFrom) const { + return Orphan( + copyFrom.getSchema(), _::OrphanBuilder::copy(arena, capTable, copyFrom.hook->addRef())); +} + +template <> +Orphan Orphanage::newOrphanCopy( + DynamicValue::Reader copyFrom) const; + +namespace _ { // private + +template <> +struct PointerHelpers { + // getDynamic() is used when an AnyPointer's get() accessor is passed arguments, because for + // non-dynamic types PointerHelpers::get() takes a default value as the third argument, and we + // don't want people to accidentally be able to provide their own default value. + static DynamicStruct::Reader getDynamic(PointerReader reader, StructSchema schema); + static DynamicStruct::Builder getDynamic(PointerBuilder builder, StructSchema schema); + static void set(PointerBuilder builder, const DynamicStruct::Reader& value); + static DynamicStruct::Builder init(PointerBuilder builder, StructSchema schema); + static inline void adopt(PointerBuilder builder, Orphan&& value) { + builder.adopt(kj::mv(value.builder)); + } + static inline Orphan disown(PointerBuilder builder, StructSchema schema) { + return Orphan(schema, builder.disown()); + } +}; + +template <> +struct PointerHelpers { + // getDynamic() is used when an AnyPointer's get() accessor is passed arguments, because for + // non-dynamic types PointerHelpers::get() takes a default value as the third argument, and we + // don't want people to accidentally be able to provide their own default value. + static DynamicList::Reader getDynamic(PointerReader reader, ListSchema schema); + static DynamicList::Builder getDynamic(PointerBuilder builder, ListSchema schema); + static void set(PointerBuilder builder, const DynamicList::Reader& value); + static DynamicList::Builder init(PointerBuilder builder, ListSchema schema, uint size); + static inline void adopt(PointerBuilder builder, Orphan&& value) { + builder.adopt(kj::mv(value.builder)); + } + static inline Orphan disown(PointerBuilder builder, ListSchema schema) { + return Orphan(schema, builder.disown()); + } +}; + +template <> +struct PointerHelpers { + // getDynamic() is used when an AnyPointer's get() accessor is passed arguments, because for + // non-dynamic types PointerHelpers::get() takes a default value as the third argument, and we + // don't want people to accidentally be able to provide their own default value. + static DynamicCapability::Client getDynamic(PointerReader reader, InterfaceSchema schema); + static DynamicCapability::Client getDynamic(PointerBuilder builder, InterfaceSchema schema); + static void set(PointerBuilder builder, DynamicCapability::Client& value); + static void set(PointerBuilder builder, DynamicCapability::Client&& value); + static inline void adopt(PointerBuilder builder, Orphan&& value) { + builder.adopt(kj::mv(value.builder)); + } + static inline Orphan disown(PointerBuilder builder, InterfaceSchema schema) { + return Orphan(schema, builder.disown()); + } +}; + +} // namespace _ (private) + +template +inline ReaderFor AnyPointer::Reader::getAs(StructSchema schema) const { + return _::PointerHelpers::getDynamic(reader, schema); +} +template +inline ReaderFor AnyPointer::Reader::getAs(ListSchema schema) const { + return _::PointerHelpers::getDynamic(reader, schema); +} +template +inline ReaderFor AnyPointer::Reader::getAs(InterfaceSchema schema) const { + return _::PointerHelpers::getDynamic(reader, schema); +} +template +inline BuilderFor AnyPointer::Builder::getAs(StructSchema schema) { + return _::PointerHelpers::getDynamic(builder, schema); +} +template +inline BuilderFor AnyPointer::Builder::getAs(ListSchema schema) { + return _::PointerHelpers::getDynamic(builder, schema); +} +template +inline BuilderFor AnyPointer::Builder::getAs(InterfaceSchema schema) { + return _::PointerHelpers::getDynamic(builder, schema); +} +template +inline BuilderFor AnyPointer::Builder::initAs(StructSchema schema) { + return _::PointerHelpers::init(builder, schema); +} +template +inline BuilderFor AnyPointer::Builder::initAs(ListSchema schema, uint elementCount) { + return _::PointerHelpers::init(builder, schema, elementCount); +} +template <> +inline void AnyPointer::Builder::setAs(DynamicStruct::Reader value) { + return _::PointerHelpers::set(builder, value); +} +template <> +inline void AnyPointer::Builder::setAs(DynamicList::Reader value) { + return _::PointerHelpers::set(builder, value); +} +template <> +inline void AnyPointer::Builder::setAs(DynamicCapability::Client value) { + return _::PointerHelpers::set(builder, kj::mv(value)); +} +template <> +void AnyPointer::Builder::adopt(Orphan&& orphan); +template +inline Orphan AnyPointer::Builder::disownAs(StructSchema schema) { + return _::PointerHelpers::disown(builder, schema); +} +template +inline Orphan AnyPointer::Builder::disownAs(ListSchema schema) { + return _::PointerHelpers::disown(builder, schema); +} +template +inline Orphan AnyPointer::Builder::disownAs(InterfaceSchema schema) { + return _::PointerHelpers::disown(builder, schema); +} + +// We have to declare the methods below inline because Clang and GCC disagree about how to mangle +// their symbol names. +template <> +inline DynamicStruct::Builder Orphan::getAs(StructSchema schema) { + return DynamicStruct::Builder(schema, builder); +} +template <> +inline DynamicStruct::Reader Orphan::getAsReader( + StructSchema schema) const { + return DynamicStruct::Reader(schema, builder); +} +template <> +inline Orphan Orphan::releaseAs(StructSchema schema) { + return Orphan(schema, kj::mv(builder)); +} +template <> +inline DynamicList::Builder Orphan::getAs(ListSchema schema) { + return DynamicList::Builder(schema, builder); +} +template <> +inline DynamicList::Reader Orphan::getAsReader(ListSchema schema) const { + return DynamicList::Reader(schema, builder); +} +template <> +inline Orphan Orphan::releaseAs(ListSchema schema) { + return Orphan(schema, kj::mv(builder)); +} +template <> +inline DynamicCapability::Client Orphan::getAs( + InterfaceSchema schema) { + return DynamicCapability::Client(schema, builder.asCapability()); +} +template <> +inline DynamicCapability::Client Orphan::getAsReader( + InterfaceSchema schema) const { + return DynamicCapability::Client(schema, builder.asCapability()); +} +template <> +inline Orphan Orphan::releaseAs( + InterfaceSchema schema) { + return Orphan(schema, kj::mv(builder)); +} + +// ======================================================================================= +// Inline implementation details. + +template +struct ToDynamic_ { + static inline DynamicStruct::Reader apply(const typename T::Reader& value) { + return DynamicStruct::Reader(Schema::from(), value._reader); + } + static inline DynamicStruct::Builder apply(typename T::Builder& value) { + return DynamicStruct::Builder(Schema::from(), value._builder); + } +}; + +template +struct ToDynamic_ { + static inline DynamicList::Reader apply(const typename T::Reader& value) { + return DynamicList::Reader(Schema::from(), value.reader); + } + static inline DynamicList::Builder apply(typename T::Builder& value) { + return DynamicList::Builder(Schema::from(), value.builder); + } +}; + +template +struct ToDynamic_ { + static inline DynamicCapability::Client apply(typename T::Client value) { + return DynamicCapability::Client(kj::mv(value)); + } + static inline DynamicCapability::Client apply(typename T::Client&& value) { + return DynamicCapability::Client(kj::mv(value)); + } +}; + +template +ReaderFor>> toDynamic(T&& value) { + return ToDynamic_>::apply(value); +} +template +BuilderFor>> toDynamic(T&& value) { + return ToDynamic_>::apply(value); +} +template +DynamicTypeFor> toDynamic(T&& value) { + return DynamicEnum(Schema::from>(), static_cast(value)); +} +template +typename DynamicTypeFor>::Client toDynamic(kj::Own&& value) { + return typename FromServer::Client(kj::mv(value)); +} + +inline DynamicValue::Reader::Reader(std::nullptr_t n): type(UNKNOWN) {} +inline DynamicValue::Builder::Builder(std::nullptr_t n): type(UNKNOWN) {} + +#define CAPNP_DECLARE_DYNAMIC_VALUE_CONSTRUCTOR(cppType, typeTag, fieldName) \ +inline DynamicValue::Reader::Reader(cppType value) \ + : type(typeTag), fieldName##Value(value) {} \ +inline DynamicValue::Builder::Builder(cppType value) \ + : type(typeTag), fieldName##Value(value) {} \ +inline Orphan::Orphan(cppType value) \ + : type(DynamicValue::typeTag), fieldName##Value(value) {} + +CAPNP_DECLARE_DYNAMIC_VALUE_CONSTRUCTOR(Void, VOID, void); +CAPNP_DECLARE_DYNAMIC_VALUE_CONSTRUCTOR(bool, BOOL, bool); +CAPNP_DECLARE_DYNAMIC_VALUE_CONSTRUCTOR(char, INT, int); +CAPNP_DECLARE_DYNAMIC_VALUE_CONSTRUCTOR(signed char, INT, int); +CAPNP_DECLARE_DYNAMIC_VALUE_CONSTRUCTOR(short, INT, int); +CAPNP_DECLARE_DYNAMIC_VALUE_CONSTRUCTOR(int, INT, int); +CAPNP_DECLARE_DYNAMIC_VALUE_CONSTRUCTOR(long, INT, int); +CAPNP_DECLARE_DYNAMIC_VALUE_CONSTRUCTOR(long long, INT, int); +CAPNP_DECLARE_DYNAMIC_VALUE_CONSTRUCTOR(unsigned char, UINT, uint); +CAPNP_DECLARE_DYNAMIC_VALUE_CONSTRUCTOR(unsigned short, UINT, uint); +CAPNP_DECLARE_DYNAMIC_VALUE_CONSTRUCTOR(unsigned int, UINT, uint); +CAPNP_DECLARE_DYNAMIC_VALUE_CONSTRUCTOR(unsigned long, UINT, uint); +CAPNP_DECLARE_DYNAMIC_VALUE_CONSTRUCTOR(unsigned long long, UINT, uint); +CAPNP_DECLARE_DYNAMIC_VALUE_CONSTRUCTOR(float, FLOAT, float); +CAPNP_DECLARE_DYNAMIC_VALUE_CONSTRUCTOR(double, FLOAT, float); +CAPNP_DECLARE_DYNAMIC_VALUE_CONSTRUCTOR(DynamicEnum, ENUM, enum); +#undef CAPNP_DECLARE_DYNAMIC_VALUE_CONSTRUCTOR + +#define CAPNP_DECLARE_DYNAMIC_VALUE_CONSTRUCTOR(cppType, typeTag, fieldName) \ +inline DynamicValue::Reader::Reader(const cppType::Reader& value) \ + : type(typeTag), fieldName##Value(value) {} \ +inline DynamicValue::Builder::Builder(cppType::Builder value) \ + : type(typeTag), fieldName##Value(value) {} + +CAPNP_DECLARE_DYNAMIC_VALUE_CONSTRUCTOR(Text, TEXT, text); +CAPNP_DECLARE_DYNAMIC_VALUE_CONSTRUCTOR(Data, DATA, data); +CAPNP_DECLARE_DYNAMIC_VALUE_CONSTRUCTOR(DynamicList, LIST, list); +CAPNP_DECLARE_DYNAMIC_VALUE_CONSTRUCTOR(DynamicStruct, STRUCT, struct); +CAPNP_DECLARE_DYNAMIC_VALUE_CONSTRUCTOR(AnyPointer, ANY_POINTER, anyPointer); + +#undef CAPNP_DECLARE_DYNAMIC_VALUE_CONSTRUCTOR + +inline DynamicValue::Reader::Reader(DynamicCapability::Client& value) + : type(CAPABILITY), capabilityValue(value) {} +inline DynamicValue::Reader::Reader(DynamicCapability::Client&& value) + : type(CAPABILITY), capabilityValue(kj::mv(value)) {} +template +inline DynamicValue::Reader::Reader(kj::Own&& value) + : type(CAPABILITY), capabilityValue(kj::mv(value)) {} +inline DynamicValue::Builder::Builder(DynamicCapability::Client& value) + : type(CAPABILITY), capabilityValue(value) {} +inline DynamicValue::Builder::Builder(DynamicCapability::Client&& value) + : type(CAPABILITY), capabilityValue(kj::mv(value)) {} + +inline DynamicValue::Reader::Reader(const char* value): Reader(Text::Reader(value)) {} + +#define CAPNP_DECLARE_TYPE(discrim, typeName) \ +template <> \ +struct DynamicValue::Reader::AsImpl { \ + static ReaderFor apply(const Reader& reader); \ +}; \ +template <> \ +struct DynamicValue::Builder::AsImpl { \ + static BuilderFor apply(Builder& builder); \ +}; + +//CAPNP_DECLARE_TYPE(VOID, Void) +CAPNP_DECLARE_TYPE(BOOL, bool) +CAPNP_DECLARE_TYPE(INT8, int8_t) +CAPNP_DECLARE_TYPE(INT16, int16_t) +CAPNP_DECLARE_TYPE(INT32, int32_t) +CAPNP_DECLARE_TYPE(INT64, int64_t) +CAPNP_DECLARE_TYPE(UINT8, uint8_t) +CAPNP_DECLARE_TYPE(UINT16, uint16_t) +CAPNP_DECLARE_TYPE(UINT32, uint32_t) +CAPNP_DECLARE_TYPE(UINT64, uint64_t) +CAPNP_DECLARE_TYPE(FLOAT32, float) +CAPNP_DECLARE_TYPE(FLOAT64, double) + +CAPNP_DECLARE_TYPE(TEXT, Text) +CAPNP_DECLARE_TYPE(DATA, Data) +CAPNP_DECLARE_TYPE(LIST, DynamicList) +CAPNP_DECLARE_TYPE(STRUCT, DynamicStruct) +CAPNP_DECLARE_TYPE(INTERFACE, DynamicCapability) +CAPNP_DECLARE_TYPE(ENUM, DynamicEnum) +CAPNP_DECLARE_TYPE(ANY_POINTER, AnyPointer) +#undef CAPNP_DECLARE_TYPE + +// CAPNP_DECLARE_TYPE(Void) causes gcc 4.7 to segfault. If I do it manually and remove the +// ReaderFor<> and BuilderFor<> wrappers, it works. +template <> +struct DynamicValue::Reader::AsImpl { + static Void apply(const Reader& reader); +}; +template <> +struct DynamicValue::Builder::AsImpl { + static Void apply(Builder& builder); +}; + +template +struct DynamicValue::Reader::AsImpl { + static T apply(const Reader& reader) { + return reader.as().as(); + } +}; +template +struct DynamicValue::Builder::AsImpl { + static T apply(Builder& builder) { + return builder.as().as(); + } +}; + +template +struct DynamicValue::Reader::AsImpl { + static typename T::Reader apply(const Reader& reader) { + return reader.as().as(); + } +}; +template +struct DynamicValue::Builder::AsImpl { + static typename T::Builder apply(Builder& builder) { + return builder.as().as(); + } +}; + +template +struct DynamicValue::Reader::AsImpl { + static typename T::Reader apply(const Reader& reader) { + return reader.as().as(); + } +}; +template +struct DynamicValue::Builder::AsImpl { + static typename T::Builder apply(Builder& builder) { + return builder.as().as(); + } +}; + +template +struct DynamicValue::Reader::AsImpl { + static typename T::Client apply(const Reader& reader) { + return reader.as().as(); + } +}; +template +struct DynamicValue::Builder::AsImpl { + static typename T::Client apply(Builder& builder) { + return builder.as().as(); + } +}; + +template <> +struct DynamicValue::Reader::AsImpl { + static DynamicValue::Reader apply(const Reader& reader) { + return reader; + } +}; +template <> +struct DynamicValue::Builder::AsImpl { + static DynamicValue::Builder apply(Builder& builder) { + return builder; + } +}; + +inline DynamicValue::Pipeline::Pipeline(std::nullptr_t n): type(UNKNOWN) {} +inline DynamicValue::Pipeline::Pipeline(DynamicStruct::Pipeline&& value) + : type(STRUCT), structValue(kj::mv(value)) {} +inline DynamicValue::Pipeline::Pipeline(DynamicCapability::Client&& value) + : type(CAPABILITY), capabilityValue(kj::mv(value)) {} + +template +struct DynamicValue::Pipeline::AsImpl { + static typename T::Pipeline apply(Pipeline& pipeline) { + return pipeline.releaseAs().releaseAs(); + } +}; +template +struct DynamicValue::Pipeline::AsImpl { + static typename T::Client apply(Pipeline& pipeline) { + return pipeline.releaseAs().releaseAs(); + } +}; +template <> +struct DynamicValue::Pipeline::AsImpl { + static PipelineFor apply(Pipeline& pipeline); +}; +template <> +struct DynamicValue::Pipeline::AsImpl { + static PipelineFor apply(Pipeline& pipeline); +}; + +// ------------------------------------------------------------------- + +template +typename T::Reader DynamicStruct::Reader::as() const { + static_assert(kind() == Kind::STRUCT, + "DynamicStruct::Reader::as() can only convert to struct types."); + schema.requireUsableAs(); + return typename T::Reader(reader); +} + +template +typename T::Builder DynamicStruct::Builder::as() { + static_assert(kind() == Kind::STRUCT, + "DynamicStruct::Builder::as() can only convert to struct types."); + schema.requireUsableAs(); + return typename T::Builder(builder); +} + +template <> +inline DynamicStruct::Reader DynamicStruct::Reader::as() const { + return *this; +} +template <> +inline DynamicStruct::Builder DynamicStruct::Builder::as() { + return *this; +} + +inline DynamicStruct::Reader DynamicStruct::Builder::asReader() const { + return DynamicStruct::Reader(schema, builder.asReader()); +} + +template <> +inline AnyStruct::Reader DynamicStruct::Reader::as() const { + return AnyStruct::Reader(reader); +} + +template <> +inline AnyStruct::Builder DynamicStruct::Builder::as() { + return AnyStruct::Builder(builder); +} + +template +typename T::Pipeline DynamicStruct::Pipeline::releaseAs() { + static_assert(kind() == Kind::STRUCT, + "DynamicStruct::Pipeline::releaseAs() can only convert to struct types."); + schema.requireUsableAs(); + return typename T::Pipeline(kj::mv(typeless)); +} + +// ------------------------------------------------------------------- + +template +typename T::Reader DynamicList::Reader::as() const { + static_assert(kind() == Kind::LIST, + "DynamicStruct::Reader::as() can only convert to list types."); + schema.requireUsableAs(); + return typename T::Reader(reader); +} +template +typename T::Builder DynamicList::Builder::as() { + static_assert(kind() == Kind::LIST, + "DynamicStruct::Builder::as() can only convert to list types."); + schema.requireUsableAs(); + return typename T::Builder(builder); +} + +template <> +inline DynamicList::Reader DynamicList::Reader::as() const { + return *this; +} +template <> +inline DynamicList::Builder DynamicList::Builder::as() { + return *this; +} + +template <> +inline AnyList::Reader DynamicList::Reader::as() const { + return AnyList::Reader(reader); +} + +template <> +inline AnyList::Builder DynamicList::Builder::as() { + return AnyList::Builder(builder); +} + +// ------------------------------------------------------------------- + +template +inline DynamicCapability::Client::Client(T&& client) + : Capability::Client(kj::mv(client)), schema(Schema::from>()) {} + +template +inline DynamicCapability::Client::Client(kj::Own&& server) + : Client(server->getSchema(), kj::mv(server)) {} +template +inline DynamicCapability::Client::Client(InterfaceSchema schema, kj::Own&& server) + : Capability::Client(kj::mv(server)), schema(schema) {} + +template +typename T::Client DynamicCapability::Client::as() { + static_assert(kind() == Kind::INTERFACE, + "DynamicCapability::Client::as() can only convert to interface types."); + schema.requireUsableAs(); + return typename T::Client(hook->addRef()); +} + +template +typename T::Client DynamicCapability::Client::releaseAs() { + static_assert(kind() == Kind::INTERFACE, + "DynamicCapability::Client::as() can only convert to interface types."); + schema.requireUsableAs(); + return typename T::Client(kj::mv(hook)); +} + +inline CallContext::CallContext( + CallContextHook& hook, StructSchema paramType, StructSchema resultType) + : hook(&hook), paramType(paramType), resultType(resultType) {} +inline DynamicStruct::Reader CallContext::getParams() { + return hook->getParams().getAs(paramType); +} +inline void CallContext::releaseParams() { + hook->releaseParams(); +} +inline DynamicStruct::Builder CallContext::getResults( + kj::Maybe sizeHint) { + return hook->getResults(sizeHint).getAs(resultType); +} +inline DynamicStruct::Builder CallContext::initResults( + kj::Maybe sizeHint) { + return hook->getResults(sizeHint).initAs(resultType); +} +inline void CallContext::setResults(DynamicStruct::Reader value) { + hook->getResults(value.totalSize()).setAs(value); +} +inline void CallContext::adoptResults(Orphan&& value) { + hook->getResults(MessageSize { 0, 0 }).adopt(kj::mv(value)); +} +inline Orphanage CallContext::getResultsOrphanage( + kj::Maybe sizeHint) { + return Orphanage::getForMessageContaining(hook->getResults(sizeHint)); +} +template +inline kj::Promise CallContext::tailCall( + Request&& tailRequest) { + return hook->tailCall(kj::mv(tailRequest.hook)); +} +inline void CallContext::allowCancellation() { + hook->allowCancellation(); +} + +template <> +inline DynamicCapability::Client Capability::Client::castAs( + InterfaceSchema schema) { + return DynamicCapability::Client(schema, hook->addRef()); +} + +// ------------------------------------------------------------------- + +template +ReaderFor ConstSchema::as() const { + return DynamicValue::Reader(*this).as(); +} + +} // namespace capnp + +#endif // CAPNP_DYNAMIC_H_ diff --git a/phonelibs/capnp-cpp/include/capnp/endian.h b/phonelibs/capnp-cpp/include/capnp/endian.h new file mode 100644 index 00000000000000..c5a6e63c5a9584 --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/endian.h @@ -0,0 +1,309 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef CAPNP_ENDIAN_H_ +#define CAPNP_ENDIAN_H_ + +#if defined(__GNUC__) && !defined(CAPNP_HEADER_WARNINGS) +#pragma GCC system_header +#endif + +#include "common.h" +#include +#include // memcpy + +namespace capnp { +namespace _ { // private + +// WireValue +// +// Wraps a primitive value as it appears on the wire. Namely, values are little-endian on the +// wire, because little-endian is the most common endianness in modern CPUs. +// +// Note: In general, code that depends cares about byte ordering is bad. See: +// http://commandcenter.blogspot.com/2012/04/byte-order-fallacy.html +// Cap'n Proto is special because it is essentially doing compiler-like things, fussing over +// allocation and layout of memory, in order to squeeze out every last drop of performance. + +#if _MSC_VER +// Assume Windows is little-endian. +// +// TODO(msvc): This is ugly. Maybe refactor later checks to be based on CAPNP_BYTE_ORDER or +// CAPNP_SWAP_BYTES or something, and define that in turn based on _MSC_VER or the GCC +// intrinsics. + +#ifndef __ORDER_BIG_ENDIAN__ +#define __ORDER_BIG_ENDIAN__ 4321 +#endif +#ifndef __ORDER_LITTLE_ENDIAN__ +#define __ORDER_LITTLE_ENDIAN__ 1234 +#endif +#ifndef __BYTE_ORDER__ +#define __BYTE_ORDER__ __ORDER_LITTLE_ENDIAN__ +#endif +#endif + +#if CAPNP_REVERSE_ENDIAN +#define CAPNP_WIRE_BYTE_ORDER __ORDER_BIG_ENDIAN__ +#define CAPNP_OPPOSITE_OF_WIRE_BYTE_ORDER __ORDER_LITTLE_ENDIAN__ +#else +#define CAPNP_WIRE_BYTE_ORDER __ORDER_LITTLE_ENDIAN__ +#define CAPNP_OPPOSITE_OF_WIRE_BYTE_ORDER __ORDER_BIG_ENDIAN__ +#endif + +#if defined(__BYTE_ORDER__) && \ + __BYTE_ORDER__ == CAPNP_WIRE_BYTE_ORDER && \ + !CAPNP_DISABLE_ENDIAN_DETECTION +// CPU is little-endian. We can just read/write the memory directly. + +template +class DirectWireValue { +public: + KJ_ALWAYS_INLINE(T get() const) { return value; } + KJ_ALWAYS_INLINE(void set(T newValue)) { value = newValue; } + +private: + T value; +}; + +template +using WireValue = DirectWireValue; +// To prevent ODR problems when endian-test, endian-reverse-test, and endian-fallback-test are +// linked together, we define each implementation with a different name and define an alias to the +// one we want to use. + +#elif defined(__BYTE_ORDER__) && \ + __BYTE_ORDER__ == CAPNP_OPPOSITE_OF_WIRE_BYTE_ORDER && \ + defined(__GNUC__) && !CAPNP_DISABLE_ENDIAN_DETECTION +// Big-endian, but GCC's __builtin_bswap() is available. + +// TODO(perf): Use dedicated instructions to read little-endian data on big-endian CPUs that have +// them. + +// TODO(perf): Verify that this code optimizes reasonably. In particular, ensure that the +// compiler optimizes away the memcpy()s and keeps everything in registers. + +template +class SwappingWireValue; + +template +class SwappingWireValue { +public: + KJ_ALWAYS_INLINE(T get() const) { return value; } + KJ_ALWAYS_INLINE(void set(T newValue)) { value = newValue; } + +private: + T value; +}; + +template +class SwappingWireValue { +public: + KJ_ALWAYS_INLINE(T get() const) { + // Not all platforms have __builtin_bswap16() for some reason. In particular, it is missing + // on gcc-4.7.3-cygwin32 (but present on gcc-4.8.1-cygwin64). + uint16_t swapped = (value << 8) | (value >> 8); + T result; + memcpy(&result, &swapped, sizeof(T)); + return result; + } + KJ_ALWAYS_INLINE(void set(T newValue)) { + uint16_t raw; + memcpy(&raw, &newValue, sizeof(T)); + // Not all platforms have __builtin_bswap16() for some reason. In particular, it is missing + // on gcc-4.7.3-cygwin32 (but present on gcc-4.8.1-cygwin64). + value = (raw << 8) | (raw >> 8); + } + +private: + uint16_t value; +}; + +template +class SwappingWireValue { +public: + KJ_ALWAYS_INLINE(T get() const) { + uint32_t swapped = __builtin_bswap32(value); + T result; + memcpy(&result, &swapped, sizeof(T)); + return result; + } + KJ_ALWAYS_INLINE(void set(T newValue)) { + uint32_t raw; + memcpy(&raw, &newValue, sizeof(T)); + value = __builtin_bswap32(raw); + } + +private: + uint32_t value; +}; + +template +class SwappingWireValue { +public: + KJ_ALWAYS_INLINE(T get() const) { + uint64_t swapped = __builtin_bswap64(value); + T result; + memcpy(&result, &swapped, sizeof(T)); + return result; + } + KJ_ALWAYS_INLINE(void set(T newValue)) { + uint64_t raw; + memcpy(&raw, &newValue, sizeof(T)); + value = __builtin_bswap64(raw); + } + +private: + uint64_t value; +}; + +template +using WireValue = SwappingWireValue; +// To prevent ODR problems when endian-test, endian-reverse-test, and endian-fallback-test are +// linked together, we define each implementation with a different name and define an alias to the +// one we want to use. + +#else +// Unknown endianness. Fall back to bit shifts. + +#if !CAPNP_DISABLE_ENDIAN_DETECTION +#if _MSC_VER +#pragma message("Couldn't detect endianness of your platform. Using unoptimized fallback implementation.") +#pragma message("Consider changing this code to detect your platform and send us a patch!") +#else +#warning "Couldn't detect endianness of your platform. Using unoptimized fallback implementation." +#warning "Consider changing this code to detect your platform and send us a patch!" +#endif +#endif // !CAPNP_DISABLE_ENDIAN_DETECTION + +template +class ShiftingWireValue; + +template +class ShiftingWireValue { +public: + KJ_ALWAYS_INLINE(T get() const) { return value; } + KJ_ALWAYS_INLINE(void set(T newValue)) { value = newValue; } + +private: + T value; +}; + +template +class ShiftingWireValue { +public: + KJ_ALWAYS_INLINE(T get() const) { + uint16_t raw = (static_cast(bytes[0]) ) | + (static_cast(bytes[1]) << 8); + T result; + memcpy(&result, &raw, sizeof(T)); + return result; + } + KJ_ALWAYS_INLINE(void set(T newValue)) { + uint16_t raw; + memcpy(&raw, &newValue, sizeof(T)); + bytes[0] = raw; + bytes[1] = raw >> 8; + } + +private: + union { + byte bytes[2]; + uint16_t align; + }; +}; + +template +class ShiftingWireValue { +public: + KJ_ALWAYS_INLINE(T get() const) { + uint32_t raw = (static_cast(bytes[0]) ) | + (static_cast(bytes[1]) << 8) | + (static_cast(bytes[2]) << 16) | + (static_cast(bytes[3]) << 24); + T result; + memcpy(&result, &raw, sizeof(T)); + return result; + } + KJ_ALWAYS_INLINE(void set(T newValue)) { + uint32_t raw; + memcpy(&raw, &newValue, sizeof(T)); + bytes[0] = raw; + bytes[1] = raw >> 8; + bytes[2] = raw >> 16; + bytes[3] = raw >> 24; + } + +private: + union { + byte bytes[4]; + uint32_t align; + }; +}; + +template +class ShiftingWireValue { +public: + KJ_ALWAYS_INLINE(T get() const) { + uint64_t raw = (static_cast(bytes[0]) ) | + (static_cast(bytes[1]) << 8) | + (static_cast(bytes[2]) << 16) | + (static_cast(bytes[3]) << 24) | + (static_cast(bytes[4]) << 32) | + (static_cast(bytes[5]) << 40) | + (static_cast(bytes[6]) << 48) | + (static_cast(bytes[7]) << 56); + T result; + memcpy(&result, &raw, sizeof(T)); + return result; + } + KJ_ALWAYS_INLINE(void set(T newValue)) { + uint64_t raw; + memcpy(&raw, &newValue, sizeof(T)); + bytes[0] = raw; + bytes[1] = raw >> 8; + bytes[2] = raw >> 16; + bytes[3] = raw >> 24; + bytes[4] = raw >> 32; + bytes[5] = raw >> 40; + bytes[6] = raw >> 48; + bytes[7] = raw >> 56; + } + +private: + union { + byte bytes[8]; + uint64_t align; + }; +}; + +template +using WireValue = ShiftingWireValue; +// To prevent ODR problems when endian-test, endian-reverse-test, and endian-fallback-test are +// linked together, we define each implementation with a different name and define an alias to the +// one we want to use. + +#endif + +} // namespace _ (private) +} // namespace capnp + +#endif // CAPNP_ENDIAN_H_ diff --git a/phonelibs/capnp-cpp/include/capnp/ez-rpc.h b/phonelibs/capnp-cpp/include/capnp/ez-rpc.h new file mode 100644 index 00000000000000..fba5ace5820255 --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/ez-rpc.h @@ -0,0 +1,254 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef CAPNP_EZ_RPC_H_ +#define CAPNP_EZ_RPC_H_ + +#if defined(__GNUC__) && !defined(CAPNP_HEADER_WARNINGS) +#pragma GCC system_header +#endif + +#include "rpc.h" +#include "message.h" + +struct sockaddr; + +namespace kj { class AsyncIoProvider; class LowLevelAsyncIoProvider; } + +namespace capnp { + +class EzRpcContext; + +class EzRpcClient { + // Super-simple interface for setting up a Cap'n Proto RPC client. Example: + // + // # Cap'n Proto schema + // interface Adder { + // add @0 (left :Int32, right :Int32) -> (value :Int32); + // } + // + // // C++ client + // int main() { + // capnp::EzRpcClient client("localhost:3456"); + // Adder::Client adder = client.getMain(); + // auto request = adder.addRequest(); + // request.setLeft(12); + // request.setRight(34); + // auto response = request.send().wait(client.getWaitScope()); + // assert(response.getValue() == 46); + // return 0; + // } + // + // // C++ server + // class AdderImpl final: public Adder::Server { + // public: + // kj::Promise add(AddContext context) override { + // auto params = context.getParams(); + // context.getResults().setValue(params.getLeft() + params.getRight()); + // return kj::READY_NOW; + // } + // }; + // + // int main() { + // capnp::EzRpcServer server(kj::heap(), "*:3456"); + // kj::NEVER_DONE.wait(server.getWaitScope()); + // } + // + // This interface is easy, but it hides a lot of useful features available from the lower-level + // classes: + // - The server can only export a small set of public, singleton capabilities under well-known + // string names. This is fine for transient services where no state needs to be kept between + // connections, but hides the power of Cap'n Proto when it comes to long-lived resources. + // - EzRpcClient/EzRpcServer automatically set up a `kj::EventLoop` and make it current for the + // thread. Only one `kj::EventLoop` can exist per thread, so you cannot use these interfaces + // if you wish to set up your own event loop. (However, you can safely create multiple + // EzRpcClient / EzRpcServer objects in a single thread; they will make sure to make no more + // than one EventLoop.) + // - These classes only support simple two-party connections, not multilateral VatNetworks. + // - These classes only support communication over a raw, unencrypted socket. If you want to + // build on an abstract stream (perhaps one which supports encryption), you must use the + // lower-level interfaces. + // + // Some of these restrictions will probably be lifted in future versions, but some things will + // always require using the low-level interfaces directly. If you are interested in working + // at a lower level, start by looking at these interfaces: + // - `kj::setupAsyncIo()` in `kj/async-io.h`. + // - `RpcSystem` in `capnp/rpc.h`. + // - `TwoPartyVatNetwork` in `capnp/rpc-twoparty.h`. + +public: + explicit EzRpcClient(kj::StringPtr serverAddress, uint defaultPort = 0, + ReaderOptions readerOpts = ReaderOptions()); + // Construct a new EzRpcClient and connect to the given address. The connection is formed in + // the background -- if it fails, calls to capabilities returned by importCap() will fail with an + // appropriate exception. + // + // `defaultPort` is the IP port number to use if `serverAddress` does not include it explicitly. + // If unspecified, the port is required in `serverAddress`. + // + // The address is parsed by `kj::Network` in `kj/async-io.h`. See that interface for more info + // on the address format, but basically it's what you'd expect. + // + // `readerOpts` is the ReaderOptions structure used to read each incoming message on the + // connection. Setting this may be necessary if you need to receive very large individual + // messages or messages. However, it is recommended that you instead think about how to change + // your protocol to send large data blobs in multiple small chunks -- this is much better for + // both security and performance. See `ReaderOptions` in `message.h` for more details. + + EzRpcClient(const struct sockaddr* serverAddress, uint addrSize, + ReaderOptions readerOpts = ReaderOptions()); + // Like the above constructor, but connects to an already-resolved socket address. Any address + // format supported by `kj::Network` in `kj/async-io.h` is accepted. + + explicit EzRpcClient(int socketFd, ReaderOptions readerOpts = ReaderOptions()); + // Create a client on top of an already-connected socket. + // `readerOpts` acts as in the first constructor. + + ~EzRpcClient() noexcept(false); + + template + typename Type::Client getMain(); + Capability::Client getMain(); + // Get the server's main (aka "bootstrap") interface. + + template + typename Type::Client importCap(kj::StringPtr name) + KJ_DEPRECATED("Change your server to export a main interface, then use getMain() instead."); + Capability::Client importCap(kj::StringPtr name) + KJ_DEPRECATED("Change your server to export a main interface, then use getMain() instead."); + // ** DEPRECATED ** + // + // Ask the sever for the capability with the given name. You may specify a type to automatically + // down-cast to that type. It is up to you to specify the correct expected type. + // + // Named interfaces are deprecated. The new preferred usage pattern is for the server to export + // a "main" interface which itself has methods for getting any other interfaces. + + kj::WaitScope& getWaitScope(); + // Get the `WaitScope` for the client's `EventLoop`, which allows you to synchronously wait on + // promises. + + kj::AsyncIoProvider& getIoProvider(); + // Get the underlying AsyncIoProvider set up by the RPC system. This is useful if you want + // to do some non-RPC I/O in asynchronous fashion. + + kj::LowLevelAsyncIoProvider& getLowLevelIoProvider(); + // Get the underlying LowLevelAsyncIoProvider set up by the RPC system. This is useful if you + // want to do some non-RPC I/O in asynchronous fashion. + +private: + struct Impl; + kj::Own impl; +}; + +class EzRpcServer { + // The server counterpart to `EzRpcClient`. See `EzRpcClient` for an example. + +public: + explicit EzRpcServer(Capability::Client mainInterface, kj::StringPtr bindAddress, + uint defaultPort = 0, ReaderOptions readerOpts = ReaderOptions()); + // Construct a new `EzRpcServer` that binds to the given address. An address of "*" means to + // bind to all local addresses. + // + // `defaultPort` is the IP port number to use if `serverAddress` does not include it explicitly. + // If unspecified, a port is chosen automatically, and you must call getPort() to find out what + // it is. + // + // The address is parsed by `kj::Network` in `kj/async-io.h`. See that interface for more info + // on the address format, but basically it's what you'd expect. + // + // The server might not begin listening immediately, especially if `bindAddress` needs to be + // resolved. If you need to wait until the server is definitely up, wait on the promise returned + // by `getPort()`. + // + // `readerOpts` is the ReaderOptions structure used to read each incoming message on the + // connection. Setting this may be necessary if you need to receive very large individual + // messages or messages. However, it is recommended that you instead think about how to change + // your protocol to send large data blobs in multiple small chunks -- this is much better for + // both security and performance. See `ReaderOptions` in `message.h` for more details. + + EzRpcServer(Capability::Client mainInterface, struct sockaddr* bindAddress, uint addrSize, + ReaderOptions readerOpts = ReaderOptions()); + // Like the above constructor, but binds to an already-resolved socket address. Any address + // format supported by `kj::Network` in `kj/async-io.h` is accepted. + + EzRpcServer(Capability::Client mainInterface, int socketFd, uint port, + ReaderOptions readerOpts = ReaderOptions()); + // Create a server on top of an already-listening socket (i.e. one on which accept() may be + // called). `port` is returned by `getPort()` -- it serves no other purpose. + // `readerOpts` acts as in the other two above constructors. + + explicit EzRpcServer(kj::StringPtr bindAddress, uint defaultPort = 0, + ReaderOptions readerOpts = ReaderOptions()) + KJ_DEPRECATED("Please specify a main interface for your server."); + EzRpcServer(struct sockaddr* bindAddress, uint addrSize, + ReaderOptions readerOpts = ReaderOptions()) + KJ_DEPRECATED("Please specify a main interface for your server."); + EzRpcServer(int socketFd, uint port, ReaderOptions readerOpts = ReaderOptions()) + KJ_DEPRECATED("Please specify a main interface for your server."); + + ~EzRpcServer() noexcept(false); + + void exportCap(kj::StringPtr name, Capability::Client cap); + // Export a capability publicly under the given name, so that clients can import it. + // + // Keep in mind that you can implicitly convert `kj::Own&&` to + // `Capability::Client`, so it's typical to pass something like + // `kj::heap()` as the second parameter. + + kj::Promise getPort(); + // Get the IP port number on which this server is listening. This promise won't resolve until + // the server is actually listening. If the address was not an IP address (e.g. it was a Unix + // domain socket) then getPort() resolves to zero. + + kj::WaitScope& getWaitScope(); + // Get the `WaitScope` for the client's `EventLoop`, which allows you to synchronously wait on + // promises. + + kj::AsyncIoProvider& getIoProvider(); + // Get the underlying AsyncIoProvider set up by the RPC system. This is useful if you want + // to do some non-RPC I/O in asynchronous fashion. + + kj::LowLevelAsyncIoProvider& getLowLevelIoProvider(); + // Get the underlying LowLevelAsyncIoProvider set up by the RPC system. This is useful if you + // want to do some non-RPC I/O in asynchronous fashion. + +private: + struct Impl; + kj::Own impl; +}; + +// ======================================================================================= +// inline implementation details + +template +inline typename Type::Client EzRpcClient::getMain() { + return getMain().castAs(); +} + +template +inline typename Type::Client EzRpcClient::importCap(kj::StringPtr name) { + return importCap(name).castAs(); +} + +} // namespace capnp + +#endif // CAPNP_EZ_RPC_H_ diff --git a/phonelibs/capnp-cpp/include/capnp/generated-header-support.h b/phonelibs/capnp-cpp/include/capnp/generated-header-support.h new file mode 100644 index 00000000000000..51b6dd7c113c63 --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/generated-header-support.h @@ -0,0 +1,407 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +// This file is included from all generated headers. + +#ifndef CAPNP_GENERATED_HEADER_SUPPORT_H_ +#define CAPNP_GENERATED_HEADER_SUPPORT_H_ + +#if defined(__GNUC__) && !defined(CAPNP_HEADER_WARNINGS) +#pragma GCC system_header +#endif + +#include "raw-schema.h" +#include "layout.h" +#include "list.h" +#include "orphan.h" +#include "pointer-helpers.h" +#include "any.h" +#include +#include + +namespace capnp { + +class MessageBuilder; // So that it can be declared a friend. + +template +struct ToDynamic_; // Defined in dynamic.h, needs to be declared as everyone's friend. + +struct DynamicStruct; // So that it can be declared a friend. + +struct Capability; // To declare brandBindingFor() + +namespace _ { // private + +#if !CAPNP_LITE + +template +inline const RawSchema& rawSchema() { + return *CapnpPrivate::schema; +} +template ::typeId> +inline const RawSchema& rawSchema() { + return *schemas::EnumInfo::schema; +} + +template +inline const RawBrandedSchema& rawBrandedSchema() { + return *CapnpPrivate::brand(); +} +template ::typeId> +inline const RawBrandedSchema& rawBrandedSchema() { + return schemas::EnumInfo::schema->defaultBrand; +} + +template +struct ChooseBrand; +// If all of `Params` are `AnyPointer`, return the type's default brand. Otherwise, return a +// specific brand instance. TypeTag is the _capnpPrivate struct for the type in question. + +template +struct ChooseBrand { + // All params were AnyPointer. No specific brand needed. + static constexpr _::RawBrandedSchema const* brand() { return &TypeTag::schema->defaultBrand; } +}; + +template +struct ChooseBrand: public ChooseBrand {}; +// The first parameter is AnyPointer, so recurse to check the rest. + +template +struct ChooseBrand { + // At least one parameter is not AnyPointer, so use the specificBrand constant. + static constexpr _::RawBrandedSchema const* brand() { return &TypeTag::specificBrand; } +}; + +template ()> +struct BrandBindingFor_; + +#define HANDLE_TYPE(Type, which) \ + template <> \ + struct BrandBindingFor_ { \ + static constexpr RawBrandedSchema::Binding get(uint16_t listDepth) { \ + return { which, listDepth, nullptr }; \ + } \ + } +HANDLE_TYPE(Void, 0); +HANDLE_TYPE(bool, 1); +HANDLE_TYPE(int8_t, 2); +HANDLE_TYPE(int16_t, 3); +HANDLE_TYPE(int32_t, 4); +HANDLE_TYPE(int64_t, 5); +HANDLE_TYPE(uint8_t, 6); +HANDLE_TYPE(uint16_t, 7); +HANDLE_TYPE(uint32_t, 8); +HANDLE_TYPE(uint64_t, 9); +HANDLE_TYPE(float, 10); +HANDLE_TYPE(double, 11); +#undef HANDLE_TYPE + +template <> +struct BrandBindingFor_ { + static constexpr RawBrandedSchema::Binding get(uint16_t listDepth) { + return { 12, listDepth, nullptr }; + } +}; + +template <> +struct BrandBindingFor_ { + static constexpr RawBrandedSchema::Binding get(uint16_t listDepth) { + return { 13, listDepth, nullptr }; + } +}; + +template +struct BrandBindingFor_, Kind::LIST> { + static constexpr RawBrandedSchema::Binding get(uint16_t listDepth) { + return BrandBindingFor_::get(listDepth + 1); + } +}; + +template +struct BrandBindingFor_ { + static constexpr RawBrandedSchema::Binding get(uint16_t listDepth) { + return { 15, listDepth, nullptr }; + } +}; + +template +struct BrandBindingFor_ { + static constexpr RawBrandedSchema::Binding get(uint16_t listDepth) { + return { 16, listDepth, T::_capnpPrivate::brand() }; + } +}; + +template +struct BrandBindingFor_ { + static constexpr RawBrandedSchema::Binding get(uint16_t listDepth) { + return { 17, listDepth, T::_capnpPrivate::brand() }; + } +}; + +template <> +struct BrandBindingFor_ { + static constexpr RawBrandedSchema::Binding get(uint16_t listDepth) { + return { 18, listDepth, 0, 0 }; + } +}; + +template <> +struct BrandBindingFor_ { + static constexpr RawBrandedSchema::Binding get(uint16_t listDepth) { + return { 18, listDepth, 0, 1 }; + } +}; + +template <> +struct BrandBindingFor_ { + static constexpr RawBrandedSchema::Binding get(uint16_t listDepth) { + return { 18, listDepth, 0, 2 }; + } +}; + +template <> +struct BrandBindingFor_ { + static constexpr RawBrandedSchema::Binding get(uint16_t listDepth) { + return { 18, listDepth, 0, 3 }; + } +}; + +template +constexpr RawBrandedSchema::Binding brandBindingFor() { + return BrandBindingFor_::get(0); +} + +kj::StringTree structString(StructReader reader, const RawBrandedSchema& schema); +kj::String enumString(uint16_t value, const RawBrandedSchema& schema); +// Declared here so that we can declare inline stringify methods on generated types. +// Defined in stringify.c++, which depends on dynamic.c++, which is allowed not to be linked in. + +template +inline kj::StringTree structString(StructReader reader) { + return structString(reader, rawBrandedSchema()); +} +template +inline kj::String enumString(T value) { + return enumString(static_cast(value), rawBrandedSchema()); +} + +#endif // !CAPNP_LITE + +// TODO(cleanup): Unify ConstStruct and ConstList. +template +class ConstStruct { +public: + ConstStruct() = delete; + KJ_DISALLOW_COPY(ConstStruct); + inline explicit constexpr ConstStruct(const word* ptr): ptr(ptr) {} + + inline typename T::Reader get() const { + return AnyPointer::Reader(PointerReader::getRootUnchecked(ptr)).getAs(); + } + + inline operator typename T::Reader() const { return get(); } + inline typename T::Reader operator*() const { return get(); } + inline TemporaryPointer operator->() const { return get(); } + +private: + const word* ptr; +}; + +template +class ConstList { +public: + ConstList() = delete; + KJ_DISALLOW_COPY(ConstList); + inline explicit constexpr ConstList(const word* ptr): ptr(ptr) {} + + inline typename List::Reader get() const { + return AnyPointer::Reader(PointerReader::getRootUnchecked(ptr)).getAs>(); + } + + inline operator typename List::Reader() const { return get(); } + inline typename List::Reader operator*() const { return get(); } + inline TemporaryPointer::Reader> operator->() const { return get(); } + +private: + const word* ptr; +}; + +template +class ConstText { +public: + ConstText() = delete; + KJ_DISALLOW_COPY(ConstText); + inline explicit constexpr ConstText(const word* ptr): ptr(ptr) {} + + inline Text::Reader get() const { + return Text::Reader(reinterpret_cast(ptr), size); + } + + inline operator Text::Reader() const { return get(); } + inline Text::Reader operator*() const { return get(); } + inline TemporaryPointer operator->() const { return get(); } + + inline kj::StringPtr toString() const { + return get(); + } + +private: + const word* ptr; +}; + +template +inline kj::StringPtr KJ_STRINGIFY(const ConstText& s) { + return s.get(); +} + +template +class ConstData { +public: + ConstData() = delete; + KJ_DISALLOW_COPY(ConstData); + inline explicit constexpr ConstData(const word* ptr): ptr(ptr) {} + + inline Data::Reader get() const { + return Data::Reader(reinterpret_cast(ptr), size); + } + + inline operator Data::Reader() const { return get(); } + inline Data::Reader operator*() const { return get(); } + inline TemporaryPointer operator->() const { return get(); } + +private: + const word* ptr; +}; + +template +inline auto KJ_STRINGIFY(const ConstData& s) -> decltype(kj::toCharSequence(s.get())) { + return kj::toCharSequence(s.get()); +} + +} // namespace _ (private) + +template +inline constexpr uint64_t typeId() { return CapnpPrivate::typeId; } +template ::typeId> +inline constexpr uint64_t typeId() { return id; } +// typeId() returns the type ID as defined in the schema. Works with structs, enums, and +// interfaces. + +template +inline constexpr uint sizeInWords() { + // Return the size, in words, of a Struct type, if allocated free-standing (not in a list). + // May be useful for pre-computing space needed in order to precisely allocate messages. + + return unbound((upgradeBound(_::structSize().data) + + _::structSize().pointers * WORDS_PER_POINTER) / WORDS); +} + +} // namespace capnp + +#if _MSC_VER +// MSVC doesn't understand floating-point constexpr yet. +// +// TODO(msvc): Remove this hack when MSVC is fixed. +#define CAPNP_NON_INT_CONSTEXPR_DECL_INIT(value) +#define CAPNP_NON_INT_CONSTEXPR_DEF_INIT(value) = value +#else +#define CAPNP_NON_INT_CONSTEXPR_DECL_INIT(value) = value +#define CAPNP_NON_INT_CONSTEXPR_DEF_INIT(value) +#endif + +#if _MSC_VER +// TODO(msvc): A little hack to allow MSVC to use C++14 return type deduction in cases where the +// explicit type exposes bugs in the compiler. +#define CAPNP_AUTO_IF_MSVC(...) auto +#else +#define CAPNP_AUTO_IF_MSVC(...) __VA_ARGS__ +#endif + +#if CAPNP_LITE + +#define CAPNP_DECLARE_SCHEMA(id) \ + extern ::capnp::word const* const bp_##id + +#define CAPNP_DECLARE_ENUM(type, id) \ + inline ::kj::String KJ_STRINGIFY(type##_##id value) { \ + return ::kj::str(static_cast(value)); \ + } \ + template <> struct EnumInfo { \ + struct IsEnum; \ + static constexpr uint64_t typeId = 0x##id; \ + static inline ::capnp::word const* encodedSchema() { return bp_##id; } \ + } + +#if _MSC_VER +// TODO(msvc): MSVC dosen't expect constexprs to have definitions. +#define CAPNP_DEFINE_ENUM(type, id) +#else +#define CAPNP_DEFINE_ENUM(type, id) \ + constexpr uint64_t EnumInfo::typeId +#endif + +#define CAPNP_DECLARE_STRUCT_HEADER(id, dataWordSize_, pointerCount_) \ + struct IsStruct; \ + static constexpr uint64_t typeId = 0x##id; \ + static constexpr uint16_t dataWordSize = dataWordSize_; \ + static constexpr uint16_t pointerCount = pointerCount_; \ + static inline ::capnp::word const* encodedSchema() { return ::capnp::schemas::bp_##id; } + +#else // CAPNP_LITE + +#define CAPNP_DECLARE_SCHEMA(id) \ + extern ::capnp::word const* const bp_##id; \ + extern const ::capnp::_::RawSchema s_##id + +#define CAPNP_DECLARE_ENUM(type, id) \ + inline ::kj::String KJ_STRINGIFY(type##_##id value) { \ + return ::capnp::_::enumString(value); \ + } \ + template <> struct EnumInfo { \ + struct IsEnum; \ + static constexpr uint64_t typeId = 0x##id; \ + static inline ::capnp::word const* encodedSchema() { return bp_##id; } \ + static constexpr ::capnp::_::RawSchema const* schema = &s_##id; \ + } +#define CAPNP_DEFINE_ENUM(type, id) \ + constexpr uint64_t EnumInfo::typeId; \ + constexpr ::capnp::_::RawSchema const* EnumInfo::schema + +#define CAPNP_DECLARE_STRUCT_HEADER(id, dataWordSize_, pointerCount_) \ + struct IsStruct; \ + static constexpr uint64_t typeId = 0x##id; \ + static constexpr ::capnp::Kind kind = ::capnp::Kind::STRUCT; \ + static constexpr uint16_t dataWordSize = dataWordSize_; \ + static constexpr uint16_t pointerCount = pointerCount_; \ + static inline ::capnp::word const* encodedSchema() { return ::capnp::schemas::bp_##id; } \ + static constexpr ::capnp::_::RawSchema const* schema = &::capnp::schemas::s_##id; + +#define CAPNP_DECLARE_INTERFACE_HEADER(id) \ + struct IsInterface; \ + static constexpr uint64_t typeId = 0x##id; \ + static constexpr ::capnp::Kind kind = ::capnp::Kind::INTERFACE; \ + static inline ::capnp::word const* encodedSchema() { return ::capnp::schemas::bp_##id; } \ + static constexpr ::capnp::_::RawSchema const* schema = &::capnp::schemas::s_##id; + +#endif // CAPNP_LITE, else + +#endif // CAPNP_GENERATED_HEADER_SUPPORT_H_ diff --git a/phonelibs/capnp-cpp/include/capnp/json.capnp b/phonelibs/capnp-cpp/include/capnp/json.capnp new file mode 100644 index 00000000000000..55188736f8bdb2 --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/json.capnp @@ -0,0 +1,58 @@ +# Copyright (c) 2015 Sandstorm Development Group, Inc. and contributors +# Licensed under the MIT License: +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in +# all copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +# THE SOFTWARE. + +@0x8ef99297a43a5e34; + +$import "/capnp/c++.capnp".namespace("capnp"); + +struct JsonValue { + union { + null @0 :Void; + boolean @1 :Bool; + number @2 :Float64; + string @3 :Text; + array @4 :List(JsonValue); + object @5 :List(Field); + # Standard JSON values. + + call @6 :Call; + # Non-standard: A "function call", applying a named function (named by a single identifier) + # to a parameter list. Examples: + # + # BinData(0, "Zm9vCg==") + # ISODate("2015-04-15T08:44:50.218Z") + # + # Mongo DB users will recognize the above as exactly the syntax Mongo uses to represent BSON + # "binary" and "date" types in text, since JSON has no analog of these. This is basically the + # reason this extension exists. We do NOT recommend using `call` unless you specifically need + # to be compatible with some silly format that uses this syntax. + } + + struct Field { + name @0 :Text; + value @1 :JsonValue; + } + + struct Call { + function @0 :Text; + params @1 :List(JsonValue); + } +} diff --git a/phonelibs/capnp-cpp/include/capnp/layout.h b/phonelibs/capnp-cpp/include/capnp/layout.h new file mode 100644 index 00000000000000..99dc533b2bf157 --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/layout.h @@ -0,0 +1,1274 @@ +// Copyright (c) 2013-2016 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +// This file is NOT intended for use by clients, except in generated code. +// +// This file defines low-level, non-type-safe classes for traversing the Cap'n Proto memory layout +// (which is also its wire format). Code generated by the Cap'n Proto compiler uses these classes, +// as does other parts of the Cap'n proto library which provide a higher-level interface for +// dynamic introspection. + +#ifndef CAPNP_LAYOUT_H_ +#define CAPNP_LAYOUT_H_ + +#if defined(__GNUC__) && !defined(CAPNP_HEADER_WARNINGS) +#pragma GCC system_header +#endif + +#include +#include +#include "common.h" +#include "blob.h" +#include "endian.h" + +#if (defined(__mips__) || defined(__hppa__)) && !defined(CAPNP_CANONICALIZE_NAN) +#define CAPNP_CANONICALIZE_NAN 1 +// Explicitly detect NaNs and canonicalize them to the quiet NaN value as would be returned by +// __builtin_nan("") on systems implementing the IEEE-754 recommended (but not required) NaN +// signalling/quiet differentiation (such as x86). Unfortunately, some architectures -- in +// particular, MIPS -- represent quiet vs. signalling nans differently than the rest of the world. +// Canonicalizing them makes output consistent (which is important!), but hurts performance +// slightly. +// +// Note that trying to convert MIPS NaNs to standard NaNs without losing data doesn't work. +// Signaling vs. quiet is indicated by a bit, with the meaning being the opposite on MIPS vs. +// everyone else. It would be great if we could just flip that bit, but we can't, because if the +// significand is all-zero, then the value is infinity rather than NaN. This means that on most +// machines, where the bit indicates quietness, there is one more quiet NaN value than signalling +// NaN value, whereas on MIPS there is one more sNaN than qNaN, and thus there is no isomorphic +// mapping that properly preserves quietness. Instead of doing something hacky, we just give up +// and blow away NaN payloads, because no one uses them anyway. +#endif + +namespace capnp { + +#if !CAPNP_LITE +class ClientHook; +#endif // !CAPNP_LITE + +namespace _ { // private + +class PointerBuilder; +class PointerReader; +class StructBuilder; +class StructReader; +class ListBuilder; +class ListReader; +class OrphanBuilder; +struct WirePointer; +struct WireHelpers; +class SegmentReader; +class SegmentBuilder; +class Arena; +class BuilderArena; + +// ============================================================================= + +#if CAPNP_DEBUG_TYPES +typedef kj::UnitRatio, BitLabel, ElementLabel> BitsPerElementTableType; +#else +typedef uint BitsPerElementTableType; +#endif + +static constexpr BitsPerElementTableType BITS_PER_ELEMENT_TABLE[8] = { + bounded< 0>() * BITS / ELEMENTS, + bounded< 1>() * BITS / ELEMENTS, + bounded< 8>() * BITS / ELEMENTS, + bounded<16>() * BITS / ELEMENTS, + bounded<32>() * BITS / ELEMENTS, + bounded<64>() * BITS / ELEMENTS, + bounded< 0>() * BITS / ELEMENTS, + bounded< 0>() * BITS / ELEMENTS +}; + +inline KJ_CONSTEXPR() BitsPerElementTableType dataBitsPerElement(ElementSize size) { + return _::BITS_PER_ELEMENT_TABLE[static_cast(size)]; +} + +inline constexpr PointersPerElementN<1> pointersPerElement(ElementSize size) { + return size == ElementSize::POINTER + ? PointersPerElementN<1>(ONE * POINTERS / ELEMENTS) + : PointersPerElementN<1>(ZERO * POINTERS / ELEMENTS); +} + +static constexpr BitsPerElementTableType BITS_PER_ELEMENT_INCLUDING_PONITERS_TABLE[8] = { + bounded< 0>() * BITS / ELEMENTS, + bounded< 1>() * BITS / ELEMENTS, + bounded< 8>() * BITS / ELEMENTS, + bounded<16>() * BITS / ELEMENTS, + bounded<32>() * BITS / ELEMENTS, + bounded<64>() * BITS / ELEMENTS, + bounded<64>() * BITS / ELEMENTS, + bounded< 0>() * BITS / ELEMENTS +}; + +inline KJ_CONSTEXPR() BitsPerElementTableType bitsPerElementIncludingPointers(ElementSize size) { + return _::BITS_PER_ELEMENT_INCLUDING_PONITERS_TABLE[static_cast(size)]; +} + +template struct ElementSizeForByteSize; +template <> struct ElementSizeForByteSize<1> { static constexpr ElementSize value = ElementSize::BYTE; }; +template <> struct ElementSizeForByteSize<2> { static constexpr ElementSize value = ElementSize::TWO_BYTES; }; +template <> struct ElementSizeForByteSize<4> { static constexpr ElementSize value = ElementSize::FOUR_BYTES; }; +template <> struct ElementSizeForByteSize<8> { static constexpr ElementSize value = ElementSize::EIGHT_BYTES; }; + +template struct ElementSizeForType { + static constexpr ElementSize value = + // Primitive types that aren't special-cased below can be determined from sizeof(). + CAPNP_KIND(T) == Kind::PRIMITIVE ? ElementSizeForByteSize::value : + CAPNP_KIND(T) == Kind::ENUM ? ElementSize::TWO_BYTES : + CAPNP_KIND(T) == Kind::STRUCT ? ElementSize::INLINE_COMPOSITE : + + // Everything else is a pointer. + ElementSize::POINTER; +}; + +// Void and bool are special. +template <> struct ElementSizeForType { static constexpr ElementSize value = ElementSize::VOID; }; +template <> struct ElementSizeForType { static constexpr ElementSize value = ElementSize::BIT; }; + +// Lists and blobs are pointers, not structs. +template struct ElementSizeForType> { + static constexpr ElementSize value = ElementSize::POINTER; +}; +template <> struct ElementSizeForType { + static constexpr ElementSize value = ElementSize::POINTER; +}; +template <> struct ElementSizeForType { + static constexpr ElementSize value = ElementSize::POINTER; +}; + +template +inline constexpr ElementSize elementSizeForType() { + return ElementSizeForType::value; +} + +struct MessageSizeCounts { + WordCountN<61, uint64_t> wordCount; // 2^64 bytes + uint capCount; + + MessageSizeCounts& operator+=(const MessageSizeCounts& other) { + // OK to truncate unchecked because this class is used to count actual stuff in memory, and + // we couldn't possibly have anywhere near 2^61 words. + wordCount = assumeBits<61>(wordCount + other.wordCount); + capCount += other.capCount; + return *this; + } + + void addWords(WordCountN<61, uint64_t> other) { + wordCount = assumeBits<61>(wordCount + other); + } + + MessageSize asPublic() { + return MessageSize { unbound(wordCount / WORDS), capCount }; + } +}; + +// ============================================================================= + +template +union AlignedData { + // Useful for declaring static constant data blobs as an array of bytes, but forcing those + // bytes to be word-aligned. + + uint8_t bytes[wordCount * sizeof(word)]; + word words[wordCount]; +}; + +struct StructSize { + StructDataWordCount data; + StructPointerCount pointers; + + inline constexpr WordCountN<17> total() const { return data + pointers * WORDS_PER_POINTER; } + + StructSize() = default; + inline constexpr StructSize(StructDataWordCount data, StructPointerCount pointers) + : data(data), pointers(pointers) {} +}; + +template +inline constexpr StructSize structSize() { + return StructSize(bounded(CapnpPrivate::dataWordSize) * WORDS, + bounded(CapnpPrivate::pointerCount) * POINTERS); +} + +template > +inline constexpr StructSize minStructSizeForElement() { + // If T is a struct, return its struct size. Otherwise return the minimum struct size big enough + // to hold a T. + + return StructSize(bounded(CapnpPrivate::dataWordSize) * WORDS, + bounded(CapnpPrivate::pointerCount) * POINTERS); +} + +template > +inline constexpr StructSize minStructSizeForElement() { + // If T is a struct, return its struct size. Otherwise return the minimum struct size big enough + // to hold a T. + + return StructSize( + dataBitsPerElement(elementSizeForType()) * ELEMENTS > ZERO * BITS + ? StructDataWordCount(ONE * WORDS) : StructDataWordCount(ZERO * WORDS), + pointersPerElement(elementSizeForType()) * ELEMENTS); +} + +// ------------------------------------------------------------------- +// Masking of default values + +template struct Mask_; +template struct Mask_ { typedef T Type; }; +template struct Mask_ { typedef uint16_t Type; }; +template <> struct Mask_ { typedef uint32_t Type; }; +template <> struct Mask_ { typedef uint64_t Type; }; + +template struct Mask_ { + // Union discriminants end up here. + static_assert(sizeof(T) == 2, "Don't know how to mask this type."); + typedef uint16_t Type; +}; + +template +using Mask = typename Mask_::Type; + +template +KJ_ALWAYS_INLINE(Mask mask(T value, Mask mask)); +template +KJ_ALWAYS_INLINE(T unmask(Mask value, Mask mask)); + +template +inline Mask mask(T value, Mask mask) { + return static_cast >(value) ^ mask; +} + +template <> +inline uint32_t mask(float value, uint32_t mask) { +#if CAPNP_CANONICALIZE_NAN + if (value != value) { + return 0x7fc00000u ^ mask; + } +#endif + + uint32_t i; + static_assert(sizeof(i) == sizeof(value), "float is not 32 bits?"); + memcpy(&i, &value, sizeof(value)); + return i ^ mask; +} + +template <> +inline uint64_t mask(double value, uint64_t mask) { +#if CAPNP_CANONICALIZE_NAN + if (value != value) { + return 0x7ff8000000000000ull ^ mask; + } +#endif + + uint64_t i; + static_assert(sizeof(i) == sizeof(value), "double is not 64 bits?"); + memcpy(&i, &value, sizeof(value)); + return i ^ mask; +} + +template +inline T unmask(Mask value, Mask mask) { + return static_cast(value ^ mask); +} + +template <> +inline float unmask(uint32_t value, uint32_t mask) { + value ^= mask; + float result; + static_assert(sizeof(result) == sizeof(value), "float is not 32 bits?"); + memcpy(&result, &value, sizeof(value)); + return result; +} + +template <> +inline double unmask(uint64_t value, uint64_t mask) { + value ^= mask; + double result; + static_assert(sizeof(result) == sizeof(value), "double is not 64 bits?"); + memcpy(&result, &value, sizeof(value)); + return result; +} + +// ------------------------------------------------------------------- + +class CapTableReader { +public: +#if !CAPNP_LITE + virtual kj::Maybe> extractCap(uint index) = 0; + // Extract the capability at the given index. If the index is invalid, returns null. +#endif // !CAPNP_LITE +}; + +class CapTableBuilder: public CapTableReader { +public: +#if !CAPNP_LITE + virtual uint injectCap(kj::Own&& cap) = 0; + // Add the capability to the message and return its index. If the same ClientHook is injected + // twice, this may return the same index both times, but in this case dropCap() needs to be + // called an equal number of times to actually remove the cap. + + virtual void dropCap(uint index) = 0; + // Remove a capability injected earlier. Called when the pointer is overwritten or zero'd out. +#endif // !CAPNP_LITE +}; + +// ------------------------------------------------------------------- + +class PointerBuilder: public kj::DisallowConstCopy { + // Represents a single pointer, usually embedded in a struct or a list. + +public: + inline PointerBuilder(): segment(nullptr), capTable(nullptr), pointer(nullptr) {} + + static inline PointerBuilder getRoot( + SegmentBuilder* segment, CapTableBuilder* capTable, word* location); + // Get a PointerBuilder representing a message root located in the given segment at the given + // location. + + inline bool isNull() { return getPointerType() == PointerType::NULL_; } + PointerType getPointerType() const; + + StructBuilder getStruct(StructSize size, const word* defaultValue); + ListBuilder getList(ElementSize elementSize, const word* defaultValue); + ListBuilder getStructList(StructSize elementSize, const word* defaultValue); + ListBuilder getListAnySize(const word* defaultValue); + template typename T::Builder getBlob( + const void* defaultValue, ByteCount defaultSize); +#if !CAPNP_LITE + kj::Own getCapability(); +#endif // !CAPNP_LITE + // Get methods: Get the value. If it is null, initialize it to a copy of the default value. + // The default value is encoded as an "unchecked message" for structs, lists, and objects, or a + // simple byte array for blobs. + + StructBuilder initStruct(StructSize size); + ListBuilder initList(ElementSize elementSize, ElementCount elementCount); + ListBuilder initStructList(ElementCount elementCount, StructSize size); + template typename T::Builder initBlob(ByteCount size); + // Init methods: Initialize the pointer to a newly-allocated object, discarding the existing + // object. + + void setStruct(const StructReader& value, bool canonical = false); + void setList(const ListReader& value, bool canonical = false); + template void setBlob(typename T::Reader value); +#if !CAPNP_LITE + void setCapability(kj::Own&& cap); +#endif // !CAPNP_LITE + // Set methods: Initialize the pointer to a newly-allocated copy of the given value, discarding + // the existing object. + + void adopt(OrphanBuilder&& orphan); + // Set the pointer to point at the given orphaned value. + + OrphanBuilder disown(); + // Set the pointer to null and return its previous value as an orphan. + + void clear(); + // Clear the pointer to null, discarding its previous value. + + void transferFrom(PointerBuilder other); + // Equivalent to `adopt(other.disown())`. + + void copyFrom(PointerReader other, bool canonical = false); + // Equivalent to `set(other.get())`. + // If you set the canonical flag, it will attempt to lay the target out + // canonically, provided enough space is available. + + PointerReader asReader() const; + + BuilderArena* getArena() const; + // Get the arena containing this pointer. + + CapTableBuilder* getCapTable(); + // Gets the capability context in which this object is operating. + + PointerBuilder imbue(CapTableBuilder* capTable); + // Return a copy of this builder except using the given capability context. + +private: + SegmentBuilder* segment; // Memory segment in which the pointer resides. + CapTableBuilder* capTable; // Table of capability indexes. + WirePointer* pointer; // Pointer to the pointer. + + inline PointerBuilder(SegmentBuilder* segment, CapTableBuilder* capTable, WirePointer* pointer) + : segment(segment), capTable(capTable), pointer(pointer) {} + + friend class StructBuilder; + friend class ListBuilder; + friend class OrphanBuilder; +}; + +class PointerReader { +public: + inline PointerReader() + : segment(nullptr), capTable(nullptr), pointer(nullptr), nestingLimit(0x7fffffff) {} + + static PointerReader getRoot(SegmentReader* segment, CapTableReader* capTable, + const word* location, int nestingLimit); + // Get a PointerReader representing a message root located in the given segment at the given + // location. + + static inline PointerReader getRootUnchecked(const word* location); + // Get a PointerReader for an unchecked message. + + MessageSizeCounts targetSize() const; + // Return the total size of the target object and everything to which it points. Does not count + // far pointer overhead. This is useful for deciding how much space is needed to copy the object + // into a flat array. However, the caller is advised NOT to treat this value as secure. Instead, + // use the result as a hint for allocating the first segment, do the copy, and then throw an + // exception if it overruns. + + inline bool isNull() const { return getPointerType() == PointerType::NULL_; } + PointerType getPointerType() const; + + StructReader getStruct(const word* defaultValue) const; + ListReader getList(ElementSize expectedElementSize, const word* defaultValue) const; + ListReader getListAnySize(const word* defaultValue) const; + template + typename T::Reader getBlob(const void* defaultValue, ByteCount defaultSize) const; +#if !CAPNP_LITE + kj::Own getCapability() const; +#endif // !CAPNP_LITE + // Get methods: Get the value. If it is null, return the default value instead. + // The default value is encoded as an "unchecked message" for structs, lists, and objects, or a + // simple byte array for blobs. + + const word* getUnchecked() const; + // If this is an unchecked message, get a word* pointing at the location of the pointer. This + // word* can actually be passed to readUnchecked() to read the designated sub-object later. If + // this isn't an unchecked message, throws an exception. + + kj::Maybe getArena() const; + // Get the arena containing this pointer. + + CapTableReader* getCapTable(); + // Gets the capability context in which this object is operating. + + PointerReader imbue(CapTableReader* capTable) const; + // Return a copy of this reader except using the given capability context. + + bool isCanonical(const word **readHead); + // Validate this pointer's canonicity, subject to the conditions: + // * All data to the left of readHead has been read thus far (for pointer + // ordering) + // * All pointers in preorder have already been checked + // * This pointer is in the first and only segment of the message + +private: + SegmentReader* segment; // Memory segment in which the pointer resides. + CapTableReader* capTable; // Table of capability indexes. + const WirePointer* pointer; // Pointer to the pointer. null = treat as null pointer. + + int nestingLimit; + // Limits the depth of message structures to guard against stack-overflow-based DoS attacks. + // Once this reaches zero, further pointers will be pruned. + + inline PointerReader(SegmentReader* segment, CapTableReader* capTable, + const WirePointer* pointer, int nestingLimit) + : segment(segment), capTable(capTable), pointer(pointer), nestingLimit(nestingLimit) {} + + friend class StructReader; + friend class ListReader; + friend class PointerBuilder; + friend class OrphanBuilder; +}; + +// ------------------------------------------------------------------- + +class StructBuilder: public kj::DisallowConstCopy { +public: + inline StructBuilder(): segment(nullptr), capTable(nullptr), data(nullptr), pointers(nullptr) {} + + inline word* getLocation() { return reinterpret_cast(data); } + // Get the object's location. Only valid for independently-allocated objects (i.e. not list + // elements). + + inline StructDataBitCount getDataSectionSize() const { return dataSize; } + inline StructPointerCount getPointerSectionSize() const { return pointerCount; } + inline kj::ArrayPtr getDataSectionAsBlob(); + inline _::ListBuilder getPointerSectionAsList(); + + template + KJ_ALWAYS_INLINE(bool hasDataField(StructDataOffset offset)); + // Return true if the field is set to something other than its default value. + + template + KJ_ALWAYS_INLINE(T getDataField(StructDataOffset offset)); + // Gets the data field value of the given type at the given offset. The offset is measured in + // multiples of the field size, determined by the type. + + template + KJ_ALWAYS_INLINE(T getDataField(StructDataOffset offset, Mask mask)); + // Like getDataField() but applies the given XOR mask to the data on load. Used for reading + // fields with non-zero default values. + + template + KJ_ALWAYS_INLINE(void setDataField(StructDataOffset offset, kj::NoInfer value)); + // Sets the data field value at the given offset. + + template + KJ_ALWAYS_INLINE(void setDataField(StructDataOffset offset, + kj::NoInfer value, Mask mask)); + // Like setDataField() but applies the given XOR mask before storing. Used for writing fields + // with non-zero default values. + + KJ_ALWAYS_INLINE(PointerBuilder getPointerField(StructPointerOffset ptrIndex)); + // Get a builder for a pointer field given the index within the pointer section. + + void clearAll(); + // Clear all pointers and data. + + void transferContentFrom(StructBuilder other); + // Adopt all pointers from `other`, and also copy all data. If `other`'s sections are larger + // than this, the extra data is not transferred, meaning there is a risk of data loss when + // transferring from messages built with future versions of the protocol. + + void copyContentFrom(StructReader other); + // Copy content from `other`. If `other`'s sections are larger than this, the extra data is not + // copied, meaning there is a risk of data loss when copying from messages built with future + // versions of the protocol. + + StructReader asReader() const; + // Gets a StructReader pointing at the same memory. + + BuilderArena* getArena(); + // Gets the arena in which this object is allocated. + + CapTableBuilder* getCapTable(); + // Gets the capability context in which this object is operating. + + StructBuilder imbue(CapTableBuilder* capTable); + // Return a copy of this builder except using the given capability context. + +private: + SegmentBuilder* segment; // Memory segment in which the struct resides. + CapTableBuilder* capTable; // Table of capability indexes. + void* data; // Pointer to the encoded data. + WirePointer* pointers; // Pointer to the encoded pointers. + + StructDataBitCount dataSize; + // Size of data section. We use a bit count rather than a word count to more easily handle the + // case of struct lists encoded with less than a word per element. + + StructPointerCount pointerCount; // Size of the pointer section. + + inline StructBuilder(SegmentBuilder* segment, CapTableBuilder* capTable, + void* data, WirePointer* pointers, + StructDataBitCount dataSize, StructPointerCount pointerCount) + : segment(segment), capTable(capTable), data(data), pointers(pointers), + dataSize(dataSize), pointerCount(pointerCount) {} + + friend class ListBuilder; + friend struct WireHelpers; + friend class OrphanBuilder; +}; + +class StructReader { +public: + inline StructReader() + : segment(nullptr), capTable(nullptr), data(nullptr), pointers(nullptr), + dataSize(ZERO * BITS), pointerCount(ZERO * POINTERS), nestingLimit(0x7fffffff) {} + inline StructReader(kj::ArrayPtr data) + : segment(nullptr), capTable(nullptr), data(data.begin()), pointers(nullptr), + dataSize(assumeBits(data.size()) * WORDS * BITS_PER_WORD), + pointerCount(ZERO * POINTERS), nestingLimit(0x7fffffff) {} + + const void* getLocation() const { return data; } + + inline StructDataBitCount getDataSectionSize() const { return dataSize; } + inline StructPointerCount getPointerSectionSize() const { return pointerCount; } + inline kj::ArrayPtr getDataSectionAsBlob(); + inline _::ListReader getPointerSectionAsList(); + + kj::Array canonicalize(); + + template + KJ_ALWAYS_INLINE(bool hasDataField(StructDataOffset offset) const); + // Return true if the field is set to something other than its default value. + + template + KJ_ALWAYS_INLINE(T getDataField(StructDataOffset offset) const); + // Get the data field value of the given type at the given offset. The offset is measured in + // multiples of the field size, determined by the type. Returns zero if the offset is past the + // end of the struct's data section. + + template + KJ_ALWAYS_INLINE(T getDataField(StructDataOffset offset, Mask mask) const); + // Like getDataField(offset), but applies the given XOR mask to the result. Used for reading + // fields with non-zero default values. + + KJ_ALWAYS_INLINE(PointerReader getPointerField(StructPointerOffset ptrIndex) const); + // Get a reader for a pointer field given the index within the pointer section. If the index + // is out-of-bounds, returns a null pointer. + + MessageSizeCounts totalSize() const; + // Return the total size of the struct and everything to which it points. Does not count far + // pointer overhead. This is useful for deciding how much space is needed to copy the struct + // into a flat array. However, the caller is advised NOT to treat this value as secure. Instead, + // use the result as a hint for allocating the first segment, do the copy, and then throw an + // exception if it overruns. + + CapTableReader* getCapTable(); + // Gets the capability context in which this object is operating. + + StructReader imbue(CapTableReader* capTable) const; + // Return a copy of this reader except using the given capability context. + + bool isCanonical(const word **readHead, const word **ptrHead, + bool *dataTrunc, bool *ptrTrunc); + // Validate this pointer's canonicity, subject to the conditions: + // * All data to the left of readHead has been read thus far (for pointer + // ordering) + // * All pointers in preorder have already been checked + // * This pointer is in the first and only segment of the message + // + // If this function returns false, the struct is non-canonical. If it + // returns true, then: + // * If it is a composite in a list, it is canonical if at least one struct + // in the list outputs dataTrunc = 1, and at least one outputs ptrTrunc = 1 + // * If it is derived from a struct pointer, it is canonical if + // dataTrunc = 1 AND ptrTrunc = 1 + +private: + SegmentReader* segment; // Memory segment in which the struct resides. + CapTableReader* capTable; // Table of capability indexes. + + const void* data; + const WirePointer* pointers; + + StructDataBitCount dataSize; + // Size of data section. We use a bit count rather than a word count to more easily handle the + // case of struct lists encoded with less than a word per element. + + StructPointerCount pointerCount; // Size of the pointer section. + + int nestingLimit; + // Limits the depth of message structures to guard against stack-overflow-based DoS attacks. + // Once this reaches zero, further pointers will be pruned. + // TODO(perf): Limit to 16 bits for better packing? + + inline StructReader(SegmentReader* segment, CapTableReader* capTable, + const void* data, const WirePointer* pointers, + StructDataBitCount dataSize, StructPointerCount pointerCount, + int nestingLimit) + : segment(segment), capTable(capTable), data(data), pointers(pointers), + dataSize(dataSize), pointerCount(pointerCount), + nestingLimit(nestingLimit) {} + + friend class ListReader; + friend class StructBuilder; + friend struct WireHelpers; +}; + +// ------------------------------------------------------------------- + +class ListBuilder: public kj::DisallowConstCopy { +public: + inline explicit ListBuilder(ElementSize elementSize) + : segment(nullptr), capTable(nullptr), ptr(nullptr), elementCount(ZERO * ELEMENTS), + step(ZERO * BITS / ELEMENTS), structDataSize(ZERO * BITS), + structPointerCount(ZERO * POINTERS), elementSize(elementSize) {} + + inline word* getLocation() { + // Get the object's location. + + if (elementSize == ElementSize::INLINE_COMPOSITE && ptr != nullptr) { + return reinterpret_cast(ptr) - POINTER_SIZE_IN_WORDS; + } else { + return reinterpret_cast(ptr); + } + } + + inline ElementSize getElementSize() const { return elementSize; } + + inline ListElementCount size() const; + // The number of elements in the list. + + Text::Builder asText(); + Data::Builder asData(); + // Reinterpret the list as a blob. Throws an exception if the elements are not byte-sized. + + template + KJ_ALWAYS_INLINE(T getDataElement(ElementCount index)); + // Get the element of the given type at the given index. + + template + KJ_ALWAYS_INLINE(void setDataElement(ElementCount index, kj::NoInfer value)); + // Set the element at the given index. + + KJ_ALWAYS_INLINE(PointerBuilder getPointerElement(ElementCount index)); + + StructBuilder getStructElement(ElementCount index); + + ListReader asReader() const; + // Get a ListReader pointing at the same memory. + + BuilderArena* getArena(); + // Gets the arena in which this object is allocated. + + CapTableBuilder* getCapTable(); + // Gets the capability context in which this object is operating. + + ListBuilder imbue(CapTableBuilder* capTable); + // Return a copy of this builder except using the given capability context. + +private: + SegmentBuilder* segment; // Memory segment in which the list resides. + CapTableBuilder* capTable; // Table of capability indexes. + + byte* ptr; // Pointer to list content. + + ListElementCount elementCount; // Number of elements in the list. + + BitsPerElementN<23> step; + // The distance between elements. The maximum value occurs when a struct contains 2^16-1 data + // words and 2^16-1 pointers, i.e. 2^17 - 2 words, or 2^23 - 128 bits. + + StructDataBitCount structDataSize; + StructPointerCount structPointerCount; + // The struct properties to use when interpreting the elements as structs. All lists can be + // interpreted as struct lists, so these are always filled in. + + ElementSize elementSize; + // The element size as a ElementSize. This is only really needed to disambiguate INLINE_COMPOSITE + // from other types when the overall size is exactly zero or one words. + + inline ListBuilder(SegmentBuilder* segment, CapTableBuilder* capTable, void* ptr, + BitsPerElementN<23> step, ListElementCount size, + StructDataBitCount structDataSize, StructPointerCount structPointerCount, + ElementSize elementSize) + : segment(segment), capTable(capTable), ptr(reinterpret_cast(ptr)), + elementCount(size), step(step), structDataSize(structDataSize), + structPointerCount(structPointerCount), elementSize(elementSize) {} + + friend class StructBuilder; + friend struct WireHelpers; + friend class OrphanBuilder; +}; + +class ListReader { +public: + inline explicit ListReader(ElementSize elementSize) + : segment(nullptr), capTable(nullptr), ptr(nullptr), elementCount(ZERO * ELEMENTS), + step(ZERO * BITS / ELEMENTS), structDataSize(ZERO * BITS), + structPointerCount(ZERO * POINTERS), elementSize(elementSize), nestingLimit(0x7fffffff) {} + + inline ListElementCount size() const; + // The number of elements in the list. + + inline ElementSize getElementSize() const { return elementSize; } + + Text::Reader asText(); + Data::Reader asData(); + // Reinterpret the list as a blob. Throws an exception if the elements are not byte-sized. + + kj::ArrayPtr asRawBytes(); + + template + KJ_ALWAYS_INLINE(T getDataElement(ElementCount index) const); + // Get the element of the given type at the given index. + + KJ_ALWAYS_INLINE(PointerReader getPointerElement(ElementCount index) const); + + StructReader getStructElement(ElementCount index) const; + + CapTableReader* getCapTable(); + // Gets the capability context in which this object is operating. + + ListReader imbue(CapTableReader* capTable) const; + // Return a copy of this reader except using the given capability context. + + bool isCanonical(const word **readHead, const WirePointer* ref); + // Validate this pointer's canonicity, subject to the conditions: + // * All data to the left of readHead has been read thus far (for pointer + // ordering) + // * All pointers in preorder have already been checked + // * This pointer is in the first and only segment of the message + +private: + SegmentReader* segment; // Memory segment in which the list resides. + CapTableReader* capTable; // Table of capability indexes. + + const byte* ptr; // Pointer to list content. + + ListElementCount elementCount; // Number of elements in the list. + + BitsPerElementN<23> step; + // The distance between elements. The maximum value occurs when a struct contains 2^16-1 data + // words and 2^16-1 pointers, i.e. 2^17 - 2 words, or 2^23 - 2 bits. + + StructDataBitCount structDataSize; + StructPointerCount structPointerCount; + // The struct properties to use when interpreting the elements as structs. All lists can be + // interpreted as struct lists, so these are always filled in. + + ElementSize elementSize; + // The element size as a ElementSize. This is only really needed to disambiguate INLINE_COMPOSITE + // from other types when the overall size is exactly zero or one words. + + int nestingLimit; + // Limits the depth of message structures to guard against stack-overflow-based DoS attacks. + // Once this reaches zero, further pointers will be pruned. + + inline ListReader(SegmentReader* segment, CapTableReader* capTable, const void* ptr, + ListElementCount elementCount, BitsPerElementN<23> step, + StructDataBitCount structDataSize, StructPointerCount structPointerCount, + ElementSize elementSize, int nestingLimit) + : segment(segment), capTable(capTable), ptr(reinterpret_cast(ptr)), + elementCount(elementCount), step(step), structDataSize(structDataSize), + structPointerCount(structPointerCount), elementSize(elementSize), + nestingLimit(nestingLimit) {} + + friend class StructReader; + friend class ListBuilder; + friend struct WireHelpers; + friend class OrphanBuilder; +}; + +// ------------------------------------------------------------------- + +class OrphanBuilder { +public: + inline OrphanBuilder(): segment(nullptr), capTable(nullptr), location(nullptr) { + memset(&tag, 0, sizeof(tag)); + } + OrphanBuilder(const OrphanBuilder& other) = delete; + inline OrphanBuilder(OrphanBuilder&& other) noexcept; + inline ~OrphanBuilder() noexcept(false); + + static OrphanBuilder initStruct(BuilderArena* arena, CapTableBuilder* capTable, StructSize size); + static OrphanBuilder initList(BuilderArena* arena, CapTableBuilder* capTable, + ElementCount elementCount, ElementSize elementSize); + static OrphanBuilder initStructList(BuilderArena* arena, CapTableBuilder* capTable, + ElementCount elementCount, StructSize elementSize); + static OrphanBuilder initText(BuilderArena* arena, CapTableBuilder* capTable, ByteCount size); + static OrphanBuilder initData(BuilderArena* arena, CapTableBuilder* capTable, ByteCount size); + + static OrphanBuilder copy(BuilderArena* arena, CapTableBuilder* capTable, StructReader copyFrom); + static OrphanBuilder copy(BuilderArena* arena, CapTableBuilder* capTable, ListReader copyFrom); + static OrphanBuilder copy(BuilderArena* arena, CapTableBuilder* capTable, PointerReader copyFrom); + static OrphanBuilder copy(BuilderArena* arena, CapTableBuilder* capTable, Text::Reader copyFrom); + static OrphanBuilder copy(BuilderArena* arena, CapTableBuilder* capTable, Data::Reader copyFrom); +#if !CAPNP_LITE + static OrphanBuilder copy(BuilderArena* arena, CapTableBuilder* capTable, + kj::Own copyFrom); +#endif // !CAPNP_LITE + + static OrphanBuilder concat(BuilderArena* arena, CapTableBuilder* capTable, + ElementSize expectedElementSize, StructSize expectedStructSize, + kj::ArrayPtr lists); + + static OrphanBuilder referenceExternalData(BuilderArena* arena, Data::Reader data); + + OrphanBuilder& operator=(const OrphanBuilder& other) = delete; + inline OrphanBuilder& operator=(OrphanBuilder&& other); + + inline bool operator==(decltype(nullptr)) const { return location == nullptr; } + inline bool operator!=(decltype(nullptr)) const { return location != nullptr; } + + StructBuilder asStruct(StructSize size); + // Interpret as a struct, or throw an exception if not a struct. + + ListBuilder asList(ElementSize elementSize); + // Interpret as a list, or throw an exception if not a list. elementSize cannot be + // INLINE_COMPOSITE -- use asStructList() instead. + + ListBuilder asStructList(StructSize elementSize); + // Interpret as a struct list, or throw an exception if not a list. + + ListBuilder asListAnySize(); + // For AnyList. + + Text::Builder asText(); + Data::Builder asData(); + // Interpret as a blob, or throw an exception if not a blob. + + StructReader asStructReader(StructSize size) const; + ListReader asListReader(ElementSize elementSize) const; + ListReader asListReaderAnySize() const; +#if !CAPNP_LITE + kj::Own asCapability() const; +#endif // !CAPNP_LITE + Text::Reader asTextReader() const; + Data::Reader asDataReader() const; + + bool truncate(ElementCount size, bool isText) KJ_WARN_UNUSED_RESULT; + // Resize the orphan list to the given size. Returns false if the list is currently empty but + // the requested size is non-zero, in which case the caller will need to allocate a new list. + + void truncate(ElementCount size, ElementSize elementSize); + void truncate(ElementCount size, StructSize elementSize); + void truncateText(ElementCount size); + // Versions of truncate() that know how to allocate a new list if needed. + +private: + static_assert(ONE * POINTERS * WORDS_PER_POINTER == ONE * WORDS, + "This struct assumes a pointer is one word."); + word tag; + // Contains an encoded WirePointer representing this object. WirePointer is defined in + // layout.c++, but fits in a word. + // + // This may be a FAR pointer. Even in that case, `location` points to the eventual destination + // of that far pointer. The reason we keep the far pointer around rather than just making `tag` + // represent the final destination is because if the eventual adopter of the pointer is not in + // the target's segment then it may be useful to reuse the far pointer landing pad. + // + // If `tag` is not a far pointer, its offset is garbage; only `location` points to the actual + // target. + + SegmentBuilder* segment; + // Segment in which the object resides. + + CapTableBuilder* capTable; + // Table of capability indexes. + + word* location; + // Pointer to the object, or nullptr if the pointer is null. For capabilities, we make this + // 0x1 just so that it is non-null for operator==, but it is never used. + + inline OrphanBuilder(const void* tagPtr, SegmentBuilder* segment, + CapTableBuilder* capTable, word* location) + : segment(segment), capTable(capTable), location(location) { + memcpy(&tag, tagPtr, sizeof(tag)); + } + + inline WirePointer* tagAsPtr() { return reinterpret_cast(&tag); } + inline const WirePointer* tagAsPtr() const { return reinterpret_cast(&tag); } + + void euthanize(); + // Erase the target object, zeroing it out and possibly reclaiming the memory. Called when + // the OrphanBuilder is being destroyed or overwritten and it is non-null. + + friend struct WireHelpers; +}; + +// ======================================================================================= +// Internal implementation details... + +// These are defined in the source file. +template <> typename Text::Builder PointerBuilder::initBlob(ByteCount size); +template <> void PointerBuilder::setBlob(typename Text::Reader value); +template <> typename Text::Builder PointerBuilder::getBlob( + const void* defaultValue, ByteCount defaultSize); +template <> typename Text::Reader PointerReader::getBlob( + const void* defaultValue, ByteCount defaultSize) const; + +template <> typename Data::Builder PointerBuilder::initBlob(ByteCount size); +template <> void PointerBuilder::setBlob(typename Data::Reader value); +template <> typename Data::Builder PointerBuilder::getBlob( + const void* defaultValue, ByteCount defaultSize); +template <> typename Data::Reader PointerReader::getBlob( + const void* defaultValue, ByteCount defaultSize) const; + +inline PointerBuilder PointerBuilder::getRoot( + SegmentBuilder* segment, CapTableBuilder* capTable, word* location) { + return PointerBuilder(segment, capTable, reinterpret_cast(location)); +} + +inline PointerReader PointerReader::getRootUnchecked(const word* location) { + return PointerReader(nullptr, nullptr, + reinterpret_cast(location), 0x7fffffff); +} + +// ------------------------------------------------------------------- + +inline kj::ArrayPtr StructBuilder::getDataSectionAsBlob() { + return kj::ArrayPtr(reinterpret_cast(data), + unbound(dataSize / BITS_PER_BYTE / BYTES)); +} + +inline _::ListBuilder StructBuilder::getPointerSectionAsList() { + return _::ListBuilder(segment, capTable, pointers, ONE * POINTERS * BITS_PER_POINTER / ELEMENTS, + pointerCount * (ONE * ELEMENTS / POINTERS), + ZERO * BITS, ONE * POINTERS, ElementSize::POINTER); +} + +template +inline bool StructBuilder::hasDataField(StructDataOffset offset) { + return getDataField>(offset) != 0; +} + +template <> +inline bool StructBuilder::hasDataField(StructDataOffset offset) { + return false; +} + +template +inline T StructBuilder::getDataField(StructDataOffset offset) { + return reinterpret_cast*>(data)[unbound(offset / ELEMENTS)].get(); +} + +template <> +inline bool StructBuilder::getDataField(StructDataOffset offset) { + BitCount32 boffset = offset * (ONE * BITS / ELEMENTS); + byte* b = reinterpret_cast(data) + boffset / BITS_PER_BYTE; + return (*reinterpret_cast(b) & + unbound(ONE << (boffset % BITS_PER_BYTE / BITS))) != 0; +} + +template <> +inline Void StructBuilder::getDataField(StructDataOffset offset) { + return VOID; +} + +template +inline T StructBuilder::getDataField(StructDataOffset offset, Mask mask) { + return unmask(getDataField >(offset), mask); +} + +template +inline void StructBuilder::setDataField(StructDataOffset offset, kj::NoInfer value) { + reinterpret_cast*>(data)[unbound(offset / ELEMENTS)].set(value); +} + +#if CAPNP_CANONICALIZE_NAN +// Use mask() on floats and doubles to make sure we canonicalize NaNs. +template <> +inline void StructBuilder::setDataField(StructDataOffset offset, float value) { + setDataField(offset, mask(value, 0)); +} +template <> +inline void StructBuilder::setDataField(StructDataOffset offset, double value) { + setDataField(offset, mask(value, 0)); +} +#endif + +template <> +inline void StructBuilder::setDataField(StructDataOffset offset, bool value) { + auto boffset = offset * (ONE * BITS / ELEMENTS); + byte* b = reinterpret_cast(data) + boffset / BITS_PER_BYTE; + uint bitnum = unboundMaxBits<3>(boffset % BITS_PER_BYTE / BITS); + *reinterpret_cast(b) = (*reinterpret_cast(b) & ~(1 << bitnum)) + | (static_cast(value) << bitnum); +} + +template <> +inline void StructBuilder::setDataField(StructDataOffset offset, Void value) {} + +template +inline void StructBuilder::setDataField(StructDataOffset offset, + kj::NoInfer value, Mask m) { + setDataField >(offset, mask(value, m)); +} + +inline PointerBuilder StructBuilder::getPointerField(StructPointerOffset ptrIndex) { + // Hacky because WirePointer is defined in the .c++ file (so is incomplete here). + return PointerBuilder(segment, capTable, reinterpret_cast( + reinterpret_cast(pointers) + ptrIndex * WORDS_PER_POINTER)); +} + +// ------------------------------------------------------------------- + +inline kj::ArrayPtr StructReader::getDataSectionAsBlob() { + return kj::ArrayPtr(reinterpret_cast(data), + unbound(dataSize / BITS_PER_BYTE / BYTES)); +} + +inline _::ListReader StructReader::getPointerSectionAsList() { + return _::ListReader(segment, capTable, pointers, pointerCount * (ONE * ELEMENTS / POINTERS), + ONE * POINTERS * BITS_PER_POINTER / ELEMENTS, ZERO * BITS, ONE * POINTERS, + ElementSize::POINTER, nestingLimit); +} + +template +inline bool StructReader::hasDataField(StructDataOffset offset) const { + return getDataField>(offset) != 0; +} + +template <> +inline bool StructReader::hasDataField(StructDataOffset offset) const { + return false; +} + +template +inline T StructReader::getDataField(StructDataOffset offset) const { + if ((offset + ONE * ELEMENTS) * capnp::bitsPerElement() <= dataSize) { + return reinterpret_cast*>(data)[unbound(offset / ELEMENTS)].get(); + } else { + return static_cast(0); + } +} + +template <> +inline bool StructReader::getDataField(StructDataOffset offset) const { + auto boffset = offset * (ONE * BITS / ELEMENTS); + if (boffset < dataSize) { + const byte* b = reinterpret_cast(data) + boffset / BITS_PER_BYTE; + return (*reinterpret_cast(b) & + unbound(ONE << (boffset % BITS_PER_BYTE / BITS))) != 0; + } else { + return false; + } +} + +template <> +inline Void StructReader::getDataField(StructDataOffset offset) const { + return VOID; +} + +template +T StructReader::getDataField(StructDataOffset offset, Mask mask) const { + return unmask(getDataField >(offset), mask); +} + +inline PointerReader StructReader::getPointerField(StructPointerOffset ptrIndex) const { + if (ptrIndex < pointerCount) { + // Hacky because WirePointer is defined in the .c++ file (so is incomplete here). + return PointerReader(segment, capTable, reinterpret_cast( + reinterpret_cast(pointers) + ptrIndex * WORDS_PER_POINTER), nestingLimit); + } else{ + return PointerReader(); + } +} + +// ------------------------------------------------------------------- + +inline ListElementCount ListBuilder::size() const { return elementCount; } + +template +inline T ListBuilder::getDataElement(ElementCount index) { + return reinterpret_cast*>( + ptr + upgradeBound(index) * step / BITS_PER_BYTE)->get(); + + // TODO(perf): Benchmark this alternate implementation, which I suspect may make better use of + // the x86 SIB byte. Also use it for all the other getData/setData implementations below, and + // the various non-inline methods that look up pointers. + // Also if using this, consider changing ptr back to void* instead of byte*. +// return reinterpret_cast*>(ptr)[ +// index / ELEMENTS * (step / capnp::bitsPerElement())].get(); +} + +template <> +inline bool ListBuilder::getDataElement(ElementCount index) { + // Ignore step for bit lists because bit lists cannot be upgraded to struct lists. + auto bindex = index * (ONE * BITS / ELEMENTS); + byte* b = ptr + bindex / BITS_PER_BYTE; + return (*reinterpret_cast(b) & + unbound(ONE << (bindex % BITS_PER_BYTE / BITS))) != 0; +} + +template <> +inline Void ListBuilder::getDataElement(ElementCount index) { + return VOID; +} + +template +inline void ListBuilder::setDataElement(ElementCount index, kj::NoInfer value) { + reinterpret_cast*>( + ptr + upgradeBound(index) * step / BITS_PER_BYTE)->set(value); +} + +#if CAPNP_CANONICALIZE_NAN +// Use mask() on floats and doubles to make sure we canonicalize NaNs. +template <> +inline void ListBuilder::setDataElement(ElementCount index, float value) { + setDataElement(index, mask(value, 0)); +} +template <> +inline void ListBuilder::setDataElement(ElementCount index, double value) { + setDataElement(index, mask(value, 0)); +} +#endif + +template <> +inline void ListBuilder::setDataElement(ElementCount index, bool value) { + // Ignore stepBytes for bit lists because bit lists cannot be upgraded to struct lists. + auto bindex = index * (ONE * BITS / ELEMENTS); + byte* b = ptr + bindex / BITS_PER_BYTE; + auto bitnum = bindex % BITS_PER_BYTE / BITS; + *reinterpret_cast(b) = (*reinterpret_cast(b) & ~(1 << unbound(bitnum))) + | (static_cast(value) << unbound(bitnum)); +} + +template <> +inline void ListBuilder::setDataElement(ElementCount index, Void value) {} + +inline PointerBuilder ListBuilder::getPointerElement(ElementCount index) { + return PointerBuilder(segment, capTable, reinterpret_cast(ptr + + upgradeBound(index) * step / BITS_PER_BYTE)); +} + +// ------------------------------------------------------------------- + +inline ListElementCount ListReader::size() const { return elementCount; } + +template +inline T ListReader::getDataElement(ElementCount index) const { + return reinterpret_cast*>( + ptr + upgradeBound(index) * step / BITS_PER_BYTE)->get(); +} + +template <> +inline bool ListReader::getDataElement(ElementCount index) const { + // Ignore step for bit lists because bit lists cannot be upgraded to struct lists. + auto bindex = index * (ONE * BITS / ELEMENTS); + const byte* b = ptr + bindex / BITS_PER_BYTE; + return (*reinterpret_cast(b) & + unbound(ONE << (bindex % BITS_PER_BYTE / BITS))) != 0; +} + +template <> +inline Void ListReader::getDataElement(ElementCount index) const { + return VOID; +} + +inline PointerReader ListReader::getPointerElement(ElementCount index) const { + return PointerReader(segment, capTable, reinterpret_cast( + ptr + upgradeBound(index) * step / BITS_PER_BYTE), nestingLimit); +} + +// ------------------------------------------------------------------- + +inline OrphanBuilder::OrphanBuilder(OrphanBuilder&& other) noexcept + : segment(other.segment), capTable(other.capTable), location(other.location) { + memcpy(&tag, &other.tag, sizeof(tag)); // Needs memcpy to comply with aliasing rules. + other.segment = nullptr; + other.location = nullptr; +} + +inline OrphanBuilder::~OrphanBuilder() noexcept(false) { + if (segment != nullptr) euthanize(); +} + +inline OrphanBuilder& OrphanBuilder::operator=(OrphanBuilder&& other) { + // With normal smart pointers, it's important to handle the case where the incoming pointer + // is actually transitively owned by this one. In this case, euthanize() would destroy `other` + // before we copied it. This isn't possible in the case of `OrphanBuilder` because it only + // owns message objects, and `other` is not itself a message object, therefore cannot possibly + // be transitively owned by `this`. + + if (segment != nullptr) euthanize(); + segment = other.segment; + capTable = other.capTable; + location = other.location; + memcpy(&tag, &other.tag, sizeof(tag)); // Needs memcpy to comply with aliasing rules. + other.segment = nullptr; + other.location = nullptr; + return *this; +} + +} // namespace _ (private) +} // namespace capnp + +#endif // CAPNP_LAYOUT_H_ diff --git a/phonelibs/capnp-cpp/include/capnp/list.h b/phonelibs/capnp-cpp/include/capnp/list.h new file mode 100644 index 00000000000000..23e5e6c10e661f --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/list.h @@ -0,0 +1,546 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef CAPNP_LIST_H_ +#define CAPNP_LIST_H_ + +#if defined(__GNUC__) && !defined(CAPNP_HEADER_WARNINGS) +#pragma GCC system_header +#endif + +#include "layout.h" +#include "orphan.h" +#include +#ifdef KJ_STD_COMPAT +#include +#endif // KJ_STD_COMPAT + +namespace capnp { +namespace _ { // private + +template +class TemporaryPointer { + // This class is a little hack which lets us define operator->() in cases where it needs to + // return a pointer to a temporary value. We instead construct a TemporaryPointer and return that + // (by value). The compiler then invokes operator->() on the TemporaryPointer, which itself is + // able to return a real pointer to its member. + +public: + TemporaryPointer(T&& value): value(kj::mv(value)) {} + TemporaryPointer(const T& value): value(value) {} + + inline T* operator->() { return &value; } +private: + T value; +}; + +template +class IndexingIterator { +public: + IndexingIterator() = default; + + inline Element operator*() const { return (*container)[index]; } + inline TemporaryPointer operator->() const { + return TemporaryPointer((*container)[index]); + } + inline Element operator[]( int off) const { return (*container)[index]; } + inline Element operator[](uint off) const { return (*container)[index]; } + + inline IndexingIterator& operator++() { ++index; return *this; } + inline IndexingIterator operator++(int) { IndexingIterator other = *this; ++index; return other; } + inline IndexingIterator& operator--() { --index; return *this; } + inline IndexingIterator operator--(int) { IndexingIterator other = *this; --index; return other; } + + inline IndexingIterator operator+(uint amount) const { return IndexingIterator(container, index + amount); } + inline IndexingIterator operator-(uint amount) const { return IndexingIterator(container, index - amount); } + inline IndexingIterator operator+( int amount) const { return IndexingIterator(container, index + amount); } + inline IndexingIterator operator-( int amount) const { return IndexingIterator(container, index - amount); } + + inline int operator-(const IndexingIterator& other) const { return index - other.index; } + + inline IndexingIterator& operator+=(uint amount) { index += amount; return *this; } + inline IndexingIterator& operator-=(uint amount) { index -= amount; return *this; } + inline IndexingIterator& operator+=( int amount) { index += amount; return *this; } + inline IndexingIterator& operator-=( int amount) { index -= amount; return *this; } + + // STL says comparing iterators of different containers is not allowed, so we only compare + // indices here. + inline bool operator==(const IndexingIterator& other) const { return index == other.index; } + inline bool operator!=(const IndexingIterator& other) const { return index != other.index; } + inline bool operator<=(const IndexingIterator& other) const { return index <= other.index; } + inline bool operator>=(const IndexingIterator& other) const { return index >= other.index; } + inline bool operator< (const IndexingIterator& other) const { return index < other.index; } + inline bool operator> (const IndexingIterator& other) const { return index > other.index; } + +private: + Container* container; + uint index; + + friend Container; + inline IndexingIterator(Container* container, uint index) + : container(container), index(index) {} +}; + +} // namespace _ (private) + +template +struct List { + // List of primitives. + + List() = delete; + + class Reader { + public: + typedef List Reads; + + inline Reader(): reader(_::elementSizeForType()) {} + inline explicit Reader(_::ListReader reader): reader(reader) {} + + inline uint size() const { return unbound(reader.size() / ELEMENTS); } + inline T operator[](uint index) const { + KJ_IREQUIRE(index < size()); + return reader.template getDataElement(bounded(index) * ELEMENTS); + } + + typedef _::IndexingIterator Iterator; + inline Iterator begin() const { return Iterator(this, 0); } + inline Iterator end() const { return Iterator(this, size()); } + + private: + _::ListReader reader; + template + friend struct _::PointerHelpers; + template + friend struct List; + friend class Orphanage; + template + friend struct ToDynamic_; + }; + + class Builder { + public: + typedef List Builds; + + inline Builder(): builder(_::elementSizeForType()) {} + inline Builder(decltype(nullptr)): Builder() {} + inline explicit Builder(_::ListBuilder builder): builder(builder) {} + + inline operator Reader() const { return Reader(builder.asReader()); } + inline Reader asReader() const { return Reader(builder.asReader()); } + + inline uint size() const { return unbound(builder.size() / ELEMENTS); } + inline T operator[](uint index) { + KJ_IREQUIRE(index < size()); + return builder.template getDataElement(bounded(index) * ELEMENTS); + } + inline void set(uint index, T value) { + // Alas, it is not possible to make operator[] return a reference to which you can assign, + // since the encoded representation does not necessarily match the compiler's representation + // of the type. We can't even return a clever class that implements operator T() and + // operator=() because it will lead to surprising behavior when using type inference (e.g. + // calling a template function with inferred argument types, or using "auto" or "decltype"). + + builder.template setDataElement(bounded(index) * ELEMENTS, value); + } + + typedef _::IndexingIterator Iterator; + inline Iterator begin() { return Iterator(this, 0); } + inline Iterator end() { return Iterator(this, size()); } + + private: + _::ListBuilder builder; + template + friend struct _::PointerHelpers; + friend class Orphanage; + template + friend struct ToDynamic_; + }; + + class Pipeline {}; + +private: + inline static _::ListBuilder initPointer(_::PointerBuilder builder, uint size) { + return builder.initList(_::elementSizeForType(), bounded(size) * ELEMENTS); + } + inline static _::ListBuilder getFromPointer(_::PointerBuilder builder, const word* defaultValue) { + return builder.getList(_::elementSizeForType(), defaultValue); + } + inline static _::ListReader getFromPointer( + const _::PointerReader& reader, const word* defaultValue) { + return reader.getList(_::elementSizeForType(), defaultValue); + } + + template + friend struct List; + template + friend struct _::PointerHelpers; +}; + +template +struct List: public List {}; + +template +struct List { + // List of structs. + + List() = delete; + + class Reader { + public: + typedef List Reads; + + inline Reader(): reader(ElementSize::INLINE_COMPOSITE) {} + inline explicit Reader(_::ListReader reader): reader(reader) {} + + inline uint size() const { return unbound(reader.size() / ELEMENTS); } + inline typename T::Reader operator[](uint index) const { + KJ_IREQUIRE(index < size()); + return typename T::Reader(reader.getStructElement(bounded(index) * ELEMENTS)); + } + + typedef _::IndexingIterator Iterator; + inline Iterator begin() const { return Iterator(this, 0); } + inline Iterator end() const { return Iterator(this, size()); } + + private: + _::ListReader reader; + template + friend struct _::PointerHelpers; + template + friend struct List; + friend class Orphanage; + template + friend struct ToDynamic_; + }; + + class Builder { + public: + typedef List Builds; + + inline Builder(): builder(ElementSize::INLINE_COMPOSITE) {} + inline Builder(decltype(nullptr)): Builder() {} + inline explicit Builder(_::ListBuilder builder): builder(builder) {} + + inline operator Reader() const { return Reader(builder.asReader()); } + inline Reader asReader() const { return Reader(builder.asReader()); } + + inline uint size() const { return unbound(builder.size() / ELEMENTS); } + inline typename T::Builder operator[](uint index) { + KJ_IREQUIRE(index < size()); + return typename T::Builder(builder.getStructElement(bounded(index) * ELEMENTS)); + } + + inline void adoptWithCaveats(uint index, Orphan&& orphan) { + // Mostly behaves like you'd expect `adopt` to behave, but with two caveats originating from + // the fact that structs in a struct list are allocated inline rather than by pointer: + // * This actually performs a shallow copy, effectively adopting each of the orphan's + // children rather than adopting the orphan itself. The orphan ends up being discarded, + // possibly wasting space in the message object. + // * If the orphan is larger than the target struct -- say, because the orphan was built + // using a newer version of the schema that has additional fields -- it will be truncated, + // losing data. + + KJ_IREQUIRE(index < size()); + + // We pass a zero-valued StructSize to asStruct() because we do not want the struct to be + // expanded under any circumstances. We're just going to throw it away anyway, and + // transferContentFrom() already carefully compares the struct sizes before transferring. + builder.getStructElement(bounded(index) * ELEMENTS).transferContentFrom( + orphan.builder.asStruct(_::StructSize(ZERO * WORDS, ZERO * POINTERS))); + } + inline void setWithCaveats(uint index, const typename T::Reader& reader) { + // Mostly behaves like you'd expect `set` to behave, but with a caveat originating from + // the fact that structs in a struct list are allocated inline rather than by pointer: + // If the source struct is larger than the target struct -- say, because the source was built + // using a newer version of the schema that has additional fields -- it will be truncated, + // losing data. + // + // Note: If you are trying to concatenate some lists, use Orphanage::newOrphanConcat() to + // do it without losing any data in case the source lists come from a newer version of the + // protocol. (Plus, it's easier to use anyhow.) + + KJ_IREQUIRE(index < size()); + builder.getStructElement(bounded(index) * ELEMENTS).copyContentFrom(reader._reader); + } + + // There are no init(), set(), adopt(), or disown() methods for lists of structs because the + // elements of the list are inlined and are initialized when the list is initialized. This + // means that init() would be redundant, and set() would risk data loss if the input struct + // were from a newer version of the protocol. + + typedef _::IndexingIterator Iterator; + inline Iterator begin() { return Iterator(this, 0); } + inline Iterator end() { return Iterator(this, size()); } + + private: + _::ListBuilder builder; + template + friend struct _::PointerHelpers; + friend class Orphanage; + template + friend struct ToDynamic_; + }; + + class Pipeline {}; + +private: + inline static _::ListBuilder initPointer(_::PointerBuilder builder, uint size) { + return builder.initStructList(bounded(size) * ELEMENTS, _::structSize()); + } + inline static _::ListBuilder getFromPointer(_::PointerBuilder builder, const word* defaultValue) { + return builder.getStructList(_::structSize(), defaultValue); + } + inline static _::ListReader getFromPointer( + const _::PointerReader& reader, const word* defaultValue) { + return reader.getList(ElementSize::INLINE_COMPOSITE, defaultValue); + } + + template + friend struct List; + template + friend struct _::PointerHelpers; +}; + +template +struct List, Kind::LIST> { + // List of lists. + + List() = delete; + + class Reader { + public: + typedef List> Reads; + + inline Reader(): reader(ElementSize::POINTER) {} + inline explicit Reader(_::ListReader reader): reader(reader) {} + + inline uint size() const { return unbound(reader.size() / ELEMENTS); } + inline typename List::Reader operator[](uint index) const { + KJ_IREQUIRE(index < size()); + return typename List::Reader(_::PointerHelpers>::get( + reader.getPointerElement(bounded(index) * ELEMENTS))); + } + + typedef _::IndexingIterator::Reader> Iterator; + inline Iterator begin() const { return Iterator(this, 0); } + inline Iterator end() const { return Iterator(this, size()); } + + private: + _::ListReader reader; + template + friend struct _::PointerHelpers; + template + friend struct List; + friend class Orphanage; + template + friend struct ToDynamic_; + }; + + class Builder { + public: + typedef List> Builds; + + inline Builder(): builder(ElementSize::POINTER) {} + inline Builder(decltype(nullptr)): Builder() {} + inline explicit Builder(_::ListBuilder builder): builder(builder) {} + + inline operator Reader() const { return Reader(builder.asReader()); } + inline Reader asReader() const { return Reader(builder.asReader()); } + + inline uint size() const { return unbound(builder.size() / ELEMENTS); } + inline typename List::Builder operator[](uint index) { + KJ_IREQUIRE(index < size()); + return typename List::Builder(_::PointerHelpers>::get( + builder.getPointerElement(bounded(index) * ELEMENTS))); + } + inline typename List::Builder init(uint index, uint size) { + KJ_IREQUIRE(index < this->size()); + return typename List::Builder(_::PointerHelpers>::init( + builder.getPointerElement(bounded(index) * ELEMENTS), size)); + } + inline void set(uint index, typename List::Reader value) { + KJ_IREQUIRE(index < size()); + builder.getPointerElement(bounded(index) * ELEMENTS).setList(value.reader); + } + void set(uint index, std::initializer_list> value) { + KJ_IREQUIRE(index < size()); + auto l = init(index, value.size()); + uint i = 0; + for (auto& element: value) { + l.set(i++, element); + } + } + inline void adopt(uint index, Orphan&& value) { + KJ_IREQUIRE(index < size()); + builder.getPointerElement(bounded(index) * ELEMENTS).adopt(kj::mv(value.builder)); + } + inline Orphan disown(uint index) { + KJ_IREQUIRE(index < size()); + return Orphan(builder.getPointerElement(bounded(index) * ELEMENTS).disown()); + } + + typedef _::IndexingIterator::Builder> Iterator; + inline Iterator begin() { return Iterator(this, 0); } + inline Iterator end() { return Iterator(this, size()); } + + private: + _::ListBuilder builder; + template + friend struct _::PointerHelpers; + friend class Orphanage; + template + friend struct ToDynamic_; + }; + + class Pipeline {}; + +private: + inline static _::ListBuilder initPointer(_::PointerBuilder builder, uint size) { + return builder.initList(ElementSize::POINTER, bounded(size) * ELEMENTS); + } + inline static _::ListBuilder getFromPointer(_::PointerBuilder builder, const word* defaultValue) { + return builder.getList(ElementSize::POINTER, defaultValue); + } + inline static _::ListReader getFromPointer( + const _::PointerReader& reader, const word* defaultValue) { + return reader.getList(ElementSize::POINTER, defaultValue); + } + + template + friend struct List; + template + friend struct _::PointerHelpers; +}; + +template +struct List { + List() = delete; + + class Reader { + public: + typedef List Reads; + + inline Reader(): reader(ElementSize::POINTER) {} + inline explicit Reader(_::ListReader reader): reader(reader) {} + + inline uint size() const { return unbound(reader.size() / ELEMENTS); } + inline typename T::Reader operator[](uint index) const { + KJ_IREQUIRE(index < size()); + return reader.getPointerElement(bounded(index) * ELEMENTS) + .template getBlob(nullptr, ZERO * BYTES); + } + + typedef _::IndexingIterator Iterator; + inline Iterator begin() const { return Iterator(this, 0); } + inline Iterator end() const { return Iterator(this, size()); } + + private: + _::ListReader reader; + template + friend struct _::PointerHelpers; + template + friend struct List; + friend class Orphanage; + template + friend struct ToDynamic_; + }; + + class Builder { + public: + typedef List Builds; + + inline Builder(): builder(ElementSize::POINTER) {} + inline Builder(decltype(nullptr)): Builder() {} + inline explicit Builder(_::ListBuilder builder): builder(builder) {} + + inline operator Reader() const { return Reader(builder.asReader()); } + inline Reader asReader() const { return Reader(builder.asReader()); } + + inline uint size() const { return unbound(builder.size() / ELEMENTS); } + inline typename T::Builder operator[](uint index) { + KJ_IREQUIRE(index < size()); + return builder.getPointerElement(bounded(index) * ELEMENTS) + .template getBlob(nullptr, ZERO * BYTES); + } + inline void set(uint index, typename T::Reader value) { + KJ_IREQUIRE(index < size()); + builder.getPointerElement(bounded(index) * ELEMENTS).template setBlob(value); + } + inline typename T::Builder init(uint index, uint size) { + KJ_IREQUIRE(index < this->size()); + return builder.getPointerElement(bounded(index) * ELEMENTS) + .template initBlob(bounded(size) * BYTES); + } + inline void adopt(uint index, Orphan&& value) { + KJ_IREQUIRE(index < size()); + builder.getPointerElement(bounded(index) * ELEMENTS).adopt(kj::mv(value.builder)); + } + inline Orphan disown(uint index) { + KJ_IREQUIRE(index < size()); + return Orphan(builder.getPointerElement(bounded(index) * ELEMENTS).disown()); + } + + typedef _::IndexingIterator Iterator; + inline Iterator begin() { return Iterator(this, 0); } + inline Iterator end() { return Iterator(this, size()); } + + private: + _::ListBuilder builder; + template + friend struct _::PointerHelpers; + friend class Orphanage; + template + friend struct ToDynamic_; + }; + + class Pipeline {}; + +private: + inline static _::ListBuilder initPointer(_::PointerBuilder builder, uint size) { + return builder.initList(ElementSize::POINTER, bounded(size) * ELEMENTS); + } + inline static _::ListBuilder getFromPointer(_::PointerBuilder builder, const word* defaultValue) { + return builder.getList(ElementSize::POINTER, defaultValue); + } + inline static _::ListReader getFromPointer( + const _::PointerReader& reader, const word* defaultValue) { + return reader.getList(ElementSize::POINTER, defaultValue); + } + + template + friend struct List; + template + friend struct _::PointerHelpers; +}; + +} // namespace capnp + +#ifdef KJ_STD_COMPAT +namespace std { + +template +struct iterator_traits> + : public std::iterator {}; + +} // namespace std +#endif // KJ_STD_COMPAT + +#endif // CAPNP_LIST_H_ diff --git a/phonelibs/capnp-cpp/include/capnp/membrane.h b/phonelibs/capnp-cpp/include/capnp/membrane.h new file mode 100644 index 00000000000000..6fa8a1335d9418 --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/membrane.h @@ -0,0 +1,202 @@ +// Copyright (c) 2015 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef CAPNP_MEMBRANE_H_ +#define CAPNP_MEMBRANE_H_ +// In capability theory, a "membrane" is a wrapper around a capability which (usually) forwards +// calls but recursively wraps capabilities in those calls in the same membrane. The purpose of a +// membrane is to enforce a barrier between two capabilities that cannot be bypassed by merely +// introducing new objects. +// +// The most common use case for a membrane is revocation: Say Alice wants to give Bob a capability +// to access Carol, but wants to be able to revoke this capability later. Alice can accomplish this +// by wrapping Carol in a revokable wrapper which passes through calls until such a time as Alice +// indicates it should be revoked, after which all calls through the wrapper will throw exceptions. +// However, a naive wrapper approach has a problem: if Bob makes a call to Carol and sends a new +// capability in that call, or if Carol returns a capability to Bob in the response to a call, then +// the two are now able to communicate using this new capability, which Alice cannot revoke. In +// order to avoid this problem, Alice must use not just a wrapper but a "membrane", which +// recursively wraps all objects that pass through it in either direction. Thus, all connections +// formed between Bob and Carol (originating from Alice's original introduction) can be revoked +// together by revoking the membrane. +// +// Note that when a capability is passed into a membrane and then passed back out, the result is +// the original capability, not a double-membraned capability. This means that in our revocation +// example, if Bob uses his capability to Carol to obtain another capability from her, then send +// it back to her, the capability Carol receives back will NOT be revoked when Bob's access to +// Carol is revoked. Thus Bob can create long-term irrevocable connections. In most practical use +// cases, this is what you want. APIs commonly rely on the fact that a capability obtained and then +// passed back can be recognized as the original capability. +// +// Mark Miller on membranes: http://www.eros-os.org/pipermail/e-lang/2003-January/008434.html + +#include "capability.h" + +namespace capnp { + +class MembranePolicy { + // Applications may implement this interface to define a membrane policy, which allows some + // calls crossing the membrane to be blocked or redirected. + +public: + virtual kj::Maybe inboundCall( + uint64_t interfaceId, uint16_t methodId, Capability::Client target) = 0; + // Given an inbound call (a call originating "outside" the membrane destined for an object + // "inside" the membrane), decides what to do with it. The policy may: + // + // - Return null to indicate that the call should proceed to the destination. All capabilities + // in the parameters or result will be properly wrapped in the same membrane. + // - Return a capability to have the call redirected to that capability. Note that the redirect + // capability will be treated as outside the membrane, so the params and results will not be + // auto-wrapped; however, the callee can easily wrap the returned capability in the membrane + // itself before returning to achieve this effect. + // - Throw an exception to cause the call to fail with that exception. + // + // `target` is the underlying capability (*inside* the membrane) for which the call is destined. + // Generally, the only way you should use `target` is to wrap it in some capability which you + // return as a redirect. The redirect capability may modify the call in some way and send it to + // `target`. Be careful to use `copyIntoMembrane()` and `copyOutOfMembrane()` as appropriate when + // copying parameters or results across the membrane. + // + // Note that since `target` is inside the capability, if you were to directly return it (rather + // than return null), the effect would be that the membrane would be broken: the call would + // proceed directly and any new capabilities introduced through it would not be membraned. You + // generally should not do that. + + virtual kj::Maybe outboundCall( + uint64_t interfaceId, uint16_t methodId, Capability::Client target) = 0; + // Like `inboundCall()`, but applies to calls originating *inside* the membrane and terminating + // outside. + // + // Note: It is strongly recommended that `outboundCall()` returns null in exactly the same cases + // that `inboundCall()` return null. Conversely, for any case where `inboundCall()` would + // redirect or throw, `outboundCall()` should also redirect or throw. Otherwise, you can run + // into inconsistent behavion when a promise is returned across a membrane, and that promise + // later resolves to a capability on the other side of the membrane: calls on the promise + // will enter and then exit the membrane, but calls on the eventual resolution will not cross + // the membrane at all, so it is important that these two cases behave the same. + + virtual kj::Own addRef() = 0; + // Return a new owned pointer to the same policy. + // + // Typically an implementation of MembranePolicy should also inherit kj::Refcounted and implement + // `addRef()` as `return kj::addRef(*this);`. + // + // Note that the membraning system considers two membranes created with the same MembranePolicy + // object actually to be the *same* membrane. This is relevant when an object passes into the + // membrane and then back out (or out and then back in): instead of double-wrapping the object, + // the wrapping will be removed. +}; + +Capability::Client membrane(Capability::Client inner, kj::Own policy); +// Wrap `inner` in a membrane specified by `policy`. `inner` is considered "inside" the membrane, +// while the returned capability should only be called from outside the membrane. + +Capability::Client reverseMembrane(Capability::Client outer, kj::Own policy); +// Like `membrane` but treat the input capability as "outside" the membrane, and return a +// capability appropriate for use inside. +// +// Applications typically won't use this directly; the membraning code automatically sets up +// reverse membranes where needed. + +template +ClientType membrane(ClientType inner, kj::Own policy); +template +ClientType reverseMembrane(ClientType inner, kj::Own policy); +// Convenience templates which return the same interface type as the input. + +template +typename ServerType::Serves::Client membrane( + kj::Own inner, kj::Own policy); +template +typename ServerType::Serves::Client reverseMembrane( + kj::Own inner, kj::Own policy); +// Convenience templates which input a capability server type and return the appropriate client +// type. + +template +Orphan::Reads> copyIntoMembrane( + Reader&& from, Orphanage to, kj::Own policy); +// Copy a Cap'n Proto object (e.g. struct or list), adding the given membrane to any capabilities +// found within it. `from` is interpreted as "outside" the membrane while `to` is "inside". + +template +Orphan::Reads> copyOutOfMembrane( + Reader&& from, Orphanage to, kj::Own policy); +// Like copyIntoMembrane() except that `from` is "inside" the membrane and `to` is "outside". + +// ======================================================================================= +// inline implementation details + +template +ClientType membrane(ClientType inner, kj::Own policy) { + return membrane(Capability::Client(kj::mv(inner)), kj::mv(policy)) + .castAs(); +} +template +ClientType reverseMembrane(ClientType inner, kj::Own policy) { + return reverseMembrane(Capability::Client(kj::mv(inner)), kj::mv(policy)) + .castAs(); +} + +template +typename ServerType::Serves::Client membrane( + kj::Own inner, kj::Own policy) { + return membrane(Capability::Client(kj::mv(inner)), kj::mv(policy)) + .castAs(); +} +template +typename ServerType::Serves::Client reverseMembrane( + kj::Own inner, kj::Own policy) { + return reverseMembrane(Capability::Client(kj::mv(inner)), kj::mv(policy)) + .castAs(); +} + +namespace _ { // private + +OrphanBuilder copyOutOfMembrane(PointerReader from, Orphanage to, + kj::Own policy, bool reverse); +OrphanBuilder copyOutOfMembrane(StructReader from, Orphanage to, + kj::Own policy, bool reverse); +OrphanBuilder copyOutOfMembrane(ListReader from, Orphanage to, + kj::Own policy, bool reverse); + +} // namespace _ (private) + +template +Orphan::Reads> copyIntoMembrane( + Reader&& from, Orphanage to, kj::Own policy) { + return _::copyOutOfMembrane( + _::PointerHelpers::Reads>::getInternalReader(from), + to, kj::mv(policy), true); +} + +template +Orphan::Reads> copyOutOfMembrane( + Reader&& from, Orphanage to, kj::Own policy) { + return _::copyOutOfMembrane( + _::PointerHelpers::Reads>::getInternalReader(from), + to, kj::mv(policy), false); +} + +} // namespace capnp + +#endif // CAPNP_MEMBRANE_H_ diff --git a/phonelibs/capnp-cpp/include/capnp/message.h b/phonelibs/capnp-cpp/include/capnp/message.h new file mode 100644 index 00000000000000..b4d5e9fc82230d --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/message.h @@ -0,0 +1,508 @@ +// Copyright (c) 2013-2016 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#include +#include +#include +#include +#include "common.h" +#include "layout.h" +#include "any.h" + +#ifndef CAPNP_MESSAGE_H_ +#define CAPNP_MESSAGE_H_ + +#if defined(__GNUC__) && !defined(CAPNP_HEADER_WARNINGS) +#pragma GCC system_header +#endif + +namespace capnp { + +namespace _ { // private + class ReaderArena; + class BuilderArena; +} + +class StructSchema; +class Orphanage; +template +class Orphan; + +// ======================================================================================= + +struct ReaderOptions { + // Options controlling how data is read. + + uint64_t traversalLimitInWords = 8 * 1024 * 1024; + // Limits how many total words of data are allowed to be traversed. Traversal is counted when + // a new struct or list builder is obtained, e.g. from a get() accessor. This means that calling + // the getter for the same sub-struct multiple times will cause it to be double-counted. Once + // the traversal limit is reached, an error will be reported. + // + // This limit exists for security reasons. It is possible for an attacker to construct a message + // in which multiple pointers point at the same location. This is technically invalid, but hard + // to detect. Using such a message, an attacker could cause a message which is small on the wire + // to appear much larger when actually traversed, possibly exhausting server resources leading to + // denial-of-service. + // + // It makes sense to set a traversal limit that is much larger than the underlying message. + // Together with sensible coding practices (e.g. trying to avoid calling sub-object getters + // multiple times, which is expensive anyway), this should provide adequate protection without + // inconvenience. + // + // The default limit is 64 MiB. This may or may not be a sensible number for any given use case, + // but probably at least prevents easy exploitation while also avoiding causing problems in most + // typical cases. + + int nestingLimit = 64; + // Limits how deeply-nested a message structure can be, e.g. structs containing other structs or + // lists of structs. + // + // Like the traversal limit, this limit exists for security reasons. Since it is common to use + // recursive code to traverse recursive data structures, an attacker could easily cause a stack + // overflow by sending a very-deeply-nested (or even cyclic) message, without the message even + // being very large. The default limit of 64 is probably low enough to prevent any chance of + // stack overflow, yet high enough that it is never a problem in practice. +}; + +class MessageReader { + // Abstract interface for an object used to read a Cap'n Proto message. Subclasses of + // MessageReader are responsible for reading the raw, flat message content. Callers should + // usually call `messageReader.getRoot()` to get a `MyStructType::Reader` + // representing the root of the message, then use that to traverse the message content. + // + // Some common subclasses of `MessageReader` include `SegmentArrayMessageReader`, whose + // constructor accepts pointers to the raw data, and `StreamFdMessageReader` (from + // `serialize.h`), which reads the message from a file descriptor. One might implement other + // subclasses to handle things like reading from shared memory segments, mmap()ed files, etc. + +public: + MessageReader(ReaderOptions options); + // It is suggested that subclasses take ReaderOptions as a constructor parameter, but give it a + // default value of "ReaderOptions()". The base class constructor doesn't have a default value + // in order to remind subclasses that they really need to give the user a way to provide this. + + virtual ~MessageReader() noexcept(false); + + virtual kj::ArrayPtr getSegment(uint id) = 0; + // Gets the segment with the given ID, or returns null if no such segment exists. This method + // will be called at most once for each segment ID. + + inline const ReaderOptions& getOptions(); + // Get the options passed to the constructor. + + template + typename RootType::Reader getRoot(); + // Get the root struct of the message, interpreting it as the given struct type. + + template + typename RootType::Reader getRoot(SchemaType schema); + // Dynamically interpret the root struct of the message using the given schema (a StructSchema). + // RootType in this case must be DynamicStruct, and you must #include to + // use this. + + bool isCanonical(); + // Returns whether the message encoded in the reader is in canonical form. + +private: + ReaderOptions options; + + // Space in which we can construct a ReaderArena. We don't use ReaderArena directly here + // because we don't want clients to have to #include arena.h, which itself includes a bunch of + // big STL headers. We don't use a pointer to a ReaderArena because that would require an + // extra malloc on every message which could be expensive when processing small messages. + void* arenaSpace[15 + sizeof(kj::MutexGuarded) / sizeof(void*)]; + bool allocatedArena; + + _::ReaderArena* arena() { return reinterpret_cast<_::ReaderArena*>(arenaSpace); } + AnyPointer::Reader getRootInternal(); +}; + +class MessageBuilder { + // Abstract interface for an object used to allocate and build a message. Subclasses of + // MessageBuilder are responsible for allocating the space in which the message will be written. + // The most common subclass is `MallocMessageBuilder`, but other subclasses may be used to do + // tricky things like allocate messages in shared memory or mmap()ed files. + // + // Creating a new message ususually means allocating a new MessageBuilder (ideally on the stack) + // and then calling `messageBuilder.initRoot()` to get a `MyStructType::Builder`. + // That, in turn, can be used to fill in the message content. When done, you can call + // `messageBuilder.getSegmentsForOutput()` to get a list of flat data arrays containing the + // message. + +public: + MessageBuilder(); + virtual ~MessageBuilder() noexcept(false); + KJ_DISALLOW_COPY(MessageBuilder); + + struct SegmentInit { + kj::ArrayPtr space; + + size_t wordsUsed; + // Number of words in `space` which are used; the rest are free space in which additional + // objects may be allocated. + }; + + explicit MessageBuilder(kj::ArrayPtr segments); + // Create a MessageBuilder backed by existing memory. This is an advanced interface that most + // people should not use. THIS METHOD IS INSECURE; see below. + // + // This allows a MessageBuilder to be constructed to modify an in-memory message without first + // making a copy of the content. This is especially useful in conjunction with mmap(). + // + // The contents of each segment must outlive the MessageBuilder, but the SegmentInit array itself + // only need outlive the constructor. + // + // SECURITY: Do not use this in conjunction with untrusted data. This constructor assumes that + // the input message is valid. This constructor is designed to be used with data you control, + // e.g. an mmap'd file which is owned and accessed by only one program. When reading data you + // do not trust, you *must* load it into a Reader and then copy into a Builder as a means of + // validating the content. + // + // WARNING: It is NOT safe to initialize a MessageBuilder in this way from memory that is + // currently in use by another MessageBuilder or MessageReader. Other readers/builders will + // not observe changes to the segment sizes nor newly-allocated segments caused by allocating + // new objects in this message. + + virtual kj::ArrayPtr allocateSegment(uint minimumSize) = 0; + // Allocates an array of at least the given number of words, throwing an exception or crashing if + // this is not possible. It is expected that this method will usually return more space than + // requested, and the caller should use that extra space as much as possible before allocating + // more. The returned space remains valid at least until the MessageBuilder is destroyed. + // + // Cap'n Proto will only call this once at a time, so the subclass need not worry about + // thread-safety. + + template + typename RootType::Builder initRoot(); + // Initialize the root struct of the message as the given struct type. + + template + void setRoot(Reader&& value); + // Set the root struct to a deep copy of the given struct. + + template + typename RootType::Builder getRoot(); + // Get the root struct of the message, interpreting it as the given struct type. + + template + typename RootType::Builder getRoot(SchemaType schema); + // Dynamically interpret the root struct of the message using the given schema (a StructSchema). + // RootType in this case must be DynamicStruct, and you must #include to + // use this. + + template + typename RootType::Builder initRoot(SchemaType schema); + // Dynamically init the root struct of the message using the given schema (a StructSchema). + // RootType in this case must be DynamicStruct, and you must #include to + // use this. + + template + void adoptRoot(Orphan&& orphan); + // Like setRoot() but adopts the orphan without copying. + + kj::ArrayPtr> getSegmentsForOutput(); + // Get the raw data that makes up the message. + + Orphanage getOrphanage(); + + bool isCanonical(); + // Check whether the message builder is in canonical form + +private: + void* arenaSpace[22]; + // Space in which we can construct a BuilderArena. We don't use BuilderArena directly here + // because we don't want clients to have to #include arena.h, which itself includes a bunch of + // big STL headers. We don't use a pointer to a BuilderArena because that would require an + // extra malloc on every message which could be expensive when processing small messages. + + bool allocatedArena = false; + // We have to initialize the arena lazily because when we do so we want to allocate the root + // pointer immediately, and this will allocate a segment, which requires a virtual function + // call on the MessageBuilder. We can't do such a call in the constructor since the subclass + // isn't constructed yet. This is kind of annoying because it means that getOrphanage() is + // not thread-safe, but that shouldn't be a huge deal... + + _::BuilderArena* arena() { return reinterpret_cast<_::BuilderArena*>(arenaSpace); } + _::SegmentBuilder* getRootSegment(); + AnyPointer::Builder getRootInternal(); +}; + +template +typename RootType::Reader readMessageUnchecked(const word* data); +// IF THE INPUT IS INVALID, THIS MAY CRASH, CORRUPT MEMORY, CREATE A SECURITY HOLE IN YOUR APP, +// MURDER YOUR FIRST-BORN CHILD, AND/OR BRING ABOUT ETERNAL DAMNATION ON ALL OF HUMANITY. DO NOT +// USE UNLESS YOU UNDERSTAND THE CONSEQUENCES. +// +// Given a pointer to a known-valid message located in a single contiguous memory segment, +// returns a reader for that message. No bounds-checking will be done while traversing this +// message. Use this only if you have already verified that all pointers are valid and in-bounds, +// and there are no far pointers in the message. +// +// To create a message that can be passed to this function, build a message using a MallocAllocator +// whose preferred segment size is larger than the message size. This guarantees that the message +// will be allocated as a single segment, meaning getSegmentsForOutput() returns a single word +// array. That word array is your message; you may pass a pointer to its first word into +// readMessageUnchecked() to read the message. +// +// This can be particularly handy for embedding messages in generated code: you can +// embed the raw bytes (using AlignedData) then make a Reader for it using this. This is the way +// default values are embedded in code generated by the Cap'n Proto compiler. E.g., if you have +// a message MyMessage, you can read its default value like so: +// MyMessage::Reader reader = Message::readMessageUnchecked(MyMessage::DEFAULT.words); +// +// To sanitize a message from an untrusted source such that it can be safely passed to +// readMessageUnchecked(), use copyToUnchecked(). + +template +void copyToUnchecked(Reader&& reader, kj::ArrayPtr uncheckedBuffer); +// Copy the content of the given reader into the given buffer, such that it can safely be passed to +// readMessageUnchecked(). The buffer's size must be exactly reader.totalSizeInWords() + 1, +// otherwise an exception will be thrown. The buffer must be zero'd before calling. + +template +typename RootType::Reader readDataStruct(kj::ArrayPtr data); +// Interprets the given data as a single, data-only struct. Only primitive fields (booleans, +// numbers, and enums) will be readable; all pointers will be null. This is useful if you want +// to use Cap'n Proto as a language/platform-neutral way to pack some bits. +// +// The input is a word array rather than a byte array to enforce alignment. If you have a byte +// array which you know is word-aligned (or if your platform supports unaligned reads and you don't +// mind the performance penalty), then you can use `reinterpret_cast` to convert a byte array into +// a word array: +// +// kj::arrayPtr(reinterpret_cast(bytes.begin()), +// reinterpret_cast(bytes.end())) + +template +typename kj::ArrayPtr writeDataStruct(BuilderType builder); +// Given a struct builder, get the underlying data section as a word array, suitable for passing +// to `readDataStruct()`. +// +// Note that you may call `.toBytes()` on the returned value to convert to `ArrayPtr`. + +template +static typename Type::Reader defaultValue(); +// Get a default instance of the given struct or list type. +// +// TODO(cleanup): Find a better home for this function? + +// ======================================================================================= + +class SegmentArrayMessageReader: public MessageReader { + // A simple MessageReader that reads from an array of word arrays representing all segments. + // In particular you can read directly from the output of MessageBuilder::getSegmentsForOutput() + // (although it would probably make more sense to call builder.getRoot().asReader() in that case). + +public: + SegmentArrayMessageReader(kj::ArrayPtr> segments, + ReaderOptions options = ReaderOptions()); + // Creates a message pointing at the given segment array, without taking ownership of the + // segments. All arrays passed in must remain valid until the MessageReader is destroyed. + + KJ_DISALLOW_COPY(SegmentArrayMessageReader); + ~SegmentArrayMessageReader() noexcept(false); + + virtual kj::ArrayPtr getSegment(uint id) override; + +private: + kj::ArrayPtr> segments; +}; + +enum class AllocationStrategy: uint8_t { + FIXED_SIZE, + // The builder will prefer to allocate the same amount of space for each segment with no + // heuristic growth. It will still allocate larger segments when the preferred size is too small + // for some single object. This mode is generally not recommended, but can be particularly useful + // for testing in order to force a message to allocate a predictable number of segments. Note + // that you can force every single object in the message to be located in a separate segment by + // using this mode with firstSegmentWords = 0. + + GROW_HEURISTICALLY + // The builder will heuristically decide how much space to allocate for each segment. Each + // allocated segment will be progressively larger than the previous segments on the assumption + // that message sizes are exponentially distributed. The total number of segments that will be + // allocated for a message of size n is O(log n). +}; + +constexpr uint SUGGESTED_FIRST_SEGMENT_WORDS = 1024; +constexpr AllocationStrategy SUGGESTED_ALLOCATION_STRATEGY = AllocationStrategy::GROW_HEURISTICALLY; + +class MallocMessageBuilder: public MessageBuilder { + // A simple MessageBuilder that uses malloc() (actually, calloc()) to allocate segments. This + // implementation should be reasonable for any case that doesn't require writing the message to + // a specific location in memory. + +public: + explicit MallocMessageBuilder(uint firstSegmentWords = SUGGESTED_FIRST_SEGMENT_WORDS, + AllocationStrategy allocationStrategy = SUGGESTED_ALLOCATION_STRATEGY); + // Creates a BuilderContext which allocates at least the given number of words for the first + // segment, and then uses the given strategy to decide how much to allocate for subsequent + // segments. When choosing a value for firstSegmentWords, consider that: + // 1) Reading and writing messages gets slower when multiple segments are involved, so it's good + // if most messages fit in a single segment. + // 2) Unused bytes will not be written to the wire, so generally it is not a big deal to allocate + // more space than you need. It only becomes problematic if you are allocating many messages + // in parallel and thus use lots of memory, or if you allocate so much extra space that just + // zeroing it out becomes a bottleneck. + // The defaults have been chosen to be reasonable for most people, so don't change them unless you + // have reason to believe you need to. + + explicit MallocMessageBuilder(kj::ArrayPtr firstSegment, + AllocationStrategy allocationStrategy = SUGGESTED_ALLOCATION_STRATEGY); + // This version always returns the given array for the first segment, and then proceeds with the + // allocation strategy. This is useful for optimization when building lots of small messages in + // a tight loop: you can reuse the space for the first segment. + // + // firstSegment MUST be zero-initialized. MallocMessageBuilder's destructor will write new zeros + // over any space that was used so that it can be reused. + + KJ_DISALLOW_COPY(MallocMessageBuilder); + virtual ~MallocMessageBuilder() noexcept(false); + + virtual kj::ArrayPtr allocateSegment(uint minimumSize) override; + +private: + uint nextSize; + AllocationStrategy allocationStrategy; + + bool ownFirstSegment; + bool returnedFirstSegment; + + void* firstSegment; + + struct MoreSegments; + kj::Maybe> moreSegments; +}; + +class FlatMessageBuilder: public MessageBuilder { + // THIS IS NOT THE CLASS YOU'RE LOOKING FOR. + // + // If you want to write a message into already-existing scratch space, use `MallocMessageBuilder` + // and pass the scratch space to its constructor. It will then only fall back to malloc() if + // the scratch space is not large enough. + // + // Do NOT use this class unless you really know what you're doing. This class is problematic + // because it requires advance knowledge of the size of your message, which is usually impossible + // to determine without actually building the message. The class was created primarily to + // implement `copyToUnchecked()`, which itself exists only to support other internal parts of + // the Cap'n Proto implementation. + +public: + explicit FlatMessageBuilder(kj::ArrayPtr array); + KJ_DISALLOW_COPY(FlatMessageBuilder); + virtual ~FlatMessageBuilder() noexcept(false); + + void requireFilled(); + // Throws an exception if the flat array is not exactly full. + + virtual kj::ArrayPtr allocateSegment(uint minimumSize) override; + +private: + kj::ArrayPtr array; + bool allocated; +}; + +// ======================================================================================= +// implementation details + +inline const ReaderOptions& MessageReader::getOptions() { + return options; +} + +template +inline typename RootType::Reader MessageReader::getRoot() { + return getRootInternal().getAs(); +} + +template +inline typename RootType::Builder MessageBuilder::initRoot() { + return getRootInternal().initAs(); +} + +template +inline void MessageBuilder::setRoot(Reader&& value) { + getRootInternal().setAs>(value); +} + +template +inline typename RootType::Builder MessageBuilder::getRoot() { + return getRootInternal().getAs(); +} + +template +void MessageBuilder::adoptRoot(Orphan&& orphan) { + return getRootInternal().adopt(kj::mv(orphan)); +} + +template +typename RootType::Reader MessageReader::getRoot(SchemaType schema) { + return getRootInternal().getAs(schema); +} + +template +typename RootType::Builder MessageBuilder::getRoot(SchemaType schema) { + return getRootInternal().getAs(schema); +} + +template +typename RootType::Builder MessageBuilder::initRoot(SchemaType schema) { + return getRootInternal().initAs(schema); +} + +template +typename RootType::Reader readMessageUnchecked(const word* data) { + return AnyPointer::Reader(_::PointerReader::getRootUnchecked(data)).getAs(); +} + +template +void copyToUnchecked(Reader&& reader, kj::ArrayPtr uncheckedBuffer) { + FlatMessageBuilder builder(uncheckedBuffer); + builder.setRoot(kj::fwd(reader)); + builder.requireFilled(); +} + +template +typename RootType::Reader readDataStruct(kj::ArrayPtr data) { + return typename RootType::Reader(_::StructReader(data)); +} + +template +typename kj::ArrayPtr writeDataStruct(BuilderType builder) { + auto bytes = _::PointerHelpers>::getInternalBuilder(kj::mv(builder)) + .getDataSectionAsBlob(); + return kj::arrayPtr(reinterpret_cast(bytes.begin()), + reinterpret_cast(bytes.end())); +} + +template +static typename Type::Reader defaultValue() { + return typename Type::Reader(_::StructReader()); +} + +template +kj::Array canonicalize(T&& reader) { + return _::PointerHelpers>::getInternalReader(reader).canonicalize(); +} + +} // namespace capnp + +#endif // CAPNP_MESSAGE_H_ diff --git a/phonelibs/capnp-cpp/include/capnp/orphan.h b/phonelibs/capnp-cpp/include/capnp/orphan.h new file mode 100644 index 00000000000000..8c8b9a6054c885 --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/orphan.h @@ -0,0 +1,440 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef CAPNP_ORPHAN_H_ +#define CAPNP_ORPHAN_H_ + +#if defined(__GNUC__) && !defined(CAPNP_HEADER_WARNINGS) +#pragma GCC system_header +#endif + +#include "layout.h" + +namespace capnp { + +class StructSchema; +class ListSchema; +struct DynamicStruct; +struct DynamicList; +namespace _ { struct OrphanageInternal; } + +template +class Orphan { + // Represents an object which is allocated within some message builder but has no pointers + // pointing at it. An Orphan can later be "adopted" by some other object as one of that object's + // fields, without having to copy the orphan. For a field `foo` of pointer type, the generated + // code will define builder methods `void adoptFoo(Orphan)` and `Orphan disownFoo()`. + // Orphans can also be created independently of any parent using an Orphanage. + // + // `Orphan` can be moved but not copied, like `Own`, so that it is impossible for one + // orphan to be adopted multiple times. If an orphan is destroyed without being adopted, its + // contents are zero'd out (and possibly reused, if we ever implement the ability to reuse space + // in a message arena). + +public: + Orphan() = default; + KJ_DISALLOW_COPY(Orphan); + Orphan(Orphan&&) = default; + Orphan& operator=(Orphan&&) = default; + inline Orphan(_::OrphanBuilder&& builder): builder(kj::mv(builder)) {} + + inline BuilderFor get(); + // Get the underlying builder. If the orphan is null, this will allocate and return a default + // object rather than crash. This is done for security -- otherwise, you might enable a DoS + // attack any time you disown a field and fail to check if it is null. In the case of structs, + // this means that the orphan is no longer null after get() returns. In the case of lists, + // no actual object is allocated since a simple empty ListBuilder can be returned. + + inline ReaderFor getReader() const; + + inline bool operator==(decltype(nullptr)) const { return builder == nullptr; } + inline bool operator!=(decltype(nullptr)) const { return builder != nullptr; } + + inline void truncate(uint size); + // Resize an object (which must be a list or a blob) to the given size. + // + // If the new size is less than the original, the remaining elements will be discarded. The + // list is never moved in this case. If the list happens to be located at the end of its segment + // (which is always true if the list was the last thing allocated), the removed memory will be + // reclaimed (reducing the messag size), otherwise it is simply zeroed. The reclaiming behavior + // is particularly useful for allocating buffer space when you aren't sure how much space you + // actually need: you can pre-allocate, say, a 4k byte array, read() from a file into it, and + // then truncate it back to the amount of space actually used. + // + // If the new size is greater than the original, the list is extended with default values. If + // the list is the last object in its segment *and* there is enough space left in the segment to + // extend it to cover the new values, then the list is extended in-place. Otherwise, it must be + // moved to a new location, leaving a zero'd hole in the previous space that won't be filled. + // This copy is shallow; sub-objects will simply be reparented, not copied. + // + // Any existing readers or builders pointing at the object are invalidated by this call (even if + // it doesn't move). You must call `get()` or `getReader()` again to get the new, valid pointer. + +private: + _::OrphanBuilder builder; + + template + friend struct _::PointerHelpers; + template + friend struct List; + template + friend class Orphan; + friend class Orphanage; + friend class MessageBuilder; +}; + +class Orphanage: private kj::DisallowConstCopy { + // Use to directly allocate Orphan objects, without having a parent object allocate and then + // disown the object. + +public: + inline Orphanage(): arena(nullptr) {} + + template + static Orphanage getForMessageContaining(BuilderType builder); + // Construct an Orphanage that allocates within the message containing the given Builder. This + // allows the constructed Orphans to be adopted by objects within said message. + // + // This constructor takes the builder rather than having the builder have a getOrphanage() method + // because this is an advanced feature and we don't want to pollute the builder APIs with it. + // + // Note that if you have a direct pointer to the `MessageBuilder`, you can simply call its + // `getOrphanage()` method. + + template + Orphan newOrphan() const; + // Allocate a new orphaned struct. + + template + Orphan newOrphan(uint size) const; + // Allocate a new orphaned list or blob. + + Orphan newOrphan(StructSchema schema) const; + // Dynamically create an orphan struct with the given schema. You must + // #include to use this. + + Orphan newOrphan(ListSchema schema, uint size) const; + // Dynamically create an orphan list with the given schema. You must #include + // to use this. + + template + Orphan> newOrphanCopy(Reader copyFrom) const; + // Allocate a new orphaned object (struct, list, or blob) and initialize it as a copy of the + // given object. + + template + Orphan>>> newOrphanConcat(kj::ArrayPtr lists) const; + template + Orphan>>> newOrphanConcat(kj::ArrayPtr lists) const; + // Given an array of List readers, copy and concatenate the lists, creating a new Orphan. + // + // Note that compared to allocating the list yourself and using `setWithCaveats()` to set each + // item, this method avoids the "caveats": the new list will be allocated with the element size + // being the maximum of that from all the input lists. This is particularly important when + // concatenating struct lists: if the lists were created using a newer version of the protocol + // in which some new fields had been added to the struct, using `setWithCaveats()` would + // truncate off those new fields. + + Orphan referenceExternalData(Data::Reader data) const; + // Creates an Orphan that points at an existing region of memory (e.g. from another message) + // without copying it. There are some SEVERE restrictions on how this can be used: + // - The memory must remain valid until the `MessageBuilder` is destroyed (even if the orphan is + // abandoned). + // - Because the data is const, you will not be allowed to obtain a `Data::Builder` + // for this blob. Any call which would return such a builder will throw an exception. You + // can, however, obtain a Reader, e.g. via orphan.getReader() or from a parent Reader (once + // the orphan is adopted). It is your responsibility to make sure your code can deal with + // these problems when using this optimization; if you can't, allocate a copy instead. + // - `data.begin()` must be aligned to a machine word boundary (32-bit or 64-bit depending on + // the CPU). Any pointer returned by malloc() as well as any data blob obtained from another + // Cap'n Proto message satisfies this. + // - If `data.size()` is not a multiple of 8, extra bytes past data.end() up until the next 8-byte + // boundary will be visible in the raw message when it is written out. Thus, there must be no + // secrets in these bytes. Data blobs obtained from other Cap'n Proto messages should be safe + // as these bytes should be zero (unless the sender had the same problem). + // + // The array will actually become one of the message's segments. The data can thus be adopted + // into the message tree without copying it. This is particularly useful when referencing very + // large blobs, such as whole mmap'd files. + +private: + _::BuilderArena* arena; + _::CapTableBuilder* capTable; + + inline explicit Orphanage(_::BuilderArena* arena, _::CapTableBuilder* capTable) + : arena(arena), capTable(capTable) {} + + template + struct GetInnerBuilder; + template + struct GetInnerReader; + template + struct NewOrphanListImpl; + + friend class MessageBuilder; + friend struct _::OrphanageInternal; +}; + +// ======================================================================================= +// Inline implementation details. + +namespace _ { // private + +template +struct OrphanGetImpl; + +template +struct OrphanGetImpl { + static inline void truncateListOf(_::OrphanBuilder& builder, ElementCount size) { + builder.truncate(size, _::elementSizeForType()); + } +}; + +template +struct OrphanGetImpl { + static inline typename T::Builder apply(_::OrphanBuilder& builder) { + return typename T::Builder(builder.asStruct(_::structSize())); + } + static inline typename T::Reader applyReader(const _::OrphanBuilder& builder) { + return typename T::Reader(builder.asStructReader(_::structSize())); + } + static inline void truncateListOf(_::OrphanBuilder& builder, ElementCount size) { + builder.truncate(size, _::structSize()); + } +}; + +#if !CAPNP_LITE +template +struct OrphanGetImpl { + static inline typename T::Client apply(_::OrphanBuilder& builder) { + return typename T::Client(builder.asCapability()); + } + static inline typename T::Client applyReader(const _::OrphanBuilder& builder) { + return typename T::Client(builder.asCapability()); + } + static inline void truncateListOf(_::OrphanBuilder& builder, ElementCount size) { + builder.truncate(size, ElementSize::POINTER); + } +}; +#endif // !CAPNP_LITE + +template +struct OrphanGetImpl, Kind::LIST> { + static inline typename List::Builder apply(_::OrphanBuilder& builder) { + return typename List::Builder(builder.asList(_::ElementSizeForType::value)); + } + static inline typename List::Reader applyReader(const _::OrphanBuilder& builder) { + return typename List::Reader(builder.asListReader(_::ElementSizeForType::value)); + } + static inline void truncateListOf(_::OrphanBuilder& builder, ElementCount size) { + builder.truncate(size, ElementSize::POINTER); + } +}; + +template +struct OrphanGetImpl, Kind::LIST> { + static inline typename List::Builder apply(_::OrphanBuilder& builder) { + return typename List::Builder(builder.asStructList(_::structSize())); + } + static inline typename List::Reader applyReader(const _::OrphanBuilder& builder) { + return typename List::Reader(builder.asListReader(_::ElementSizeForType::value)); + } + static inline void truncateListOf(_::OrphanBuilder& builder, ElementCount size) { + builder.truncate(size, ElementSize::POINTER); + } +}; + +template <> +struct OrphanGetImpl { + static inline Text::Builder apply(_::OrphanBuilder& builder) { + return Text::Builder(builder.asText()); + } + static inline Text::Reader applyReader(const _::OrphanBuilder& builder) { + return Text::Reader(builder.asTextReader()); + } + static inline void truncateListOf(_::OrphanBuilder& builder, ElementCount size) { + builder.truncate(size, ElementSize::POINTER); + } +}; + +template <> +struct OrphanGetImpl { + static inline Data::Builder apply(_::OrphanBuilder& builder) { + return Data::Builder(builder.asData()); + } + static inline Data::Reader applyReader(const _::OrphanBuilder& builder) { + return Data::Reader(builder.asDataReader()); + } + static inline void truncateListOf(_::OrphanBuilder& builder, ElementCount size) { + builder.truncate(size, ElementSize::POINTER); + } +}; + +struct OrphanageInternal { + static inline _::BuilderArena* getArena(Orphanage orphanage) { return orphanage.arena; } + static inline _::CapTableBuilder* getCapTable(Orphanage orphanage) { return orphanage.capTable; } +}; + +} // namespace _ (private) + +template +inline BuilderFor Orphan::get() { + return _::OrphanGetImpl::apply(builder); +} + +template +inline ReaderFor Orphan::getReader() const { + return _::OrphanGetImpl::applyReader(builder); +} + +template +inline void Orphan::truncate(uint size) { + _::OrphanGetImpl>::truncateListOf(builder, bounded(size) * ELEMENTS); +} + +template <> +inline void Orphan::truncate(uint size) { + builder.truncateText(bounded(size) * ELEMENTS); +} + +template <> +inline void Orphan::truncate(uint size) { + builder.truncate(bounded(size) * ELEMENTS, ElementSize::BYTE); +} + +template +struct Orphanage::GetInnerBuilder { + static inline _::StructBuilder apply(typename T::Builder& t) { + return t._builder; + } +}; + +template +struct Orphanage::GetInnerBuilder { + static inline _::ListBuilder apply(typename T::Builder& t) { + return t.builder; + } +}; + +template +Orphanage Orphanage::getForMessageContaining(BuilderType builder) { + auto inner = GetInnerBuilder>::apply(builder); + return Orphanage(inner.getArena(), inner.getCapTable()); +} + +template +Orphan Orphanage::newOrphan() const { + return Orphan(_::OrphanBuilder::initStruct(arena, capTable, _::structSize())); +} + +template +struct Orphanage::NewOrphanListImpl> { + static inline _::OrphanBuilder apply( + _::BuilderArena* arena, _::CapTableBuilder* capTable, uint size) { + return _::OrphanBuilder::initList( + arena, capTable, bounded(size) * ELEMENTS, _::ElementSizeForType::value); + } +}; + +template +struct Orphanage::NewOrphanListImpl> { + static inline _::OrphanBuilder apply( + _::BuilderArena* arena, _::CapTableBuilder* capTable, uint size) { + return _::OrphanBuilder::initStructList( + arena, capTable, bounded(size) * ELEMENTS, _::structSize()); + } +}; + +template <> +struct Orphanage::NewOrphanListImpl { + static inline _::OrphanBuilder apply( + _::BuilderArena* arena, _::CapTableBuilder* capTable, uint size) { + return _::OrphanBuilder::initText(arena, capTable, bounded(size) * BYTES); + } +}; + +template <> +struct Orphanage::NewOrphanListImpl { + static inline _::OrphanBuilder apply( + _::BuilderArena* arena, _::CapTableBuilder* capTable, uint size) { + return _::OrphanBuilder::initData(arena, capTable, bounded(size) * BYTES); + } +}; + +template +Orphan Orphanage::newOrphan(uint size) const { + return Orphan(NewOrphanListImpl::apply(arena, capTable, size)); +} + +template +struct Orphanage::GetInnerReader { + static inline _::StructReader apply(const typename T::Reader& t) { + return t._reader; + } +}; + +template +struct Orphanage::GetInnerReader { + static inline _::ListReader apply(const typename T::Reader& t) { + return t.reader; + } +}; + +template +struct Orphanage::GetInnerReader { + static inline const typename T::Reader& apply(const typename T::Reader& t) { + return t; + } +}; + +template +inline Orphan> Orphanage::newOrphanCopy(Reader copyFrom) const { + return Orphan>(_::OrphanBuilder::copy( + arena, capTable, GetInnerReader>::apply(copyFrom))); +} + +template +inline Orphan>>> +Orphanage::newOrphanConcat(kj::ArrayPtr lists) const { + return newOrphanConcat(kj::implicitCast>(lists)); +} +template +inline Orphan>>> +Orphanage::newOrphanConcat(kj::ArrayPtr lists) const { + // Optimization / simplification: Rely on List::Reader containing nothing except a + // _::ListReader. + static_assert(sizeof(T) == sizeof(_::ListReader), "lists are not bare readers?"); + kj::ArrayPtr raw( + reinterpret_cast(lists.begin()), lists.size()); + typedef ListElementType> Element; + return Orphan>( + _::OrphanBuilder::concat(arena, capTable, + _::elementSizeForType(), + _::minStructSizeForElement(), raw)); +} + +inline Orphan Orphanage::referenceExternalData(Data::Reader data) const { + return Orphan(_::OrphanBuilder::referenceExternalData(arena, data)); +} + +} // namespace capnp + +#endif // CAPNP_ORPHAN_H_ diff --git a/phonelibs/capnp-cpp/include/capnp/persistent.capnp b/phonelibs/capnp-cpp/include/capnp/persistent.capnp new file mode 100644 index 00000000000000..a13b47168a4cc8 --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/persistent.capnp @@ -0,0 +1,139 @@ +# Copyright (c) 2014 Sandstorm Development Group, Inc. and contributors +# Licensed under the MIT License: +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in +# all copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +# THE SOFTWARE. + +@0xb8630836983feed7; + +$import "/capnp/c++.capnp".namespace("capnp"); + +interface Persistent@0xc8cb212fcd9f5691(SturdyRef, Owner) { + # Interface implemented by capabilities that outlive a single connection. A client may save() + # the capability, producing a SturdyRef. The SturdyRef can be stored to disk, then later used to + # obtain a new reference to the capability on a future connection. + # + # The exact format of SturdyRef depends on the "realm" in which the SturdyRef appears. A "realm" + # is an abstract space in which all SturdyRefs have the same format and refer to the same set of + # resources. Every vat is in exactly one realm. All capability clients within that vat must + # produce SturdyRefs of the format appropriate for the realm. + # + # Similarly, every VatNetwork also resides in a particular realm. Usually, a vat's "realm" + # corresponds to the realm of its main VatNetwork. However, a Vat can in fact communicate over + # a VatNetwork in a different realm -- in this case, all SturdyRefs need to be transformed when + # coming or going through said VatNetwork. The RPC system has hooks for registering + # transformation callbacks for this purpose. + # + # Since the format of SturdyRef is realm-dependent, it is not defined here. An application should + # choose an appropriate realm for itself as part of its design. Note that under Sandstorm, every + # application exists in its own realm and is therefore free to define its own SturdyRef format; + # the Sandstorm platform handles translating between realms. + # + # Note that whether a capability is persistent is often orthogonal to its type. In these cases, + # the capability's interface should NOT inherit `Persistent`; instead, just perform a cast at + # runtime. It's not type-safe, but trying to be type-safe in these cases will likely lead to + # tears. In cases where a particular interface only makes sense on persistent capabilities, it + # still should not explicitly inherit Persistent because the `SturdyRef` and `Owner` types will + # vary between realms (they may even be different at the call site than they are on the + # implementation). Instead, mark persistent interfaces with the $persistent annotation (defined + # below). + # + # Sealing + # ------- + # + # As an added security measure, SturdyRefs may be "sealed" to a particular owner, such that + # if the SturdyRef itself leaks to a third party, that party cannot actually restore it because + # they are not the owner. To restore a sealed capability, you must first prove to its host that + # you are the rightful owner. The precise mechanism for this authentication is defined by the + # realm. + # + # Sealing is a defense-in-depth mechanism meant to mitigate damage in the case of catastrophic + # attacks. For example, say an attacker temporarily gains read access to a database full of + # SturdyRefs: it would be unfortunate if it were then necessary to revoke every single reference + # in the database to prevent the attacker from using them. + # + # In general, an "owner" is a course-grained identity. Because capability-based security is still + # the primary mechanism of security, it is not necessary nor desirable to have a separate "owner" + # identity for every single process or object; that is exactly what capabilities are supposed to + # avoid! Instead, it makes sense for an "owner" to literally identify the owner of the machines + # where the capability is stored. If untrusted third parties are able to run arbitrary code on + # said machines, then the sandbox for that code should be designed using Distributed Confinement + # such that the third-party code never sees the bits of the SturdyRefs and cannot directly + # exercise the owner's power to restore refs. See: + # + # http://www.erights.org/elib/capability/dist-confine.html + # + # Resist the urge to represent an Owner as a simple public key. The whole point of sealing is to + # defend against leaked-storage attacks. Such attacks can easily result in the owner's private + # key being stolen as well. A better solution is for `Owner` to contain a simple globally unique + # identifier for the owner, and for everyone to separately maintain a mapping of owner IDs to + # public keys. If an owner's private key is compromised, then humans will need to communicate + # and agree on a replacement public key, then update the mapping. + # + # As a concrete example, an `Owner` could simply contain a domain name, and restoring a SturdyRef + # would require signing a request using the domain's private key. Authenticating this key could + # be accomplished through certificate authorities or web-of-trust techniques. + + save @0 SaveParams -> SaveResults; + # Save a capability persistently so that it can be restored by a future connection. Not all + # capabilities can be saved -- application interfaces should define which capabilities support + # this and which do not. + + struct SaveParams { + sealFor @0 :Owner; + # Seal the SturdyRef so that it can only be restored by the specified Owner. This is meant + # to mitigate damage when a SturdyRef is leaked. See comments above. + # + # Leaving this value null may or may not be allowed; it is up to the realm to decide. If a + # realm does allow a null owner, this should indicate that anyone is allowed to restore the + # ref. + } + struct SaveResults { + sturdyRef @0 :SturdyRef; + } +} + +interface RealmGateway(InternalRef, ExternalRef, InternalOwner, ExternalOwner) { + # Interface invoked when a SturdyRef is about to cross realms. The RPC system supports providing + # a RealmGateway as a callback hook when setting up RPC over some VatNetwork. + + import @0 (cap :Persistent(ExternalRef, ExternalOwner), + params :Persistent(InternalRef, InternalOwner).SaveParams) + -> Persistent(InternalRef, InternalOwner).SaveResults; + # Given an external capability, save it and return an internal reference. Used when someone + # inside the realm tries to save a capability from outside the realm. + + export @1 (cap :Persistent(InternalRef, InternalOwner), + params :Persistent(ExternalRef, ExternalOwner).SaveParams) + -> Persistent(ExternalRef, ExternalOwner).SaveResults; + # Given an internal capability, save it and return an external reference. Used when someone + # outside the realm tries to save a capability from inside the realm. +} + +annotation persistent(interface, field) :Void; +# Apply this annotation to interfaces for objects that will always be persistent, instead of +# extending the Persistent capability, since the correct type parameters to Persistent depend on +# the realm, which is orthogonal to the interface type and therefore should not be defined +# along-side it. +# +# You may also apply this annotation to a capability-typed field which will always contain a +# persistent capability, but where the capability's interface itself is not already marked +# persistent. +# +# Note that absence of the $persistent annotation doesn't mean a capability of that type isn't +# persistent; it just means not *all* such capabilities are persistent. diff --git a/phonelibs/capnp-cpp/include/capnp/persistent.capnp.h b/phonelibs/capnp-cpp/include/capnp/persistent.capnp.h new file mode 100644 index 00000000000000..f9b443220a9584 --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/persistent.capnp.h @@ -0,0 +1,1328 @@ +// Generated by Cap'n Proto compiler, DO NOT EDIT +// source: persistent.capnp + +#ifndef CAPNP_INCLUDED_b8630836983feed7_ +#define CAPNP_INCLUDED_b8630836983feed7_ + +#include +#if !CAPNP_LITE +#include +#endif // !CAPNP_LITE + +#if CAPNP_VERSION != 6001 +#error "Version mismatch between generated code and library headers. You must use the same version of the Cap'n Proto compiler and library." +#endif + + +namespace capnp { +namespace schemas { + +CAPNP_DECLARE_SCHEMA(c8cb212fcd9f5691); +CAPNP_DECLARE_SCHEMA(f76fba59183073a5); +CAPNP_DECLARE_SCHEMA(b76848c18c40efbf); +CAPNP_DECLARE_SCHEMA(84ff286cd00a3ed4); +CAPNP_DECLARE_SCHEMA(f0c2cc1d3909574d); +CAPNP_DECLARE_SCHEMA(ecafa18b482da3aa); +CAPNP_DECLARE_SCHEMA(f622595091cafb67); + +} // namespace schemas +} // namespace capnp + +namespace capnp { + +template +struct Persistent { + Persistent() = delete; + +#if !CAPNP_LITE + class Client; + class Server; +#endif // !CAPNP_LITE + + struct SaveParams; + struct SaveResults; + + #if !CAPNP_LITE + struct _capnpPrivate { + CAPNP_DECLARE_INTERFACE_HEADER(c8cb212fcd9f5691) + static const ::capnp::_::RawBrandedSchema::Scope brandScopes[]; + static const ::capnp::_::RawBrandedSchema::Binding brandBindings[]; + static const ::capnp::_::RawBrandedSchema::Dependency brandDependencies[]; + static const ::capnp::_::RawBrandedSchema specificBrand; + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return ::capnp::_::ChooseBrand<_capnpPrivate, SturdyRef, Owner>::brand(); } + }; + #endif // !CAPNP_LITE +}; + +template +struct Persistent::SaveParams { + SaveParams() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(f76fba59183073a5, 0, 1) + #if !CAPNP_LITE + static const ::capnp::_::RawBrandedSchema::Scope brandScopes[]; + static const ::capnp::_::RawBrandedSchema::Binding brandBindings[]; + static const ::capnp::_::RawBrandedSchema specificBrand; + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return ::capnp::_::ChooseBrand<_capnpPrivate, SturdyRef, Owner>::brand(); } + #endif // !CAPNP_LITE + }; +}; + +template +struct Persistent::SaveResults { + SaveResults() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(b76848c18c40efbf, 0, 1) + #if !CAPNP_LITE + static const ::capnp::_::RawBrandedSchema::Scope brandScopes[]; + static const ::capnp::_::RawBrandedSchema::Binding brandBindings[]; + static const ::capnp::_::RawBrandedSchema specificBrand; + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return ::capnp::_::ChooseBrand<_capnpPrivate, SturdyRef, Owner>::brand(); } + #endif // !CAPNP_LITE + }; +}; + +template +struct RealmGateway { + RealmGateway() = delete; + +#if !CAPNP_LITE + class Client; + class Server; +#endif // !CAPNP_LITE + + struct ImportParams; + struct ExportParams; + + #if !CAPNP_LITE + struct _capnpPrivate { + CAPNP_DECLARE_INTERFACE_HEADER(84ff286cd00a3ed4) + static const ::capnp::_::RawBrandedSchema::Scope brandScopes[]; + static const ::capnp::_::RawBrandedSchema::Binding brandBindings[]; + static const ::capnp::_::RawBrandedSchema::Dependency brandDependencies[]; + static const ::capnp::_::RawBrandedSchema specificBrand; + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return ::capnp::_::ChooseBrand<_capnpPrivate, InternalRef, ExternalRef, InternalOwner, ExternalOwner>::brand(); } + }; + #endif // !CAPNP_LITE +}; + +template +struct RealmGateway::ImportParams { + ImportParams() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(f0c2cc1d3909574d, 0, 2) + #if !CAPNP_LITE + static const ::capnp::_::RawBrandedSchema::Scope brandScopes[]; + static const ::capnp::_::RawBrandedSchema::Binding brandBindings[]; + static const ::capnp::_::RawBrandedSchema::Dependency brandDependencies[]; + static const ::capnp::_::RawBrandedSchema specificBrand; + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return ::capnp::_::ChooseBrand<_capnpPrivate, InternalRef, ExternalRef, InternalOwner, ExternalOwner>::brand(); } + #endif // !CAPNP_LITE + }; +}; + +template +struct RealmGateway::ExportParams { + ExportParams() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(ecafa18b482da3aa, 0, 2) + #if !CAPNP_LITE + static const ::capnp::_::RawBrandedSchema::Scope brandScopes[]; + static const ::capnp::_::RawBrandedSchema::Binding brandBindings[]; + static const ::capnp::_::RawBrandedSchema::Dependency brandDependencies[]; + static const ::capnp::_::RawBrandedSchema specificBrand; + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return ::capnp::_::ChooseBrand<_capnpPrivate, InternalRef, ExternalRef, InternalOwner, ExternalOwner>::brand(); } + #endif // !CAPNP_LITE + }; +}; + +// ======================================================================================= + +#if !CAPNP_LITE +template +class Persistent::Client + : public virtual ::capnp::Capability::Client { +public: + typedef Persistent Calls; + typedef Persistent Reads; + + Client(decltype(nullptr)); + explicit Client(::kj::Own< ::capnp::ClientHook>&& hook); + template ()>> + Client(::kj::Own<_t>&& server); + template ()>> + Client(::kj::Promise<_t>&& promise); + Client(::kj::Exception&& exception); + Client(Client&) = default; + Client(Client&&) = default; + Client& operator=(Client& other); + Client& operator=(Client&& other); + + template + typename Persistent::Client asGeneric() { + return castAs>(); + } + + CAPNP_AUTO_IF_MSVC(::capnp::Request::SaveParams, typename ::capnp::Persistent::SaveResults>) saveRequest( + ::kj::Maybe< ::capnp::MessageSize> sizeHint = nullptr); + +protected: + Client() = default; +}; + +template +class Persistent::Server + : public virtual ::capnp::Capability::Server { +public: + typedef Persistent Serves; + + ::kj::Promise dispatchCall(uint64_t interfaceId, uint16_t methodId, + ::capnp::CallContext< ::capnp::AnyPointer, ::capnp::AnyPointer> context) + override; + +protected: + typedef ::capnp::CallContext::SaveParams, typename ::capnp::Persistent::SaveResults> SaveContext; + virtual ::kj::Promise save(SaveContext context); + + inline typename ::capnp::Persistent::Client thisCap() { + return ::capnp::Capability::Server::thisCap() + .template castAs< ::capnp::Persistent>(); + } + + ::kj::Promise dispatchCallInternal(uint16_t methodId, + ::capnp::CallContext< ::capnp::AnyPointer, ::capnp::AnyPointer> context); +}; +#endif // !CAPNP_LITE + +template +class Persistent::SaveParams::Reader { +public: + typedef SaveParams Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + template + typename Persistent::SaveParams::Reader asPersistentGeneric() { + return typename Persistent::SaveParams::Reader(_reader); + } + + inline bool hasSealFor() const; + inline ::capnp::ReaderFor getSealFor() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +template +class Persistent::SaveParams::Builder { +public: + typedef SaveParams Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + template + typename Persistent::SaveParams::Builder asPersistentGeneric() { + return typename Persistent::SaveParams::Builder(_builder); + } + + inline bool hasSealFor(); + inline ::capnp::BuilderFor getSealFor(); + inline void setSealFor( ::capnp::ReaderFor value); + inline ::capnp::BuilderFor initSealFor(); + inline ::capnp::BuilderFor initSealFor(unsigned int size); + inline void adoptSealFor(::capnp::Orphan&& value); + inline ::capnp::Orphan disownSealFor(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +template +class Persistent::SaveParams::Pipeline { +public: + typedef SaveParams Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::capnp::PipelineFor getSealFor(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +template +class Persistent::SaveResults::Reader { +public: + typedef SaveResults Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + template + typename Persistent::SaveResults::Reader asPersistentGeneric() { + return typename Persistent::SaveResults::Reader(_reader); + } + + inline bool hasSturdyRef() const; + inline ::capnp::ReaderFor getSturdyRef() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +template +class Persistent::SaveResults::Builder { +public: + typedef SaveResults Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + template + typename Persistent::SaveResults::Builder asPersistentGeneric() { + return typename Persistent::SaveResults::Builder(_builder); + } + + inline bool hasSturdyRef(); + inline ::capnp::BuilderFor getSturdyRef(); + inline void setSturdyRef( ::capnp::ReaderFor value); + inline ::capnp::BuilderFor initSturdyRef(); + inline ::capnp::BuilderFor initSturdyRef(unsigned int size); + inline void adoptSturdyRef(::capnp::Orphan&& value); + inline ::capnp::Orphan disownSturdyRef(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +template +class Persistent::SaveResults::Pipeline { +public: + typedef SaveResults Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::capnp::PipelineFor getSturdyRef(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +#if !CAPNP_LITE +template +class RealmGateway::Client + : public virtual ::capnp::Capability::Client { +public: + typedef RealmGateway Calls; + typedef RealmGateway Reads; + + Client(decltype(nullptr)); + explicit Client(::kj::Own< ::capnp::ClientHook>&& hook); + template ()>> + Client(::kj::Own<_t>&& server); + template ()>> + Client(::kj::Promise<_t>&& promise); + Client(::kj::Exception&& exception); + Client(Client&) = default; + Client(Client&&) = default; + Client& operator=(Client& other); + Client& operator=(Client&& other); + + template + typename RealmGateway::Client asGeneric() { + return castAs>(); + } + + CAPNP_AUTO_IF_MSVC(::capnp::Request::ImportParams, typename ::capnp::Persistent::SaveResults>) importRequest( + ::kj::Maybe< ::capnp::MessageSize> sizeHint = nullptr); + CAPNP_AUTO_IF_MSVC(::capnp::Request::ExportParams, typename ::capnp::Persistent::SaveResults>) exportRequest( + ::kj::Maybe< ::capnp::MessageSize> sizeHint = nullptr); + +protected: + Client() = default; +}; + +template +class RealmGateway::Server + : public virtual ::capnp::Capability::Server { +public: + typedef RealmGateway Serves; + + ::kj::Promise dispatchCall(uint64_t interfaceId, uint16_t methodId, + ::capnp::CallContext< ::capnp::AnyPointer, ::capnp::AnyPointer> context) + override; + +protected: + typedef typename ::capnp::RealmGateway::ImportParams ImportParams; + typedef ::capnp::CallContext::SaveResults> ImportContext; + virtual ::kj::Promise import(ImportContext context); + typedef typename ::capnp::RealmGateway::ExportParams ExportParams; + typedef ::capnp::CallContext::SaveResults> ExportContext; + virtual ::kj::Promise export_(ExportContext context); + + inline typename ::capnp::RealmGateway::Client thisCap() { + return ::capnp::Capability::Server::thisCap() + .template castAs< ::capnp::RealmGateway>(); + } + + ::kj::Promise dispatchCallInternal(uint16_t methodId, + ::capnp::CallContext< ::capnp::AnyPointer, ::capnp::AnyPointer> context); +}; +#endif // !CAPNP_LITE + +template +class RealmGateway::ImportParams::Reader { +public: + typedef ImportParams Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + template + typename RealmGateway::ImportParams::Reader asRealmGatewayGeneric() { + return typename RealmGateway::ImportParams::Reader(_reader); + } + + inline bool hasCap() const; +#if !CAPNP_LITE + inline typename ::capnp::Persistent::Client getCap() const; +#endif // !CAPNP_LITE + + inline bool hasParams() const; + inline typename ::capnp::Persistent::SaveParams::Reader getParams() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +template +class RealmGateway::ImportParams::Builder { +public: + typedef ImportParams Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + template + typename RealmGateway::ImportParams::Builder asRealmGatewayGeneric() { + return typename RealmGateway::ImportParams::Builder(_builder); + } + + inline bool hasCap(); +#if !CAPNP_LITE + inline typename ::capnp::Persistent::Client getCap(); + inline void setCap(typename ::capnp::Persistent::Client&& value); + inline void setCap(typename ::capnp::Persistent::Client& value); + inline void adoptCap(::capnp::Orphan< ::capnp::Persistent>&& value); + inline ::capnp::Orphan< ::capnp::Persistent> disownCap(); +#endif // !CAPNP_LITE + + inline bool hasParams(); + inline typename ::capnp::Persistent::SaveParams::Builder getParams(); + inline void setParams(typename ::capnp::Persistent::SaveParams::Reader value); + inline typename ::capnp::Persistent::SaveParams::Builder initParams(); + inline void adoptParams(::capnp::Orphan::SaveParams>&& value); + inline ::capnp::Orphan::SaveParams> disownParams(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +template +class RealmGateway::ImportParams::Pipeline { +public: + typedef ImportParams Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline typename ::capnp::Persistent::Client getCap(); + inline typename ::capnp::Persistent::SaveParams::Pipeline getParams(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +template +class RealmGateway::ExportParams::Reader { +public: + typedef ExportParams Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + template + typename RealmGateway::ExportParams::Reader asRealmGatewayGeneric() { + return typename RealmGateway::ExportParams::Reader(_reader); + } + + inline bool hasCap() const; +#if !CAPNP_LITE + inline typename ::capnp::Persistent::Client getCap() const; +#endif // !CAPNP_LITE + + inline bool hasParams() const; + inline typename ::capnp::Persistent::SaveParams::Reader getParams() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +template +class RealmGateway::ExportParams::Builder { +public: + typedef ExportParams Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + template + typename RealmGateway::ExportParams::Builder asRealmGatewayGeneric() { + return typename RealmGateway::ExportParams::Builder(_builder); + } + + inline bool hasCap(); +#if !CAPNP_LITE + inline typename ::capnp::Persistent::Client getCap(); + inline void setCap(typename ::capnp::Persistent::Client&& value); + inline void setCap(typename ::capnp::Persistent::Client& value); + inline void adoptCap(::capnp::Orphan< ::capnp::Persistent>&& value); + inline ::capnp::Orphan< ::capnp::Persistent> disownCap(); +#endif // !CAPNP_LITE + + inline bool hasParams(); + inline typename ::capnp::Persistent::SaveParams::Builder getParams(); + inline void setParams(typename ::capnp::Persistent::SaveParams::Reader value); + inline typename ::capnp::Persistent::SaveParams::Builder initParams(); + inline void adoptParams(::capnp::Orphan::SaveParams>&& value); + inline ::capnp::Orphan::SaveParams> disownParams(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +template +class RealmGateway::ExportParams::Pipeline { +public: + typedef ExportParams Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline typename ::capnp::Persistent::Client getCap(); + inline typename ::capnp::Persistent::SaveParams::Pipeline getParams(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +// ======================================================================================= + +#if !CAPNP_LITE +template +inline Persistent::Client::Client(decltype(nullptr)) + : ::capnp::Capability::Client(nullptr) {} +template +inline Persistent::Client::Client( + ::kj::Own< ::capnp::ClientHook>&& hook) + : ::capnp::Capability::Client(::kj::mv(hook)) {} +template +template +inline Persistent::Client::Client(::kj::Own<_t>&& server) + : ::capnp::Capability::Client(::kj::mv(server)) {} +template +template +inline Persistent::Client::Client(::kj::Promise<_t>&& promise) + : ::capnp::Capability::Client(::kj::mv(promise)) {} +template +inline Persistent::Client::Client(::kj::Exception&& exception) + : ::capnp::Capability::Client(::kj::mv(exception)) {} +template +inline typename ::capnp::Persistent::Client& Persistent::Client::operator=(Client& other) { + ::capnp::Capability::Client::operator=(other); + return *this; +} +template +inline typename ::capnp::Persistent::Client& Persistent::Client::operator=(Client&& other) { + ::capnp::Capability::Client::operator=(kj::mv(other)); + return *this; +} + +#endif // !CAPNP_LITE +template +inline bool Persistent::SaveParams::Reader::hasSealFor() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +template +inline bool Persistent::SaveParams::Builder::hasSealFor() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +template +inline ::capnp::ReaderFor Persistent::SaveParams::Reader::getSealFor() const { + return ::capnp::_::PointerHelpers::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +template +inline ::capnp::BuilderFor Persistent::SaveParams::Builder::getSealFor() { + return ::capnp::_::PointerHelpers::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +template +inline ::capnp::PipelineFor Persistent::SaveParams::Pipeline::getSealFor() { + return ::capnp::PipelineFor(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +template +inline void Persistent::SaveParams::Builder::setSealFor( ::capnp::ReaderFor value) { + ::capnp::_::PointerHelpers::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +template +inline ::capnp::BuilderFor Persistent::SaveParams::Builder::initSealFor() { + return ::capnp::_::PointerHelpers::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +template +inline ::capnp::BuilderFor Persistent::SaveParams::Builder::initSealFor(unsigned int size) { + return ::capnp::_::PointerHelpers::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), size); +} +template +inline void Persistent::SaveParams::Builder::adoptSealFor( + ::capnp::Orphan&& value) { + ::capnp::_::PointerHelpers::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +template +inline ::capnp::Orphan Persistent::SaveParams::Builder::disownSealFor() { + return ::capnp::_::PointerHelpers::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +// Persistent::SaveParams +template +constexpr uint16_t Persistent::SaveParams::_capnpPrivate::dataWordSize; +template +constexpr uint16_t Persistent::SaveParams::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +template +constexpr ::capnp::Kind Persistent::SaveParams::_capnpPrivate::kind; +template +constexpr ::capnp::_::RawSchema const* Persistent::SaveParams::_capnpPrivate::schema; +template +const ::capnp::_::RawBrandedSchema::Scope Persistent::SaveParams::_capnpPrivate::brandScopes[] = { + { 0xc8cb212fcd9f5691, brandBindings + 0, 2, false}, +}; +template +const ::capnp::_::RawBrandedSchema::Binding Persistent::SaveParams::_capnpPrivate::brandBindings[] = { + ::capnp::_::brandBindingFor(), + ::capnp::_::brandBindingFor(), +}; +template +const ::capnp::_::RawBrandedSchema Persistent::SaveParams::_capnpPrivate::specificBrand = { + &::capnp::schemas::s_f76fba59183073a5, brandScopes, nullptr, + 1, 0, nullptr +}; +#endif // !CAPNP_LITE + +template +inline bool Persistent::SaveResults::Reader::hasSturdyRef() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +template +inline bool Persistent::SaveResults::Builder::hasSturdyRef() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +template +inline ::capnp::ReaderFor Persistent::SaveResults::Reader::getSturdyRef() const { + return ::capnp::_::PointerHelpers::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +template +inline ::capnp::BuilderFor Persistent::SaveResults::Builder::getSturdyRef() { + return ::capnp::_::PointerHelpers::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +template +inline ::capnp::PipelineFor Persistent::SaveResults::Pipeline::getSturdyRef() { + return ::capnp::PipelineFor(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +template +inline void Persistent::SaveResults::Builder::setSturdyRef( ::capnp::ReaderFor value) { + ::capnp::_::PointerHelpers::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +template +inline ::capnp::BuilderFor Persistent::SaveResults::Builder::initSturdyRef() { + return ::capnp::_::PointerHelpers::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +template +inline ::capnp::BuilderFor Persistent::SaveResults::Builder::initSturdyRef(unsigned int size) { + return ::capnp::_::PointerHelpers::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), size); +} +template +inline void Persistent::SaveResults::Builder::adoptSturdyRef( + ::capnp::Orphan&& value) { + ::capnp::_::PointerHelpers::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +template +inline ::capnp::Orphan Persistent::SaveResults::Builder::disownSturdyRef() { + return ::capnp::_::PointerHelpers::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +// Persistent::SaveResults +template +constexpr uint16_t Persistent::SaveResults::_capnpPrivate::dataWordSize; +template +constexpr uint16_t Persistent::SaveResults::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +template +constexpr ::capnp::Kind Persistent::SaveResults::_capnpPrivate::kind; +template +constexpr ::capnp::_::RawSchema const* Persistent::SaveResults::_capnpPrivate::schema; +template +const ::capnp::_::RawBrandedSchema::Scope Persistent::SaveResults::_capnpPrivate::brandScopes[] = { + { 0xc8cb212fcd9f5691, brandBindings + 0, 2, false}, +}; +template +const ::capnp::_::RawBrandedSchema::Binding Persistent::SaveResults::_capnpPrivate::brandBindings[] = { + ::capnp::_::brandBindingFor(), + ::capnp::_::brandBindingFor(), +}; +template +const ::capnp::_::RawBrandedSchema Persistent::SaveResults::_capnpPrivate::specificBrand = { + &::capnp::schemas::s_b76848c18c40efbf, brandScopes, nullptr, + 1, 0, nullptr +}; +#endif // !CAPNP_LITE + +#if !CAPNP_LITE +template +CAPNP_AUTO_IF_MSVC(::capnp::Request::SaveParams, typename ::capnp::Persistent::SaveResults>) +Persistent::Client::saveRequest(::kj::Maybe< ::capnp::MessageSize> sizeHint) { + return newCall::SaveParams, typename ::capnp::Persistent::SaveResults>( + 0xc8cb212fcd9f5691ull, 0, sizeHint); +} +template +::kj::Promise Persistent::Server::save(SaveContext) { + return ::capnp::Capability::Server::internalUnimplemented( + "capnp/persistent.capnp:Persistent", "save", + 0xc8cb212fcd9f5691ull, 0); +} +template +::kj::Promise Persistent::Server::dispatchCall( + uint64_t interfaceId, uint16_t methodId, + ::capnp::CallContext< ::capnp::AnyPointer, ::capnp::AnyPointer> context) { + switch (interfaceId) { + case 0xc8cb212fcd9f5691ull: + return dispatchCallInternal(methodId, context); + default: + return internalUnimplemented("capnp/persistent.capnp:Persistent", interfaceId); + } +} +template +::kj::Promise Persistent::Server::dispatchCallInternal( + uint16_t methodId, + ::capnp::CallContext< ::capnp::AnyPointer, ::capnp::AnyPointer> context) { + switch (methodId) { + case 0: + return save(::capnp::Capability::Server::internalGetTypedContext< + typename ::capnp::Persistent::SaveParams, typename ::capnp::Persistent::SaveResults>(context)); + default: + (void)context; + return ::capnp::Capability::Server::internalUnimplemented( + "capnp/persistent.capnp:Persistent", + 0xc8cb212fcd9f5691ull, methodId); + } +} +#endif // !CAPNP_LITE + +// Persistent +#if !CAPNP_LITE +template +constexpr ::capnp::Kind Persistent::_capnpPrivate::kind; +template +constexpr ::capnp::_::RawSchema const* Persistent::_capnpPrivate::schema; +template +const ::capnp::_::RawBrandedSchema::Scope Persistent::_capnpPrivate::brandScopes[] = { + { 0xc8cb212fcd9f5691, brandBindings + 0, 2, false}, +}; +template +const ::capnp::_::RawBrandedSchema::Binding Persistent::_capnpPrivate::brandBindings[] = { + ::capnp::_::brandBindingFor(), + ::capnp::_::brandBindingFor(), +}; +template +const ::capnp::_::RawBrandedSchema::Dependency Persistent::_capnpPrivate::brandDependencies[] = { + { 33554432, ::capnp::Persistent::SaveParams::_capnpPrivate::brand() }, + { 50331648, ::capnp::Persistent::SaveResults::_capnpPrivate::brand() }, +}; +template +const ::capnp::_::RawBrandedSchema Persistent::_capnpPrivate::specificBrand = { + &::capnp::schemas::s_c8cb212fcd9f5691, brandScopes, brandDependencies, + 1, 2, nullptr +}; +#endif // !CAPNP_LITE + +#if !CAPNP_LITE +template +inline RealmGateway::Client::Client(decltype(nullptr)) + : ::capnp::Capability::Client(nullptr) {} +template +inline RealmGateway::Client::Client( + ::kj::Own< ::capnp::ClientHook>&& hook) + : ::capnp::Capability::Client(::kj::mv(hook)) {} +template +template +inline RealmGateway::Client::Client(::kj::Own<_t>&& server) + : ::capnp::Capability::Client(::kj::mv(server)) {} +template +template +inline RealmGateway::Client::Client(::kj::Promise<_t>&& promise) + : ::capnp::Capability::Client(::kj::mv(promise)) {} +template +inline RealmGateway::Client::Client(::kj::Exception&& exception) + : ::capnp::Capability::Client(::kj::mv(exception)) {} +template +inline typename ::capnp::RealmGateway::Client& RealmGateway::Client::operator=(Client& other) { + ::capnp::Capability::Client::operator=(other); + return *this; +} +template +inline typename ::capnp::RealmGateway::Client& RealmGateway::Client::operator=(Client&& other) { + ::capnp::Capability::Client::operator=(kj::mv(other)); + return *this; +} + +#endif // !CAPNP_LITE +template +inline bool RealmGateway::ImportParams::Reader::hasCap() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +template +inline bool RealmGateway::ImportParams::Builder::hasCap() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +#if !CAPNP_LITE +template +inline typename ::capnp::Persistent::Client RealmGateway::ImportParams::Reader::getCap() const { + return ::capnp::_::PointerHelpers< ::capnp::Persistent>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +template +inline typename ::capnp::Persistent::Client RealmGateway::ImportParams::Builder::getCap() { + return ::capnp::_::PointerHelpers< ::capnp::Persistent>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +template +inline typename ::capnp::Persistent::Client RealmGateway::ImportParams::Pipeline::getCap() { + return typename ::capnp::Persistent::Client(_typeless.getPointerField(0).asCap()); +} +template +inline void RealmGateway::ImportParams::Builder::setCap(typename ::capnp::Persistent::Client&& cap) { + ::capnp::_::PointerHelpers< ::capnp::Persistent>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(cap)); +} +template +inline void RealmGateway::ImportParams::Builder::setCap(typename ::capnp::Persistent::Client& cap) { + ::capnp::_::PointerHelpers< ::capnp::Persistent>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), cap); +} +template +inline void RealmGateway::ImportParams::Builder::adoptCap( + ::capnp::Orphan< ::capnp::Persistent>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Persistent>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +template +inline ::capnp::Orphan< ::capnp::Persistent> RealmGateway::ImportParams::Builder::disownCap() { + return ::capnp::_::PointerHelpers< ::capnp::Persistent>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#endif // !CAPNP_LITE + +template +inline bool RealmGateway::ImportParams::Reader::hasParams() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +template +inline bool RealmGateway::ImportParams::Builder::hasParams() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +template +inline typename ::capnp::Persistent::SaveParams::Reader RealmGateway::ImportParams::Reader::getParams() const { + return ::capnp::_::PointerHelpers::SaveParams>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +template +inline typename ::capnp::Persistent::SaveParams::Builder RealmGateway::ImportParams::Builder::getParams() { + return ::capnp::_::PointerHelpers::SaveParams>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +template +inline typename ::capnp::Persistent::SaveParams::Pipeline RealmGateway::ImportParams::Pipeline::getParams() { + return typename ::capnp::Persistent::SaveParams::Pipeline(_typeless.getPointerField(1)); +} +#endif // !CAPNP_LITE +template +inline void RealmGateway::ImportParams::Builder::setParams(typename ::capnp::Persistent::SaveParams::Reader value) { + ::capnp::_::PointerHelpers::SaveParams>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +template +inline typename ::capnp::Persistent::SaveParams::Builder RealmGateway::ImportParams::Builder::initParams() { + return ::capnp::_::PointerHelpers::SaveParams>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +template +inline void RealmGateway::ImportParams::Builder::adoptParams( + ::capnp::Orphan::SaveParams>&& value) { + ::capnp::_::PointerHelpers::SaveParams>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +template +inline ::capnp::Orphan::SaveParams> RealmGateway::ImportParams::Builder::disownParams() { + return ::capnp::_::PointerHelpers::SaveParams>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +// RealmGateway::ImportParams +template +constexpr uint16_t RealmGateway::ImportParams::_capnpPrivate::dataWordSize; +template +constexpr uint16_t RealmGateway::ImportParams::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +template +constexpr ::capnp::Kind RealmGateway::ImportParams::_capnpPrivate::kind; +template +constexpr ::capnp::_::RawSchema const* RealmGateway::ImportParams::_capnpPrivate::schema; +template +const ::capnp::_::RawBrandedSchema::Scope RealmGateway::ImportParams::_capnpPrivate::brandScopes[] = { + { 0x84ff286cd00a3ed4, brandBindings + 0, 4, false}, +}; +template +const ::capnp::_::RawBrandedSchema::Binding RealmGateway::ImportParams::_capnpPrivate::brandBindings[] = { + ::capnp::_::brandBindingFor(), + ::capnp::_::brandBindingFor(), + ::capnp::_::brandBindingFor(), + ::capnp::_::brandBindingFor(), +}; +template +const ::capnp::_::RawBrandedSchema::Dependency RealmGateway::ImportParams::_capnpPrivate::brandDependencies[] = { + { 16777216, ::capnp::Persistent::_capnpPrivate::brand() }, + { 16777217, ::capnp::Persistent::SaveParams::_capnpPrivate::brand() }, +}; +template +const ::capnp::_::RawBrandedSchema RealmGateway::ImportParams::_capnpPrivate::specificBrand = { + &::capnp::schemas::s_f0c2cc1d3909574d, brandScopes, brandDependencies, + 1, 2, nullptr +}; +#endif // !CAPNP_LITE + +template +inline bool RealmGateway::ExportParams::Reader::hasCap() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +template +inline bool RealmGateway::ExportParams::Builder::hasCap() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +#if !CAPNP_LITE +template +inline typename ::capnp::Persistent::Client RealmGateway::ExportParams::Reader::getCap() const { + return ::capnp::_::PointerHelpers< ::capnp::Persistent>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +template +inline typename ::capnp::Persistent::Client RealmGateway::ExportParams::Builder::getCap() { + return ::capnp::_::PointerHelpers< ::capnp::Persistent>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +template +inline typename ::capnp::Persistent::Client RealmGateway::ExportParams::Pipeline::getCap() { + return typename ::capnp::Persistent::Client(_typeless.getPointerField(0).asCap()); +} +template +inline void RealmGateway::ExportParams::Builder::setCap(typename ::capnp::Persistent::Client&& cap) { + ::capnp::_::PointerHelpers< ::capnp::Persistent>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(cap)); +} +template +inline void RealmGateway::ExportParams::Builder::setCap(typename ::capnp::Persistent::Client& cap) { + ::capnp::_::PointerHelpers< ::capnp::Persistent>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), cap); +} +template +inline void RealmGateway::ExportParams::Builder::adoptCap( + ::capnp::Orphan< ::capnp::Persistent>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Persistent>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +template +inline ::capnp::Orphan< ::capnp::Persistent> RealmGateway::ExportParams::Builder::disownCap() { + return ::capnp::_::PointerHelpers< ::capnp::Persistent>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#endif // !CAPNP_LITE + +template +inline bool RealmGateway::ExportParams::Reader::hasParams() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +template +inline bool RealmGateway::ExportParams::Builder::hasParams() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +template +inline typename ::capnp::Persistent::SaveParams::Reader RealmGateway::ExportParams::Reader::getParams() const { + return ::capnp::_::PointerHelpers::SaveParams>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +template +inline typename ::capnp::Persistent::SaveParams::Builder RealmGateway::ExportParams::Builder::getParams() { + return ::capnp::_::PointerHelpers::SaveParams>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +template +inline typename ::capnp::Persistent::SaveParams::Pipeline RealmGateway::ExportParams::Pipeline::getParams() { + return typename ::capnp::Persistent::SaveParams::Pipeline(_typeless.getPointerField(1)); +} +#endif // !CAPNP_LITE +template +inline void RealmGateway::ExportParams::Builder::setParams(typename ::capnp::Persistent::SaveParams::Reader value) { + ::capnp::_::PointerHelpers::SaveParams>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +template +inline typename ::capnp::Persistent::SaveParams::Builder RealmGateway::ExportParams::Builder::initParams() { + return ::capnp::_::PointerHelpers::SaveParams>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +template +inline void RealmGateway::ExportParams::Builder::adoptParams( + ::capnp::Orphan::SaveParams>&& value) { + ::capnp::_::PointerHelpers::SaveParams>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +template +inline ::capnp::Orphan::SaveParams> RealmGateway::ExportParams::Builder::disownParams() { + return ::capnp::_::PointerHelpers::SaveParams>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +// RealmGateway::ExportParams +template +constexpr uint16_t RealmGateway::ExportParams::_capnpPrivate::dataWordSize; +template +constexpr uint16_t RealmGateway::ExportParams::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +template +constexpr ::capnp::Kind RealmGateway::ExportParams::_capnpPrivate::kind; +template +constexpr ::capnp::_::RawSchema const* RealmGateway::ExportParams::_capnpPrivate::schema; +template +const ::capnp::_::RawBrandedSchema::Scope RealmGateway::ExportParams::_capnpPrivate::brandScopes[] = { + { 0x84ff286cd00a3ed4, brandBindings + 0, 4, false}, +}; +template +const ::capnp::_::RawBrandedSchema::Binding RealmGateway::ExportParams::_capnpPrivate::brandBindings[] = { + ::capnp::_::brandBindingFor(), + ::capnp::_::brandBindingFor(), + ::capnp::_::brandBindingFor(), + ::capnp::_::brandBindingFor(), +}; +template +const ::capnp::_::RawBrandedSchema::Dependency RealmGateway::ExportParams::_capnpPrivate::brandDependencies[] = { + { 16777216, ::capnp::Persistent::_capnpPrivate::brand() }, + { 16777217, ::capnp::Persistent::SaveParams::_capnpPrivate::brand() }, +}; +template +const ::capnp::_::RawBrandedSchema RealmGateway::ExportParams::_capnpPrivate::specificBrand = { + &::capnp::schemas::s_ecafa18b482da3aa, brandScopes, brandDependencies, + 1, 2, nullptr +}; +#endif // !CAPNP_LITE + +#if !CAPNP_LITE +template +CAPNP_AUTO_IF_MSVC(::capnp::Request::ImportParams, typename ::capnp::Persistent::SaveResults>) +RealmGateway::Client::importRequest(::kj::Maybe< ::capnp::MessageSize> sizeHint) { + return newCall::ImportParams, typename ::capnp::Persistent::SaveResults>( + 0x84ff286cd00a3ed4ull, 0, sizeHint); +} +template +::kj::Promise RealmGateway::Server::import(ImportContext) { + return ::capnp::Capability::Server::internalUnimplemented( + "capnp/persistent.capnp:RealmGateway", "import", + 0x84ff286cd00a3ed4ull, 0); +} +template +CAPNP_AUTO_IF_MSVC(::capnp::Request::ExportParams, typename ::capnp::Persistent::SaveResults>) +RealmGateway::Client::exportRequest(::kj::Maybe< ::capnp::MessageSize> sizeHint) { + return newCall::ExportParams, typename ::capnp::Persistent::SaveResults>( + 0x84ff286cd00a3ed4ull, 1, sizeHint); +} +template +::kj::Promise RealmGateway::Server::export_(ExportContext) { + return ::capnp::Capability::Server::internalUnimplemented( + "capnp/persistent.capnp:RealmGateway", "export", + 0x84ff286cd00a3ed4ull, 1); +} +template +::kj::Promise RealmGateway::Server::dispatchCall( + uint64_t interfaceId, uint16_t methodId, + ::capnp::CallContext< ::capnp::AnyPointer, ::capnp::AnyPointer> context) { + switch (interfaceId) { + case 0x84ff286cd00a3ed4ull: + return dispatchCallInternal(methodId, context); + default: + return internalUnimplemented("capnp/persistent.capnp:RealmGateway", interfaceId); + } +} +template +::kj::Promise RealmGateway::Server::dispatchCallInternal( + uint16_t methodId, + ::capnp::CallContext< ::capnp::AnyPointer, ::capnp::AnyPointer> context) { + switch (methodId) { + case 0: + return import(::capnp::Capability::Server::internalGetTypedContext< + typename ::capnp::RealmGateway::ImportParams, typename ::capnp::Persistent::SaveResults>(context)); + case 1: + return export_(::capnp::Capability::Server::internalGetTypedContext< + typename ::capnp::RealmGateway::ExportParams, typename ::capnp::Persistent::SaveResults>(context)); + default: + (void)context; + return ::capnp::Capability::Server::internalUnimplemented( + "capnp/persistent.capnp:RealmGateway", + 0x84ff286cd00a3ed4ull, methodId); + } +} +#endif // !CAPNP_LITE + +// RealmGateway +#if !CAPNP_LITE +template +constexpr ::capnp::Kind RealmGateway::_capnpPrivate::kind; +template +constexpr ::capnp::_::RawSchema const* RealmGateway::_capnpPrivate::schema; +template +const ::capnp::_::RawBrandedSchema::Scope RealmGateway::_capnpPrivate::brandScopes[] = { + { 0x84ff286cd00a3ed4, brandBindings + 0, 4, false}, +}; +template +const ::capnp::_::RawBrandedSchema::Binding RealmGateway::_capnpPrivate::brandBindings[] = { + ::capnp::_::brandBindingFor(), + ::capnp::_::brandBindingFor(), + ::capnp::_::brandBindingFor(), + ::capnp::_::brandBindingFor(), +}; +template +const ::capnp::_::RawBrandedSchema::Dependency RealmGateway::_capnpPrivate::brandDependencies[] = { + { 33554432, ::capnp::RealmGateway::ImportParams::_capnpPrivate::brand() }, + { 33554433, ::capnp::RealmGateway::ExportParams::_capnpPrivate::brand() }, + { 50331648, ::capnp::Persistent::SaveResults::_capnpPrivate::brand() }, + { 50331649, ::capnp::Persistent::SaveResults::_capnpPrivate::brand() }, +}; +template +const ::capnp::_::RawBrandedSchema RealmGateway::_capnpPrivate::specificBrand = { + &::capnp::schemas::s_84ff286cd00a3ed4, brandScopes, brandDependencies, + 1, 4, nullptr +}; +#endif // !CAPNP_LITE + +} // namespace + +#endif // CAPNP_INCLUDED_b8630836983feed7_ diff --git a/phonelibs/capnp-cpp/include/capnp/pointer-helpers.h b/phonelibs/capnp-cpp/include/capnp/pointer-helpers.h new file mode 100644 index 00000000000000..fe70e5036ff221 --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/pointer-helpers.h @@ -0,0 +1,160 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef CAPNP_POINTER_HELPERS_H_ +#define CAPNP_POINTER_HELPERS_H_ + +#if defined(__GNUC__) && !defined(CAPNP_HEADER_WARNINGS) +#pragma GCC system_header +#endif + +#include "layout.h" +#include "list.h" + +namespace capnp { +namespace _ { // private + +// PointerHelpers is a template class that assists in wrapping/unwrapping the low-level types in +// layout.h with the high-level public API and generated types. This way, the code generator +// and other templates do not have to specialize on each kind of pointer. + +template +struct PointerHelpers { + static inline typename T::Reader get(PointerReader reader, const word* defaultValue = nullptr) { + return typename T::Reader(reader.getStruct(defaultValue)); + } + static inline typename T::Builder get(PointerBuilder builder, + const word* defaultValue = nullptr) { + return typename T::Builder(builder.getStruct(structSize(), defaultValue)); + } + static inline void set(PointerBuilder builder, typename T::Reader value) { + builder.setStruct(value._reader); + } + static inline void setCanonical(PointerBuilder builder, typename T::Reader value) { + builder.setStruct(value._reader, true); + } + static inline typename T::Builder init(PointerBuilder builder) { + return typename T::Builder(builder.initStruct(structSize())); + } + static inline void adopt(PointerBuilder builder, Orphan&& value) { + builder.adopt(kj::mv(value.builder)); + } + static inline Orphan disown(PointerBuilder builder) { + return Orphan(builder.disown()); + } + static inline _::StructReader getInternalReader(const typename T::Reader& reader) { + return reader._reader; + } + static inline _::StructBuilder getInternalBuilder(typename T::Builder&& builder) { + return builder._builder; + } +}; + +template +struct PointerHelpers, Kind::LIST> { + static inline typename List::Reader get(PointerReader reader, + const word* defaultValue = nullptr) { + return typename List::Reader(List::getFromPointer(reader, defaultValue)); + } + static inline typename List::Builder get(PointerBuilder builder, + const word* defaultValue = nullptr) { + return typename List::Builder(List::getFromPointer(builder, defaultValue)); + } + static inline void set(PointerBuilder builder, typename List::Reader value) { + builder.setList(value.reader); + } + static inline void setCanonical(PointerBuilder builder, typename List::Reader value) { + builder.setList(value.reader, true); + } + static void set(PointerBuilder builder, kj::ArrayPtr> value) { + auto l = init(builder, value.size()); + uint i = 0; + for (auto& element: value) { + l.set(i++, element); + } + } + static inline typename List::Builder init(PointerBuilder builder, uint size) { + return typename List::Builder(List::initPointer(builder, size)); + } + static inline void adopt(PointerBuilder builder, Orphan>&& value) { + builder.adopt(kj::mv(value.builder)); + } + static inline Orphan> disown(PointerBuilder builder) { + return Orphan>(builder.disown()); + } + static inline _::ListReader getInternalReader(const typename List::Reader& reader) { + return reader.reader; + } + static inline _::ListBuilder getInternalBuilder(typename List::Builder&& builder) { + return builder.builder; + } +}; + +template +struct PointerHelpers { + static inline typename T::Reader get(PointerReader reader, + const void* defaultValue = nullptr, + uint defaultBytes = 0) { + return reader.getBlob(defaultValue, bounded(defaultBytes) * BYTES); + } + static inline typename T::Builder get(PointerBuilder builder, + const void* defaultValue = nullptr, + uint defaultBytes = 0) { + return builder.getBlob(defaultValue, bounded(defaultBytes) * BYTES); + } + static inline void set(PointerBuilder builder, typename T::Reader value) { + builder.setBlob(value); + } + static inline void setCanonical(PointerBuilder builder, typename T::Reader value) { + builder.setBlob(value); + } + static inline typename T::Builder init(PointerBuilder builder, uint size) { + return builder.initBlob(bounded(size) * BYTES); + } + static inline void adopt(PointerBuilder builder, Orphan&& value) { + builder.adopt(kj::mv(value.builder)); + } + static inline Orphan disown(PointerBuilder builder) { + return Orphan(builder.disown()); + } +}; + +struct UncheckedMessage { + typedef const word* Reader; +}; + +template <> struct Kind_ { static constexpr Kind kind = Kind::OTHER; }; + +template <> +struct PointerHelpers { + // Reads an AnyPointer field as an unchecked message pointer. Requires that the containing + // message is itself unchecked. This hack is currently private. It is used to locate default + // values within encoded schemas. + + static inline const word* get(PointerReader reader) { + return reader.getUnchecked(); + } +}; + +} // namespace _ (private) +} // namespace capnp + +#endif // CAPNP_POINTER_HELPERS_H_ diff --git a/phonelibs/capnp-cpp/include/capnp/pretty-print.h b/phonelibs/capnp-cpp/include/capnp/pretty-print.h new file mode 100644 index 00000000000000..e6458bca496b5e --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/pretty-print.h @@ -0,0 +1,47 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef CAPNP_PRETTY_PRINT_H_ +#define CAPNP_PRETTY_PRINT_H_ + +#if defined(__GNUC__) && !defined(CAPNP_HEADER_WARNINGS) +#pragma GCC system_header +#endif + +#include "dynamic.h" +#include + +namespace capnp { + +kj::StringTree prettyPrint(DynamicStruct::Reader value); +kj::StringTree prettyPrint(DynamicStruct::Builder value); +kj::StringTree prettyPrint(DynamicList::Reader value); +kj::StringTree prettyPrint(DynamicList::Builder value); +// Print the given Cap'n Proto struct or list with nice indentation. Note that you can pass any +// struct or list reader or builder type to this method, since they can be implicitly converted +// to one of the dynamic types. +// +// If you don't want indentation, just use the value's KJ stringifier (e.g. pass it to kj::str(), +// any of the KJ debug macros, etc.). + +} // namespace capnp + +#endif // PRETTY_PRINT_H_ diff --git a/phonelibs/capnp-cpp/include/capnp/raw-schema.h b/phonelibs/capnp-cpp/include/capnp/raw-schema.h new file mode 100644 index 00000000000000..ed9425a6241b19 --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/raw-schema.h @@ -0,0 +1,242 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef CAPNP_RAW_SCHEMA_H_ +#define CAPNP_RAW_SCHEMA_H_ + +#if defined(__GNUC__) && !defined(CAPNP_HEADER_WARNINGS) +#pragma GCC system_header +#endif + +#include "common.h" // for uint and friends + +#if _MSC_VER +#include +#endif + +namespace capnp { +namespace _ { // private + +struct RawSchema; + +struct RawBrandedSchema { + // Represents a combination of a schema and bindings for its generic parameters. + // + // Note that while we generate one `RawSchema` per type, we generate a `RawBrandedSchema` for + // every _instance_ of a generic type -- or, at least, every instance that is actually used. For + // generated-code types, we use template magic to initialize these. + + const RawSchema* generic; + // Generic type which we're branding. + + struct Binding { + uint8_t which; // Numeric value of one of schema::Type::Which. + + bool isImplicitParameter; + // For AnyPointer, true if it's an implicit method parameter. + + uint16_t listDepth; // Number of times to wrap the base type in List(). + + uint16_t paramIndex; + // For AnyPointer. If it's a type parameter (scopeId is non-zero) or it's an implicit parameter + // (isImplicitParameter is true), then this is the parameter index. Otherwise this is a numeric + // value of one of schema::Type::AnyPointer::Unconstrained::Which. + + union { + const RawBrandedSchema* schema; // for struct, enum, interface + uint64_t scopeId; // for AnyPointer, if it's a type parameter + }; + + Binding() = default; + inline constexpr Binding(uint8_t which, uint16_t listDepth, const RawBrandedSchema* schema) + : which(which), isImplicitParameter(false), listDepth(listDepth), paramIndex(0), + schema(schema) {} + inline constexpr Binding(uint8_t which, uint16_t listDepth, + uint64_t scopeId, uint16_t paramIndex) + : which(which), isImplicitParameter(false), listDepth(listDepth), paramIndex(paramIndex), + scopeId(scopeId) {} + inline constexpr Binding(uint8_t which, uint16_t listDepth, uint16_t implicitParamIndex) + : which(which), isImplicitParameter(true), listDepth(listDepth), + paramIndex(implicitParamIndex), scopeId(0) {} + }; + + struct Scope { + uint64_t typeId; + // Type ID whose parameters are being bound. + + const Binding* bindings; + uint bindingCount; + // Bindings for those parameters. + + bool isUnbound; + // This scope is unbound, in the sense of SchemaLoader::getUnbound(). + }; + + const Scope* scopes; + // Array of enclosing scopes for which generic variables have been bound, sorted by type ID. + + struct Dependency { + uint location; + const RawBrandedSchema* schema; + }; + + const Dependency* dependencies; + // Map of branded schemas for dependencies of this type, given our brand. Only dependencies that + // are branded are included in this map; if a dependency is missing, use its `defaultBrand`. + + uint32_t scopeCount; + uint32_t dependencyCount; + + enum class DepKind { + // Component of a Dependency::location. Specifies what sort of dependency this is. + + INVALID, + // Mostly defined to ensure that zero is not a valid location. + + FIELD, + // Binding needed for a field's type. The index is the field index (NOT ordinal!). + + METHOD_PARAMS, + // Bindings needed for a method's params type. The index is the method number. + + METHOD_RESULTS, + // Bindings needed for a method's results type. The index is the method ordinal. + + SUPERCLASS, + // Bindings needed for a superclass type. The index is the superclass's index in the + // "extends" list. + + CONST_TYPE + // Bindings needed for the type of a constant. The index is zero. + }; + + static inline uint makeDepLocation(DepKind kind, uint index) { + // Make a number representing the location of a particular dependency within its parent + // schema. + + return (static_cast(kind) << 24) | index; + } + + class Initializer { + public: + virtual void init(const RawBrandedSchema* generic) const = 0; + }; + + const Initializer* lazyInitializer; + // Lazy initializer, invoked by ensureInitialized(). + + inline void ensureInitialized() const { + // Lazy initialization support. Invoke to ensure that initialization has taken place. This + // is required in particular when traversing the dependency list. RawSchemas for compiled-in + // types are always initialized; only dynamically-loaded schemas may be lazy. + +#if __GNUC__ + const Initializer* i = __atomic_load_n(&lazyInitializer, __ATOMIC_ACQUIRE); +#elif _MSC_VER + const Initializer* i = *static_cast(&lazyInitializer); + std::atomic_thread_fence(std::memory_order_acquire); +#else +#error "Platform not supported" +#endif + if (i != nullptr) i->init(this); + } + + inline bool isUnbound() const; + // Checks if this schema is the result of calling SchemaLoader::getUnbound(), in which case + // binding lookups need to be handled specially. +}; + +struct RawSchema { + // The generated code defines a constant RawSchema for every compiled declaration. + // + // This is an internal structure which could change in the future. + + uint64_t id; + + const word* encodedNode; + // Encoded SchemaNode, readable via readMessageUnchecked(encodedNode). + + uint32_t encodedSize; + // Size of encodedNode, in words. + + const RawSchema* const* dependencies; + // Pointers to other types on which this one depends, sorted by ID. The schemas in this table + // may be uninitialized -- you must call ensureInitialized() on the one you wish to use before + // using it. + // + // TODO(someday): Make this a hashtable. + + const uint16_t* membersByName; + // Indexes of members sorted by name. Used to implement name lookup. + // TODO(someday): Make this a hashtable. + + uint32_t dependencyCount; + uint32_t memberCount; + // Sizes of above tables. + + const uint16_t* membersByDiscriminant; + // List of all member indexes ordered by discriminant value. Those which don't have a + // discriminant value are listed at the end, in order by ordinal. + + const RawSchema* canCastTo; + // Points to the RawSchema of a compiled-in type to which it is safe to cast any DynamicValue + // with this schema. This is null for all compiled-in types; it is only set by SchemaLoader on + // dynamically-loaded types. + + class Initializer { + public: + virtual void init(const RawSchema* schema) const = 0; + }; + + const Initializer* lazyInitializer; + // Lazy initializer, invoked by ensureInitialized(). + + inline void ensureInitialized() const { + // Lazy initialization support. Invoke to ensure that initialization has taken place. This + // is required in particular when traversing the dependency list. RawSchemas for compiled-in + // types are always initialized; only dynamically-loaded schemas may be lazy. + +#if __GNUC__ + const Initializer* i = __atomic_load_n(&lazyInitializer, __ATOMIC_ACQUIRE); +#elif _MSC_VER + const Initializer* i = *static_cast(&lazyInitializer); + std::atomic_thread_fence(std::memory_order_acquire); +#else +#error "Platform not supported" +#endif + if (i != nullptr) i->init(this); + } + + RawBrandedSchema defaultBrand; + // Specifies the brand to use for this schema if no generic parameters have been bound to + // anything. Generally, in the default brand, all generic parameters are treated as if they were + // bound to `AnyPointer`. +}; + +inline bool RawBrandedSchema::isUnbound() const { + // The unbound schema is the only one that has no scopes but is not the default schema. + return scopeCount == 0 && this != &generic->defaultBrand; +} + +} // namespace _ (private) +} // namespace capnp + +#endif // CAPNP_RAW_SCHEMA_H_ diff --git a/phonelibs/capnp-cpp/include/capnp/rpc-prelude.h b/phonelibs/capnp-cpp/include/capnp/rpc-prelude.h new file mode 100644 index 00000000000000..7d26e39de8a68e --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/rpc-prelude.h @@ -0,0 +1,130 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +// This file contains a bunch of internal declarations that must appear before rpc.h can start. +// We don't define these directly in rpc.h because it makes the file hard to read. + +#ifndef CAPNP_RPC_PRELUDE_H_ +#define CAPNP_RPC_PRELUDE_H_ + +#if defined(__GNUC__) && !defined(CAPNP_HEADER_WARNINGS) +#pragma GCC system_header +#endif + +#include "capability.h" +#include "persistent.capnp.h" + +namespace capnp { + +class OutgoingRpcMessage; +class IncomingRpcMessage; + +template +class RpcSystem; + +namespace _ { // private + +class VatNetworkBase { + // Non-template version of VatNetwork. Ignore this class; see VatNetwork in rpc.h. + +public: + class Connection; + + struct ConnectionAndProvisionId { + kj::Own connection; + kj::Own firstMessage; + Orphan provisionId; + }; + + class Connection { + public: + virtual kj::Own newOutgoingMessage(uint firstSegmentWordSize) = 0; + virtual kj::Promise>> receiveIncomingMessage() = 0; + virtual kj::Promise shutdown() = 0; + virtual AnyStruct::Reader baseGetPeerVatId() = 0; + }; + virtual kj::Maybe> baseConnect(AnyStruct::Reader vatId) = 0; + virtual kj::Promise> baseAccept() = 0; +}; + +class SturdyRefRestorerBase { +public: + virtual Capability::Client baseRestore(AnyPointer::Reader ref) = 0; +}; + +class BootstrapFactoryBase { + // Non-template version of BootstrapFactory. Ignore this class; see BootstrapFactory in rpc.h. +public: + virtual Capability::Client baseCreateFor(AnyStruct::Reader clientId) = 0; +}; + +class RpcSystemBase { + // Non-template version of RpcSystem. Ignore this class; see RpcSystem in rpc.h. + +public: + RpcSystemBase(VatNetworkBase& network, kj::Maybe bootstrapInterface, + kj::Maybe::Client> gateway); + RpcSystemBase(VatNetworkBase& network, BootstrapFactoryBase& bootstrapFactory, + kj::Maybe::Client> gateway); + RpcSystemBase(VatNetworkBase& network, SturdyRefRestorerBase& restorer); + RpcSystemBase(RpcSystemBase&& other) noexcept; + ~RpcSystemBase() noexcept(false); + +private: + class Impl; + kj::Own impl; + + Capability::Client baseBootstrap(AnyStruct::Reader vatId); + Capability::Client baseRestore(AnyStruct::Reader vatId, AnyPointer::Reader objectId); + void baseSetFlowLimit(size_t words); + + template + friend class capnp::RpcSystem; +}; + +template struct InternalRefFromRealmGateway_; +template +struct InternalRefFromRealmGateway_> { + typedef InternalRef Type; +}; +template +using InternalRefFromRealmGateway = typename InternalRefFromRealmGateway_::Type; +template +using InternalRefFromRealmGatewayClient = InternalRefFromRealmGateway; + +template struct ExternalRefFromRealmGateway_; +template +struct ExternalRefFromRealmGateway_> { + typedef ExternalRef Type; +}; +template +using ExternalRefFromRealmGateway = typename ExternalRefFromRealmGateway_::Type; +template +using ExternalRefFromRealmGatewayClient = ExternalRefFromRealmGateway; + +} // namespace _ (private) +} // namespace capnp + +#endif // CAPNP_RPC_PRELUDE_H_ diff --git a/phonelibs/capnp-cpp/include/capnp/rpc-twoparty.capnp b/phonelibs/capnp-cpp/include/capnp/rpc-twoparty.capnp new file mode 100644 index 00000000000000..0b670e8ac3fc24 --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/rpc-twoparty.capnp @@ -0,0 +1,169 @@ +# Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +# Licensed under the MIT License: +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in +# all copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +# THE SOFTWARE. + +@0xa184c7885cdaf2a1; +# This file defines the "network-specific parameters" in rpc.capnp to support a network consisting +# of two vats. Each of these vats may in fact be in communication with other vats, but any +# capabilities they forward must be proxied. Thus, to each end of the connection, all capabilities +# received from the other end appear to live in a single vat. +# +# Two notable use cases for this model include: +# - Regular client-server communications, where a remote client machine (perhaps living on an end +# user's personal device) connects to a server. The server may be part of a cluster, and may +# call on other servers in the cluster to help service the user's request. It may even obtain +# capabilities from these other servers which it passes on to the user. To simplify network +# common traversal problems (e.g. if the user is behind a firewall), it is probably desirable to +# multiplex all communications between the server cluster and the client over the original +# connection rather than form new ones. This connection should use the two-party protocol, as +# the client has no interest in knowing about additional servers. +# - Applications running in a sandbox. A supervisor process may execute a confined application +# such that all of the confined app's communications with the outside world must pass through +# the supervisor. In this case, the connection between the confined app and the supervisor might +# as well use the two-party protocol, because the confined app is intentionally prevented from +# talking to any other vat anyway. Any external resources will be proxied through the supervisor, +# and so to the contained app will appear as if they were hosted by the supervisor itself. +# +# Since there are only two vats in this network, there is never a need for three-way introductions, +# so level 3 is free. Moreover, because it is never necessary to form new connections, the +# two-party protocol can be used easily anywhere where a two-way byte stream exists, without regard +# to where that byte stream goes or how it was initiated. This makes the two-party runtime library +# highly reusable. +# +# Joins (level 4) _could_ be needed in cases where one or both vats are participating in other +# networks that use joins. For instance, if Alice and Bob are speaking through the two-party +# protocol, and Bob is also participating on another network, Bob may send Alice two or more +# proxied capabilities which, unbeknownst to Bob at the time, are in fact pointing at the same +# remote object. Alice may then request to join these capabilities, at which point Bob will have +# to forward the join to the other network. Note, however, that if Alice is _not_ participating on +# any other network, then Alice will never need to _receive_ a Join, because Alice would always +# know when two locally-hosted capabilities are the same and would never export a redundant alias +# to Bob. So, Alice can respond to all incoming joins with an error, and only needs to implement +# outgoing joins if she herself desires to use this feature. Also, outgoing joins are relatively +# easy to implement in this scenario. +# +# What all this means is that a level 4 implementation of the confined network is barely more +# complicated than a level 2 implementation. However, such an implementation allows the "client" +# or "confined" app to access the server's/supervisor's network with equal functionality to any +# native participant. In other words, an application which implements only the two-party protocol +# can be paired with a proxy app in order to participate in any network. +# +# So, when implementing Cap'n Proto in a new language, it makes sense to implement only the +# two-party protocol initially, and then pair applications with an appropriate proxy written in +# C++, rather than implement other parameterizations of the RPC protocol directly. + +using Cxx = import "/capnp/c++.capnp"; +$Cxx.namespace("capnp::rpc::twoparty"); + +# Note: SturdyRef is not specified here. It is up to the application to define semantics of +# SturdyRefs if desired. + +enum Side { + server @0; + # The object lives on the "server" or "supervisor" end of the connection. Only the + # server/supervisor knows how to interpret the ref; to the client, it is opaque. + # + # Note that containers intending to implement strong confinement should rewrite SturdyRefs + # received from the external network before passing them on to the confined app. The confined + # app thus does not ever receive the raw bits of the SturdyRef (which it could perhaps + # maliciously leak), but instead receives only a thing that it can pass back to the container + # later to restore the ref. See: + # http://www.erights.org/elib/capability/dist-confine.html + + client @1; + # The object lives on the "client" or "confined app" end of the connection. Only the client + # knows how to interpret the ref; to the server/supervisor, it is opaque. Most clients do not + # actually know how to persist capabilities at all, so use of this is unusual. +} + +struct VatId { + side @0 :Side; +} + +struct ProvisionId { + # Only used for joins, since three-way introductions never happen on a two-party network. + + joinId @0 :UInt32; + # The ID from `JoinKeyPart`. +} + +struct RecipientId {} +# Never used, because there are only two parties. + +struct ThirdPartyCapId {} +# Never used, because there is no third party. + +struct JoinKeyPart { + # Joins in the two-party case are simplified by a few observations. + # + # First, on a two-party network, a Join only ever makes sense if the receiving end is also + # connected to other networks. A vat which is not connected to any other network can safely + # reject all joins. + # + # Second, since a two-party connection bisects the network -- there can be no other connections + # between the networks at either end of the connection -- if one part of a join crosses the + # connection, then _all_ parts must cross it. Therefore, a vat which is receiving a Join request + # off some other network which needs to be forwarded across the two-party connection can + # collect all the parts on its end and only forward them across the two-party connection when all + # have been received. + # + # For example, imagine that Alice and Bob are vats connected over a two-party connection, and + # each is also connected to other networks. At some point, Alice receives one part of a Join + # request off her network. The request is addressed to a capability that Alice received from + # Bob and is proxying to her other network. Alice goes ahead and responds to the Join part as + # if she hosted the capability locally (this is important so that if not all the Join parts end + # up at Alice, the original sender can detect the failed Join without hanging). As other parts + # trickle in, Alice verifies that each part is addressed to a capability from Bob and continues + # to respond to each one. Once the complete set of join parts is received, Alice checks if they + # were all for the exact same capability. If so, she doesn't need to send anything to Bob at + # all. Otherwise, she collects the set of capabilities (from Bob) to which the join parts were + # addressed and essentially initiates a _new_ Join request on those capabilities to Bob. Alice + # does not forward the Join parts she received herself, but essentially forwards the Join as a + # whole. + # + # On Bob's end, since he knows that Alice will always send all parts of a Join together, he + # simply waits until he's received them all, then performs a join on the respective capabilities + # as if it had been requested locally. + + joinId @0 :UInt32; + # A number identifying this join, chosen by the sender. May be reused once `Finish` messages are + # sent corresponding to all of the `Join` messages. + + partCount @1 :UInt16; + # The number of capabilities to be joined. + + partNum @2 :UInt16; + # Which part this request targets -- a number in the range [0, partCount). +} + +struct JoinResult { + joinId @0 :UInt32; + # Matches `JoinKeyPart`. + + succeeded @1 :Bool; + # All JoinResults in the set will have the same value for `succeeded`. The receiver actually + # implements the join by waiting for all the `JoinKeyParts` and then performing its own join on + # them, then going back and answering all the join requests afterwards. + + cap @2 :AnyPointer; + # One of the JoinResults will have a non-null `cap` which is the joined capability. + # + # TODO(cleanup): Change `AnyPointer` to `Capability` when that is supported. +} diff --git a/phonelibs/capnp-cpp/include/capnp/rpc-twoparty.capnp.h b/phonelibs/capnp-cpp/include/capnp/rpc-twoparty.capnp.h new file mode 100644 index 00000000000000..9d7820646a75ec --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/rpc-twoparty.capnp.h @@ -0,0 +1,726 @@ +// Generated by Cap'n Proto compiler, DO NOT EDIT +// source: rpc-twoparty.capnp + +#ifndef CAPNP_INCLUDED_a184c7885cdaf2a1_ +#define CAPNP_INCLUDED_a184c7885cdaf2a1_ + +#include + +#if CAPNP_VERSION != 6001 +#error "Version mismatch between generated code and library headers. You must use the same version of the Cap'n Proto compiler and library." +#endif + + +namespace capnp { +namespace schemas { + +CAPNP_DECLARE_SCHEMA(9fd69ebc87b9719c); +enum class Side_9fd69ebc87b9719c: uint16_t { + SERVER, + CLIENT, +}; +CAPNP_DECLARE_ENUM(Side, 9fd69ebc87b9719c); +CAPNP_DECLARE_SCHEMA(d20b909fee733a8e); +CAPNP_DECLARE_SCHEMA(b88d09a9c5f39817); +CAPNP_DECLARE_SCHEMA(89f389b6fd4082c1); +CAPNP_DECLARE_SCHEMA(b47f4979672cb59d); +CAPNP_DECLARE_SCHEMA(95b29059097fca83); +CAPNP_DECLARE_SCHEMA(9d263a3630b7ebee); + +} // namespace schemas +} // namespace capnp + +namespace capnp { +namespace rpc { +namespace twoparty { + +typedef ::capnp::schemas::Side_9fd69ebc87b9719c Side; + +struct VatId { + VatId() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(d20b909fee733a8e, 1, 0) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct ProvisionId { + ProvisionId() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(b88d09a9c5f39817, 1, 0) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct RecipientId { + RecipientId() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(89f389b6fd4082c1, 0, 0) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct ThirdPartyCapId { + ThirdPartyCapId() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(b47f4979672cb59d, 0, 0) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct JoinKeyPart { + JoinKeyPart() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(95b29059097fca83, 1, 0) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct JoinResult { + JoinResult() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(9d263a3630b7ebee, 1, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +// ======================================================================================= + +class VatId::Reader { +public: + typedef VatId Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline ::capnp::rpc::twoparty::Side getSide() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class VatId::Builder { +public: + typedef VatId Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::capnp::rpc::twoparty::Side getSide(); + inline void setSide( ::capnp::rpc::twoparty::Side value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class VatId::Pipeline { +public: + typedef VatId Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class ProvisionId::Reader { +public: + typedef ProvisionId Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline ::uint32_t getJoinId() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class ProvisionId::Builder { +public: + typedef ProvisionId Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint32_t getJoinId(); + inline void setJoinId( ::uint32_t value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class ProvisionId::Pipeline { +public: + typedef ProvisionId Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class RecipientId::Reader { +public: + typedef RecipientId Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class RecipientId::Builder { +public: + typedef RecipientId Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class RecipientId::Pipeline { +public: + typedef RecipientId Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class ThirdPartyCapId::Reader { +public: + typedef ThirdPartyCapId Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class ThirdPartyCapId::Builder { +public: + typedef ThirdPartyCapId Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class ThirdPartyCapId::Pipeline { +public: + typedef ThirdPartyCapId Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class JoinKeyPart::Reader { +public: + typedef JoinKeyPart Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline ::uint32_t getJoinId() const; + + inline ::uint16_t getPartCount() const; + + inline ::uint16_t getPartNum() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class JoinKeyPart::Builder { +public: + typedef JoinKeyPart Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint32_t getJoinId(); + inline void setJoinId( ::uint32_t value); + + inline ::uint16_t getPartCount(); + inline void setPartCount( ::uint16_t value); + + inline ::uint16_t getPartNum(); + inline void setPartNum( ::uint16_t value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class JoinKeyPart::Pipeline { +public: + typedef JoinKeyPart Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class JoinResult::Reader { +public: + typedef JoinResult Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline ::uint32_t getJoinId() const; + + inline bool getSucceeded() const; + + inline bool hasCap() const; + inline ::capnp::AnyPointer::Reader getCap() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class JoinResult::Builder { +public: + typedef JoinResult Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint32_t getJoinId(); + inline void setJoinId( ::uint32_t value); + + inline bool getSucceeded(); + inline void setSucceeded(bool value); + + inline bool hasCap(); + inline ::capnp::AnyPointer::Builder getCap(); + inline ::capnp::AnyPointer::Builder initCap(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class JoinResult::Pipeline { +public: + typedef JoinResult Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +// ======================================================================================= + +inline ::capnp::rpc::twoparty::Side VatId::Reader::getSide() const { + return _reader.getDataField< ::capnp::rpc::twoparty::Side>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::capnp::rpc::twoparty::Side VatId::Builder::getSide() { + return _builder.getDataField< ::capnp::rpc::twoparty::Side>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void VatId::Builder::setSide( ::capnp::rpc::twoparty::Side value) { + _builder.setDataField< ::capnp::rpc::twoparty::Side>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline ::uint32_t ProvisionId::Reader::getJoinId() const { + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t ProvisionId::Builder::getJoinId() { + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void ProvisionId::Builder::setJoinId( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline ::uint32_t JoinKeyPart::Reader::getJoinId() const { + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t JoinKeyPart::Builder::getJoinId() { + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void JoinKeyPart::Builder::setJoinId( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline ::uint16_t JoinKeyPart::Reader::getPartCount() const { + return _reader.getDataField< ::uint16_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} + +inline ::uint16_t JoinKeyPart::Builder::getPartCount() { + return _builder.getDataField< ::uint16_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} +inline void JoinKeyPart::Builder::setPartCount( ::uint16_t value) { + _builder.setDataField< ::uint16_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, value); +} + +inline ::uint16_t JoinKeyPart::Reader::getPartNum() const { + return _reader.getDataField< ::uint16_t>( + ::capnp::bounded<3>() * ::capnp::ELEMENTS); +} + +inline ::uint16_t JoinKeyPart::Builder::getPartNum() { + return _builder.getDataField< ::uint16_t>( + ::capnp::bounded<3>() * ::capnp::ELEMENTS); +} +inline void JoinKeyPart::Builder::setPartNum( ::uint16_t value) { + _builder.setDataField< ::uint16_t>( + ::capnp::bounded<3>() * ::capnp::ELEMENTS, value); +} + +inline ::uint32_t JoinResult::Reader::getJoinId() const { + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t JoinResult::Builder::getJoinId() { + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void JoinResult::Builder::setJoinId( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool JoinResult::Reader::getSucceeded() const { + return _reader.getDataField( + ::capnp::bounded<32>() * ::capnp::ELEMENTS); +} + +inline bool JoinResult::Builder::getSucceeded() { + return _builder.getDataField( + ::capnp::bounded<32>() * ::capnp::ELEMENTS); +} +inline void JoinResult::Builder::setSucceeded(bool value) { + _builder.setDataField( + ::capnp::bounded<32>() * ::capnp::ELEMENTS, value); +} + +inline bool JoinResult::Reader::hasCap() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool JoinResult::Builder::hasCap() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::AnyPointer::Reader JoinResult::Reader::getCap() const { + return ::capnp::AnyPointer::Reader(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::AnyPointer::Builder JoinResult::Builder::getCap() { + return ::capnp::AnyPointer::Builder(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::AnyPointer::Builder JoinResult::Builder::initCap() { + auto result = ::capnp::AnyPointer::Builder(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); + result.clear(); + return result; +} + +} // namespace +} // namespace +} // namespace + +#endif // CAPNP_INCLUDED_a184c7885cdaf2a1_ diff --git a/phonelibs/capnp-cpp/include/capnp/rpc-twoparty.h b/phonelibs/capnp-cpp/include/capnp/rpc-twoparty.h new file mode 100644 index 00000000000000..093c1fecdf9f35 --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/rpc-twoparty.h @@ -0,0 +1,160 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef CAPNP_RPC_TWOPARTY_H_ +#define CAPNP_RPC_TWOPARTY_H_ + +#if defined(__GNUC__) && !defined(CAPNP_HEADER_WARNINGS) +#pragma GCC system_header +#endif + +#include "rpc.h" +#include "message.h" +#include +#include + +namespace capnp { + +namespace rpc { + namespace twoparty { + typedef VatId SturdyRefHostId; // For backwards-compatibility with version 0.4. + } +} + +typedef VatNetwork + TwoPartyVatNetworkBase; + +class TwoPartyVatNetwork: public TwoPartyVatNetworkBase, + private TwoPartyVatNetworkBase::Connection { + // A `VatNetwork` that consists of exactly two parties communicating over an arbitrary byte + // stream. This is used to implement the common case of a client/server network. + // + // See `ez-rpc.h` for a simple interface for setting up two-party clients and servers. + // Use `TwoPartyVatNetwork` only if you need the advanced features. + +public: + TwoPartyVatNetwork(kj::AsyncIoStream& stream, rpc::twoparty::Side side, + ReaderOptions receiveOptions = ReaderOptions()); + KJ_DISALLOW_COPY(TwoPartyVatNetwork); + + kj::Promise onDisconnect() { return disconnectPromise.addBranch(); } + // Returns a promise that resolves when the peer disconnects. + + rpc::twoparty::Side getSide() { return side; } + + // implements VatNetwork ----------------------------------------------------- + + kj::Maybe> connect( + rpc::twoparty::VatId::Reader ref) override; + kj::Promise> accept() override; + +private: + class OutgoingMessageImpl; + class IncomingMessageImpl; + + kj::AsyncIoStream& stream; + rpc::twoparty::Side side; + MallocMessageBuilder peerVatId; + ReaderOptions receiveOptions; + bool accepted = false; + + kj::Maybe> previousWrite; + // Resolves when the previous write completes. This effectively serves as the write queue. + // Becomes null when shutdown() is called. + + kj::Own>> acceptFulfiller; + // Fulfiller for the promise returned by acceptConnectionAsRefHost() on the client side, or the + // second call on the server side. Never fulfilled, because there is only one connection. + + kj::ForkedPromise disconnectPromise = nullptr; + + class FulfillerDisposer: public kj::Disposer { + // Hack: TwoPartyVatNetwork is both a VatNetwork and a VatNetwork::Connection. When the RPC + // system detects (or initiates) a disconnection, it drops its reference to the Connection. + // When all references have been dropped, then we want disconnectPromise to be fulfilled. + // So we hand out Owns with this disposer attached, so that we can detect when + // they are dropped. + + public: + mutable kj::Own> fulfiller; + mutable uint refcount = 0; + + void disposeImpl(void* pointer) const override; + }; + FulfillerDisposer disconnectFulfiller; + + kj::Own asConnection(); + // Returns a pointer to this with the disposer set to disconnectFulfiller. + + // implements Connection ----------------------------------------------------- + + rpc::twoparty::VatId::Reader getPeerVatId() override; + kj::Own newOutgoingMessage(uint firstSegmentWordSize) override; + kj::Promise>> receiveIncomingMessage() override; + kj::Promise shutdown() override; +}; + +class TwoPartyServer: private kj::TaskSet::ErrorHandler { + // Convenience class which implements a simple server which accepts connections on a listener + // socket and serices them as two-party connections. + +public: + explicit TwoPartyServer(Capability::Client bootstrapInterface); + + void accept(kj::Own&& connection); + // Accepts the connection for servicing. + + kj::Promise listen(kj::ConnectionReceiver& listener); + // Listens for connections on the given listener. The returned promise never resolves unless an + // exception is thrown while trying to accept. You may discard the returned promise to cancel + // listening. + +private: + Capability::Client bootstrapInterface; + kj::TaskSet tasks; + + struct AcceptedConnection; + + void taskFailed(kj::Exception&& exception) override; +}; + +class TwoPartyClient { + // Convenience class which implements a simple client. + +public: + explicit TwoPartyClient(kj::AsyncIoStream& connection); + TwoPartyClient(kj::AsyncIoStream& connection, Capability::Client bootstrapInterface, + rpc::twoparty::Side side = rpc::twoparty::Side::CLIENT); + + Capability::Client bootstrap(); + // Get the server's bootstrap interface. + + inline kj::Promise onDisconnect() { return network.onDisconnect(); } + +private: + TwoPartyVatNetwork network; + RpcSystem rpcSystem; +}; + +} // namespace capnp + +#endif // CAPNP_RPC_TWOPARTY_H_ diff --git a/phonelibs/capnp-cpp/include/capnp/rpc.capnp b/phonelibs/capnp-cpp/include/capnp/rpc.capnp new file mode 100644 index 00000000000000..cd808b39f70466 --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/rpc.capnp @@ -0,0 +1,1399 @@ +# Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +# Licensed under the MIT License: +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in +# all copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +# THE SOFTWARE. + +@0xb312981b2552a250; +# Recall that Cap'n Proto RPC allows messages to contain references to remote objects that +# implement interfaces. These references are called "capabilities", because they both designate +# the remote object to use and confer permission to use it. +# +# Recall also that Cap'n Proto RPC has the feature that when a method call itself returns a +# capability, the caller can begin calling methods on that capability _before the first call has +# returned_. The caller essentially sends a message saying "Hey server, as soon as you finish +# that previous call, do this with the result!". Cap'n Proto's RPC protocol makes this possible. +# +# The protocol is significantly more complicated than most RPC protocols. However, this is +# implementation complexity that underlies an easy-to-grasp higher-level model of object oriented +# programming. That is, just like TCP is a surprisingly complicated protocol that implements a +# conceptually-simple byte stream abstraction, Cap'n Proto is a surprisingly complicated protocol +# that implements a conceptually-simple object abstraction. +# +# Cap'n Proto RPC is based heavily on CapTP, the object-capability protocol used by the E +# programming language: +# http://www.erights.org/elib/distrib/captp/index.html +# +# Cap'n Proto RPC takes place between "vats". A vat hosts some set of objects and talks to other +# vats through direct bilateral connections. Typically, there is a 1:1 correspondence between vats +# and processes (in the unix sense of the word), although this is not strictly always true (one +# process could run multiple vats, or a distributed virtual vat might live across many processes). +# +# Cap'n Proto does not distinguish between "clients" and "servers" -- this is up to the application. +# Either end of any connection can potentially hold capabilities pointing to the other end, and +# can call methods on those capabilities. In the doc comments below, we use the words "sender" +# and "receiver". These refer to the sender and receiver of an instance of the struct or field +# being documented. Sometimes we refer to a "third-party" that is neither the sender nor the +# receiver. Documentation is generally written from the point of view of the sender. +# +# It is generally up to the vat network implementation to securely verify that connections are made +# to the intended vat as well as to encrypt transmitted data for privacy and integrity. See the +# `VatNetwork` example interface near the end of this file. +# +# When a new connection is formed, the only interesting things that can be done are to send a +# `Bootstrap` (level 0) or `Accept` (level 3) message. +# +# Unless otherwise specified, messages must be delivered to the receiving application in the same +# order in which they were initiated by the sending application. The goal is to support "E-Order", +# which states that two calls made on the same reference must be delivered in the order which they +# were made: +# http://erights.org/elib/concurrency/partial-order.html +# +# Since the full protocol is complicated, we define multiple levels of support that an +# implementation may target. For many applications, level 1 support will be sufficient. +# Comments in this file indicate which level requires the corresponding feature to be +# implemented. +# +# * **Level 0:** The implementation does not support object references. Only the bootstrap interface +# can be called. At this level, the implementation does not support object-oriented protocols and +# is similar in complexity to JSON-RPC or Protobuf services. This level should be considered only +# a temporary stepping-stone toward level 1 as the lack of object references drastically changes +# how protocols are designed. Applications _should not_ attempt to design their protocols around +# the limitations of level 0 implementations. +# +# * **Level 1:** The implementation supports simple bilateral interaction with object references +# and promise pipelining, but interactions between three or more parties are supported only via +# proxying of objects. E.g. if Alice (in Vat A) wants to send Bob (in Vat B) a capability +# pointing to Carol (in Vat C), Alice must create a proxy of Carol within Vat A and send Bob a +# reference to that; Bob cannot form a direct connection to Carol. Level 1 implementations do +# not support checking if two capabilities received from different vats actually point to the +# same object ("join"), although they should be able to do this check on capabilities received +# from the same vat. +# +# * **Level 2:** The implementation supports saving persistent capabilities -- i.e. capabilities +# that remain valid even after disconnect, and can be restored on a future connection. When a +# capability is saved, the requester receives a `SturdyRef`, which is a token that can be used +# to restore the capability later. +# +# * **Level 3:** The implementation supports three-way interactions. That is, if Alice (in Vat A) +# sends Bob (in Vat B) a capability pointing to Carol (in Vat C), then Vat B will automatically +# form a direct connection to Vat C rather than have requests be proxied through Vat A. +# +# * **Level 4:** The entire protocol is implemented, including joins (checking if two capabilities +# are equivalent). +# +# Note that an implementation must also support specific networks (transports), as described in +# the "Network-specific Parameters" section below. An implementation might have different levels +# depending on the network used. +# +# New implementations of Cap'n Proto should start out targeting the simplistic two-party network +# type as defined in `rpc-twoparty.capnp`. With this network type, level 3 is irrelevant and +# levels 2 and 4 are much easier than usual to implement. When such an implementation is paired +# with a container proxy, the contained app effectively gets to make full use of the proxy's +# network at level 4. And since Cap'n Proto IPC is extremely fast, it may never make sense to +# bother implementing any other vat network protocol -- just use the correct container type and get +# it for free. + +using Cxx = import "/capnp/c++.capnp"; +$Cxx.namespace("capnp::rpc"); + +# ======================================================================================== +# The Four Tables +# +# Cap'n Proto RPC connections are stateful (although an application built on Cap'n Proto could +# export a stateless interface). As in CapTP, for each open connection, a vat maintains four state +# tables: questions, answers, imports, and exports. See the diagram at: +# http://www.erights.org/elib/distrib/captp/4tables.html +# +# The question table corresponds to the other end's answer table, and the imports table corresponds +# to the other end's exports table. +# +# The entries in each table are identified by ID numbers (defined below as 32-bit integers). These +# numbers are always specific to the connection; a newly-established connection starts with no +# valid IDs. Since low-numbered IDs will pack better, it is suggested that IDs be assigned like +# Unix file descriptors -- prefer the lowest-number ID that is currently available. +# +# IDs in the questions/answers tables are chosen by the questioner and generally represent method +# calls that are in progress. +# +# IDs in the imports/exports tables are chosen by the exporter and generally represent objects on +# which methods may be called. Exports may be "settled", meaning the exported object is an actual +# object living in the exporter's vat, or they may be "promises", meaning the exported object is +# the as-yet-unknown result of an ongoing operation and will eventually be resolved to some other +# object once that operation completes. Calls made to a promise will be forwarded to the eventual +# target once it is known. The eventual replacement object does *not* get the same ID as the +# promise, as it may turn out to be an object that is already exported (so already has an ID) or +# may even live in a completely different vat (and so won't get an ID on the same export table +# at all). +# +# IDs can be reused over time. To make this safe, we carefully define the lifetime of IDs. Since +# messages using the ID could be traveling in both directions simultaneously, we must define the +# end of life of each ID _in each direction_. The ID is only safe to reuse once it has been +# released by both sides. +# +# When a Cap'n Proto connection is lost, everything on the four tables is lost. All questions are +# canceled and throw exceptions. All imports become broken (all future calls to them throw +# exceptions). All exports and answers are implicitly released. The only things not lost are +# persistent capabilities (`SturdyRef`s). The application must plan for this and should respond by +# establishing a new connection and restoring from these persistent capabilities. + +using QuestionId = UInt32; +# **(level 0)** +# +# Identifies a question in the sender's question table (which corresponds to the receiver's answer +# table). The questioner (caller) chooses an ID when making a call. The ID remains valid in +# caller -> callee messages until a Finish message is sent, and remains valid in callee -> caller +# messages until a Return message is sent. + +using AnswerId = QuestionId; +# **(level 0)** +# +# Identifies an answer in the sender's answer table (which corresponds to the receiver's question +# table). +# +# AnswerId is physically equivalent to QuestionId, since the question and answer tables correspond, +# but we define a separate type for documentation purposes: we always use the type representing +# the sender's point of view. + +using ExportId = UInt32; +# **(level 1)** +# +# Identifies an exported capability or promise in the sender's export table (which corresponds +# to the receiver's import table). The exporter chooses an ID before sending a capability over the +# wire. If the capability is already in the table, the exporter should reuse the same ID. If the +# ID is a promise (as opposed to a settled capability), this must be indicated at the time the ID +# is introduced (e.g. by using `senderPromise` instead of `senderHosted` in `CapDescriptor`); in +# this case, the importer shall expect a later `Resolve` message that replaces the promise. +# +# ExportId/ImportIds are subject to reference counting. Whenever an `ExportId` is sent over the +# wire (from the exporter to the importer), the export's reference count is incremented (unless +# otherwise specified). The reference count is later decremented by a `Release` message. Since +# the `Release` message can specify an arbitrary number by which to reduce the reference count, the +# importer should usually batch reference decrements and only send a `Release` when it believes the +# reference count has hit zero. Of course, it is possible that a new reference to the export is +# in-flight at the time that the `Release` message is sent, so it is necessary for the exporter to +# keep track of the reference count on its end as well to avoid race conditions. +# +# When a connection is lost, all exports are implicitly released. It is not possible to restore +# a connection state after disconnect (although a transport layer could implement a concept of +# persistent connections if it is transparent to the RPC layer). + +using ImportId = ExportId; +# **(level 1)** +# +# Identifies an imported capability or promise in the sender's import table (which corresponds to +# the receiver's export table). +# +# ImportId is physically equivalent to ExportId, since the export and import tables correspond, +# but we define a separate type for documentation purposes: we always use the type representing +# the sender's point of view. +# +# An `ImportId` remains valid in importer -> exporter messages until the importer has sent +# `Release` messages that (it believes) have reduced the reference count to zero. + +# ======================================================================================== +# Messages + +struct Message { + # An RPC connection is a bi-directional stream of Messages. + + union { + unimplemented @0 :Message; + # The sender previously received this message from the peer but didn't understand it or doesn't + # yet implement the functionality that was requested. So, the sender is echoing the message + # back. In some cases, the receiver may be able to recover from this by pretending the sender + # had taken some appropriate "null" action. + # + # For example, say `resolve` is received by a level 0 implementation (because a previous call + # or return happened to contain a promise). The level 0 implementation will echo it back as + # `unimplemented`. The original sender can then simply release the cap to which the promise + # had resolved, thus avoiding a leak. + # + # For any message type that introduces a question, if the message comes back unimplemented, + # the original sender may simply treat it as if the question failed with an exception. + # + # In cases where there is no sensible way to react to an `unimplemented` message (without + # resource leaks or other serious problems), the connection may need to be aborted. This is + # a gray area; different implementations may take different approaches. + + abort @1 :Exception; + # Sent when a connection is being aborted due to an unrecoverable error. This could be e.g. + # because the sender received an invalid or nonsensical message (`isCallersFault` is true) or + # because the sender had an internal error (`isCallersFault` is false). The sender will shut + # down the outgoing half of the connection after `abort` and will completely close the + # connection shortly thereafter (it's up to the sender how much of a time buffer they want to + # offer for the client to receive the `abort` before the connection is reset). + + # Level 0 features ----------------------------------------------- + + bootstrap @8 :Bootstrap; # Request the peer's bootstrap interface. + call @2 :Call; # Begin a method call. + return @3 :Return; # Complete a method call. + finish @4 :Finish; # Release a returned answer / cancel a call. + + # Level 1 features ----------------------------------------------- + + resolve @5 :Resolve; # Resolve a previously-sent promise. + release @6 :Release; # Release a capability so that the remote object can be deallocated. + disembargo @13 :Disembargo; # Lift an embargo used to enforce E-order over promise resolution. + + # Level 2 features ----------------------------------------------- + + obsoleteSave @7 :AnyPointer; + # Obsolete request to save a capability, resulting in a SturdyRef. This has been replaced + # by the `Persistent` interface defined in `persistent.capnp`. This operation was never + # implemented. + + obsoleteDelete @9 :AnyPointer; + # Obsolete way to delete a SturdyRef. This operation was never implemented. + + # Level 3 features ----------------------------------------------- + + provide @10 :Provide; # Provide a capability to a third party. + accept @11 :Accept; # Accept a capability provided by a third party. + + # Level 4 features ----------------------------------------------- + + join @12 :Join; # Directly connect to the common root of two or more proxied caps. + } +} + +# Level 0 message types ---------------------------------------------- + +struct Bootstrap { + # **(level 0)** + # + # Get the "bootstrap" interface exported by the remote vat. + # + # For level 0, 1, and 2 implementations, the "bootstrap" interface is simply the main interface + # exported by a vat. If the vat acts as a server fielding connections from clients, then the + # bootstrap interface defines the basic functionality available to a client when it connects. + # The exact interface definition obviously depends on the application. + # + # We call this a "bootstrap" because in an ideal Cap'n Proto world, bootstrap interfaces would + # never be used. In such a world, any time you connect to a new vat, you do so because you + # received an introduction from some other vat (see `ThirdPartyCapId`). Thus, the first message + # you send is `Accept`, and further communications derive from there. `Bootstrap` is not used. + # + # In such an ideal world, DNS itself would support Cap'n Proto -- performing a DNS lookup would + # actually return a new Cap'n Proto capability, thus introducing you to the target system via + # level 3 RPC. Applications would receive the capability to talk to DNS in the first place as + # an initial endowment or part of a Powerbox interaction. Therefore, an app can form arbitrary + # connections without ever using `Bootstrap`. + # + # Of course, in the real world, DNS is not Cap'n-Proto-based, and we don't want Cap'n Proto to + # require a whole new internet infrastructure to be useful. Therefore, we offer bootstrap + # interfaces as a way to get up and running without a level 3 introduction. Thus, bootstrap + # interfaces are used to "bootstrap" from other, non-Cap'n-Proto-based means of service discovery, + # such as legacy DNS. + # + # Note that a vat need not provide a bootstrap interface, and in fact many vats (especially those + # acting as clients) do not. In this case, the vat should either reply to `Bootstrap` with a + # `Return` indicating an exception, or should return a dummy capability with no methods. + + questionId @0 :QuestionId; + # A new question ID identifying this request, which will eventually receive a Return message + # containing the restored capability. + + deprecatedObjectId @1 :AnyPointer; + # ** DEPRECATED ** + # + # A Vat may export multiple bootstrap interfaces. In this case, `deprecatedObjectId` specifies + # which one to return. If this pointer is null, then the default bootstrap interface is returned. + # + # As of verison 0.5, use of this field is deprecated. If a service wants to export multiple + # bootstrap interfaces, it should instead define a single bootstarp interface that has methods + # that return each of the other interfaces. + # + # **History** + # + # In the first version of Cap'n Proto RPC (0.4.x) the `Bootstrap` message was called `Restore`. + # At the time, it was thought that this would eventually serve as the way to restore SturdyRefs + # (level 2). Meanwhile, an application could offer its "main" interface on a well-known + # (non-secret) SturdyRef. + # + # Since level 2 RPC was not implemented at the time, the `Restore` message was in practice only + # used to obtain the main interface. Since most applications had only one main interface that + # they wanted to restore, they tended to designate this with a null `objectId`. + # + # Unfortunately, the earliest version of the EZ RPC interfaces set a precedent of exporting + # multiple main interfaces by allowing them to be exported under string names. In this case, + # `objectId` was a Text value specifying the name. + # + # All of this proved problematic for several reasons: + # + # - The arrangement assumed that a client wishing to restore a SturdyRef would know exactly what + # machine to connect to and would be able to immediately restore a SturdyRef on connection. + # However, in practice, the ability to restore SturdyRefs is itself a capability that may + # require going through an authentication process to obtain. Thus, it makes more sense to + # define a "restorer service" as a full Cap'n Proto interface. If this restorer interface is + # offered as the vat's bootstrap interface, then this is equivalent to the old arrangement. + # + # - Overloading "Restore" for the purpose of obtaining well-known capabilities encouraged the + # practice of exporting singleton services with string names. If singleton services are desired, + # it is better to have one main interface that has methods that can be used to obtain each + # service, in order to get all the usual benefits of schemas and type checking. + # + # - Overloading "Restore" also had a security problem: Often, "main" or "well-known" + # capabilities exported by a vat are in fact not public: they are intended to be accessed only + # by clients who are capable of forming a connection to the vat. This can lead to trouble if + # the client itself has other clients and wishes to foward some `Restore` requests from those + # external clients -- it has to be very careful not to allow through `Restore` requests + # addressing the default capability. + # + # For example, consider the case of a sandboxed Sandstorm application and its supervisor. The + # application exports a default capability to its supervisor that provides access to + # functionality that only the supervisor is supposed to access. Meanwhile, though, applications + # may publish other capabilities that may be persistent, in which case the application needs + # to field `Restore` requests that could come from anywhere. These requests of course have to + # pass through the supervisor, as all communications with the outside world must. But, the + # supervisor has to be careful not to honor an external request addressing the application's + # default capability, since this capability is privileged. Unfortunately, the default + # capability cannot be given an unguessable name, because then the supervisor itself would not + # be able to address it! + # + # As of Cap'n Proto 0.5, `Restore` has been renamed to `Bootstrap` and is no longer planned for + # use in restoring SturdyRefs. + # + # Note that 0.4 also defined a message type called `Delete` that, like `Restore`, addressed a + # SturdyRef, but indicated that the client would not restore the ref again in the future. This + # operation was never implemented, so it was removed entirely. If a "delete" operation is desired, + # it should exist as a method on the same interface that handles restoring SturdyRefs. However, + # the utility of such an operation is questionable. You wouldn't be able to rely on it for + # garbage collection since a client could always disappear permanently without remembering to + # delete all its SturdyRefs, thus leaving them dangling forever. Therefore, it is advisable to + # design systems such that SturdyRefs never represent "owned" pointers. + # + # For example, say a SturdyRef points to an image file hosted on some server. That image file + # should also live inside a collection (a gallery, perhaps) hosted on the same server, owned by + # a user who can delete the image at any time. If the user deletes the image, the SturdyRef + # stops working. On the other hand, if the SturdyRef is discarded, this has no effect on the + # existence of the image in its collection. +} + +struct Call { + # **(level 0)** + # + # Message type initiating a method call on a capability. + + questionId @0 :QuestionId; + # A number, chosen by the caller, that identifies this call in future messages. This number + # must be different from all other calls originating from the same end of the connection (but + # may overlap with question IDs originating from the opposite end). A fine strategy is to use + # sequential question IDs, but the recipient should not assume this. + # + # A question ID can be reused once both: + # - A matching Return has been received from the callee. + # - A matching Finish has been sent from the caller. + + target @1 :MessageTarget; + # The object that should receive this call. + + interfaceId @2 :UInt64; + # The type ID of the interface being called. Each capability may implement multiple interfaces. + + methodId @3 :UInt16; + # The ordinal number of the method to call within the requested interface. + + allowThirdPartyTailCall @8 :Bool = false; + # Indicates whether or not the receiver is allowed to send a `Return` containing + # `acceptFromThirdParty`. Level 3 implementations should set this true. Otherwise, the callee + # will have to proxy the return in the case of a tail call to a third-party vat. + + params @4 :Payload; + # The call parameters. `params.content` is a struct whose fields correspond to the parameters of + # the method. + + sendResultsTo :union { + # Where should the return message be sent? + + caller @5 :Void; + # Send the return message back to the caller (the usual). + + yourself @6 :Void; + # **(level 1)** + # + # Don't actually return the results to the sender. Instead, hold on to them and await + # instructions from the sender regarding what to do with them. In particular, the sender + # may subsequently send a `Return` for some other call (which the receiver had previously made + # to the sender) with `takeFromOtherQuestion` set. The results from this call are then used + # as the results of the other call. + # + # When `yourself` is used, the receiver must still send a `Return` for the call, but sets the + # field `resultsSentElsewhere` in that `Return` rather than including the results. + # + # This feature can be used to implement tail calls in which a call from Vat A to Vat B ends up + # returning the result of a call from Vat B back to Vat A. + # + # In particular, the most common use case for this feature is when Vat A makes a call to a + # promise in Vat B, and then that promise ends up resolving to a capability back in Vat A. + # Vat B must forward all the queued calls on that promise back to Vat A, but can set `yourself` + # in the calls so that the results need not pass back through Vat B. + # + # For example: + # - Alice, in Vat A, call foo() on Bob in Vat B. + # - Alice makes a pipelined call bar() on the promise returned by foo(). + # - Later on, Bob resolves the promise from foo() to point at Carol, who lives in Vat A (next + # to Alice). + # - Vat B dutifully forwards the bar() call to Carol. Let us call this forwarded call bar'(). + # Notice that bar() and bar'() are travelling in opposite directions on the same network + # link. + # - The `Call` for bar'() has `sendResultsTo` set to `yourself`, with the value being the + # question ID originally assigned to the bar() call. + # - Vat A receives bar'() and delivers it to Carol. + # - When bar'() returns, Vat A immediately takes the results and returns them from bar(). + # - Meanwhile, Vat A sends a `Return` for bar'() to Vat B, with `resultsSentElsewhere` set in + # place of results. + # - Vat A sends a `Finish` for that call to Vat B. + # - Vat B receives the `Return` for bar'() and sends a `Return` for bar(), with + # `receivedFromYourself` set in place of the results. + # - Vat B receives the `Finish` for bar() and sends a `Finish` to bar'(). + + thirdParty @7 :RecipientId; + # **(level 3)** + # + # The call's result should be returned to a different vat. The receiver (the callee) expects + # to receive an `Accept` message from the indicated vat, and should return the call's result + # to it, rather than to the sender of the `Call`. + # + # This operates much like `yourself`, above, except that Carol is in a separate Vat C. `Call` + # messages are sent from Vat A -> Vat B and Vat B -> Vat C. A `Return` message is sent from + # Vat B -> Vat A that contains `acceptFromThirdParty` in place of results. When Vat A sends + # an `Accept` to Vat C, it receives back a `Return` containing the call's actual result. Vat C + # also sends a `Return` to Vat B with `resultsSentElsewhere`. + } +} + +struct Return { + # **(level 0)** + # + # Message type sent from callee to caller indicating that the call has completed. + + answerId @0 :AnswerId; + # Equal to the QuestionId of the corresponding `Call` message. + + releaseParamCaps @1 :Bool = true; + # If true, all capabilities that were in the params should be considered released. The sender + # must not send separate `Release` messages for them. Level 0 implementations in particular + # should always set this true. This defaults true because if level 0 implementations forget to + # set it they'll never notice (just silently leak caps), but if level >=1 implementations forget + # to set it to false they'll quickly get errors. + + union { + results @2 :Payload; + # The result. + # + # For regular method calls, `results.content` points to the result struct. + # + # For a `Return` in response to an `Accept`, `results` contains a single capability (rather + # than a struct), and `results.content` is just a capability pointer with index 0. A `Finish` + # is still required in this case. + + exception @3 :Exception; + # Indicates that the call failed and explains why. + + canceled @4 :Void; + # Indicates that the call was canceled due to the caller sending a Finish message + # before the call had completed. + + resultsSentElsewhere @5 :Void; + # This is set when returning from a `Call` that had `sendResultsTo` set to something other + # than `caller`. + + takeFromOtherQuestion @6 :QuestionId; + # The sender has also sent (before this message) a `Call` with the given question ID and with + # `sendResultsTo.yourself` set, and the results of that other call should be used as the + # results here. + + acceptFromThirdParty @7 :ThirdPartyCapId; + # **(level 3)** + # + # The caller should contact a third-party vat to pick up the results. An `Accept` message + # sent to the vat will return the result. This pairs with `Call.sendResultsTo.thirdParty`. + # It should only be used if the corresponding `Call` had `allowThirdPartyTailCall` set. + } +} + +struct Finish { + # **(level 0)** + # + # Message type sent from the caller to the callee to indicate: + # 1) The questionId will no longer be used in any messages sent by the callee (no further + # pipelined requests). + # 2) If the call has not returned yet, the caller no longer cares about the result. If nothing + # else cares about the result either (e.g. there are no other outstanding calls pipelined on + # the result of this one) then the callee may wish to immediately cancel the operation and + # send back a Return message with "canceled" set. However, implementations are not required + # to support premature cancellation -- instead, the implementation may wait until the call + # actually completes and send a normal `Return` message. + # + # TODO(someday): Should we separate (1) and implicitly releasing result capabilities? It would be + # possible and useful to notify the server that it doesn't need to keep around the response to + # service pipeline requests even though the caller still wants to receive it / hasn't yet + # finished processing it. It could also be useful to notify the server that it need not marshal + # the results because the caller doesn't want them anyway, even if the caller is still sending + # pipelined calls, although this seems less useful (just saving some bytes on the wire). + + questionId @0 :QuestionId; + # ID of the call whose result is to be released. + + releaseResultCaps @1 :Bool = true; + # If true, all capabilities that were in the results should be considered released. The sender + # must not send separate `Release` messages for them. Level 0 implementations in particular + # should always set this true. This defaults true because if level 0 implementations forget to + # set it they'll never notice (just silently leak caps), but if level >=1 implementations forget + # set it false they'll quickly get errors. +} + +# Level 1 message types ---------------------------------------------- + +struct Resolve { + # **(level 1)** + # + # Message type sent to indicate that a previously-sent promise has now been resolved to some other + # object (possibly another promise) -- or broken, or canceled. + # + # Keep in mind that it's possible for a `Resolve` to be sent to a level 0 implementation that + # doesn't implement it. For example, a method call or return might contain a capability in the + # payload. Normally this is fine even if the receiver is level 0, because they will implicitly + # release all such capabilities on return / finish. But if the cap happens to be a promise, then + # a follow-up `Resolve` may be sent regardless of this release. The level 0 receiver will reply + # with an `unimplemented` message, and the sender (of the `Resolve`) can respond to this as if the + # receiver had immediately released any capability to which the promise resolved. + # + # When implementing promise resolution, it's important to understand how embargos work and the + # tricky case of the Tribble 4-way race condition. See the comments for the Disembargo message, + # below. + + promiseId @0 :ExportId; + # The ID of the promise to be resolved. + # + # Unlike all other instances of `ExportId` sent from the exporter, the `Resolve` message does + # _not_ increase the reference count of `promiseId`. In fact, it is expected that the receiver + # will release the export soon after receiving `Resolve`, and the sender will not send this + # `ExportId` again until it has been released and recycled. + # + # When an export ID sent over the wire (e.g. in a `CapDescriptor`) is indicated to be a promise, + # this indicates that the sender will follow up at some point with a `Resolve` message. If the + # same `promiseId` is sent again before `Resolve`, still only one `Resolve` is sent. If the + # same ID is sent again later _after_ a `Resolve`, it can only be because the export's + # reference count hit zero in the meantime and the ID was re-assigned to a new export, therefore + # this later promise does _not_ correspond to the earlier `Resolve`. + # + # If a promise ID's reference count reaches zero before a `Resolve` is sent, the `Resolve` + # message may or may not still be sent (the `Resolve` may have already been in-flight when + # `Release` was sent, but if the `Release` is received before `Resolve` then there is no longer + # any reason to send a `Resolve`). Thus a `Resolve` may be received for a promise of which + # the receiver has no knowledge, because it already released it earlier. In this case, the + # receiver should simply release the capability to which the promise resolved. + + union { + cap @1 :CapDescriptor; + # The object to which the promise resolved. + # + # The sender promises that from this point forth, until `promiseId` is released, it shall + # simply forward all messages to the capability designated by `cap`. This is true even if + # `cap` itself happens to desigate another promise, and that other promise later resolves -- + # messages sent to `promiseId` shall still go to that other promise, not to its resolution. + # This is important in the case that the receiver of the `Resolve` ends up sending a + # `Disembargo` message towards `promiseId` in order to control message ordering -- that + # `Disembargo` really needs to reflect back to exactly the object designated by `cap` even + # if that object is itself a promise. + + exception @2 :Exception; + # Indicates that the promise was broken. + } +} + +struct Release { + # **(level 1)** + # + # Message type sent to indicate that the sender is done with the given capability and the receiver + # can free resources allocated to it. + + id @0 :ImportId; + # What to release. + + referenceCount @1 :UInt32; + # The amount by which to decrement the reference count. The export is only actually released + # when the reference count reaches zero. +} + +struct Disembargo { + # **(level 1)** + # + # Message sent to indicate that an embargo on a recently-resolved promise may now be lifted. + # + # Embargos are used to enforce E-order in the presence of promise resolution. That is, if an + # application makes two calls foo() and bar() on the same capability reference, in that order, + # the calls should be delivered in the order in which they were made. But if foo() is called + # on a promise, and that promise happens to resolve before bar() is called, then the two calls + # may travel different paths over the network, and thus could arrive in the wrong order. In + # this case, the call to `bar()` must be embargoed, and a `Disembargo` message must be sent along + # the same path as `foo()` to ensure that the `Disembargo` arrives after `foo()`. Once the + # `Disembargo` arrives, `bar()` can then be delivered. + # + # There are two particular cases where embargos are important. Consider object Alice, in Vat A, + # who holds a promise P, pointing towards Vat B, that eventually resolves to Carol. The two + # cases are: + # - Carol lives in Vat A, i.e. next to Alice. In this case, Vat A needs to send a `Disembargo` + # message that echos through Vat B and back, to ensure that all pipelined calls on the promise + # have been delivered. + # - Carol lives in a different Vat C. When the promise resolves, a three-party handoff occurs + # (see `Provide` and `Accept`, which constitute level 3 of the protocol). In this case, we + # piggyback on the state that has already been set up to handle the handoff: the `Accept` + # message (from Vat A to Vat C) is embargoed, as are all pipelined messages sent to it, while + # a `Disembargo` message is sent from Vat A through Vat B to Vat C. See `Accept.embargo` for + # an example. + # + # Note that in the case where Carol actually lives in Vat B (i.e., the same vat that the promise + # already pointed at), no embargo is needed, because the pipelined calls are delivered over the + # same path as the later direct calls. + # + # Keep in mind that promise resolution happens both in the form of Resolve messages as well as + # Return messages (which resolve PromisedAnswers). Embargos apply in both cases. + # + # An alternative strategy for enforcing E-order over promise resolution could be for Vat A to + # implement the embargo internally. When Vat A is notified of promise resolution, it could + # send a dummy no-op call to promise P and wait for it to complete. Until that call completes, + # all calls to the capability are queued locally. This strategy works, but is pessimistic: + # in the three-party case, it requires an A -> B -> C -> B -> A round trip before calls can start + # being delivered directly to from Vat A to Vat C. The `Disembargo` message allows latency to be + # reduced. (In the two-party loopback case, the `Disembargo` message is just a more explicit way + # of accomplishing the same thing as a no-op call, but isn't any faster.) + # + # *The Tribble 4-way Race Condition* + # + # Any implementation of promise resolution and embargos must be aware of what we call the + # "Tribble 4-way race condition", after Dean Tribble, who explained the problem in a lively + # Friam meeting. + # + # Embargos are designed to work in the case where a two-hop path is being shortened to one hop. + # But sometimes there are more hops. Imagine that Alice has a reference to a remote promise P1 + # that eventually resolves to _another_ remote promise P2 (in a third vat), which _at the same + # time_ happens to resolve to Bob (in a fourth vat). In this case, we're shortening from a 3-hop + # path (with four parties) to a 1-hop path (Alice -> Bob). + # + # Extending the embargo/disembargo protocol to be able to shorted multiple hops at once seems + # difficult. Instead, we make a rule that prevents this case from coming up: + # + # One a promise P has been resolved to a remove object reference R, then all further messages + # received addressed to P will be forwarded strictly to R. Even if it turns out later that R is + # itself a promise, and has resolved to some other object Q, messages sent to P will still be + # forwarded to R, not directly to Q (R will of course further forward the messages to Q). + # + # This rule does not cause a significant performance burden because once P has resolved to R, it + # is expected that people sending messages to P will shortly start sending them to R instead and + # drop P. P is at end-of-life anyway, so it doesn't matter if it ignores chances to further + # optimize its path. + + target @0 :MessageTarget; + # What is to be disembargoed. + + using EmbargoId = UInt32; + # Used in `senderLoopback` and `receiverLoopback`, below. + + context :union { + senderLoopback @1 :EmbargoId; + # The sender is requesting a disembargo on a promise that is known to resolve back to a + # capability hosted by the sender. As soon as the receiver has echoed back all pipelined calls + # on this promise, it will deliver the Disembargo back to the sender with `receiverLoopback` + # set to the same value as `senderLoopback`. This value is chosen by the sender, and since + # it is also consumed be the sender, the sender can use whatever strategy it wants to make sure + # the value is unambiguous. + # + # The receiver must verify that the target capability actually resolves back to the sender's + # vat. Otherwise, the sender has committed a protocol error and should be disconnected. + + receiverLoopback @2 :EmbargoId; + # The receiver previously sent a `senderLoopback` Disembargo towards a promise resolving to + # this capability, and that Disembargo is now being echoed back. + + accept @3 :Void; + # **(level 3)** + # + # The sender is requesting a disembargo on a promise that is known to resolve to a third-party + # capability that the sender is currently in the process of accepting (using `Accept`). + # The receiver of this `Disembargo` has an outstanding `Provide` on said capability. The + # receiver should now send a `Disembargo` with `provide` set to the question ID of that + # `Provide` message. + # + # See `Accept.embargo` for an example. + + provide @4 :QuestionId; + # **(level 3)** + # + # The sender is requesting a disembargo on a capability currently being provided to a third + # party. The question ID identifies the `Provide` message previously sent by the sender to + # this capability. On receipt, the receiver (the capability host) shall release the embargo + # on the `Accept` message that it has received from the third party. See `Accept.embargo` for + # an example. + } +} + +# Level 2 message types ---------------------------------------------- + +# See persistent.capnp. + +# Level 3 message types ---------------------------------------------- + +struct Provide { + # **(level 3)** + # + # Message type sent to indicate that the sender wishes to make a particular capability implemented + # by the receiver available to a third party for direct access (without the need for the third + # party to proxy through the sender). + # + # (In CapTP, `Provide` and `Accept` are methods of the global `NonceLocator` object exported by + # every vat. In Cap'n Proto, we bake this into the core protocol.) + + questionId @0 :QuestionId; + # Question ID to be held open until the recipient has received the capability. A result will be + # returned once the third party has successfully received the capability. The sender must at some + # point send a `Finish` message as with any other call, and that message can be used to cancel the + # whole operation. + + target @1 :MessageTarget; + # What is to be provided to the third party. + + recipient @2 :RecipientId; + # Identity of the third party that is expected to pick up the capability. +} + +struct Accept { + # **(level 3)** + # + # Message type sent to pick up a capability hosted by the receiving vat and provided by a third + # party. The third party previously designated the capability using `Provide`. + # + # This message is also used to pick up a redirected return -- see `Return.redirect`. + + questionId @0 :QuestionId; + # A new question ID identifying this accept message, which will eventually receive a Return + # message containing the provided capability (or the call result in the case of a redirected + # return). + + provision @1 :ProvisionId; + # Identifies the provided object to be picked up. + + embargo @2 :Bool; + # If true, this accept shall be temporarily embargoed. The resulting `Return` will not be sent, + # and any pipelined calls will not be delivered, until the embargo is released. The receiver + # (the capability host) will expect the provider (the vat that sent the `Provide` message) to + # eventually send a `Disembargo` message with the field `context.provide` set to the question ID + # of the original `Provide` message. At that point, the embargo is released and the queued + # messages are delivered. + # + # For example: + # - Alice, in Vat A, holds a promise P, which currently points toward Vat B. + # - Alice calls foo() on P. The `Call` message is sent to Vat B. + # - The promise P in Vat B ends up resolving to Carol, in Vat C. + # - Vat B sends a `Provide` message to Vat C, identifying Vat A as the recipient. + # - Vat B sends a `Resolve` message to Vat A, indicating that the promise has resolved to a + # `ThirdPartyCapId` identifying Carol in Vat C. + # - Vat A sends an `Accept` message to Vat C to pick up the capability. Since Vat A knows that + # it has an outstanding call to the promise, it sets `embargo` to `true` in the `Accept` + # message. + # - Vat A sends a `Disembargo` message to Vat B on promise P, with `context.accept` set. + # - Alice makes a call bar() to promise P, which is now pointing towards Vat C. Alice doesn't + # know anything about the mechanics of promise resolution happening under the hood, but she + # expects that bar() will be delivered after foo() because that is the order in which she + # initiated the calls. + # - Vat A sends the bar() call to Vat C, as a pipelined call on the result of the `Accept` (which + # hasn't returned yet, due to the embargo). Since calls to the newly-accepted capability + # are embargoed, Vat C does not deliver the call yet. + # - At some point, Vat B forwards the foo() call from the beginning of this example on to Vat C. + # - Vat B forwards the `Disembargo` from Vat A on to vat C. It sets `context.provide` to the + # question ID of the `Provide` message it had sent previously. + # - Vat C receives foo() before `Disembargo`, thus allowing it to correctly deliver foo() + # before delivering bar(). + # - Vat C receives `Disembargo` from Vat B. It can now send a `Return` for the `Accept` from + # Vat A, as well as deliver bar(). +} + +# Level 4 message types ---------------------------------------------- + +struct Join { + # **(level 4)** + # + # Message type sent to implement E.join(), which, given a number of capabilities that are + # expected to be equivalent, finds the underlying object upon which they all agree and forms a + # direct connection to it, skipping any proxies that may have been constructed by other vats + # while transmitting the capability. See: + # http://erights.org/elib/equality/index.html + # + # Note that this should only serve to bypass fully-transparent proxies -- proxies that were + # created merely for convenience, without any intention of hiding the underlying object. + # + # For example, say Bob holds two capabilities hosted by Alice and Carol, but he expects that both + # are simply proxies for a capability hosted elsewhere. He then issues a join request, which + # operates as follows: + # - Bob issues Join requests on both Alice and Carol. Each request contains a different piece + # of the JoinKey. + # - Alice is proxying a capability hosted by Dana, so forwards the request to Dana's cap. + # - Dana receives the first request and sees that the JoinKeyPart is one of two. She notes that + # she doesn't have the other part yet, so she records the request and responds with a + # JoinResult. + # - Alice relays the JoinAswer back to Bob. + # - Carol is also proxying a capability from Dana, and so forwards her Join request to Dana as + # well. + # - Dana receives Carol's request and notes that she now has both parts of a JoinKey. She + # combines them in order to form information needed to form a secure connection to Bob. She + # also responds with another JoinResult. + # - Bob receives the responses from Alice and Carol. He uses the returned JoinResults to + # determine how to connect to Dana and attempts to form the connection. Since Bob and Dana now + # agree on a secret key that neither Alice nor Carol ever saw, this connection can be made + # securely even if Alice or Carol is conspiring against the other. (If Alice and Carol are + # conspiring _together_, they can obviously reproduce the key, but this doesn't matter because + # the whole point of the join is to verify that Alice and Carol agree on what capability they + # are proxying.) + # + # If the two capabilities aren't actually proxies of the same object, then the join requests + # will come back with conflicting `hostId`s and the join will fail before attempting to form any + # connection. + + questionId @0 :QuestionId; + # Question ID used to respond to this Join. (Note that this ID only identifies one part of the + # request for one hop; each part has a different ID and relayed copies of the request have + # (probably) different IDs still.) + # + # The receiver will reply with a `Return` whose `results` is a JoinResult. This `JoinResult` + # is relayed from the joined object's host, possibly with transformation applied as needed + # by the network. + # + # Like any return, the result must be released using a `Finish`. However, this release + # should not occur until the joiner has either successfully connected to the joined object. + # Vats relaying a `Join` message similarly must not release the result they receive until the + # return they relayed back towards the joiner has itself been released. This allows the + # joined object's host to detect when the Join operation is canceled before completing -- if + # it receives a `Finish` for one of the join results before the joiner successfully + # connects. It can then free any resources it had allocated as part of the join. + + target @1 :MessageTarget; + # The capability to join. + + keyPart @2 :JoinKeyPart; + # A part of the join key. These combine to form the complete join key, which is used to establish + # a direct connection. + + # TODO(before implementing): Change this so that multiple parts can be sent in a single Join + # message, so that if multiple join parts are going to cross the same connection they can be sent + # together, so that the receive can potentially optimize its handling of them. In the case where + # all parts are bundled together, should the recipient be expected to simply return a cap, so + # that the caller can immediately start pipelining to it? +} + +# ======================================================================================== +# Common structures used in messages + +struct MessageTarget { + # The target of a `Call` or other messages that target a capability. + + union { + importedCap @0 :ImportId; + # This message is to a capability or promise previously imported by the caller (exported by + # the receiver). + + promisedAnswer @1 :PromisedAnswer; + # This message is to a capability that is expected to be returned by another call that has not + # yet been completed. + # + # At level 0, this is supported only for addressing the result of a previous `Bootstrap`, so + # that initial startup doesn't require a round trip. + } +} + +struct Payload { + # Represents some data structure that might contain capabilities. + + content @0 :AnyPointer; + # Some Cap'n Proto data structure. Capability pointers embedded in this structure index into + # `capTable`. + + capTable @1 :List(CapDescriptor); + # Descriptors corresponding to the cap pointers in `content`. +} + +struct CapDescriptor { + # **(level 1)** + # + # When an application-defined type contains an interface pointer, that pointer contains an index + # into the message's capability table -- i.e. the `capTable` part of the `Payload`. Each + # capability in the table is represented as a `CapDescriptor`. The runtime API should not reveal + # the CapDescriptor directly to the application, but should instead wrap it in some kind of + # callable object with methods corresponding to the interface that the capability implements. + # + # Keep in mind that `ExportIds` in a `CapDescriptor` are subject to reference counting. See the + # description of `ExportId`. + + union { + none @0 :Void; + # There is no capability here. This `CapDescriptor` should not appear in the payload content. + # A `none` CapDescriptor can be generated when an application inserts a capability into a + # message and then later changes its mind and removes it -- rewriting all of the other + # capability pointers may be hard, so instead a tombstone is left, similar to the way a removed + # struct or list instance is zeroed out of the message but the space is not reclaimed. + # Hopefully this is unusual. + + senderHosted @1 :ExportId; + # A capability newly exported by the sender. This is the ID of the new capability in the + # sender's export table (receiver's import table). + + senderPromise @2 :ExportId; + # A promise that the sender will resolve later. The sender will send exactly one Resolve + # message at a future point in time to replace this promise. Note that even if the same + # `senderPromise` is received multiple times, only one `Resolve` is sent to cover all of + # them. If `senderPromise` is released before the `Resolve` is sent, the sender (of this + # `CapDescriptor`) may choose not to send the `Resolve` at all. + + receiverHosted @3 :ImportId; + # A capability (or promise) previously exported by the receiver (imported by the sender). + + receiverAnswer @4 :PromisedAnswer; + # A capability expected to be returned in the results of a currently-outstanding call posed + # by the sender. + + thirdPartyHosted @5 :ThirdPartyCapDescriptor; + # **(level 3)** + # + # A capability that lives in neither the sender's nor the receiver's vat. The sender needs + # to form a direct connection to a third party to pick up the capability. + # + # Level 1 and 2 implementations that receive a `thirdPartyHosted` may simply send calls to its + # `vine` instead. + } +} + +struct PromisedAnswer { + # **(mostly level 1)** + # + # Specifies how to derive a promise from an unanswered question, by specifying the path of fields + # to follow from the root of the eventual result struct to get to the desired capability. Used + # to address method calls to a not-yet-returned capability or to pass such a capability as an + # input to some other method call. + # + # Level 0 implementations must support `PromisedAnswer` only for the case where the answer is + # to a `Bootstrap` message. In this case, `path` is always empty since `Bootstrap` always returns + # a raw capability. + + questionId @0 :QuestionId; + # ID of the question (in the sender's question table / receiver's answer table) whose answer is + # expected to contain the capability. + + transform @1 :List(Op); + # Operations / transformations to apply to the result in order to get the capability actually + # being addressed. E.g. if the result is a struct and you want to call a method on a capability + # pointed to by a field of the struct, you need a `getPointerField` op. + + struct Op { + union { + noop @0 :Void; + # Does nothing. This member is mostly defined so that we can make `Op` a union even + # though (as of this writing) only one real operation is defined. + + getPointerField @1 :UInt16; + # Get a pointer field within a struct. The number is an index into the pointer section, NOT + # a field ordinal, so that the receiver does not need to understand the schema. + + # TODO(someday): We could add: + # - For lists, the ability to address every member of the list, or a slice of the list, the + # result of which would be another list. This is useful for implementing the equivalent of + # a SQL table join (not to be confused with the `Join` message type). + # - Maybe some ability to test a union. + # - Probably not a good idea: the ability to specify an arbitrary script to run on the + # result. We could define a little stack-based language where `Op` specifies one + # "instruction" or transformation to apply. Although this is not a good idea + # (over-engineered), any narrower additions to `Op` should be designed as if this + # were the eventual goal. + } + } +} + +struct ThirdPartyCapDescriptor { + # **(level 3)** + # + # Identifies a capability in a third-party vat that the sender wants the receiver to pick up. + + id @0 :ThirdPartyCapId; + # Identifies the third-party host and the specific capability to accept from it. + + vineId @1 :ExportId; + # A proxy for the third-party object exported by the sender. In CapTP terminology this is called + # a "vine", because it is an indirect reference to the third-party object that snakes through the + # sender vat. This serves two purposes: + # + # * Level 1 and 2 implementations that don't understand how to connect to a third party may + # simply send calls to the vine. Such calls will be forwarded to the third-party by the + # sender. + # + # * Level 3 implementations must release the vine once they have successfully picked up the + # object from the third party. This ensures that the capability is not released by the sender + # prematurely. + # + # The sender will close the `Provide` request that it has sent to the third party as soon as + # it receives either a `Call` or a `Release` message directed at the vine. +} + +struct Exception { + # **(level 0)** + # + # Describes an arbitrary error that prevented an operation (e.g. a call) from completing. + # + # Cap'n Proto exceptions always indicate that something went wrong. In other words, in a fantasy + # world where everything always works as expected, no exceptions would ever be thrown. Clients + # should only ever catch exceptions as a means to implement fault-tolerance, where "fault" can + # mean: + # - Bugs. + # - Invalid input. + # - Configuration errors. + # - Network problems. + # - Insufficient resources. + # - Version skew (unimplemented functionality). + # - Other logistical problems. + # + # Exceptions should NOT be used to flag application-specific conditions that a client is expected + # to handle in an application-specific way. Put another way, in the Cap'n Proto world, + # "checked exceptions" (where an interface explicitly defines the exceptions it throws and + # clients are forced by the type system to handle those exceptions) do NOT make sense. + + reason @0 :Text; + # Human-readable failure description. + + type @3 :Type; + # The type of the error. The purpose of this enum is not to describe the error itself, but + # rather to describe how the client might want to respond to the error. + + enum Type { + failed @0; + # A generic problem occurred, and it is believed that if the operation were repeated without + # any change in the state of the world, the problem would occur again. + # + # A client might respond to this error by logging it for investigation by the developer and/or + # displaying it to the user. + + overloaded @1; + # The request was rejected due to a temporary lack of resources. + # + # Examples include: + # - There's not enough CPU time to keep up with incoming requests, so some are rejected. + # - The server ran out of RAM or disk space during the request. + # - The operation timed out (took significantly longer than it should have). + # + # A client might respond to this error by scheduling to retry the operation much later. The + # client should NOT retry again immediately since this would likely exacerbate the problem. + + disconnected @2; + # The method failed because a connection to some necessary capability was lost. + # + # Examples include: + # - The client introduced the server to a third-party capability, the connection to that third + # party was subsequently lost, and then the client requested that the server use the dead + # capability for something. + # - The client previously requested that the server obtain a capability from some third party. + # The server returned a capability to an object wrapping the third-party capability. Later, + # the server's connection to the third party was lost. + # - The capability has been revoked. Revocation does not necessarily mean that the client is + # no longer authorized to use the capability; it is often used simply as a way to force the + # client to repeat the setup process, perhaps to efficiently move them to a new back-end or + # get them to recognize some other change that has occurred. + # + # A client should normally respond to this error by releasing all capabilities it is currently + # holding related to the one it called and then re-creating them by restoring SturdyRefs and/or + # repeating the method calls used to create them originally. In other words, disconnect and + # start over. This should in turn cause the server to obtain a new copy of the capability that + # it lost, thus making everything work. + # + # If the client receives another `disconnencted` error in the process of rebuilding the + # capability and retrying the call, it should treat this as an `overloaded` error: the network + # is currently unreliable, possibly due to load or other temporary issues. + + unimplemented @3; + # The server doesn't implement the requested method. If there is some other method that the + # client could call (perhaps an older and/or slower interface), it should try that instead. + # Otherwise, this should be treated like `failed`. + } + + obsoleteIsCallersFault @1 :Bool; + # OBSOLETE. Ignore. + + obsoleteDurability @2 :UInt16; + # OBSOLETE. See `type` instead. +} + +# ======================================================================================== +# Network-specific Parameters +# +# Some parts of the Cap'n Proto RPC protocol are not specified here because different vat networks +# may wish to use different approaches to solving them. For example, on the public internet, you +# may want to authenticate vats using public-key cryptography, but on a local intranet with trusted +# infrastructure, you may be happy to authenticate based on network address only, or some other +# lightweight mechanism. +# +# To accommodate this, we specify several "parameter" types. Each type is defined here as an +# alias for `AnyPointer`, but a specific network will want to define a specific set of types to use. +# All vats in a vat network must agree on these parameters in order to be able to communicate. +# Inter-network communication can be accomplished through "gateways" that perform translation +# between the primitives used on each network; these gateways may need to be deeply stateful, +# depending on the translations they perform. +# +# For interaction over the global internet between parties with no other prior arrangement, a +# particular set of bindings for these types is defined elsewhere. (TODO(someday): Specify where +# these common definitions live.) +# +# Another common network type is the two-party network, in which one of the parties typically +# interacts with the outside world entirely through the other party. In such a connection between +# Alice and Bob, all objects that exist on Bob's other networks appear to Alice as if they were +# hosted by Bob himself, and similarly all objects on Alice's network (if she even has one) appear +# to Bob as if they were hosted by Alice. This network type is interesting because from the point +# of view of a simple application that communicates with only one other party via the two-party +# protocol, there are no three-party interactions at all, and joins are unusually simple to +# implement, so implementing at level 4 is barely more complicated than implementing at level 1. +# Moreover, if you pair an app implementing the two-party network with a container that implements +# some other network, the app can then participate on the container's network just as if it +# implemented that network directly. The types used by the two-party network are defined in +# `rpc-twoparty.capnp`. +# +# The things that we need to parameterize are: +# - How to store capabilities long-term without holding a connection open (mostly level 2). +# - How to authenticate vats in three-party introductions (level 3). +# - How to implement `Join` (level 4). +# +# Persistent references +# --------------------- +# +# **(mostly level 2)** +# +# We want to allow some capabilities to be stored long-term, even if a connection is lost and later +# recreated. ExportId is a short-term identifier that is specific to a connection, so it doesn't +# help here. We need a way to specify long-term identifiers, as well as a strategy for +# reconnecting to a referenced capability later. +# +# Three-party interactions +# ------------------------ +# +# **(level 3)** +# +# In cases where more than two vats are interacting, we have situations where VatA holds a +# capability hosted by VatB and wants to send that capability to VatC. This can be accomplished +# by VatA proxying requests on the new capability, but doing so has two big problems: +# - It's inefficient, requiring an extra network hop. +# - If VatC receives another capability to the same object from VatD, it is difficult for VatC to +# detect that the two capabilities are really the same and to implement the E "join" operation, +# which is necessary for certain four-or-more-party interactions, such as the escrow pattern. +# See: http://www.erights.org/elib/equality/grant-matcher/index.html +# +# Instead, we want a way for VatC to form a direct, authenticated connection to VatB. +# +# Join +# ---- +# +# **(level 4)** +# +# The `Join` message type and corresponding operation arranges for a direct connection to be formed +# between the joiner and the host of the joined object, and this connection must be authenticated. +# Thus, the details are network-dependent. + +using SturdyRef = AnyPointer; +# **(level 2)** +# +# Identifies a persisted capability that can be restored in the future. How exactly a SturdyRef +# is restored to a live object is specified along with the SturdyRef definition (i.e. not by +# rpc.capnp). +# +# Generally a SturdyRef needs to specify three things: +# - How to reach the vat that can restore the ref (e.g. a hostname or IP address). +# - How to authenticate the vat after connecting (e.g. a public key fingerprint). +# - The identity of a specific object hosted by the vat. Generally, this is an opaque pointer whose +# format is defined by the specific vat -- the client has no need to inspect the object ID. +# It is important that the objec ID be unguessable if the object is not public (and objects +# should almost never be public). +# +# The above are only suggestions. Some networks might work differently. For example, a private +# network might employ a special restorer service whose sole purpose is to restore SturdyRefs. +# In this case, the entire contents of SturdyRef might be opaque, because they are intended only +# to be forwarded to the restorer service. + +using ProvisionId = AnyPointer; +# **(level 3)** +# +# The information that must be sent in an `Accept` message to identify the object being accepted. +# +# In a network where each vat has a public/private key pair, this could simply be the public key +# fingerprint of the provider vat along with the question ID used in the `Provide` message sent from +# that provider. + +using RecipientId = AnyPointer; +# **(level 3)** +# +# The information that must be sent in a `Provide` message to identify the recipient of the +# capability. +# +# In a network where each vat has a public/private key pair, this could simply be the public key +# fingerprint of the recipient. (CapTP also calls for a nonce to identify the object. In our +# case, the `Provide` message's `questionId` can serve as the nonce.) + +using ThirdPartyCapId = AnyPointer; +# **(level 3)** +# +# The information needed to connect to a third party and accept a capability from it. +# +# In a network where each vat has a public/private key pair, this could be a combination of the +# third party's public key fingerprint, hints on how to connect to the third party (e.g. an IP +# address), and the question ID used in the corresponding `Provide` message sent to that third party +# (used to identify which capability to pick up). + +using JoinKeyPart = AnyPointer; +# **(level 4)** +# +# A piece of a secret key. One piece is sent along each path that is expected to lead to the same +# place. Once the pieces are combined, a direct connection may be formed between the sender and +# the receiver, bypassing any men-in-the-middle along the paths. See the `Join` message type. +# +# The motivation for Joins is discussed under "Supporting Equality" in the "Unibus" protocol +# sketch: http://www.erights.org/elib/distrib/captp/unibus.html +# +# In a network where each vat has a public/private key pair and each vat forms no more than one +# connection to each other vat, Joins will rarely -- perhaps never -- be needed, as objects never +# need to be transparently proxied and references to the same object sent over the same connection +# have the same export ID. Thus, a successful join requires only checking that the two objects +# come from the same connection and have the same ID, and then completes immediately. +# +# However, in networks where two vats may form more than one connection between each other, or +# where proxying of objects occurs, joins are necessary. +# +# Typically, each JoinKeyPart would include a fixed-length data value such that all value parts +# XOR'd together forms a shared secret that can be used to form an encrypted connection between +# the joiner and the joined object's host. Each JoinKeyPart should also include an indication of +# how many parts to expect and a hash of the shared secret (used to match up parts). + +using JoinResult = AnyPointer; +# **(level 4)** +# +# Information returned as the result to a `Join` message, needed by the joiner in order to form a +# direct connection to a joined object. This might simply be the address of the joined object's +# host vat, since the `JoinKey` has already been communicated so the two vats already have a shared +# secret to use to authenticate each other. +# +# The `JoinResult` should also contain information that can be used to detect when the Join +# requests ended up reaching different objects, so that this situation can be detected easily. +# This could be a simple matter of including a sequence number -- if the joiner receives two +# `JoinResult`s with sequence number 0, then they must have come from different objects and the +# whole join is a failure. + +# ======================================================================================== +# Network interface sketch +# +# The interfaces below are meant to be pseudo-code to illustrate how the details of a particular +# vat network might be abstracted away. They are written like Cap'n Proto interfaces, but in +# practice you'd probably define these interfaces manually in the target programming language. A +# Cap'n Proto RPC implementation should be able to use these interfaces without knowing the +# definitions of the various network-specific parameters defined above. + +# interface VatNetwork { +# # Represents a vat network, with the ability to connect to particular vats and receive +# # connections from vats. +# # +# # Note that methods returning a `Connection` may return a pre-existing `Connection`, and the +# # caller is expected to find and share state with existing users of the connection. +# +# # Level 0 features ----------------------------------------------- +# +# connect(vatId :VatId) :Connection; +# # Connect to the given vat. The transport should return a promise that does not +# # resolve until authentication has completed, but allows messages to be pipelined in before +# # that; the transport either queues these messages until authenticated, or sends them encrypted +# # such that only the authentic vat would be able to decrypt them. The latter approach avoids a +# # round trip for authentication. +# +# accept() :Connection; +# # Wait for the next incoming connection and return it. Only connections formed by +# # connect() are returned by this method. +# +# # Level 4 features ----------------------------------------------- +# +# newJoiner(count :UInt32) :NewJoinerResponse; +# # Prepare a new Join operation, which will eventually lead to forming a new direct connection +# # to the host of the joined capability. `count` is the number of capabilities to join. +# +# struct NewJoinerResponse { +# joinKeyParts :List(JoinKeyPart); +# # Key parts to send in Join messages to each capability. +# +# joiner :Joiner; +# # Used to establish the final connection. +# } +# +# interface Joiner { +# addJoinResult(result :JoinResult) :Void; +# # Add a JoinResult received in response to one of the `Join` messages. All `JoinResult`s +# # returned from all paths must be added before trying to connect. +# +# connect() :ConnectionAndProvisionId; +# # Try to form a connection to the joined capability's host, verifying that it has received +# # all of the JoinKeyParts. Once the connection is formed, the caller should send an `Accept` +# # message on it with the specified `ProvisionId` in order to receive the final capability. +# } +# +# acceptConnectionFromJoiner(parts :List(JoinKeyPart), paths :List(VatPath)) +# :ConnectionAndProvisionId; +# # Called on a joined capability's host to receive the connection from the joiner, once all +# # key parts have arrived. The caller should expect to receive an `Accept` message over the +# # connection with the given ProvisionId. +# } +# +# interface Connection { +# # Level 0 features ----------------------------------------------- +# +# send(message :Message) :Void; +# # Send the message. Returns successfully when the message (and all preceding messages) has +# # been acknowledged by the recipient. +# +# receive() :Message; +# # Receive the next message, and acknowledges receipt to the sender. Messages are received in +# # the order in which they are sent. +# +# # Level 3 features ----------------------------------------------- +# +# introduceTo(recipient :Connection) :IntroductionInfo; +# # Call before starting a three-way introduction, assuming a `Provide` message is to be sent on +# # this connection and a `ThirdPartyCapId` is to be sent to `recipient`. +# +# struct IntroductionInfo { +# sendToRecipient :ThirdPartyCapId; +# sendToTarget :RecipientId; +# } +# +# connectToIntroduced(capId :ThirdPartyCapId) :ConnectionAndProvisionId; +# # Given a ThirdPartyCapId received over this connection, connect to the third party. The +# # caller should then send an `Accept` message over the new connection. +# +# acceptIntroducedConnection(recipientId :RecipientId) :Connection; +# # Given a RecipientId received in a `Provide` message on this `Connection`, wait for the +# # recipient to connect, and return the connection formed. Usually, the first message received +# # on the new connection will be an `Accept` message. +# } +# +# struct ConnectionAndProvisionId { +# # **(level 3)** +# +# connection :Connection; +# # Connection on which to issue `Accept` message. +# +# provision :ProvisionId; +# # `ProvisionId` to send in the `Accept` message. +# } diff --git a/phonelibs/capnp-cpp/include/capnp/rpc.capnp.h b/phonelibs/capnp-cpp/include/capnp/rpc.capnp.h new file mode 100644 index 00000000000000..0a440397fc3b51 --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/rpc.capnp.h @@ -0,0 +1,4898 @@ +// Generated by Cap'n Proto compiler, DO NOT EDIT +// source: rpc.capnp + +#ifndef CAPNP_INCLUDED_b312981b2552a250_ +#define CAPNP_INCLUDED_b312981b2552a250_ + +#include + +#if CAPNP_VERSION != 6001 +#error "Version mismatch between generated code and library headers. You must use the same version of the Cap'n Proto compiler and library." +#endif + + +namespace capnp { +namespace schemas { + +CAPNP_DECLARE_SCHEMA(91b79f1f808db032); +CAPNP_DECLARE_SCHEMA(e94ccf8031176ec4); +CAPNP_DECLARE_SCHEMA(836a53ce789d4cd4); +CAPNP_DECLARE_SCHEMA(dae8b0f61aab5f99); +CAPNP_DECLARE_SCHEMA(9e19b28d3db3573a); +CAPNP_DECLARE_SCHEMA(d37d2eb2c2f80e63); +CAPNP_DECLARE_SCHEMA(bbc29655fa89086e); +CAPNP_DECLARE_SCHEMA(ad1a6c0d7dd07497); +CAPNP_DECLARE_SCHEMA(f964368b0fbd3711); +CAPNP_DECLARE_SCHEMA(d562b4df655bdd4d); +CAPNP_DECLARE_SCHEMA(9c6a046bfbc1ac5a); +CAPNP_DECLARE_SCHEMA(d4c9b56290554016); +CAPNP_DECLARE_SCHEMA(fbe1980490e001af); +CAPNP_DECLARE_SCHEMA(95bc14545813fbc1); +CAPNP_DECLARE_SCHEMA(9a0e61223d96743b); +CAPNP_DECLARE_SCHEMA(8523ddc40b86b8b0); +CAPNP_DECLARE_SCHEMA(d800b1d6cd6f1ca0); +CAPNP_DECLARE_SCHEMA(f316944415569081); +CAPNP_DECLARE_SCHEMA(d37007fde1f0027d); +CAPNP_DECLARE_SCHEMA(d625b7063acf691a); +CAPNP_DECLARE_SCHEMA(b28c96e23f4cbd58); +enum class Type_b28c96e23f4cbd58: uint16_t { + FAILED, + OVERLOADED, + DISCONNECTED, + UNIMPLEMENTED, +}; +CAPNP_DECLARE_ENUM(Type, b28c96e23f4cbd58); + +} // namespace schemas +} // namespace capnp + +namespace capnp { +namespace rpc { + +struct Message { + Message() = delete; + + class Reader; + class Builder; + class Pipeline; + enum Which: uint16_t { + UNIMPLEMENTED, + ABORT, + CALL, + RETURN, + FINISH, + RESOLVE, + RELEASE, + OBSOLETE_SAVE, + BOOTSTRAP, + OBSOLETE_DELETE, + PROVIDE, + ACCEPT, + JOIN, + DISEMBARGO, + }; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(91b79f1f808db032, 1, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Bootstrap { + Bootstrap() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(e94ccf8031176ec4, 1, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Call { + Call() = delete; + + class Reader; + class Builder; + class Pipeline; + struct SendResultsTo; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(836a53ce789d4cd4, 3, 3) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Call::SendResultsTo { + SendResultsTo() = delete; + + class Reader; + class Builder; + class Pipeline; + enum Which: uint16_t { + CALLER, + YOURSELF, + THIRD_PARTY, + }; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(dae8b0f61aab5f99, 3, 3) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Return { + Return() = delete; + + class Reader; + class Builder; + class Pipeline; + enum Which: uint16_t { + RESULTS, + EXCEPTION, + CANCELED, + RESULTS_SENT_ELSEWHERE, + TAKE_FROM_OTHER_QUESTION, + ACCEPT_FROM_THIRD_PARTY, + }; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(9e19b28d3db3573a, 2, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Finish { + Finish() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(d37d2eb2c2f80e63, 1, 0) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Resolve { + Resolve() = delete; + + class Reader; + class Builder; + class Pipeline; + enum Which: uint16_t { + CAP, + EXCEPTION, + }; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(bbc29655fa89086e, 1, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Release { + Release() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(ad1a6c0d7dd07497, 1, 0) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Disembargo { + Disembargo() = delete; + + class Reader; + class Builder; + class Pipeline; + struct Context; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(f964368b0fbd3711, 1, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Disembargo::Context { + Context() = delete; + + class Reader; + class Builder; + class Pipeline; + enum Which: uint16_t { + SENDER_LOOPBACK, + RECEIVER_LOOPBACK, + ACCEPT, + PROVIDE, + }; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(d562b4df655bdd4d, 1, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Provide { + Provide() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(9c6a046bfbc1ac5a, 1, 2) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Accept { + Accept() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(d4c9b56290554016, 1, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Join { + Join() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(fbe1980490e001af, 1, 2) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct MessageTarget { + MessageTarget() = delete; + + class Reader; + class Builder; + class Pipeline; + enum Which: uint16_t { + IMPORTED_CAP, + PROMISED_ANSWER, + }; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(95bc14545813fbc1, 1, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Payload { + Payload() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(9a0e61223d96743b, 0, 2) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct CapDescriptor { + CapDescriptor() = delete; + + class Reader; + class Builder; + class Pipeline; + enum Which: uint16_t { + NONE, + SENDER_HOSTED, + SENDER_PROMISE, + RECEIVER_HOSTED, + RECEIVER_ANSWER, + THIRD_PARTY_HOSTED, + }; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(8523ddc40b86b8b0, 1, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct PromisedAnswer { + PromisedAnswer() = delete; + + class Reader; + class Builder; + class Pipeline; + struct Op; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(d800b1d6cd6f1ca0, 1, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct PromisedAnswer::Op { + Op() = delete; + + class Reader; + class Builder; + class Pipeline; + enum Which: uint16_t { + NOOP, + GET_POINTER_FIELD, + }; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(f316944415569081, 1, 0) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct ThirdPartyCapDescriptor { + ThirdPartyCapDescriptor() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(d37007fde1f0027d, 1, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Exception { + Exception() = delete; + + class Reader; + class Builder; + class Pipeline; + typedef ::capnp::schemas::Type_b28c96e23f4cbd58 Type; + + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(d625b7063acf691a, 1, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +// ======================================================================================= + +class Message::Reader { +public: + typedef Message Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline Which which() const; + inline bool isUnimplemented() const; + inline bool hasUnimplemented() const; + inline ::capnp::rpc::Message::Reader getUnimplemented() const; + + inline bool isAbort() const; + inline bool hasAbort() const; + inline ::capnp::rpc::Exception::Reader getAbort() const; + + inline bool isCall() const; + inline bool hasCall() const; + inline ::capnp::rpc::Call::Reader getCall() const; + + inline bool isReturn() const; + inline bool hasReturn() const; + inline ::capnp::rpc::Return::Reader getReturn() const; + + inline bool isFinish() const; + inline bool hasFinish() const; + inline ::capnp::rpc::Finish::Reader getFinish() const; + + inline bool isResolve() const; + inline bool hasResolve() const; + inline ::capnp::rpc::Resolve::Reader getResolve() const; + + inline bool isRelease() const; + inline bool hasRelease() const; + inline ::capnp::rpc::Release::Reader getRelease() const; + + inline bool isObsoleteSave() const; + inline bool hasObsoleteSave() const; + inline ::capnp::AnyPointer::Reader getObsoleteSave() const; + + inline bool isBootstrap() const; + inline bool hasBootstrap() const; + inline ::capnp::rpc::Bootstrap::Reader getBootstrap() const; + + inline bool isObsoleteDelete() const; + inline bool hasObsoleteDelete() const; + inline ::capnp::AnyPointer::Reader getObsoleteDelete() const; + + inline bool isProvide() const; + inline bool hasProvide() const; + inline ::capnp::rpc::Provide::Reader getProvide() const; + + inline bool isAccept() const; + inline bool hasAccept() const; + inline ::capnp::rpc::Accept::Reader getAccept() const; + + inline bool isJoin() const; + inline bool hasJoin() const; + inline ::capnp::rpc::Join::Reader getJoin() const; + + inline bool isDisembargo() const; + inline bool hasDisembargo() const; + inline ::capnp::rpc::Disembargo::Reader getDisembargo() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Message::Builder { +public: + typedef Message Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline Which which(); + inline bool isUnimplemented(); + inline bool hasUnimplemented(); + inline ::capnp::rpc::Message::Builder getUnimplemented(); + inline void setUnimplemented( ::capnp::rpc::Message::Reader value); + inline ::capnp::rpc::Message::Builder initUnimplemented(); + inline void adoptUnimplemented(::capnp::Orphan< ::capnp::rpc::Message>&& value); + inline ::capnp::Orphan< ::capnp::rpc::Message> disownUnimplemented(); + + inline bool isAbort(); + inline bool hasAbort(); + inline ::capnp::rpc::Exception::Builder getAbort(); + inline void setAbort( ::capnp::rpc::Exception::Reader value); + inline ::capnp::rpc::Exception::Builder initAbort(); + inline void adoptAbort(::capnp::Orphan< ::capnp::rpc::Exception>&& value); + inline ::capnp::Orphan< ::capnp::rpc::Exception> disownAbort(); + + inline bool isCall(); + inline bool hasCall(); + inline ::capnp::rpc::Call::Builder getCall(); + inline void setCall( ::capnp::rpc::Call::Reader value); + inline ::capnp::rpc::Call::Builder initCall(); + inline void adoptCall(::capnp::Orphan< ::capnp::rpc::Call>&& value); + inline ::capnp::Orphan< ::capnp::rpc::Call> disownCall(); + + inline bool isReturn(); + inline bool hasReturn(); + inline ::capnp::rpc::Return::Builder getReturn(); + inline void setReturn( ::capnp::rpc::Return::Reader value); + inline ::capnp::rpc::Return::Builder initReturn(); + inline void adoptReturn(::capnp::Orphan< ::capnp::rpc::Return>&& value); + inline ::capnp::Orphan< ::capnp::rpc::Return> disownReturn(); + + inline bool isFinish(); + inline bool hasFinish(); + inline ::capnp::rpc::Finish::Builder getFinish(); + inline void setFinish( ::capnp::rpc::Finish::Reader value); + inline ::capnp::rpc::Finish::Builder initFinish(); + inline void adoptFinish(::capnp::Orphan< ::capnp::rpc::Finish>&& value); + inline ::capnp::Orphan< ::capnp::rpc::Finish> disownFinish(); + + inline bool isResolve(); + inline bool hasResolve(); + inline ::capnp::rpc::Resolve::Builder getResolve(); + inline void setResolve( ::capnp::rpc::Resolve::Reader value); + inline ::capnp::rpc::Resolve::Builder initResolve(); + inline void adoptResolve(::capnp::Orphan< ::capnp::rpc::Resolve>&& value); + inline ::capnp::Orphan< ::capnp::rpc::Resolve> disownResolve(); + + inline bool isRelease(); + inline bool hasRelease(); + inline ::capnp::rpc::Release::Builder getRelease(); + inline void setRelease( ::capnp::rpc::Release::Reader value); + inline ::capnp::rpc::Release::Builder initRelease(); + inline void adoptRelease(::capnp::Orphan< ::capnp::rpc::Release>&& value); + inline ::capnp::Orphan< ::capnp::rpc::Release> disownRelease(); + + inline bool isObsoleteSave(); + inline bool hasObsoleteSave(); + inline ::capnp::AnyPointer::Builder getObsoleteSave(); + inline ::capnp::AnyPointer::Builder initObsoleteSave(); + + inline bool isBootstrap(); + inline bool hasBootstrap(); + inline ::capnp::rpc::Bootstrap::Builder getBootstrap(); + inline void setBootstrap( ::capnp::rpc::Bootstrap::Reader value); + inline ::capnp::rpc::Bootstrap::Builder initBootstrap(); + inline void adoptBootstrap(::capnp::Orphan< ::capnp::rpc::Bootstrap>&& value); + inline ::capnp::Orphan< ::capnp::rpc::Bootstrap> disownBootstrap(); + + inline bool isObsoleteDelete(); + inline bool hasObsoleteDelete(); + inline ::capnp::AnyPointer::Builder getObsoleteDelete(); + inline ::capnp::AnyPointer::Builder initObsoleteDelete(); + + inline bool isProvide(); + inline bool hasProvide(); + inline ::capnp::rpc::Provide::Builder getProvide(); + inline void setProvide( ::capnp::rpc::Provide::Reader value); + inline ::capnp::rpc::Provide::Builder initProvide(); + inline void adoptProvide(::capnp::Orphan< ::capnp::rpc::Provide>&& value); + inline ::capnp::Orphan< ::capnp::rpc::Provide> disownProvide(); + + inline bool isAccept(); + inline bool hasAccept(); + inline ::capnp::rpc::Accept::Builder getAccept(); + inline void setAccept( ::capnp::rpc::Accept::Reader value); + inline ::capnp::rpc::Accept::Builder initAccept(); + inline void adoptAccept(::capnp::Orphan< ::capnp::rpc::Accept>&& value); + inline ::capnp::Orphan< ::capnp::rpc::Accept> disownAccept(); + + inline bool isJoin(); + inline bool hasJoin(); + inline ::capnp::rpc::Join::Builder getJoin(); + inline void setJoin( ::capnp::rpc::Join::Reader value); + inline ::capnp::rpc::Join::Builder initJoin(); + inline void adoptJoin(::capnp::Orphan< ::capnp::rpc::Join>&& value); + inline ::capnp::Orphan< ::capnp::rpc::Join> disownJoin(); + + inline bool isDisembargo(); + inline bool hasDisembargo(); + inline ::capnp::rpc::Disembargo::Builder getDisembargo(); + inline void setDisembargo( ::capnp::rpc::Disembargo::Reader value); + inline ::capnp::rpc::Disembargo::Builder initDisembargo(); + inline void adoptDisembargo(::capnp::Orphan< ::capnp::rpc::Disembargo>&& value); + inline ::capnp::Orphan< ::capnp::rpc::Disembargo> disownDisembargo(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Message::Pipeline { +public: + typedef Message Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Bootstrap::Reader { +public: + typedef Bootstrap Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline ::uint32_t getQuestionId() const; + + inline bool hasDeprecatedObjectId() const; + inline ::capnp::AnyPointer::Reader getDeprecatedObjectId() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Bootstrap::Builder { +public: + typedef Bootstrap Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint32_t getQuestionId(); + inline void setQuestionId( ::uint32_t value); + + inline bool hasDeprecatedObjectId(); + inline ::capnp::AnyPointer::Builder getDeprecatedObjectId(); + inline ::capnp::AnyPointer::Builder initDeprecatedObjectId(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Bootstrap::Pipeline { +public: + typedef Bootstrap Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Call::Reader { +public: + typedef Call Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline ::uint32_t getQuestionId() const; + + inline bool hasTarget() const; + inline ::capnp::rpc::MessageTarget::Reader getTarget() const; + + inline ::uint64_t getInterfaceId() const; + + inline ::uint16_t getMethodId() const; + + inline bool hasParams() const; + inline ::capnp::rpc::Payload::Reader getParams() const; + + inline typename SendResultsTo::Reader getSendResultsTo() const; + + inline bool getAllowThirdPartyTailCall() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Call::Builder { +public: + typedef Call Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint32_t getQuestionId(); + inline void setQuestionId( ::uint32_t value); + + inline bool hasTarget(); + inline ::capnp::rpc::MessageTarget::Builder getTarget(); + inline void setTarget( ::capnp::rpc::MessageTarget::Reader value); + inline ::capnp::rpc::MessageTarget::Builder initTarget(); + inline void adoptTarget(::capnp::Orphan< ::capnp::rpc::MessageTarget>&& value); + inline ::capnp::Orphan< ::capnp::rpc::MessageTarget> disownTarget(); + + inline ::uint64_t getInterfaceId(); + inline void setInterfaceId( ::uint64_t value); + + inline ::uint16_t getMethodId(); + inline void setMethodId( ::uint16_t value); + + inline bool hasParams(); + inline ::capnp::rpc::Payload::Builder getParams(); + inline void setParams( ::capnp::rpc::Payload::Reader value); + inline ::capnp::rpc::Payload::Builder initParams(); + inline void adoptParams(::capnp::Orphan< ::capnp::rpc::Payload>&& value); + inline ::capnp::Orphan< ::capnp::rpc::Payload> disownParams(); + + inline typename SendResultsTo::Builder getSendResultsTo(); + inline typename SendResultsTo::Builder initSendResultsTo(); + + inline bool getAllowThirdPartyTailCall(); + inline void setAllowThirdPartyTailCall(bool value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Call::Pipeline { +public: + typedef Call Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::capnp::rpc::MessageTarget::Pipeline getTarget(); + inline ::capnp::rpc::Payload::Pipeline getParams(); + inline typename SendResultsTo::Pipeline getSendResultsTo(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Call::SendResultsTo::Reader { +public: + typedef SendResultsTo Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline Which which() const; + inline bool isCaller() const; + inline ::capnp::Void getCaller() const; + + inline bool isYourself() const; + inline ::capnp::Void getYourself() const; + + inline bool isThirdParty() const; + inline bool hasThirdParty() const; + inline ::capnp::AnyPointer::Reader getThirdParty() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Call::SendResultsTo::Builder { +public: + typedef SendResultsTo Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline Which which(); + inline bool isCaller(); + inline ::capnp::Void getCaller(); + inline void setCaller( ::capnp::Void value = ::capnp::VOID); + + inline bool isYourself(); + inline ::capnp::Void getYourself(); + inline void setYourself( ::capnp::Void value = ::capnp::VOID); + + inline bool isThirdParty(); + inline bool hasThirdParty(); + inline ::capnp::AnyPointer::Builder getThirdParty(); + inline ::capnp::AnyPointer::Builder initThirdParty(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Call::SendResultsTo::Pipeline { +public: + typedef SendResultsTo Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Return::Reader { +public: + typedef Return Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline Which which() const; + inline ::uint32_t getAnswerId() const; + + inline bool getReleaseParamCaps() const; + + inline bool isResults() const; + inline bool hasResults() const; + inline ::capnp::rpc::Payload::Reader getResults() const; + + inline bool isException() const; + inline bool hasException() const; + inline ::capnp::rpc::Exception::Reader getException() const; + + inline bool isCanceled() const; + inline ::capnp::Void getCanceled() const; + + inline bool isResultsSentElsewhere() const; + inline ::capnp::Void getResultsSentElsewhere() const; + + inline bool isTakeFromOtherQuestion() const; + inline ::uint32_t getTakeFromOtherQuestion() const; + + inline bool isAcceptFromThirdParty() const; + inline bool hasAcceptFromThirdParty() const; + inline ::capnp::AnyPointer::Reader getAcceptFromThirdParty() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Return::Builder { +public: + typedef Return Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline Which which(); + inline ::uint32_t getAnswerId(); + inline void setAnswerId( ::uint32_t value); + + inline bool getReleaseParamCaps(); + inline void setReleaseParamCaps(bool value); + + inline bool isResults(); + inline bool hasResults(); + inline ::capnp::rpc::Payload::Builder getResults(); + inline void setResults( ::capnp::rpc::Payload::Reader value); + inline ::capnp::rpc::Payload::Builder initResults(); + inline void adoptResults(::capnp::Orphan< ::capnp::rpc::Payload>&& value); + inline ::capnp::Orphan< ::capnp::rpc::Payload> disownResults(); + + inline bool isException(); + inline bool hasException(); + inline ::capnp::rpc::Exception::Builder getException(); + inline void setException( ::capnp::rpc::Exception::Reader value); + inline ::capnp::rpc::Exception::Builder initException(); + inline void adoptException(::capnp::Orphan< ::capnp::rpc::Exception>&& value); + inline ::capnp::Orphan< ::capnp::rpc::Exception> disownException(); + + inline bool isCanceled(); + inline ::capnp::Void getCanceled(); + inline void setCanceled( ::capnp::Void value = ::capnp::VOID); + + inline bool isResultsSentElsewhere(); + inline ::capnp::Void getResultsSentElsewhere(); + inline void setResultsSentElsewhere( ::capnp::Void value = ::capnp::VOID); + + inline bool isTakeFromOtherQuestion(); + inline ::uint32_t getTakeFromOtherQuestion(); + inline void setTakeFromOtherQuestion( ::uint32_t value); + + inline bool isAcceptFromThirdParty(); + inline bool hasAcceptFromThirdParty(); + inline ::capnp::AnyPointer::Builder getAcceptFromThirdParty(); + inline ::capnp::AnyPointer::Builder initAcceptFromThirdParty(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Return::Pipeline { +public: + typedef Return Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Finish::Reader { +public: + typedef Finish Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline ::uint32_t getQuestionId() const; + + inline bool getReleaseResultCaps() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Finish::Builder { +public: + typedef Finish Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint32_t getQuestionId(); + inline void setQuestionId( ::uint32_t value); + + inline bool getReleaseResultCaps(); + inline void setReleaseResultCaps(bool value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Finish::Pipeline { +public: + typedef Finish Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Resolve::Reader { +public: + typedef Resolve Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline Which which() const; + inline ::uint32_t getPromiseId() const; + + inline bool isCap() const; + inline bool hasCap() const; + inline ::capnp::rpc::CapDescriptor::Reader getCap() const; + + inline bool isException() const; + inline bool hasException() const; + inline ::capnp::rpc::Exception::Reader getException() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Resolve::Builder { +public: + typedef Resolve Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline Which which(); + inline ::uint32_t getPromiseId(); + inline void setPromiseId( ::uint32_t value); + + inline bool isCap(); + inline bool hasCap(); + inline ::capnp::rpc::CapDescriptor::Builder getCap(); + inline void setCap( ::capnp::rpc::CapDescriptor::Reader value); + inline ::capnp::rpc::CapDescriptor::Builder initCap(); + inline void adoptCap(::capnp::Orphan< ::capnp::rpc::CapDescriptor>&& value); + inline ::capnp::Orphan< ::capnp::rpc::CapDescriptor> disownCap(); + + inline bool isException(); + inline bool hasException(); + inline ::capnp::rpc::Exception::Builder getException(); + inline void setException( ::capnp::rpc::Exception::Reader value); + inline ::capnp::rpc::Exception::Builder initException(); + inline void adoptException(::capnp::Orphan< ::capnp::rpc::Exception>&& value); + inline ::capnp::Orphan< ::capnp::rpc::Exception> disownException(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Resolve::Pipeline { +public: + typedef Resolve Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Release::Reader { +public: + typedef Release Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline ::uint32_t getId() const; + + inline ::uint32_t getReferenceCount() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Release::Builder { +public: + typedef Release Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint32_t getId(); + inline void setId( ::uint32_t value); + + inline ::uint32_t getReferenceCount(); + inline void setReferenceCount( ::uint32_t value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Release::Pipeline { +public: + typedef Release Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Disembargo::Reader { +public: + typedef Disembargo Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasTarget() const; + inline ::capnp::rpc::MessageTarget::Reader getTarget() const; + + inline typename Context::Reader getContext() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Disembargo::Builder { +public: + typedef Disembargo Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasTarget(); + inline ::capnp::rpc::MessageTarget::Builder getTarget(); + inline void setTarget( ::capnp::rpc::MessageTarget::Reader value); + inline ::capnp::rpc::MessageTarget::Builder initTarget(); + inline void adoptTarget(::capnp::Orphan< ::capnp::rpc::MessageTarget>&& value); + inline ::capnp::Orphan< ::capnp::rpc::MessageTarget> disownTarget(); + + inline typename Context::Builder getContext(); + inline typename Context::Builder initContext(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Disembargo::Pipeline { +public: + typedef Disembargo Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::capnp::rpc::MessageTarget::Pipeline getTarget(); + inline typename Context::Pipeline getContext(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Disembargo::Context::Reader { +public: + typedef Context Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline Which which() const; + inline bool isSenderLoopback() const; + inline ::uint32_t getSenderLoopback() const; + + inline bool isReceiverLoopback() const; + inline ::uint32_t getReceiverLoopback() const; + + inline bool isAccept() const; + inline ::capnp::Void getAccept() const; + + inline bool isProvide() const; + inline ::uint32_t getProvide() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Disembargo::Context::Builder { +public: + typedef Context Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline Which which(); + inline bool isSenderLoopback(); + inline ::uint32_t getSenderLoopback(); + inline void setSenderLoopback( ::uint32_t value); + + inline bool isReceiverLoopback(); + inline ::uint32_t getReceiverLoopback(); + inline void setReceiverLoopback( ::uint32_t value); + + inline bool isAccept(); + inline ::capnp::Void getAccept(); + inline void setAccept( ::capnp::Void value = ::capnp::VOID); + + inline bool isProvide(); + inline ::uint32_t getProvide(); + inline void setProvide( ::uint32_t value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Disembargo::Context::Pipeline { +public: + typedef Context Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Provide::Reader { +public: + typedef Provide Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline ::uint32_t getQuestionId() const; + + inline bool hasTarget() const; + inline ::capnp::rpc::MessageTarget::Reader getTarget() const; + + inline bool hasRecipient() const; + inline ::capnp::AnyPointer::Reader getRecipient() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Provide::Builder { +public: + typedef Provide Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint32_t getQuestionId(); + inline void setQuestionId( ::uint32_t value); + + inline bool hasTarget(); + inline ::capnp::rpc::MessageTarget::Builder getTarget(); + inline void setTarget( ::capnp::rpc::MessageTarget::Reader value); + inline ::capnp::rpc::MessageTarget::Builder initTarget(); + inline void adoptTarget(::capnp::Orphan< ::capnp::rpc::MessageTarget>&& value); + inline ::capnp::Orphan< ::capnp::rpc::MessageTarget> disownTarget(); + + inline bool hasRecipient(); + inline ::capnp::AnyPointer::Builder getRecipient(); + inline ::capnp::AnyPointer::Builder initRecipient(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Provide::Pipeline { +public: + typedef Provide Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::capnp::rpc::MessageTarget::Pipeline getTarget(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Accept::Reader { +public: + typedef Accept Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline ::uint32_t getQuestionId() const; + + inline bool hasProvision() const; + inline ::capnp::AnyPointer::Reader getProvision() const; + + inline bool getEmbargo() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Accept::Builder { +public: + typedef Accept Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint32_t getQuestionId(); + inline void setQuestionId( ::uint32_t value); + + inline bool hasProvision(); + inline ::capnp::AnyPointer::Builder getProvision(); + inline ::capnp::AnyPointer::Builder initProvision(); + + inline bool getEmbargo(); + inline void setEmbargo(bool value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Accept::Pipeline { +public: + typedef Accept Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Join::Reader { +public: + typedef Join Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline ::uint32_t getQuestionId() const; + + inline bool hasTarget() const; + inline ::capnp::rpc::MessageTarget::Reader getTarget() const; + + inline bool hasKeyPart() const; + inline ::capnp::AnyPointer::Reader getKeyPart() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Join::Builder { +public: + typedef Join Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint32_t getQuestionId(); + inline void setQuestionId( ::uint32_t value); + + inline bool hasTarget(); + inline ::capnp::rpc::MessageTarget::Builder getTarget(); + inline void setTarget( ::capnp::rpc::MessageTarget::Reader value); + inline ::capnp::rpc::MessageTarget::Builder initTarget(); + inline void adoptTarget(::capnp::Orphan< ::capnp::rpc::MessageTarget>&& value); + inline ::capnp::Orphan< ::capnp::rpc::MessageTarget> disownTarget(); + + inline bool hasKeyPart(); + inline ::capnp::AnyPointer::Builder getKeyPart(); + inline ::capnp::AnyPointer::Builder initKeyPart(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Join::Pipeline { +public: + typedef Join Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::capnp::rpc::MessageTarget::Pipeline getTarget(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class MessageTarget::Reader { +public: + typedef MessageTarget Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline Which which() const; + inline bool isImportedCap() const; + inline ::uint32_t getImportedCap() const; + + inline bool isPromisedAnswer() const; + inline bool hasPromisedAnswer() const; + inline ::capnp::rpc::PromisedAnswer::Reader getPromisedAnswer() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class MessageTarget::Builder { +public: + typedef MessageTarget Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline Which which(); + inline bool isImportedCap(); + inline ::uint32_t getImportedCap(); + inline void setImportedCap( ::uint32_t value); + + inline bool isPromisedAnswer(); + inline bool hasPromisedAnswer(); + inline ::capnp::rpc::PromisedAnswer::Builder getPromisedAnswer(); + inline void setPromisedAnswer( ::capnp::rpc::PromisedAnswer::Reader value); + inline ::capnp::rpc::PromisedAnswer::Builder initPromisedAnswer(); + inline void adoptPromisedAnswer(::capnp::Orphan< ::capnp::rpc::PromisedAnswer>&& value); + inline ::capnp::Orphan< ::capnp::rpc::PromisedAnswer> disownPromisedAnswer(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class MessageTarget::Pipeline { +public: + typedef MessageTarget Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Payload::Reader { +public: + typedef Payload Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasContent() const; + inline ::capnp::AnyPointer::Reader getContent() const; + + inline bool hasCapTable() const; + inline ::capnp::List< ::capnp::rpc::CapDescriptor>::Reader getCapTable() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Payload::Builder { +public: + typedef Payload Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasContent(); + inline ::capnp::AnyPointer::Builder getContent(); + inline ::capnp::AnyPointer::Builder initContent(); + + inline bool hasCapTable(); + inline ::capnp::List< ::capnp::rpc::CapDescriptor>::Builder getCapTable(); + inline void setCapTable( ::capnp::List< ::capnp::rpc::CapDescriptor>::Reader value); + inline ::capnp::List< ::capnp::rpc::CapDescriptor>::Builder initCapTable(unsigned int size); + inline void adoptCapTable(::capnp::Orphan< ::capnp::List< ::capnp::rpc::CapDescriptor>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::capnp::rpc::CapDescriptor>> disownCapTable(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Payload::Pipeline { +public: + typedef Payload Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class CapDescriptor::Reader { +public: + typedef CapDescriptor Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline Which which() const; + inline bool isNone() const; + inline ::capnp::Void getNone() const; + + inline bool isSenderHosted() const; + inline ::uint32_t getSenderHosted() const; + + inline bool isSenderPromise() const; + inline ::uint32_t getSenderPromise() const; + + inline bool isReceiverHosted() const; + inline ::uint32_t getReceiverHosted() const; + + inline bool isReceiverAnswer() const; + inline bool hasReceiverAnswer() const; + inline ::capnp::rpc::PromisedAnswer::Reader getReceiverAnswer() const; + + inline bool isThirdPartyHosted() const; + inline bool hasThirdPartyHosted() const; + inline ::capnp::rpc::ThirdPartyCapDescriptor::Reader getThirdPartyHosted() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class CapDescriptor::Builder { +public: + typedef CapDescriptor Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline Which which(); + inline bool isNone(); + inline ::capnp::Void getNone(); + inline void setNone( ::capnp::Void value = ::capnp::VOID); + + inline bool isSenderHosted(); + inline ::uint32_t getSenderHosted(); + inline void setSenderHosted( ::uint32_t value); + + inline bool isSenderPromise(); + inline ::uint32_t getSenderPromise(); + inline void setSenderPromise( ::uint32_t value); + + inline bool isReceiverHosted(); + inline ::uint32_t getReceiverHosted(); + inline void setReceiverHosted( ::uint32_t value); + + inline bool isReceiverAnswer(); + inline bool hasReceiverAnswer(); + inline ::capnp::rpc::PromisedAnswer::Builder getReceiverAnswer(); + inline void setReceiverAnswer( ::capnp::rpc::PromisedAnswer::Reader value); + inline ::capnp::rpc::PromisedAnswer::Builder initReceiverAnswer(); + inline void adoptReceiverAnswer(::capnp::Orphan< ::capnp::rpc::PromisedAnswer>&& value); + inline ::capnp::Orphan< ::capnp::rpc::PromisedAnswer> disownReceiverAnswer(); + + inline bool isThirdPartyHosted(); + inline bool hasThirdPartyHosted(); + inline ::capnp::rpc::ThirdPartyCapDescriptor::Builder getThirdPartyHosted(); + inline void setThirdPartyHosted( ::capnp::rpc::ThirdPartyCapDescriptor::Reader value); + inline ::capnp::rpc::ThirdPartyCapDescriptor::Builder initThirdPartyHosted(); + inline void adoptThirdPartyHosted(::capnp::Orphan< ::capnp::rpc::ThirdPartyCapDescriptor>&& value); + inline ::capnp::Orphan< ::capnp::rpc::ThirdPartyCapDescriptor> disownThirdPartyHosted(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class CapDescriptor::Pipeline { +public: + typedef CapDescriptor Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class PromisedAnswer::Reader { +public: + typedef PromisedAnswer Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline ::uint32_t getQuestionId() const; + + inline bool hasTransform() const; + inline ::capnp::List< ::capnp::rpc::PromisedAnswer::Op>::Reader getTransform() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class PromisedAnswer::Builder { +public: + typedef PromisedAnswer Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint32_t getQuestionId(); + inline void setQuestionId( ::uint32_t value); + + inline bool hasTransform(); + inline ::capnp::List< ::capnp::rpc::PromisedAnswer::Op>::Builder getTransform(); + inline void setTransform( ::capnp::List< ::capnp::rpc::PromisedAnswer::Op>::Reader value); + inline ::capnp::List< ::capnp::rpc::PromisedAnswer::Op>::Builder initTransform(unsigned int size); + inline void adoptTransform(::capnp::Orphan< ::capnp::List< ::capnp::rpc::PromisedAnswer::Op>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::capnp::rpc::PromisedAnswer::Op>> disownTransform(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class PromisedAnswer::Pipeline { +public: + typedef PromisedAnswer Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class PromisedAnswer::Op::Reader { +public: + typedef Op Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline Which which() const; + inline bool isNoop() const; + inline ::capnp::Void getNoop() const; + + inline bool isGetPointerField() const; + inline ::uint16_t getGetPointerField() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class PromisedAnswer::Op::Builder { +public: + typedef Op Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline Which which(); + inline bool isNoop(); + inline ::capnp::Void getNoop(); + inline void setNoop( ::capnp::Void value = ::capnp::VOID); + + inline bool isGetPointerField(); + inline ::uint16_t getGetPointerField(); + inline void setGetPointerField( ::uint16_t value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class PromisedAnswer::Op::Pipeline { +public: + typedef Op Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class ThirdPartyCapDescriptor::Reader { +public: + typedef ThirdPartyCapDescriptor Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasId() const; + inline ::capnp::AnyPointer::Reader getId() const; + + inline ::uint32_t getVineId() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class ThirdPartyCapDescriptor::Builder { +public: + typedef ThirdPartyCapDescriptor Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasId(); + inline ::capnp::AnyPointer::Builder getId(); + inline ::capnp::AnyPointer::Builder initId(); + + inline ::uint32_t getVineId(); + inline void setVineId( ::uint32_t value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class ThirdPartyCapDescriptor::Pipeline { +public: + typedef ThirdPartyCapDescriptor Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Exception::Reader { +public: + typedef Exception Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasReason() const; + inline ::capnp::Text::Reader getReason() const; + + inline bool getObsoleteIsCallersFault() const; + + inline ::uint16_t getObsoleteDurability() const; + + inline ::capnp::rpc::Exception::Type getType() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Exception::Builder { +public: + typedef Exception Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasReason(); + inline ::capnp::Text::Builder getReason(); + inline void setReason( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initReason(unsigned int size); + inline void adoptReason(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownReason(); + + inline bool getObsoleteIsCallersFault(); + inline void setObsoleteIsCallersFault(bool value); + + inline ::uint16_t getObsoleteDurability(); + inline void setObsoleteDurability( ::uint16_t value); + + inline ::capnp::rpc::Exception::Type getType(); + inline void setType( ::capnp::rpc::Exception::Type value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Exception::Pipeline { +public: + typedef Exception Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +// ======================================================================================= + +inline ::capnp::rpc::Message::Which Message::Reader::which() const { + return _reader.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline ::capnp::rpc::Message::Which Message::Builder::which() { + return _builder.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline bool Message::Reader::isUnimplemented() const { + return which() == Message::UNIMPLEMENTED; +} +inline bool Message::Builder::isUnimplemented() { + return which() == Message::UNIMPLEMENTED; +} +inline bool Message::Reader::hasUnimplemented() const { + if (which() != Message::UNIMPLEMENTED) return false; + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Message::Builder::hasUnimplemented() { + if (which() != Message::UNIMPLEMENTED) return false; + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::rpc::Message::Reader Message::Reader::getUnimplemented() const { + KJ_IREQUIRE((which() == Message::UNIMPLEMENTED), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Message>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::rpc::Message::Builder Message::Builder::getUnimplemented() { + KJ_IREQUIRE((which() == Message::UNIMPLEMENTED), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Message>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Message::Builder::setUnimplemented( ::capnp::rpc::Message::Reader value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::UNIMPLEMENTED); + ::capnp::_::PointerHelpers< ::capnp::rpc::Message>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::rpc::Message::Builder Message::Builder::initUnimplemented() { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::UNIMPLEMENTED); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Message>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Message::Builder::adoptUnimplemented( + ::capnp::Orphan< ::capnp::rpc::Message>&& value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::UNIMPLEMENTED); + ::capnp::_::PointerHelpers< ::capnp::rpc::Message>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::rpc::Message> Message::Builder::disownUnimplemented() { + KJ_IREQUIRE((which() == Message::UNIMPLEMENTED), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Message>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool Message::Reader::isAbort() const { + return which() == Message::ABORT; +} +inline bool Message::Builder::isAbort() { + return which() == Message::ABORT; +} +inline bool Message::Reader::hasAbort() const { + if (which() != Message::ABORT) return false; + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Message::Builder::hasAbort() { + if (which() != Message::ABORT) return false; + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::rpc::Exception::Reader Message::Reader::getAbort() const { + KJ_IREQUIRE((which() == Message::ABORT), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Exception>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::rpc::Exception::Builder Message::Builder::getAbort() { + KJ_IREQUIRE((which() == Message::ABORT), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Exception>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Message::Builder::setAbort( ::capnp::rpc::Exception::Reader value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::ABORT); + ::capnp::_::PointerHelpers< ::capnp::rpc::Exception>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::rpc::Exception::Builder Message::Builder::initAbort() { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::ABORT); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Exception>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Message::Builder::adoptAbort( + ::capnp::Orphan< ::capnp::rpc::Exception>&& value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::ABORT); + ::capnp::_::PointerHelpers< ::capnp::rpc::Exception>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::rpc::Exception> Message::Builder::disownAbort() { + KJ_IREQUIRE((which() == Message::ABORT), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Exception>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool Message::Reader::isCall() const { + return which() == Message::CALL; +} +inline bool Message::Builder::isCall() { + return which() == Message::CALL; +} +inline bool Message::Reader::hasCall() const { + if (which() != Message::CALL) return false; + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Message::Builder::hasCall() { + if (which() != Message::CALL) return false; + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::rpc::Call::Reader Message::Reader::getCall() const { + KJ_IREQUIRE((which() == Message::CALL), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Call>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::rpc::Call::Builder Message::Builder::getCall() { + KJ_IREQUIRE((which() == Message::CALL), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Call>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Message::Builder::setCall( ::capnp::rpc::Call::Reader value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::CALL); + ::capnp::_::PointerHelpers< ::capnp::rpc::Call>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::rpc::Call::Builder Message::Builder::initCall() { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::CALL); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Call>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Message::Builder::adoptCall( + ::capnp::Orphan< ::capnp::rpc::Call>&& value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::CALL); + ::capnp::_::PointerHelpers< ::capnp::rpc::Call>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::rpc::Call> Message::Builder::disownCall() { + KJ_IREQUIRE((which() == Message::CALL), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Call>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool Message::Reader::isReturn() const { + return which() == Message::RETURN; +} +inline bool Message::Builder::isReturn() { + return which() == Message::RETURN; +} +inline bool Message::Reader::hasReturn() const { + if (which() != Message::RETURN) return false; + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Message::Builder::hasReturn() { + if (which() != Message::RETURN) return false; + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::rpc::Return::Reader Message::Reader::getReturn() const { + KJ_IREQUIRE((which() == Message::RETURN), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Return>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::rpc::Return::Builder Message::Builder::getReturn() { + KJ_IREQUIRE((which() == Message::RETURN), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Return>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Message::Builder::setReturn( ::capnp::rpc::Return::Reader value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::RETURN); + ::capnp::_::PointerHelpers< ::capnp::rpc::Return>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::rpc::Return::Builder Message::Builder::initReturn() { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::RETURN); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Return>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Message::Builder::adoptReturn( + ::capnp::Orphan< ::capnp::rpc::Return>&& value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::RETURN); + ::capnp::_::PointerHelpers< ::capnp::rpc::Return>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::rpc::Return> Message::Builder::disownReturn() { + KJ_IREQUIRE((which() == Message::RETURN), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Return>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool Message::Reader::isFinish() const { + return which() == Message::FINISH; +} +inline bool Message::Builder::isFinish() { + return which() == Message::FINISH; +} +inline bool Message::Reader::hasFinish() const { + if (which() != Message::FINISH) return false; + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Message::Builder::hasFinish() { + if (which() != Message::FINISH) return false; + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::rpc::Finish::Reader Message::Reader::getFinish() const { + KJ_IREQUIRE((which() == Message::FINISH), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Finish>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::rpc::Finish::Builder Message::Builder::getFinish() { + KJ_IREQUIRE((which() == Message::FINISH), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Finish>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Message::Builder::setFinish( ::capnp::rpc::Finish::Reader value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::FINISH); + ::capnp::_::PointerHelpers< ::capnp::rpc::Finish>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::rpc::Finish::Builder Message::Builder::initFinish() { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::FINISH); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Finish>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Message::Builder::adoptFinish( + ::capnp::Orphan< ::capnp::rpc::Finish>&& value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::FINISH); + ::capnp::_::PointerHelpers< ::capnp::rpc::Finish>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::rpc::Finish> Message::Builder::disownFinish() { + KJ_IREQUIRE((which() == Message::FINISH), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Finish>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool Message::Reader::isResolve() const { + return which() == Message::RESOLVE; +} +inline bool Message::Builder::isResolve() { + return which() == Message::RESOLVE; +} +inline bool Message::Reader::hasResolve() const { + if (which() != Message::RESOLVE) return false; + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Message::Builder::hasResolve() { + if (which() != Message::RESOLVE) return false; + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::rpc::Resolve::Reader Message::Reader::getResolve() const { + KJ_IREQUIRE((which() == Message::RESOLVE), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Resolve>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::rpc::Resolve::Builder Message::Builder::getResolve() { + KJ_IREQUIRE((which() == Message::RESOLVE), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Resolve>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Message::Builder::setResolve( ::capnp::rpc::Resolve::Reader value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::RESOLVE); + ::capnp::_::PointerHelpers< ::capnp::rpc::Resolve>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::rpc::Resolve::Builder Message::Builder::initResolve() { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::RESOLVE); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Resolve>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Message::Builder::adoptResolve( + ::capnp::Orphan< ::capnp::rpc::Resolve>&& value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::RESOLVE); + ::capnp::_::PointerHelpers< ::capnp::rpc::Resolve>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::rpc::Resolve> Message::Builder::disownResolve() { + KJ_IREQUIRE((which() == Message::RESOLVE), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Resolve>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool Message::Reader::isRelease() const { + return which() == Message::RELEASE; +} +inline bool Message::Builder::isRelease() { + return which() == Message::RELEASE; +} +inline bool Message::Reader::hasRelease() const { + if (which() != Message::RELEASE) return false; + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Message::Builder::hasRelease() { + if (which() != Message::RELEASE) return false; + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::rpc::Release::Reader Message::Reader::getRelease() const { + KJ_IREQUIRE((which() == Message::RELEASE), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Release>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::rpc::Release::Builder Message::Builder::getRelease() { + KJ_IREQUIRE((which() == Message::RELEASE), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Release>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Message::Builder::setRelease( ::capnp::rpc::Release::Reader value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::RELEASE); + ::capnp::_::PointerHelpers< ::capnp::rpc::Release>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::rpc::Release::Builder Message::Builder::initRelease() { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::RELEASE); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Release>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Message::Builder::adoptRelease( + ::capnp::Orphan< ::capnp::rpc::Release>&& value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::RELEASE); + ::capnp::_::PointerHelpers< ::capnp::rpc::Release>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::rpc::Release> Message::Builder::disownRelease() { + KJ_IREQUIRE((which() == Message::RELEASE), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Release>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool Message::Reader::isObsoleteSave() const { + return which() == Message::OBSOLETE_SAVE; +} +inline bool Message::Builder::isObsoleteSave() { + return which() == Message::OBSOLETE_SAVE; +} +inline bool Message::Reader::hasObsoleteSave() const { + if (which() != Message::OBSOLETE_SAVE) return false; + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Message::Builder::hasObsoleteSave() { + if (which() != Message::OBSOLETE_SAVE) return false; + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::AnyPointer::Reader Message::Reader::getObsoleteSave() const { + KJ_IREQUIRE((which() == Message::OBSOLETE_SAVE), + "Must check which() before get()ing a union member."); + return ::capnp::AnyPointer::Reader(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::AnyPointer::Builder Message::Builder::getObsoleteSave() { + KJ_IREQUIRE((which() == Message::OBSOLETE_SAVE), + "Must check which() before get()ing a union member."); + return ::capnp::AnyPointer::Builder(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::AnyPointer::Builder Message::Builder::initObsoleteSave() { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::OBSOLETE_SAVE); + auto result = ::capnp::AnyPointer::Builder(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); + result.clear(); + return result; +} + +inline bool Message::Reader::isBootstrap() const { + return which() == Message::BOOTSTRAP; +} +inline bool Message::Builder::isBootstrap() { + return which() == Message::BOOTSTRAP; +} +inline bool Message::Reader::hasBootstrap() const { + if (which() != Message::BOOTSTRAP) return false; + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Message::Builder::hasBootstrap() { + if (which() != Message::BOOTSTRAP) return false; + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::rpc::Bootstrap::Reader Message::Reader::getBootstrap() const { + KJ_IREQUIRE((which() == Message::BOOTSTRAP), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Bootstrap>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::rpc::Bootstrap::Builder Message::Builder::getBootstrap() { + KJ_IREQUIRE((which() == Message::BOOTSTRAP), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Bootstrap>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Message::Builder::setBootstrap( ::capnp::rpc::Bootstrap::Reader value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::BOOTSTRAP); + ::capnp::_::PointerHelpers< ::capnp::rpc::Bootstrap>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::rpc::Bootstrap::Builder Message::Builder::initBootstrap() { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::BOOTSTRAP); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Bootstrap>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Message::Builder::adoptBootstrap( + ::capnp::Orphan< ::capnp::rpc::Bootstrap>&& value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::BOOTSTRAP); + ::capnp::_::PointerHelpers< ::capnp::rpc::Bootstrap>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::rpc::Bootstrap> Message::Builder::disownBootstrap() { + KJ_IREQUIRE((which() == Message::BOOTSTRAP), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Bootstrap>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool Message::Reader::isObsoleteDelete() const { + return which() == Message::OBSOLETE_DELETE; +} +inline bool Message::Builder::isObsoleteDelete() { + return which() == Message::OBSOLETE_DELETE; +} +inline bool Message::Reader::hasObsoleteDelete() const { + if (which() != Message::OBSOLETE_DELETE) return false; + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Message::Builder::hasObsoleteDelete() { + if (which() != Message::OBSOLETE_DELETE) return false; + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::AnyPointer::Reader Message::Reader::getObsoleteDelete() const { + KJ_IREQUIRE((which() == Message::OBSOLETE_DELETE), + "Must check which() before get()ing a union member."); + return ::capnp::AnyPointer::Reader(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::AnyPointer::Builder Message::Builder::getObsoleteDelete() { + KJ_IREQUIRE((which() == Message::OBSOLETE_DELETE), + "Must check which() before get()ing a union member."); + return ::capnp::AnyPointer::Builder(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::AnyPointer::Builder Message::Builder::initObsoleteDelete() { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::OBSOLETE_DELETE); + auto result = ::capnp::AnyPointer::Builder(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); + result.clear(); + return result; +} + +inline bool Message::Reader::isProvide() const { + return which() == Message::PROVIDE; +} +inline bool Message::Builder::isProvide() { + return which() == Message::PROVIDE; +} +inline bool Message::Reader::hasProvide() const { + if (which() != Message::PROVIDE) return false; + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Message::Builder::hasProvide() { + if (which() != Message::PROVIDE) return false; + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::rpc::Provide::Reader Message::Reader::getProvide() const { + KJ_IREQUIRE((which() == Message::PROVIDE), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Provide>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::rpc::Provide::Builder Message::Builder::getProvide() { + KJ_IREQUIRE((which() == Message::PROVIDE), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Provide>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Message::Builder::setProvide( ::capnp::rpc::Provide::Reader value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::PROVIDE); + ::capnp::_::PointerHelpers< ::capnp::rpc::Provide>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::rpc::Provide::Builder Message::Builder::initProvide() { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::PROVIDE); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Provide>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Message::Builder::adoptProvide( + ::capnp::Orphan< ::capnp::rpc::Provide>&& value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::PROVIDE); + ::capnp::_::PointerHelpers< ::capnp::rpc::Provide>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::rpc::Provide> Message::Builder::disownProvide() { + KJ_IREQUIRE((which() == Message::PROVIDE), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Provide>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool Message::Reader::isAccept() const { + return which() == Message::ACCEPT; +} +inline bool Message::Builder::isAccept() { + return which() == Message::ACCEPT; +} +inline bool Message::Reader::hasAccept() const { + if (which() != Message::ACCEPT) return false; + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Message::Builder::hasAccept() { + if (which() != Message::ACCEPT) return false; + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::rpc::Accept::Reader Message::Reader::getAccept() const { + KJ_IREQUIRE((which() == Message::ACCEPT), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Accept>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::rpc::Accept::Builder Message::Builder::getAccept() { + KJ_IREQUIRE((which() == Message::ACCEPT), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Accept>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Message::Builder::setAccept( ::capnp::rpc::Accept::Reader value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::ACCEPT); + ::capnp::_::PointerHelpers< ::capnp::rpc::Accept>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::rpc::Accept::Builder Message::Builder::initAccept() { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::ACCEPT); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Accept>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Message::Builder::adoptAccept( + ::capnp::Orphan< ::capnp::rpc::Accept>&& value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::ACCEPT); + ::capnp::_::PointerHelpers< ::capnp::rpc::Accept>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::rpc::Accept> Message::Builder::disownAccept() { + KJ_IREQUIRE((which() == Message::ACCEPT), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Accept>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool Message::Reader::isJoin() const { + return which() == Message::JOIN; +} +inline bool Message::Builder::isJoin() { + return which() == Message::JOIN; +} +inline bool Message::Reader::hasJoin() const { + if (which() != Message::JOIN) return false; + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Message::Builder::hasJoin() { + if (which() != Message::JOIN) return false; + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::rpc::Join::Reader Message::Reader::getJoin() const { + KJ_IREQUIRE((which() == Message::JOIN), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Join>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::rpc::Join::Builder Message::Builder::getJoin() { + KJ_IREQUIRE((which() == Message::JOIN), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Join>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Message::Builder::setJoin( ::capnp::rpc::Join::Reader value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::JOIN); + ::capnp::_::PointerHelpers< ::capnp::rpc::Join>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::rpc::Join::Builder Message::Builder::initJoin() { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::JOIN); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Join>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Message::Builder::adoptJoin( + ::capnp::Orphan< ::capnp::rpc::Join>&& value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::JOIN); + ::capnp::_::PointerHelpers< ::capnp::rpc::Join>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::rpc::Join> Message::Builder::disownJoin() { + KJ_IREQUIRE((which() == Message::JOIN), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Join>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool Message::Reader::isDisembargo() const { + return which() == Message::DISEMBARGO; +} +inline bool Message::Builder::isDisembargo() { + return which() == Message::DISEMBARGO; +} +inline bool Message::Reader::hasDisembargo() const { + if (which() != Message::DISEMBARGO) return false; + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Message::Builder::hasDisembargo() { + if (which() != Message::DISEMBARGO) return false; + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::rpc::Disembargo::Reader Message::Reader::getDisembargo() const { + KJ_IREQUIRE((which() == Message::DISEMBARGO), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Disembargo>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::rpc::Disembargo::Builder Message::Builder::getDisembargo() { + KJ_IREQUIRE((which() == Message::DISEMBARGO), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Disembargo>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Message::Builder::setDisembargo( ::capnp::rpc::Disembargo::Reader value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::DISEMBARGO); + ::capnp::_::PointerHelpers< ::capnp::rpc::Disembargo>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::rpc::Disembargo::Builder Message::Builder::initDisembargo() { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::DISEMBARGO); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Disembargo>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Message::Builder::adoptDisembargo( + ::capnp::Orphan< ::capnp::rpc::Disembargo>&& value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Message::DISEMBARGO); + ::capnp::_::PointerHelpers< ::capnp::rpc::Disembargo>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::rpc::Disembargo> Message::Builder::disownDisembargo() { + KJ_IREQUIRE((which() == Message::DISEMBARGO), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Disembargo>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline ::uint32_t Bootstrap::Reader::getQuestionId() const { + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t Bootstrap::Builder::getQuestionId() { + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Bootstrap::Builder::setQuestionId( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Bootstrap::Reader::hasDeprecatedObjectId() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Bootstrap::Builder::hasDeprecatedObjectId() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::AnyPointer::Reader Bootstrap::Reader::getDeprecatedObjectId() const { + return ::capnp::AnyPointer::Reader(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::AnyPointer::Builder Bootstrap::Builder::getDeprecatedObjectId() { + return ::capnp::AnyPointer::Builder(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::AnyPointer::Builder Bootstrap::Builder::initDeprecatedObjectId() { + auto result = ::capnp::AnyPointer::Builder(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); + result.clear(); + return result; +} + +inline ::uint32_t Call::Reader::getQuestionId() const { + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t Call::Builder::getQuestionId() { + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Call::Builder::setQuestionId( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Call::Reader::hasTarget() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Call::Builder::hasTarget() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::rpc::MessageTarget::Reader Call::Reader::getTarget() const { + return ::capnp::_::PointerHelpers< ::capnp::rpc::MessageTarget>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::rpc::MessageTarget::Builder Call::Builder::getTarget() { + return ::capnp::_::PointerHelpers< ::capnp::rpc::MessageTarget>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::capnp::rpc::MessageTarget::Pipeline Call::Pipeline::getTarget() { + return ::capnp::rpc::MessageTarget::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void Call::Builder::setTarget( ::capnp::rpc::MessageTarget::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::rpc::MessageTarget>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::rpc::MessageTarget::Builder Call::Builder::initTarget() { + return ::capnp::_::PointerHelpers< ::capnp::rpc::MessageTarget>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Call::Builder::adoptTarget( + ::capnp::Orphan< ::capnp::rpc::MessageTarget>&& value) { + ::capnp::_::PointerHelpers< ::capnp::rpc::MessageTarget>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::rpc::MessageTarget> Call::Builder::disownTarget() { + return ::capnp::_::PointerHelpers< ::capnp::rpc::MessageTarget>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline ::uint64_t Call::Reader::getInterfaceId() const { + return _reader.getDataField< ::uint64_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline ::uint64_t Call::Builder::getInterfaceId() { + return _builder.getDataField< ::uint64_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void Call::Builder::setInterfaceId( ::uint64_t value) { + _builder.setDataField< ::uint64_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline ::uint16_t Call::Reader::getMethodId() const { + return _reader.getDataField< ::uint16_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} + +inline ::uint16_t Call::Builder::getMethodId() { + return _builder.getDataField< ::uint16_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} +inline void Call::Builder::setMethodId( ::uint16_t value) { + _builder.setDataField< ::uint16_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, value); +} + +inline bool Call::Reader::hasParams() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool Call::Builder::hasParams() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::rpc::Payload::Reader Call::Reader::getParams() const { + return ::capnp::_::PointerHelpers< ::capnp::rpc::Payload>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::rpc::Payload::Builder Call::Builder::getParams() { + return ::capnp::_::PointerHelpers< ::capnp::rpc::Payload>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::capnp::rpc::Payload::Pipeline Call::Pipeline::getParams() { + return ::capnp::rpc::Payload::Pipeline(_typeless.getPointerField(1)); +} +#endif // !CAPNP_LITE +inline void Call::Builder::setParams( ::capnp::rpc::Payload::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::rpc::Payload>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::rpc::Payload::Builder Call::Builder::initParams() { + return ::capnp::_::PointerHelpers< ::capnp::rpc::Payload>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void Call::Builder::adoptParams( + ::capnp::Orphan< ::capnp::rpc::Payload>&& value) { + ::capnp::_::PointerHelpers< ::capnp::rpc::Payload>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::rpc::Payload> Call::Builder::disownParams() { + return ::capnp::_::PointerHelpers< ::capnp::rpc::Payload>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline typename Call::SendResultsTo::Reader Call::Reader::getSendResultsTo() const { + return typename Call::SendResultsTo::Reader(_reader); +} +inline typename Call::SendResultsTo::Builder Call::Builder::getSendResultsTo() { + return typename Call::SendResultsTo::Builder(_builder); +} +#if !CAPNP_LITE +inline typename Call::SendResultsTo::Pipeline Call::Pipeline::getSendResultsTo() { + return typename Call::SendResultsTo::Pipeline(_typeless.noop()); +} +#endif // !CAPNP_LITE +inline typename Call::SendResultsTo::Builder Call::Builder::initSendResultsTo() { + _builder.setDataField< ::uint16_t>(::capnp::bounded<3>() * ::capnp::ELEMENTS, 0); + _builder.getPointerField(::capnp::bounded<2>() * ::capnp::POINTERS).clear(); + return typename Call::SendResultsTo::Builder(_builder); +} +inline bool Call::Reader::getAllowThirdPartyTailCall() const { + return _reader.getDataField( + ::capnp::bounded<128>() * ::capnp::ELEMENTS); +} + +inline bool Call::Builder::getAllowThirdPartyTailCall() { + return _builder.getDataField( + ::capnp::bounded<128>() * ::capnp::ELEMENTS); +} +inline void Call::Builder::setAllowThirdPartyTailCall(bool value) { + _builder.setDataField( + ::capnp::bounded<128>() * ::capnp::ELEMENTS, value); +} + +inline ::capnp::rpc::Call::SendResultsTo::Which Call::SendResultsTo::Reader::which() const { + return _reader.getDataField( + ::capnp::bounded<3>() * ::capnp::ELEMENTS); +} +inline ::capnp::rpc::Call::SendResultsTo::Which Call::SendResultsTo::Builder::which() { + return _builder.getDataField( + ::capnp::bounded<3>() * ::capnp::ELEMENTS); +} + +inline bool Call::SendResultsTo::Reader::isCaller() const { + return which() == Call::SendResultsTo::CALLER; +} +inline bool Call::SendResultsTo::Builder::isCaller() { + return which() == Call::SendResultsTo::CALLER; +} +inline ::capnp::Void Call::SendResultsTo::Reader::getCaller() const { + KJ_IREQUIRE((which() == Call::SendResultsTo::CALLER), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::capnp::Void Call::SendResultsTo::Builder::getCaller() { + KJ_IREQUIRE((which() == Call::SendResultsTo::CALLER), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Call::SendResultsTo::Builder::setCaller( ::capnp::Void value) { + _builder.setDataField( + ::capnp::bounded<3>() * ::capnp::ELEMENTS, Call::SendResultsTo::CALLER); + _builder.setDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Call::SendResultsTo::Reader::isYourself() const { + return which() == Call::SendResultsTo::YOURSELF; +} +inline bool Call::SendResultsTo::Builder::isYourself() { + return which() == Call::SendResultsTo::YOURSELF; +} +inline ::capnp::Void Call::SendResultsTo::Reader::getYourself() const { + KJ_IREQUIRE((which() == Call::SendResultsTo::YOURSELF), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::capnp::Void Call::SendResultsTo::Builder::getYourself() { + KJ_IREQUIRE((which() == Call::SendResultsTo::YOURSELF), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Call::SendResultsTo::Builder::setYourself( ::capnp::Void value) { + _builder.setDataField( + ::capnp::bounded<3>() * ::capnp::ELEMENTS, Call::SendResultsTo::YOURSELF); + _builder.setDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Call::SendResultsTo::Reader::isThirdParty() const { + return which() == Call::SendResultsTo::THIRD_PARTY; +} +inline bool Call::SendResultsTo::Builder::isThirdParty() { + return which() == Call::SendResultsTo::THIRD_PARTY; +} +inline bool Call::SendResultsTo::Reader::hasThirdParty() const { + if (which() != Call::SendResultsTo::THIRD_PARTY) return false; + return !_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline bool Call::SendResultsTo::Builder::hasThirdParty() { + if (which() != Call::SendResultsTo::THIRD_PARTY) return false; + return !_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::AnyPointer::Reader Call::SendResultsTo::Reader::getThirdParty() const { + KJ_IREQUIRE((which() == Call::SendResultsTo::THIRD_PARTY), + "Must check which() before get()ing a union member."); + return ::capnp::AnyPointer::Reader(_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline ::capnp::AnyPointer::Builder Call::SendResultsTo::Builder::getThirdParty() { + KJ_IREQUIRE((which() == Call::SendResultsTo::THIRD_PARTY), + "Must check which() before get()ing a union member."); + return ::capnp::AnyPointer::Builder(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline ::capnp::AnyPointer::Builder Call::SendResultsTo::Builder::initThirdParty() { + _builder.setDataField( + ::capnp::bounded<3>() * ::capnp::ELEMENTS, Call::SendResultsTo::THIRD_PARTY); + auto result = ::capnp::AnyPointer::Builder(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); + result.clear(); + return result; +} + +inline ::capnp::rpc::Return::Which Return::Reader::which() const { + return _reader.getDataField( + ::capnp::bounded<3>() * ::capnp::ELEMENTS); +} +inline ::capnp::rpc::Return::Which Return::Builder::which() { + return _builder.getDataField( + ::capnp::bounded<3>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t Return::Reader::getAnswerId() const { + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t Return::Builder::getAnswerId() { + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Return::Builder::setAnswerId( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Return::Reader::getReleaseParamCaps() const { + return _reader.getDataField( + ::capnp::bounded<32>() * ::capnp::ELEMENTS, true); +} + +inline bool Return::Builder::getReleaseParamCaps() { + return _builder.getDataField( + ::capnp::bounded<32>() * ::capnp::ELEMENTS, true); +} +inline void Return::Builder::setReleaseParamCaps(bool value) { + _builder.setDataField( + ::capnp::bounded<32>() * ::capnp::ELEMENTS, value, true); +} + +inline bool Return::Reader::isResults() const { + return which() == Return::RESULTS; +} +inline bool Return::Builder::isResults() { + return which() == Return::RESULTS; +} +inline bool Return::Reader::hasResults() const { + if (which() != Return::RESULTS) return false; + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Return::Builder::hasResults() { + if (which() != Return::RESULTS) return false; + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::rpc::Payload::Reader Return::Reader::getResults() const { + KJ_IREQUIRE((which() == Return::RESULTS), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Payload>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::rpc::Payload::Builder Return::Builder::getResults() { + KJ_IREQUIRE((which() == Return::RESULTS), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Payload>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Return::Builder::setResults( ::capnp::rpc::Payload::Reader value) { + _builder.setDataField( + ::capnp::bounded<3>() * ::capnp::ELEMENTS, Return::RESULTS); + ::capnp::_::PointerHelpers< ::capnp::rpc::Payload>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::rpc::Payload::Builder Return::Builder::initResults() { + _builder.setDataField( + ::capnp::bounded<3>() * ::capnp::ELEMENTS, Return::RESULTS); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Payload>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Return::Builder::adoptResults( + ::capnp::Orphan< ::capnp::rpc::Payload>&& value) { + _builder.setDataField( + ::capnp::bounded<3>() * ::capnp::ELEMENTS, Return::RESULTS); + ::capnp::_::PointerHelpers< ::capnp::rpc::Payload>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::rpc::Payload> Return::Builder::disownResults() { + KJ_IREQUIRE((which() == Return::RESULTS), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Payload>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool Return::Reader::isException() const { + return which() == Return::EXCEPTION; +} +inline bool Return::Builder::isException() { + return which() == Return::EXCEPTION; +} +inline bool Return::Reader::hasException() const { + if (which() != Return::EXCEPTION) return false; + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Return::Builder::hasException() { + if (which() != Return::EXCEPTION) return false; + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::rpc::Exception::Reader Return::Reader::getException() const { + KJ_IREQUIRE((which() == Return::EXCEPTION), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Exception>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::rpc::Exception::Builder Return::Builder::getException() { + KJ_IREQUIRE((which() == Return::EXCEPTION), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Exception>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Return::Builder::setException( ::capnp::rpc::Exception::Reader value) { + _builder.setDataField( + ::capnp::bounded<3>() * ::capnp::ELEMENTS, Return::EXCEPTION); + ::capnp::_::PointerHelpers< ::capnp::rpc::Exception>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::rpc::Exception::Builder Return::Builder::initException() { + _builder.setDataField( + ::capnp::bounded<3>() * ::capnp::ELEMENTS, Return::EXCEPTION); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Exception>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Return::Builder::adoptException( + ::capnp::Orphan< ::capnp::rpc::Exception>&& value) { + _builder.setDataField( + ::capnp::bounded<3>() * ::capnp::ELEMENTS, Return::EXCEPTION); + ::capnp::_::PointerHelpers< ::capnp::rpc::Exception>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::rpc::Exception> Return::Builder::disownException() { + KJ_IREQUIRE((which() == Return::EXCEPTION), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Exception>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool Return::Reader::isCanceled() const { + return which() == Return::CANCELED; +} +inline bool Return::Builder::isCanceled() { + return which() == Return::CANCELED; +} +inline ::capnp::Void Return::Reader::getCanceled() const { + KJ_IREQUIRE((which() == Return::CANCELED), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::capnp::Void Return::Builder::getCanceled() { + KJ_IREQUIRE((which() == Return::CANCELED), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Return::Builder::setCanceled( ::capnp::Void value) { + _builder.setDataField( + ::capnp::bounded<3>() * ::capnp::ELEMENTS, Return::CANCELED); + _builder.setDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Return::Reader::isResultsSentElsewhere() const { + return which() == Return::RESULTS_SENT_ELSEWHERE; +} +inline bool Return::Builder::isResultsSentElsewhere() { + return which() == Return::RESULTS_SENT_ELSEWHERE; +} +inline ::capnp::Void Return::Reader::getResultsSentElsewhere() const { + KJ_IREQUIRE((which() == Return::RESULTS_SENT_ELSEWHERE), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::capnp::Void Return::Builder::getResultsSentElsewhere() { + KJ_IREQUIRE((which() == Return::RESULTS_SENT_ELSEWHERE), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Return::Builder::setResultsSentElsewhere( ::capnp::Void value) { + _builder.setDataField( + ::capnp::bounded<3>() * ::capnp::ELEMENTS, Return::RESULTS_SENT_ELSEWHERE); + _builder.setDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Return::Reader::isTakeFromOtherQuestion() const { + return which() == Return::TAKE_FROM_OTHER_QUESTION; +} +inline bool Return::Builder::isTakeFromOtherQuestion() { + return which() == Return::TAKE_FROM_OTHER_QUESTION; +} +inline ::uint32_t Return::Reader::getTakeFromOtherQuestion() const { + KJ_IREQUIRE((which() == Return::TAKE_FROM_OTHER_QUESTION), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t Return::Builder::getTakeFromOtherQuestion() { + KJ_IREQUIRE((which() == Return::TAKE_FROM_OTHER_QUESTION), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} +inline void Return::Builder::setTakeFromOtherQuestion( ::uint32_t value) { + _builder.setDataField( + ::capnp::bounded<3>() * ::capnp::ELEMENTS, Return::TAKE_FROM_OTHER_QUESTION); + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, value); +} + +inline bool Return::Reader::isAcceptFromThirdParty() const { + return which() == Return::ACCEPT_FROM_THIRD_PARTY; +} +inline bool Return::Builder::isAcceptFromThirdParty() { + return which() == Return::ACCEPT_FROM_THIRD_PARTY; +} +inline bool Return::Reader::hasAcceptFromThirdParty() const { + if (which() != Return::ACCEPT_FROM_THIRD_PARTY) return false; + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Return::Builder::hasAcceptFromThirdParty() { + if (which() != Return::ACCEPT_FROM_THIRD_PARTY) return false; + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::AnyPointer::Reader Return::Reader::getAcceptFromThirdParty() const { + KJ_IREQUIRE((which() == Return::ACCEPT_FROM_THIRD_PARTY), + "Must check which() before get()ing a union member."); + return ::capnp::AnyPointer::Reader(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::AnyPointer::Builder Return::Builder::getAcceptFromThirdParty() { + KJ_IREQUIRE((which() == Return::ACCEPT_FROM_THIRD_PARTY), + "Must check which() before get()ing a union member."); + return ::capnp::AnyPointer::Builder(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::AnyPointer::Builder Return::Builder::initAcceptFromThirdParty() { + _builder.setDataField( + ::capnp::bounded<3>() * ::capnp::ELEMENTS, Return::ACCEPT_FROM_THIRD_PARTY); + auto result = ::capnp::AnyPointer::Builder(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); + result.clear(); + return result; +} + +inline ::uint32_t Finish::Reader::getQuestionId() const { + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t Finish::Builder::getQuestionId() { + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Finish::Builder::setQuestionId( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Finish::Reader::getReleaseResultCaps() const { + return _reader.getDataField( + ::capnp::bounded<32>() * ::capnp::ELEMENTS, true); +} + +inline bool Finish::Builder::getReleaseResultCaps() { + return _builder.getDataField( + ::capnp::bounded<32>() * ::capnp::ELEMENTS, true); +} +inline void Finish::Builder::setReleaseResultCaps(bool value) { + _builder.setDataField( + ::capnp::bounded<32>() * ::capnp::ELEMENTS, value, true); +} + +inline ::capnp::rpc::Resolve::Which Resolve::Reader::which() const { + return _reader.getDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} +inline ::capnp::rpc::Resolve::Which Resolve::Builder::which() { + return _builder.getDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t Resolve::Reader::getPromiseId() const { + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t Resolve::Builder::getPromiseId() { + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Resolve::Builder::setPromiseId( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Resolve::Reader::isCap() const { + return which() == Resolve::CAP; +} +inline bool Resolve::Builder::isCap() { + return which() == Resolve::CAP; +} +inline bool Resolve::Reader::hasCap() const { + if (which() != Resolve::CAP) return false; + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Resolve::Builder::hasCap() { + if (which() != Resolve::CAP) return false; + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::rpc::CapDescriptor::Reader Resolve::Reader::getCap() const { + KJ_IREQUIRE((which() == Resolve::CAP), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::CapDescriptor>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::rpc::CapDescriptor::Builder Resolve::Builder::getCap() { + KJ_IREQUIRE((which() == Resolve::CAP), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::CapDescriptor>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Resolve::Builder::setCap( ::capnp::rpc::CapDescriptor::Reader value) { + _builder.setDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, Resolve::CAP); + ::capnp::_::PointerHelpers< ::capnp::rpc::CapDescriptor>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::rpc::CapDescriptor::Builder Resolve::Builder::initCap() { + _builder.setDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, Resolve::CAP); + return ::capnp::_::PointerHelpers< ::capnp::rpc::CapDescriptor>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Resolve::Builder::adoptCap( + ::capnp::Orphan< ::capnp::rpc::CapDescriptor>&& value) { + _builder.setDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, Resolve::CAP); + ::capnp::_::PointerHelpers< ::capnp::rpc::CapDescriptor>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::rpc::CapDescriptor> Resolve::Builder::disownCap() { + KJ_IREQUIRE((which() == Resolve::CAP), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::CapDescriptor>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool Resolve::Reader::isException() const { + return which() == Resolve::EXCEPTION; +} +inline bool Resolve::Builder::isException() { + return which() == Resolve::EXCEPTION; +} +inline bool Resolve::Reader::hasException() const { + if (which() != Resolve::EXCEPTION) return false; + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Resolve::Builder::hasException() { + if (which() != Resolve::EXCEPTION) return false; + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::rpc::Exception::Reader Resolve::Reader::getException() const { + KJ_IREQUIRE((which() == Resolve::EXCEPTION), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Exception>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::rpc::Exception::Builder Resolve::Builder::getException() { + KJ_IREQUIRE((which() == Resolve::EXCEPTION), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Exception>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Resolve::Builder::setException( ::capnp::rpc::Exception::Reader value) { + _builder.setDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, Resolve::EXCEPTION); + ::capnp::_::PointerHelpers< ::capnp::rpc::Exception>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::rpc::Exception::Builder Resolve::Builder::initException() { + _builder.setDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, Resolve::EXCEPTION); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Exception>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Resolve::Builder::adoptException( + ::capnp::Orphan< ::capnp::rpc::Exception>&& value) { + _builder.setDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, Resolve::EXCEPTION); + ::capnp::_::PointerHelpers< ::capnp::rpc::Exception>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::rpc::Exception> Resolve::Builder::disownException() { + KJ_IREQUIRE((which() == Resolve::EXCEPTION), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::Exception>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline ::uint32_t Release::Reader::getId() const { + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t Release::Builder::getId() { + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Release::Builder::setId( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline ::uint32_t Release::Reader::getReferenceCount() const { + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t Release::Builder::getReferenceCount() { + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void Release::Builder::setReferenceCount( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline bool Disembargo::Reader::hasTarget() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Disembargo::Builder::hasTarget() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::rpc::MessageTarget::Reader Disembargo::Reader::getTarget() const { + return ::capnp::_::PointerHelpers< ::capnp::rpc::MessageTarget>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::rpc::MessageTarget::Builder Disembargo::Builder::getTarget() { + return ::capnp::_::PointerHelpers< ::capnp::rpc::MessageTarget>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::capnp::rpc::MessageTarget::Pipeline Disembargo::Pipeline::getTarget() { + return ::capnp::rpc::MessageTarget::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void Disembargo::Builder::setTarget( ::capnp::rpc::MessageTarget::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::rpc::MessageTarget>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::rpc::MessageTarget::Builder Disembargo::Builder::initTarget() { + return ::capnp::_::PointerHelpers< ::capnp::rpc::MessageTarget>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Disembargo::Builder::adoptTarget( + ::capnp::Orphan< ::capnp::rpc::MessageTarget>&& value) { + ::capnp::_::PointerHelpers< ::capnp::rpc::MessageTarget>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::rpc::MessageTarget> Disembargo::Builder::disownTarget() { + return ::capnp::_::PointerHelpers< ::capnp::rpc::MessageTarget>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline typename Disembargo::Context::Reader Disembargo::Reader::getContext() const { + return typename Disembargo::Context::Reader(_reader); +} +inline typename Disembargo::Context::Builder Disembargo::Builder::getContext() { + return typename Disembargo::Context::Builder(_builder); +} +#if !CAPNP_LITE +inline typename Disembargo::Context::Pipeline Disembargo::Pipeline::getContext() { + return typename Disembargo::Context::Pipeline(_typeless.noop()); +} +#endif // !CAPNP_LITE +inline typename Disembargo::Context::Builder Disembargo::Builder::initContext() { + _builder.setDataField< ::uint32_t>(::capnp::bounded<0>() * ::capnp::ELEMENTS, 0); + _builder.setDataField< ::uint16_t>(::capnp::bounded<2>() * ::capnp::ELEMENTS, 0); + return typename Disembargo::Context::Builder(_builder); +} +inline ::capnp::rpc::Disembargo::Context::Which Disembargo::Context::Reader::which() const { + return _reader.getDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} +inline ::capnp::rpc::Disembargo::Context::Which Disembargo::Context::Builder::which() { + return _builder.getDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} + +inline bool Disembargo::Context::Reader::isSenderLoopback() const { + return which() == Disembargo::Context::SENDER_LOOPBACK; +} +inline bool Disembargo::Context::Builder::isSenderLoopback() { + return which() == Disembargo::Context::SENDER_LOOPBACK; +} +inline ::uint32_t Disembargo::Context::Reader::getSenderLoopback() const { + KJ_IREQUIRE((which() == Disembargo::Context::SENDER_LOOPBACK), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t Disembargo::Context::Builder::getSenderLoopback() { + KJ_IREQUIRE((which() == Disembargo::Context::SENDER_LOOPBACK), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Disembargo::Context::Builder::setSenderLoopback( ::uint32_t value) { + _builder.setDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, Disembargo::Context::SENDER_LOOPBACK); + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Disembargo::Context::Reader::isReceiverLoopback() const { + return which() == Disembargo::Context::RECEIVER_LOOPBACK; +} +inline bool Disembargo::Context::Builder::isReceiverLoopback() { + return which() == Disembargo::Context::RECEIVER_LOOPBACK; +} +inline ::uint32_t Disembargo::Context::Reader::getReceiverLoopback() const { + KJ_IREQUIRE((which() == Disembargo::Context::RECEIVER_LOOPBACK), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t Disembargo::Context::Builder::getReceiverLoopback() { + KJ_IREQUIRE((which() == Disembargo::Context::RECEIVER_LOOPBACK), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Disembargo::Context::Builder::setReceiverLoopback( ::uint32_t value) { + _builder.setDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, Disembargo::Context::RECEIVER_LOOPBACK); + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Disembargo::Context::Reader::isAccept() const { + return which() == Disembargo::Context::ACCEPT; +} +inline bool Disembargo::Context::Builder::isAccept() { + return which() == Disembargo::Context::ACCEPT; +} +inline ::capnp::Void Disembargo::Context::Reader::getAccept() const { + KJ_IREQUIRE((which() == Disembargo::Context::ACCEPT), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::capnp::Void Disembargo::Context::Builder::getAccept() { + KJ_IREQUIRE((which() == Disembargo::Context::ACCEPT), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Disembargo::Context::Builder::setAccept( ::capnp::Void value) { + _builder.setDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, Disembargo::Context::ACCEPT); + _builder.setDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Disembargo::Context::Reader::isProvide() const { + return which() == Disembargo::Context::PROVIDE; +} +inline bool Disembargo::Context::Builder::isProvide() { + return which() == Disembargo::Context::PROVIDE; +} +inline ::uint32_t Disembargo::Context::Reader::getProvide() const { + KJ_IREQUIRE((which() == Disembargo::Context::PROVIDE), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t Disembargo::Context::Builder::getProvide() { + KJ_IREQUIRE((which() == Disembargo::Context::PROVIDE), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Disembargo::Context::Builder::setProvide( ::uint32_t value) { + _builder.setDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, Disembargo::Context::PROVIDE); + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline ::uint32_t Provide::Reader::getQuestionId() const { + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t Provide::Builder::getQuestionId() { + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Provide::Builder::setQuestionId( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Provide::Reader::hasTarget() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Provide::Builder::hasTarget() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::rpc::MessageTarget::Reader Provide::Reader::getTarget() const { + return ::capnp::_::PointerHelpers< ::capnp::rpc::MessageTarget>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::rpc::MessageTarget::Builder Provide::Builder::getTarget() { + return ::capnp::_::PointerHelpers< ::capnp::rpc::MessageTarget>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::capnp::rpc::MessageTarget::Pipeline Provide::Pipeline::getTarget() { + return ::capnp::rpc::MessageTarget::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void Provide::Builder::setTarget( ::capnp::rpc::MessageTarget::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::rpc::MessageTarget>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::rpc::MessageTarget::Builder Provide::Builder::initTarget() { + return ::capnp::_::PointerHelpers< ::capnp::rpc::MessageTarget>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Provide::Builder::adoptTarget( + ::capnp::Orphan< ::capnp::rpc::MessageTarget>&& value) { + ::capnp::_::PointerHelpers< ::capnp::rpc::MessageTarget>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::rpc::MessageTarget> Provide::Builder::disownTarget() { + return ::capnp::_::PointerHelpers< ::capnp::rpc::MessageTarget>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool Provide::Reader::hasRecipient() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool Provide::Builder::hasRecipient() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::AnyPointer::Reader Provide::Reader::getRecipient() const { + return ::capnp::AnyPointer::Reader(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::AnyPointer::Builder Provide::Builder::getRecipient() { + return ::capnp::AnyPointer::Builder(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::AnyPointer::Builder Provide::Builder::initRecipient() { + auto result = ::capnp::AnyPointer::Builder(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); + result.clear(); + return result; +} + +inline ::uint32_t Accept::Reader::getQuestionId() const { + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t Accept::Builder::getQuestionId() { + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Accept::Builder::setQuestionId( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Accept::Reader::hasProvision() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Accept::Builder::hasProvision() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::AnyPointer::Reader Accept::Reader::getProvision() const { + return ::capnp::AnyPointer::Reader(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::AnyPointer::Builder Accept::Builder::getProvision() { + return ::capnp::AnyPointer::Builder(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::AnyPointer::Builder Accept::Builder::initProvision() { + auto result = ::capnp::AnyPointer::Builder(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); + result.clear(); + return result; +} + +inline bool Accept::Reader::getEmbargo() const { + return _reader.getDataField( + ::capnp::bounded<32>() * ::capnp::ELEMENTS); +} + +inline bool Accept::Builder::getEmbargo() { + return _builder.getDataField( + ::capnp::bounded<32>() * ::capnp::ELEMENTS); +} +inline void Accept::Builder::setEmbargo(bool value) { + _builder.setDataField( + ::capnp::bounded<32>() * ::capnp::ELEMENTS, value); +} + +inline ::uint32_t Join::Reader::getQuestionId() const { + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t Join::Builder::getQuestionId() { + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Join::Builder::setQuestionId( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Join::Reader::hasTarget() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Join::Builder::hasTarget() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::rpc::MessageTarget::Reader Join::Reader::getTarget() const { + return ::capnp::_::PointerHelpers< ::capnp::rpc::MessageTarget>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::rpc::MessageTarget::Builder Join::Builder::getTarget() { + return ::capnp::_::PointerHelpers< ::capnp::rpc::MessageTarget>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::capnp::rpc::MessageTarget::Pipeline Join::Pipeline::getTarget() { + return ::capnp::rpc::MessageTarget::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void Join::Builder::setTarget( ::capnp::rpc::MessageTarget::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::rpc::MessageTarget>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::rpc::MessageTarget::Builder Join::Builder::initTarget() { + return ::capnp::_::PointerHelpers< ::capnp::rpc::MessageTarget>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Join::Builder::adoptTarget( + ::capnp::Orphan< ::capnp::rpc::MessageTarget>&& value) { + ::capnp::_::PointerHelpers< ::capnp::rpc::MessageTarget>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::rpc::MessageTarget> Join::Builder::disownTarget() { + return ::capnp::_::PointerHelpers< ::capnp::rpc::MessageTarget>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool Join::Reader::hasKeyPart() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool Join::Builder::hasKeyPart() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::AnyPointer::Reader Join::Reader::getKeyPart() const { + return ::capnp::AnyPointer::Reader(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::AnyPointer::Builder Join::Builder::getKeyPart() { + return ::capnp::AnyPointer::Builder(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::AnyPointer::Builder Join::Builder::initKeyPart() { + auto result = ::capnp::AnyPointer::Builder(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); + result.clear(); + return result; +} + +inline ::capnp::rpc::MessageTarget::Which MessageTarget::Reader::which() const { + return _reader.getDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} +inline ::capnp::rpc::MessageTarget::Which MessageTarget::Builder::which() { + return _builder.getDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} + +inline bool MessageTarget::Reader::isImportedCap() const { + return which() == MessageTarget::IMPORTED_CAP; +} +inline bool MessageTarget::Builder::isImportedCap() { + return which() == MessageTarget::IMPORTED_CAP; +} +inline ::uint32_t MessageTarget::Reader::getImportedCap() const { + KJ_IREQUIRE((which() == MessageTarget::IMPORTED_CAP), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t MessageTarget::Builder::getImportedCap() { + KJ_IREQUIRE((which() == MessageTarget::IMPORTED_CAP), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void MessageTarget::Builder::setImportedCap( ::uint32_t value) { + _builder.setDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, MessageTarget::IMPORTED_CAP); + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool MessageTarget::Reader::isPromisedAnswer() const { + return which() == MessageTarget::PROMISED_ANSWER; +} +inline bool MessageTarget::Builder::isPromisedAnswer() { + return which() == MessageTarget::PROMISED_ANSWER; +} +inline bool MessageTarget::Reader::hasPromisedAnswer() const { + if (which() != MessageTarget::PROMISED_ANSWER) return false; + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool MessageTarget::Builder::hasPromisedAnswer() { + if (which() != MessageTarget::PROMISED_ANSWER) return false; + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::rpc::PromisedAnswer::Reader MessageTarget::Reader::getPromisedAnswer() const { + KJ_IREQUIRE((which() == MessageTarget::PROMISED_ANSWER), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::PromisedAnswer>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::rpc::PromisedAnswer::Builder MessageTarget::Builder::getPromisedAnswer() { + KJ_IREQUIRE((which() == MessageTarget::PROMISED_ANSWER), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::PromisedAnswer>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void MessageTarget::Builder::setPromisedAnswer( ::capnp::rpc::PromisedAnswer::Reader value) { + _builder.setDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, MessageTarget::PROMISED_ANSWER); + ::capnp::_::PointerHelpers< ::capnp::rpc::PromisedAnswer>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::rpc::PromisedAnswer::Builder MessageTarget::Builder::initPromisedAnswer() { + _builder.setDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, MessageTarget::PROMISED_ANSWER); + return ::capnp::_::PointerHelpers< ::capnp::rpc::PromisedAnswer>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void MessageTarget::Builder::adoptPromisedAnswer( + ::capnp::Orphan< ::capnp::rpc::PromisedAnswer>&& value) { + _builder.setDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, MessageTarget::PROMISED_ANSWER); + ::capnp::_::PointerHelpers< ::capnp::rpc::PromisedAnswer>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::rpc::PromisedAnswer> MessageTarget::Builder::disownPromisedAnswer() { + KJ_IREQUIRE((which() == MessageTarget::PROMISED_ANSWER), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::PromisedAnswer>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool Payload::Reader::hasContent() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Payload::Builder::hasContent() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::AnyPointer::Reader Payload::Reader::getContent() const { + return ::capnp::AnyPointer::Reader(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::AnyPointer::Builder Payload::Builder::getContent() { + return ::capnp::AnyPointer::Builder(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::AnyPointer::Builder Payload::Builder::initContent() { + auto result = ::capnp::AnyPointer::Builder(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); + result.clear(); + return result; +} + +inline bool Payload::Reader::hasCapTable() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool Payload::Builder::hasCapTable() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::capnp::rpc::CapDescriptor>::Reader Payload::Reader::getCapTable() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::rpc::CapDescriptor>>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::capnp::rpc::CapDescriptor>::Builder Payload::Builder::getCapTable() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::rpc::CapDescriptor>>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void Payload::Builder::setCapTable( ::capnp::List< ::capnp::rpc::CapDescriptor>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::rpc::CapDescriptor>>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::capnp::rpc::CapDescriptor>::Builder Payload::Builder::initCapTable(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::rpc::CapDescriptor>>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), size); +} +inline void Payload::Builder::adoptCapTable( + ::capnp::Orphan< ::capnp::List< ::capnp::rpc::CapDescriptor>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::rpc::CapDescriptor>>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::capnp::rpc::CapDescriptor>> Payload::Builder::disownCapTable() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::rpc::CapDescriptor>>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline ::capnp::rpc::CapDescriptor::Which CapDescriptor::Reader::which() const { + return _reader.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline ::capnp::rpc::CapDescriptor::Which CapDescriptor::Builder::which() { + return _builder.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline bool CapDescriptor::Reader::isNone() const { + return which() == CapDescriptor::NONE; +} +inline bool CapDescriptor::Builder::isNone() { + return which() == CapDescriptor::NONE; +} +inline ::capnp::Void CapDescriptor::Reader::getNone() const { + KJ_IREQUIRE((which() == CapDescriptor::NONE), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::capnp::Void CapDescriptor::Builder::getNone() { + KJ_IREQUIRE((which() == CapDescriptor::NONE), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void CapDescriptor::Builder::setNone( ::capnp::Void value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, CapDescriptor::NONE); + _builder.setDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool CapDescriptor::Reader::isSenderHosted() const { + return which() == CapDescriptor::SENDER_HOSTED; +} +inline bool CapDescriptor::Builder::isSenderHosted() { + return which() == CapDescriptor::SENDER_HOSTED; +} +inline ::uint32_t CapDescriptor::Reader::getSenderHosted() const { + KJ_IREQUIRE((which() == CapDescriptor::SENDER_HOSTED), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t CapDescriptor::Builder::getSenderHosted() { + KJ_IREQUIRE((which() == CapDescriptor::SENDER_HOSTED), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void CapDescriptor::Builder::setSenderHosted( ::uint32_t value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, CapDescriptor::SENDER_HOSTED); + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline bool CapDescriptor::Reader::isSenderPromise() const { + return which() == CapDescriptor::SENDER_PROMISE; +} +inline bool CapDescriptor::Builder::isSenderPromise() { + return which() == CapDescriptor::SENDER_PROMISE; +} +inline ::uint32_t CapDescriptor::Reader::getSenderPromise() const { + KJ_IREQUIRE((which() == CapDescriptor::SENDER_PROMISE), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t CapDescriptor::Builder::getSenderPromise() { + KJ_IREQUIRE((which() == CapDescriptor::SENDER_PROMISE), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void CapDescriptor::Builder::setSenderPromise( ::uint32_t value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, CapDescriptor::SENDER_PROMISE); + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline bool CapDescriptor::Reader::isReceiverHosted() const { + return which() == CapDescriptor::RECEIVER_HOSTED; +} +inline bool CapDescriptor::Builder::isReceiverHosted() { + return which() == CapDescriptor::RECEIVER_HOSTED; +} +inline ::uint32_t CapDescriptor::Reader::getReceiverHosted() const { + KJ_IREQUIRE((which() == CapDescriptor::RECEIVER_HOSTED), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t CapDescriptor::Builder::getReceiverHosted() { + KJ_IREQUIRE((which() == CapDescriptor::RECEIVER_HOSTED), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void CapDescriptor::Builder::setReceiverHosted( ::uint32_t value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, CapDescriptor::RECEIVER_HOSTED); + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline bool CapDescriptor::Reader::isReceiverAnswer() const { + return which() == CapDescriptor::RECEIVER_ANSWER; +} +inline bool CapDescriptor::Builder::isReceiverAnswer() { + return which() == CapDescriptor::RECEIVER_ANSWER; +} +inline bool CapDescriptor::Reader::hasReceiverAnswer() const { + if (which() != CapDescriptor::RECEIVER_ANSWER) return false; + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool CapDescriptor::Builder::hasReceiverAnswer() { + if (which() != CapDescriptor::RECEIVER_ANSWER) return false; + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::rpc::PromisedAnswer::Reader CapDescriptor::Reader::getReceiverAnswer() const { + KJ_IREQUIRE((which() == CapDescriptor::RECEIVER_ANSWER), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::PromisedAnswer>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::rpc::PromisedAnswer::Builder CapDescriptor::Builder::getReceiverAnswer() { + KJ_IREQUIRE((which() == CapDescriptor::RECEIVER_ANSWER), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::PromisedAnswer>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void CapDescriptor::Builder::setReceiverAnswer( ::capnp::rpc::PromisedAnswer::Reader value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, CapDescriptor::RECEIVER_ANSWER); + ::capnp::_::PointerHelpers< ::capnp::rpc::PromisedAnswer>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::rpc::PromisedAnswer::Builder CapDescriptor::Builder::initReceiverAnswer() { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, CapDescriptor::RECEIVER_ANSWER); + return ::capnp::_::PointerHelpers< ::capnp::rpc::PromisedAnswer>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void CapDescriptor::Builder::adoptReceiverAnswer( + ::capnp::Orphan< ::capnp::rpc::PromisedAnswer>&& value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, CapDescriptor::RECEIVER_ANSWER); + ::capnp::_::PointerHelpers< ::capnp::rpc::PromisedAnswer>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::rpc::PromisedAnswer> CapDescriptor::Builder::disownReceiverAnswer() { + KJ_IREQUIRE((which() == CapDescriptor::RECEIVER_ANSWER), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::PromisedAnswer>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool CapDescriptor::Reader::isThirdPartyHosted() const { + return which() == CapDescriptor::THIRD_PARTY_HOSTED; +} +inline bool CapDescriptor::Builder::isThirdPartyHosted() { + return which() == CapDescriptor::THIRD_PARTY_HOSTED; +} +inline bool CapDescriptor::Reader::hasThirdPartyHosted() const { + if (which() != CapDescriptor::THIRD_PARTY_HOSTED) return false; + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool CapDescriptor::Builder::hasThirdPartyHosted() { + if (which() != CapDescriptor::THIRD_PARTY_HOSTED) return false; + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::rpc::ThirdPartyCapDescriptor::Reader CapDescriptor::Reader::getThirdPartyHosted() const { + KJ_IREQUIRE((which() == CapDescriptor::THIRD_PARTY_HOSTED), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::ThirdPartyCapDescriptor>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::rpc::ThirdPartyCapDescriptor::Builder CapDescriptor::Builder::getThirdPartyHosted() { + KJ_IREQUIRE((which() == CapDescriptor::THIRD_PARTY_HOSTED), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::ThirdPartyCapDescriptor>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void CapDescriptor::Builder::setThirdPartyHosted( ::capnp::rpc::ThirdPartyCapDescriptor::Reader value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, CapDescriptor::THIRD_PARTY_HOSTED); + ::capnp::_::PointerHelpers< ::capnp::rpc::ThirdPartyCapDescriptor>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::rpc::ThirdPartyCapDescriptor::Builder CapDescriptor::Builder::initThirdPartyHosted() { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, CapDescriptor::THIRD_PARTY_HOSTED); + return ::capnp::_::PointerHelpers< ::capnp::rpc::ThirdPartyCapDescriptor>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void CapDescriptor::Builder::adoptThirdPartyHosted( + ::capnp::Orphan< ::capnp::rpc::ThirdPartyCapDescriptor>&& value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, CapDescriptor::THIRD_PARTY_HOSTED); + ::capnp::_::PointerHelpers< ::capnp::rpc::ThirdPartyCapDescriptor>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::rpc::ThirdPartyCapDescriptor> CapDescriptor::Builder::disownThirdPartyHosted() { + KJ_IREQUIRE((which() == CapDescriptor::THIRD_PARTY_HOSTED), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::rpc::ThirdPartyCapDescriptor>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline ::uint32_t PromisedAnswer::Reader::getQuestionId() const { + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t PromisedAnswer::Builder::getQuestionId() { + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void PromisedAnswer::Builder::setQuestionId( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool PromisedAnswer::Reader::hasTransform() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool PromisedAnswer::Builder::hasTransform() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::capnp::rpc::PromisedAnswer::Op>::Reader PromisedAnswer::Reader::getTransform() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::rpc::PromisedAnswer::Op>>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::capnp::rpc::PromisedAnswer::Op>::Builder PromisedAnswer::Builder::getTransform() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::rpc::PromisedAnswer::Op>>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void PromisedAnswer::Builder::setTransform( ::capnp::List< ::capnp::rpc::PromisedAnswer::Op>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::rpc::PromisedAnswer::Op>>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::capnp::rpc::PromisedAnswer::Op>::Builder PromisedAnswer::Builder::initTransform(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::rpc::PromisedAnswer::Op>>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), size); +} +inline void PromisedAnswer::Builder::adoptTransform( + ::capnp::Orphan< ::capnp::List< ::capnp::rpc::PromisedAnswer::Op>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::rpc::PromisedAnswer::Op>>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::capnp::rpc::PromisedAnswer::Op>> PromisedAnswer::Builder::disownTransform() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::rpc::PromisedAnswer::Op>>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline ::capnp::rpc::PromisedAnswer::Op::Which PromisedAnswer::Op::Reader::which() const { + return _reader.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline ::capnp::rpc::PromisedAnswer::Op::Which PromisedAnswer::Op::Builder::which() { + return _builder.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline bool PromisedAnswer::Op::Reader::isNoop() const { + return which() == PromisedAnswer::Op::NOOP; +} +inline bool PromisedAnswer::Op::Builder::isNoop() { + return which() == PromisedAnswer::Op::NOOP; +} +inline ::capnp::Void PromisedAnswer::Op::Reader::getNoop() const { + KJ_IREQUIRE((which() == PromisedAnswer::Op::NOOP), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::capnp::Void PromisedAnswer::Op::Builder::getNoop() { + KJ_IREQUIRE((which() == PromisedAnswer::Op::NOOP), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void PromisedAnswer::Op::Builder::setNoop( ::capnp::Void value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, PromisedAnswer::Op::NOOP); + _builder.setDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool PromisedAnswer::Op::Reader::isGetPointerField() const { + return which() == PromisedAnswer::Op::GET_POINTER_FIELD; +} +inline bool PromisedAnswer::Op::Builder::isGetPointerField() { + return which() == PromisedAnswer::Op::GET_POINTER_FIELD; +} +inline ::uint16_t PromisedAnswer::Op::Reader::getGetPointerField() const { + KJ_IREQUIRE((which() == PromisedAnswer::Op::GET_POINTER_FIELD), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::uint16_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline ::uint16_t PromisedAnswer::Op::Builder::getGetPointerField() { + KJ_IREQUIRE((which() == PromisedAnswer::Op::GET_POINTER_FIELD), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::uint16_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void PromisedAnswer::Op::Builder::setGetPointerField( ::uint16_t value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, PromisedAnswer::Op::GET_POINTER_FIELD); + _builder.setDataField< ::uint16_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline bool ThirdPartyCapDescriptor::Reader::hasId() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool ThirdPartyCapDescriptor::Builder::hasId() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::AnyPointer::Reader ThirdPartyCapDescriptor::Reader::getId() const { + return ::capnp::AnyPointer::Reader(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::AnyPointer::Builder ThirdPartyCapDescriptor::Builder::getId() { + return ::capnp::AnyPointer::Builder(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::AnyPointer::Builder ThirdPartyCapDescriptor::Builder::initId() { + auto result = ::capnp::AnyPointer::Builder(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); + result.clear(); + return result; +} + +inline ::uint32_t ThirdPartyCapDescriptor::Reader::getVineId() const { + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t ThirdPartyCapDescriptor::Builder::getVineId() { + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void ThirdPartyCapDescriptor::Builder::setVineId( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Exception::Reader::hasReason() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Exception::Builder::hasReason() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader Exception::Reader::getReason() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder Exception::Builder::getReason() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Exception::Builder::setReason( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder Exception::Builder::initReason(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), size); +} +inline void Exception::Builder::adoptReason( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> Exception::Builder::disownReason() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool Exception::Reader::getObsoleteIsCallersFault() const { + return _reader.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline bool Exception::Builder::getObsoleteIsCallersFault() { + return _builder.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Exception::Builder::setObsoleteIsCallersFault(bool value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline ::uint16_t Exception::Reader::getObsoleteDurability() const { + return _reader.getDataField< ::uint16_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline ::uint16_t Exception::Builder::getObsoleteDurability() { + return _builder.getDataField< ::uint16_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void Exception::Builder::setObsoleteDurability( ::uint16_t value) { + _builder.setDataField< ::uint16_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline ::capnp::rpc::Exception::Type Exception::Reader::getType() const { + return _reader.getDataField< ::capnp::rpc::Exception::Type>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} + +inline ::capnp::rpc::Exception::Type Exception::Builder::getType() { + return _builder.getDataField< ::capnp::rpc::Exception::Type>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} +inline void Exception::Builder::setType( ::capnp::rpc::Exception::Type value) { + _builder.setDataField< ::capnp::rpc::Exception::Type>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, value); +} + +} // namespace +} // namespace + +#endif // CAPNP_INCLUDED_b312981b2552a250_ diff --git a/phonelibs/capnp-cpp/include/capnp/rpc.h b/phonelibs/capnp-cpp/include/capnp/rpc.h new file mode 100644 index 00000000000000..d84ed982e78314 --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/rpc.h @@ -0,0 +1,537 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef CAPNP_RPC_H_ +#define CAPNP_RPC_H_ + +#if defined(__GNUC__) && !defined(CAPNP_HEADER_WARNINGS) +#pragma GCC system_header +#endif + +#include "capability.h" +#include "rpc-prelude.h" + +namespace capnp { + +template +class VatNetwork; +template +class SturdyRefRestorer; + +template +class BootstrapFactory: public _::BootstrapFactoryBase { + // Interface that constructs per-client bootstrap interfaces. Use this if you want each client + // who connects to see a different bootstrap interface based on their (authenticated) VatId. + // This allows an application to bootstrap off of the authentication performed at the VatNetwork + // level. (Typically VatId is some sort of public key.) + // + // This is only useful for multi-party networks. For TwoPartyVatNetwork, there's no reason to + // use a BootstrapFactory; just specify a single bootstrap capability in this case. + +public: + virtual Capability::Client createFor(typename VatId::Reader clientId) = 0; + // Create a bootstrap capability appropriate for exposing to the given client. VatNetwork will + // have authenticated the client VatId before this is called. + +private: + Capability::Client baseCreateFor(AnyStruct::Reader clientId) override; +}; + +template +class RpcSystem: public _::RpcSystemBase { + // Represents the RPC system, which is the portal to objects available on the network. + // + // The RPC implementation sits on top of an implementation of `VatNetwork`. The `VatNetwork` + // determines how to form connections between vats -- specifically, two-way, private, reliable, + // sequenced datagram connections. The RPC implementation determines how to use such connections + // to manage object references and make method calls. + // + // See `makeRpcServer()` and `makeRpcClient()` below for convenient syntax for setting up an + // `RpcSystem` given a `VatNetwork`. + // + // See `ez-rpc.h` for an even simpler interface for setting up RPC in a typical two-party + // client/server scenario. + +public: + template + RpcSystem( + VatNetwork& network, + kj::Maybe bootstrapInterface, + kj::Maybe::Client> gateway = nullptr); + + template + RpcSystem( + VatNetwork& network, + BootstrapFactory& bootstrapFactory, + kj::Maybe::Client> gateway = nullptr); + + template + RpcSystem( + VatNetwork& network, + SturdyRefRestorer& restorer); + + RpcSystem(RpcSystem&& other) = default; + + Capability::Client bootstrap(typename VatId::Reader vatId); + // Connect to the given vat and return its bootstrap interface. + + Capability::Client restore(typename VatId::Reader hostId, AnyPointer::Reader objectId) + KJ_DEPRECATED("Please transition to using a bootstrap interface instead."); + // ** DEPRECATED ** + // + // Restores the given SturdyRef from the network and return the capability representing it. + // + // `hostId` identifies the host from which to request the ref, in the format specified by the + // `VatNetwork` in use. `objectId` is the object ID in whatever format is expected by said host. + // + // This method will be removed in a future version of Cap'n Proto. Instead, please transition + // to using bootstrap(), which is equivalent to calling restore() with a null `objectId`. + // You may emulate the old concept of object IDs by exporting a bootstrap interface which has + // methods that can be used to obtain other capabilities by ID. + + void setFlowLimit(size_t words); + // Sets the incoming call flow limit. If more than `words` worth of call messages have not yet + // received responses, the RpcSystem will not read further messages from the stream. This can be + // used as a crude way to prevent a resource exhaustion attack (or bug) in which a peer makes an + // excessive number of simultaneous calls that consume the receiver's RAM. + // + // There are some caveats. When over the flow limit, all messages are blocked, including returns. + // If the outstanding calls are themselves waiting on calls going in the opposite direction, the + // flow limit may prevent those calls from completing, leading to deadlock. However, a + // sufficiently high limit should make this unlikely. + // + // Note that a call's parameter size counts against the flow limit until the call returns, even + // if the recipient calls releaseParams() to free the parameter memory early. This is because + // releaseParams() may simply indicate that the parameters have been forwarded to another + // machine, but are still in-memory there. For illustration, say that Alice made a call to Bob + // who forwarded the call to Carol. Bob has imposed a flow limit on Alice. Alice's calls are + // being forwarded to Carol, so Bob never keeps the parameters in-memory for more than a brief + // period. However, the flow limit counts all calls that haven't returned, even if Bob has + // already freed the memory they consumed. You might argue that the right solution here is + // instead for Carol to impose her own flow limit on Bob. This has a serious problem, though: + // Bob might be forwarding requests to Carol on behalf of many different parties, not just Alice. + // If Alice can pump enough data to hit the Bob -> Carol flow limit, then those other parties + // will be disrupted. Thus, we can only really impose the limit on the Alice -> Bob link, which + // only affects Alice. We need that one flow limit to limit Alice's impact on the whole system, + // so it has to count all in-flight calls. + // + // In Sandstorm, flow limits are imposed by the supervisor on calls coming out of a grain, in + // order to prevent a grain from inundating the system with in-flight calls. In practice, the + // main time this happens is when a grain is pushing a large file download and doesn't implement + // proper cooperative flow control. +}; + +template +RpcSystem makeRpcServer( + VatNetwork& network, + Capability::Client bootstrapInterface); +// Make an RPC server. Typical usage (e.g. in a main() function): +// +// MyEventLoop eventLoop; +// kj::WaitScope waitScope(eventLoop); +// MyNetwork network; +// MyMainInterface::Client bootstrap = makeMain(); +// auto server = makeRpcServer(network, bootstrap); +// kj::NEVER_DONE.wait(waitScope); // run forever +// +// See also ez-rpc.h, which has simpler instructions for the common case of a two-party +// client-server RPC connection. + +template , + typename ExternalRef = _::ExternalRefFromRealmGatewayClient> +RpcSystem makeRpcServer( + VatNetwork& network, + Capability::Client bootstrapInterface, RealmGatewayClient gateway); +// Make an RPC server for a VatNetwork that resides in a different realm from the application. +// The given RealmGateway is used to translate SturdyRefs between the app's ("internal") format +// and the network's ("external") format. + +template +RpcSystem makeRpcServer( + VatNetwork& network, + BootstrapFactory& bootstrapFactory); +// Make an RPC server that can serve different bootstrap interfaces to different clients via a +// BootstrapInterface. + +template , + typename ExternalRef = _::ExternalRefFromRealmGatewayClient> +RpcSystem makeRpcServer( + VatNetwork& network, + BootstrapFactory& bootstrapFactory, RealmGatewayClient gateway); +// Make an RPC server that can serve different bootstrap interfaces to different clients via a +// BootstrapInterface and communicates with a different realm than the application is in via a +// RealmGateway. + +template +RpcSystem makeRpcServer( + VatNetwork& network, + SturdyRefRestorer& restorer) + KJ_DEPRECATED("Please transition to using a bootstrap interface instead."); +// ** DEPRECATED ** +// +// Create an RPC server which exports multiple main interfaces by object ID. The `restorer` object +// can be used to look up objects by ID. +// +// Please transition to exporting only one interface, which is known as the "bootstrap" interface. +// For backwards-compatibility with old clients, continue to implement SturdyRefRestorer, but +// return the new bootstrap interface when the request object ID is null. When new clients connect +// and request the bootstrap interface, they will get that interface. Eventually, once all clients +// are updated to request only the bootstrap interface, stop implementing SturdyRefRestorer and +// switch to passing the bootstrap capability itself as the second parameter to `makeRpcServer()`. + +template +RpcSystem makeRpcClient( + VatNetwork& network); +// Make an RPC client. Typical usage (e.g. in a main() function): +// +// MyEventLoop eventLoop; +// kj::WaitScope waitScope(eventLoop); +// MyNetwork network; +// auto client = makeRpcClient(network); +// MyCapability::Client cap = client.restore(hostId, objId).castAs(); +// auto response = cap.fooRequest().send().wait(waitScope); +// handleMyResponse(response); +// +// See also ez-rpc.h, which has simpler instructions for the common case of a two-party +// client-server RPC connection. + +template , + typename ExternalRef = _::ExternalRefFromRealmGatewayClient> +RpcSystem makeRpcClient( + VatNetwork& network, + RealmGatewayClient gateway); +// Make an RPC client for a VatNetwork that resides in a different realm from the application. +// The given RealmGateway is used to translate SturdyRefs between the app's ("internal") format +// and the network's ("external") format. + +template +class SturdyRefRestorer: public _::SturdyRefRestorerBase { + // ** DEPRECATED ** + // + // In Cap'n Proto 0.4.x, applications could export multiple main interfaces identified by + // object IDs. The callback used to map object IDs to objects was `SturdyRefRestorer`, as we + // imagined this would eventually be used for restoring SturdyRefs as well. In practice, it was + // never used for real SturdyRefs, only for exporting singleton objects under well-known names. + // + // The new preferred strategy is to export only a _single_ such interface, called the + // "bootstrap interface". That interface can itself have methods for obtaining other objects, of + // course, but that is up to the app. `SturdyRefRestorer` exists for backwards-compatibility. + // + // Hint: Use SturdyRefRestorer to define a server that exports services under + // string names. + +public: + virtual Capability::Client restore(typename SturdyRefObjectId::Reader ref) + KJ_DEPRECATED( + "Please transition to using bootstrap interfaces instead of SturdyRefRestorer.") = 0; + // Restore the given object, returning a capability representing it. + +private: + Capability::Client baseRestore(AnyPointer::Reader ref) override final; +}; + +// ======================================================================================= +// VatNetwork + +class OutgoingRpcMessage { + // A message to be sent by a `VatNetwork`. + +public: + virtual AnyPointer::Builder getBody() = 0; + // Get the message body, which the caller may fill in any way it wants. (The standard RPC + // implementation initializes it as a Message as defined in rpc.capnp.) + + virtual void send() = 0; + // Send the message, or at least put it in a queue to be sent later. Note that the builder + // returned by `getBody()` remains valid at least until the `OutgoingRpcMessage` is destroyed. +}; + +class IncomingRpcMessage { + // A message received from a `VatNetwork`. + +public: + virtual AnyPointer::Reader getBody() = 0; + // Get the message body, to be interpreted by the caller. (The standard RPC implementation + // interprets it as a Message as defined in rpc.capnp.) +}; + +template +class VatNetwork: public _::VatNetworkBase { + // Cap'n Proto RPC operates between vats, where a "vat" is some sort of host of objects. + // Typically one Cap'n Proto process (in the Unix sense) is one vat. The RPC system is what + // allows calls between objects hosted in different vats. + // + // The RPC implementation sits on top of an implementation of `VatNetwork`. The `VatNetwork` + // determines how to form connections between vats -- specifically, two-way, private, reliable, + // sequenced datagram connections. The RPC implementation determines how to use such connections + // to manage object references and make method calls. + // + // The most common implementation of VatNetwork is TwoPartyVatNetwork (rpc-twoparty.h). Most + // simple client-server apps will want to use it. (You may even want to use the EZ RPC + // interfaces in `ez-rpc.h` and avoid all of this.) + // + // TODO(someday): Provide a standard implementation for the public internet. + +public: + class Connection; + + struct ConnectionAndProvisionId { + // Result of connecting to a vat introduced by another vat. + + kj::Own connection; + // Connection to the new vat. + + kj::Own firstMessage; + // An already-allocated `OutgoingRpcMessage` associated with `connection`. The RPC system will + // construct this as an `Accept` message and send it. + + Orphan provisionId; + // A `ProvisionId` already allocated inside `firstMessage`, which the RPC system will use to + // build the `Accept` message. + }; + + class Connection: public _::VatNetworkBase::Connection { + // A two-way RPC connection. + // + // This object may represent a connection that doesn't exist yet, but is expected to exist + // in the future. In this case, sent messages will automatically be queued and sent once the + // connection is ready, so that the caller doesn't need to know the difference. + + public: + // Level 0 features ---------------------------------------------- + + virtual typename VatId::Reader getPeerVatId() = 0; + // Returns the connected vat's authenticated VatId. It is the VatNetwork's responsibility to + // authenticate this, so that the caller can be assured that they are really talking to the + // identified vat and not an imposter. + + virtual kj::Own newOutgoingMessage(uint firstSegmentWordSize) override = 0; + // Allocate a new message to be sent on this connection. + // + // If `firstSegmentWordSize` is non-zero, it should be treated as a hint suggesting how large + // to make the first segment. This is entirely a hint and the connection may adjust it up or + // down. If it is zero, the connection should choose the size itself. + + virtual kj::Promise>> receiveIncomingMessage() override = 0; + // Wait for a message to be received and return it. If the read stream cleanly terminates, + // return null. If any other problem occurs, throw an exception. + + virtual kj::Promise shutdown() override KJ_WARN_UNUSED_RESULT = 0; + // Waits until all outgoing messages have been sent, then shuts down the outgoing stream. The + // returned promise resolves after shutdown is complete. + + private: + AnyStruct::Reader baseGetPeerVatId() override; + }; + + // Level 0 features ------------------------------------------------ + + virtual kj::Maybe> connect(typename VatId::Reader hostId) = 0; + // Connect to a VatId. Note that this method immediately returns a `Connection`, even + // if the network connection has not yet been established. Messages can be queued to this + // connection and will be delivered once it is open. The caller must attempt to read from the + // connection to verify that it actually succeeded; the read will fail if the connection + // couldn't be opened. Some network implementations may actually start sending messages before + // hearing back from the server at all, to avoid a round trip. + // + // Returns nullptr if `hostId` refers to the local host. + + virtual kj::Promise> accept() = 0; + // Wait for the next incoming connection and return it. + + // Level 4 features ------------------------------------------------ + // TODO(someday) + +private: + kj::Maybe> + baseConnect(AnyStruct::Reader hostId) override final; + kj::Promise> baseAccept() override final; +}; + +// ======================================================================================= +// *************************************************************************************** +// Inline implementation details start here +// *************************************************************************************** +// ======================================================================================= + +template +Capability::Client BootstrapFactory::baseCreateFor(AnyStruct::Reader clientId) { + return createFor(clientId.as()); +} + +template +kj::Maybe> + VatNetwork:: + baseConnect(AnyStruct::Reader ref) { + auto maybe = connect(ref.as()); + return maybe.map([](kj::Own& conn) -> kj::Own<_::VatNetworkBase::Connection> { + return kj::mv(conn); + }); +} + +template +kj::Promise> + VatNetwork::baseAccept() { + return accept().then( + [](kj::Own&& connection) -> kj::Own<_::VatNetworkBase::Connection> { + return kj::mv(connection); + }); +} + +template +AnyStruct::Reader VatNetwork< + SturdyRef, ProvisionId, RecipientId, ThirdPartyCapId, JoinResult>:: + Connection::baseGetPeerVatId() { + return getPeerVatId(); +} + +template +Capability::Client SturdyRefRestorer::baseRestore(AnyPointer::Reader ref) { +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wdeprecated-declarations" + return restore(ref.getAs()); +#pragma GCC diagnostic pop +} + +template +template +RpcSystem::RpcSystem( + VatNetwork& network, + kj::Maybe bootstrap, + kj::Maybe::Client> gateway) + : _::RpcSystemBase(network, kj::mv(bootstrap), kj::mv(gateway)) {} + +template +template +RpcSystem::RpcSystem( + VatNetwork& network, + BootstrapFactory& bootstrapFactory, + kj::Maybe::Client> gateway) + : _::RpcSystemBase(network, bootstrapFactory, kj::mv(gateway)) {} + +template +template +RpcSystem::RpcSystem( + VatNetwork& network, + SturdyRefRestorer& restorer) + : _::RpcSystemBase(network, restorer) {} + +template +Capability::Client RpcSystem::bootstrap(typename VatId::Reader vatId) { + return baseBootstrap(_::PointerHelpers::getInternalReader(vatId)); +} + +template +Capability::Client RpcSystem::restore( + typename VatId::Reader hostId, AnyPointer::Reader objectId) { + return baseRestore(_::PointerHelpers::getInternalReader(hostId), objectId); +} + +template +inline void RpcSystem::setFlowLimit(size_t words) { + baseSetFlowLimit(words); +} + +template +RpcSystem makeRpcServer( + VatNetwork& network, + Capability::Client bootstrapInterface) { + return RpcSystem(network, kj::mv(bootstrapInterface)); +} + +template +RpcSystem makeRpcServer( + VatNetwork& network, + Capability::Client bootstrapInterface, RealmGatewayClient gateway) { + return RpcSystem(network, kj::mv(bootstrapInterface), + gateway.template castAs>()); +} + +template +RpcSystem makeRpcServer( + VatNetwork& network, + BootstrapFactory& bootstrapFactory) { + return RpcSystem(network, bootstrapFactory); +} + +template +RpcSystem makeRpcServer( + VatNetwork& network, + BootstrapFactory& bootstrapFactory, RealmGatewayClient gateway) { + return RpcSystem(network, bootstrapFactory, gateway.template castAs>()); +} + +template +RpcSystem makeRpcServer( + VatNetwork& network, + SturdyRefRestorer& restorer) { + return RpcSystem(network, restorer); +} + +template +RpcSystem makeRpcClient( + VatNetwork& network) { + return RpcSystem(network, nullptr); +} + +template +RpcSystem makeRpcClient( + VatNetwork& network, + RealmGatewayClient gateway) { + return RpcSystem(network, nullptr, gateway.template castAs>()); +} + +} // namespace capnp + +#endif // CAPNP_RPC_H_ diff --git a/phonelibs/capnp-cpp/include/capnp/schema-lite.h b/phonelibs/capnp-cpp/include/capnp/schema-lite.h new file mode 100644 index 00000000000000..58a8c14c05b73e --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/schema-lite.h @@ -0,0 +1,48 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef CAPNP_SCHEMA_LITE_H_ +#define CAPNP_SCHEMA_LITE_H_ + +#if defined(__GNUC__) && !defined(CAPNP_HEADER_WARNINGS) +#pragma GCC system_header +#endif + +#include +#include "message.h" + +namespace capnp { + +template +inline schema::Node::Reader schemaProto() { + // Get the schema::Node for this type's schema. This function works even in lite mode. + return readMessageUnchecked(CapnpPrivate::encodedSchema()); +} + +template ::typeId> +inline schema::Node::Reader schemaProto() { + // Get the schema::Node for this type's schema. This function works even in lite mode. + return readMessageUnchecked(schemas::EnumInfo::encodedSchema()); +} + +} // namespace capnp + +#endif // CAPNP_SCHEMA_LITE_H_ diff --git a/phonelibs/capnp-cpp/include/capnp/schema-loader.h b/phonelibs/capnp-cpp/include/capnp/schema-loader.h new file mode 100644 index 00000000000000..0e34cba77fdbb8 --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/schema-loader.h @@ -0,0 +1,173 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef CAPNP_SCHEMA_LOADER_H_ +#define CAPNP_SCHEMA_LOADER_H_ + +#if defined(__GNUC__) && !defined(CAPNP_HEADER_WARNINGS) +#pragma GCC system_header +#endif + +#include "schema.h" +#include +#include + +namespace capnp { + +class SchemaLoader { + // Class which can be used to construct Schema objects from schema::Nodes as defined in + // schema.capnp. + // + // It is a bad idea to use this class on untrusted input with exceptions disabled -- you may + // be exposing yourself to denial-of-service attacks, as attackers can easily construct schemas + // that are subtly inconsistent in a way that causes exceptions to be thrown either by + // SchemaLoader or by the dynamic API when the schemas are subsequently used. If you enable and + // properly catch exceptions, you should be OK -- assuming no bugs in the Cap'n Proto + // implementation, of course. + +public: + class LazyLoadCallback { + public: + virtual void load(const SchemaLoader& loader, uint64_t id) const = 0; + // Request that the schema node with the given ID be loaded into the given SchemaLoader. If + // the callback is able to find a schema for this ID, it should invoke `loadOnce()` on + // `loader` to load it. If no such node exists, it should simply do nothing and return. + // + // The callback is allowed to load schema nodes other than the one requested, e.g. because it + // expects they will be needed soon. + // + // If the `SchemaLoader` is used from multiple threads, the callback must be thread-safe. + // In particular, it's possible for multiple threads to invoke `load()` with the same ID. + // If the callback performs a large amount of work to look up IDs, it should be sure to + // de-dup these requests. + }; + + SchemaLoader(); + + SchemaLoader(const LazyLoadCallback& callback); + // Construct a SchemaLoader which will invoke the given callback when a schema node is requested + // that isn't already loaded. + + ~SchemaLoader() noexcept(false); + KJ_DISALLOW_COPY(SchemaLoader); + + Schema get(uint64_t id, schema::Brand::Reader brand = schema::Brand::Reader(), + Schema scope = Schema()) const; + // Gets the schema for the given ID, throwing an exception if it isn't present. + // + // The returned schema may be invalidated if load() is called with a new schema for the same ID. + // In general, you should not call load() while a schema from this loader is in-use. + // + // `brand` and `scope` are used to determine brand bindings where relevant. `brand` gives + // parameter bindings for the target type's brand parameters that were specified at the reference + // site. `scope` specifies the scope in which the type ID appeared -- if `brand` itself contains + // parameter references or indicates that some parameters will be inherited, these will be + // interpreted within / inherited from `scope`. + + kj::Maybe tryGet(uint64_t id, schema::Brand::Reader bindings = schema::Brand::Reader(), + Schema scope = Schema()) const; + // Like get() but doesn't throw. + + Schema getUnbound(uint64_t id) const; + // Gets a special version of the schema in which all brand parameters are "unbound". This means + // that if you look up a type via the Schema API, and it resolves to a brand parameter, the + // returned Type's getBrandParameter() method will return info about that parameter. Otherwise, + // normally, all brand parameters that aren't otherwise bound are assumed to simply be + // "AnyPointer". + + Type getType(schema::Type::Reader type, Schema scope = Schema()) const; + // Convenience method which interprets a schema::Type to produce a Type object. Implemented in + // terms of get(). + + Schema load(const schema::Node::Reader& reader); + // Loads the given schema node. Validates the node and throws an exception if invalid. This + // makes a copy of the schema, so the object passed in can be destroyed after this returns. + // + // If the node has any dependencies which are not already loaded, they will be initialized as + // stubs -- empty schemas of whichever kind is expected. + // + // If another schema for the given reader has already been seen, the loader will inspect both + // schemas to determine which one is newer, and use that that one. If the two versions are + // found to be incompatible, an exception is thrown. If the two versions differ but are + // compatible and the loader cannot determine which is newer (e.g., the only changes are renames), + // the existing schema will be preferred. Note that in any case, the loader will end up keeping + // around copies of both schemas, so you shouldn't repeatedly reload schemas into the same loader. + // + // The following properties of the schema node are validated: + // - Struct size and preferred list encoding are valid and consistent. + // - Struct members are fields or unions. + // - Union members are fields. + // - Field offsets are in-bounds. + // - Ordinals and codeOrders are sequential starting from zero. + // - Values are of the right union case to match their types. + // + // You should assume anything not listed above is NOT validated. In particular, things that are + // not validated now, but could be in the future, include but are not limited to: + // - Names. + // - Annotation values. (This is hard because the annotation declaration is not always + // available.) + // - Content of default/constant values of pointer type. (Validating these would require knowing + // their schema, but even if the schemas are available at validation time, they could be + // updated by a subsequent load(), invalidating existing values. Instead, these values are + // validated at the time they are used, as usual for Cap'n Proto objects.) + // + // Also note that unknown types are not considered invalid. Instead, the dynamic API returns + // a DynamicValue with type UNKNOWN for these. + + Schema loadOnce(const schema::Node::Reader& reader) const; + // Like `load()` but does nothing if a schema with the same ID is already loaded. In contrast, + // `load()` would attempt to compare the schemas and take the newer one. `loadOnce()` is safe + // to call even while concurrently using schemas from this loader. It should be considered an + // error to call `loadOnce()` with two non-identical schemas that share the same ID, although + // this error may or may not actually be detected by the implementation. + + template + void loadCompiledTypeAndDependencies(); + // Load the schema for the given compiled-in type and all of its dependencies. + // + // If you want to be able to cast a DynamicValue built from this SchemaLoader to the compiled-in + // type using as(), you must call this method before constructing the DynamicValue. Otherwise, + // as() will throw an exception complaining about type mismatch. + + kj::Array getAllLoaded() const; + // Get a complete list of all loaded schema nodes. It is particularly useful to call this after + // loadCompiledTypeAndDependencies() in order to get a flat list of all of T's transitive + // dependencies. + +private: + class Validator; + class CompatibilityChecker; + class Impl; + class InitializerImpl; + class BrandedInitializerImpl; + kj::MutexGuarded> impl; + + void loadNative(const _::RawSchema* nativeSchema); +}; + +template +inline void SchemaLoader::loadCompiledTypeAndDependencies() { + loadNative(&_::rawSchema()); +} + +} // namespace capnp + +#endif // CAPNP_SCHEMA_LOADER_H_ diff --git a/phonelibs/capnp-cpp/include/capnp/schema-parser.h b/phonelibs/capnp-cpp/include/capnp/schema-parser.h new file mode 100644 index 00000000000000..3322bbfbfbc77a --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/schema-parser.h @@ -0,0 +1,207 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef CAPNP_SCHEMA_PARSER_H_ +#define CAPNP_SCHEMA_PARSER_H_ + +#if defined(__GNUC__) && !defined(CAPNP_HEADER_WARNINGS) +#pragma GCC system_header +#endif + +#include "schema-loader.h" +#include + +namespace capnp { + +class ParsedSchema; +class SchemaFile; + +class SchemaParser { + // Parses `.capnp` files to produce `Schema` objects. + // + // This class is thread-safe, hence all its methods are const. + +public: + SchemaParser(); + ~SchemaParser() noexcept(false); + + ParsedSchema parseDiskFile(kj::StringPtr displayName, kj::StringPtr diskPath, + kj::ArrayPtr importPath) const; + // Parse a file located on disk. Throws an exception if the file dosen't exist. + // + // Parameters: + // * `displayName`: The name that will appear in the file's schema node. (If the file has + // already been parsed, this will be ignored and the display name from the first time it was + // parsed will be kept.) + // * `diskPath`: The path to the file on disk. + // * `importPath`: Directories to search when resolving absolute imports within this file + // (imports that start with a `/`). Must remain valid until the SchemaParser is destroyed. + // (If the file has already been parsed, this will be ignored and the import path from the + // first time it was parsed will be kept.) + // + // This method is a shortcut, equivalent to: + // parser.parseFile(SchemaFile::newDiskFile(displayName, diskPath, importPath))`; + // + // This method throws an exception if any errors are encountered in the file or in anything the + // file depends on. Note that merely importing another file does not count as a dependency on + // anything in the imported file -- only the imported types which are actually used are + // "dependencies". + + ParsedSchema parseFile(kj::Own&& file) const; + // Advanced interface for parsing a file that may or may not be located in any global namespace. + // Most users will prefer `parseDiskFile()`. + // + // If the file has already been parsed (that is, a SchemaFile that compares equal to this one + // was parsed previously), the existing schema will be returned again. + // + // This method reports errors by calling SchemaFile::reportError() on the file where the error + // is located. If that call does not throw an exception, `parseFile()` may in fact return + // normally. In this case, the result is a best-effort attempt to compile the schema, but it + // may be invalid or corrupt, and using it for anything may cause exceptions to be thrown. + + template + inline void loadCompiledTypeAndDependencies() { + // See SchemaLoader::loadCompiledTypeAndDependencies(). + getLoader().loadCompiledTypeAndDependencies(); + } + +private: + struct Impl; + class ModuleImpl; + kj::Own impl; + mutable bool hadErrors = false; + + ModuleImpl& getModuleImpl(kj::Own&& file) const; + SchemaLoader& getLoader(); + + friend class ParsedSchema; +}; + +class ParsedSchema: public Schema { + // ParsedSchema is an extension of Schema which also has the ability to look up nested nodes + // by name. See `SchemaParser`. + +public: + inline ParsedSchema(): parser(nullptr) {} + + kj::Maybe findNested(kj::StringPtr name) const; + // Gets the nested node with the given name, or returns null if there is no such nested + // declaration. + + ParsedSchema getNested(kj::StringPtr name) const; + // Gets the nested node with the given name, or throws an exception if there is no such nested + // declaration. + +private: + inline ParsedSchema(Schema inner, const SchemaParser& parser): Schema(inner), parser(&parser) {} + + const SchemaParser* parser; + friend class SchemaParser; +}; + +// ======================================================================================= +// Advanced API + +class SchemaFile { + // Abstract interface representing a schema file. You can implement this yourself in order to + // gain more control over how the compiler resolves imports and reads files. For the + // common case of files on disk or other global filesystem-like namespaces, use + // `SchemaFile::newDiskFile()`. + +public: + class FileReader { + public: + virtual bool exists(kj::StringPtr path) const = 0; + virtual kj::Array read(kj::StringPtr path) const = 0; + }; + + class DiskFileReader final: public FileReader { + // Implementation of FileReader that uses the local disk. Files are read using mmap() if + // possible. + + public: + static const DiskFileReader instance; + + bool exists(kj::StringPtr path) const override; + kj::Array read(kj::StringPtr path) const override; + }; + + static kj::Own newDiskFile( + kj::StringPtr displayName, kj::StringPtr diskPath, + kj::ArrayPtr importPath, + const FileReader& fileReader = DiskFileReader::instance); + // Construct a SchemaFile representing a file on disk (or located in the filesystem-like + // namespace represented by `fileReader`). + // + // Parameters: + // * `displayName`: The name that will appear in the file's schema node. + // * `diskPath`: The path to the file on disk. + // * `importPath`: Directories to search when resolving absolute imports within this file + // (imports that start with a `/`). The array content must remain valid as long as the + // SchemaFile exists (which is at least as long as the SchemaParser that parses it exists). + // * `fileReader`: Allows you to use a filesystem other than the actual local disk. Although, + // if you find yourself using this, it may make more sense for you to implement SchemaFile + // yourself. + // + // The SchemaFile compares equal to any other SchemaFile that has exactly the same disk path, + // after canonicalization. + // + // The SchemaFile will throw an exception if any errors are reported. + + // ----------------------------------------------------------------- + // For more control, you can implement this interface. + + virtual kj::StringPtr getDisplayName() const = 0; + // Get the file's name, as it should appear in the schema. + + virtual kj::Array readContent() const = 0; + // Read the file's entire content and return it as a byte array. + + virtual kj::Maybe> import(kj::StringPtr path) const = 0; + // Resolve an import, relative to this file. + // + // `path` is exactly what appears between quotes after the `import` keyword in the source code. + // It is entirely up to the `SchemaFile` to decide how to map this to another file. Typically, + // a leading '/' means that the file is an "absolute" path and is searched for in some list of + // schema file repositories. On the other hand, a path that doesn't start with '/' is relative + // to the importing file. + + virtual bool operator==(const SchemaFile& other) const = 0; + virtual bool operator!=(const SchemaFile& other) const = 0; + virtual size_t hashCode() const = 0; + // Compare two SchemaFiles to see if they refer to the same underlying file. This is an + // optimization used to avoid the need to re-parse a file to check its ID. + + struct SourcePos { + uint byte; + uint line; + uint column; + }; + virtual void reportError(SourcePos start, SourcePos end, kj::StringPtr message) const = 0; + // Report that the file contains an error at the given interval. + +private: + class DiskSchemaFile; +}; + +} // namespace capnp + +#endif // CAPNP_SCHEMA_PARSER_H_ diff --git a/phonelibs/capnp-cpp/include/capnp/schema.capnp b/phonelibs/capnp-cpp/include/capnp/schema.capnp new file mode 100644 index 00000000000000..4bef693f6cfd3e --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/schema.capnp @@ -0,0 +1,498 @@ +# Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +# Licensed under the MIT License: +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in +# all copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +# THE SOFTWARE. + +using Cxx = import "/capnp/c++.capnp"; + +@0xa93fc509624c72d9; +$Cxx.namespace("capnp::schema"); + +using Id = UInt64; +# The globally-unique ID of a file, type, or annotation. + +struct Node { + id @0 :Id; + + displayName @1 :Text; + # Name to present to humans to identify this Node. You should not attempt to parse this. Its + # format could change. It is not guaranteed to be unique. + # + # (On Zooko's triangle, this is the node's nickname.) + + displayNamePrefixLength @2 :UInt32; + # If you want a shorter version of `displayName` (just naming this node, without its surrounding + # scope), chop off this many characters from the beginning of `displayName`. + + scopeId @3 :Id; + # ID of the lexical parent node. Typically, the scope node will have a NestedNode pointing back + # at this node, but robust code should avoid relying on this (and, in fact, group nodes are not + # listed in the outer struct's nestedNodes, since they are listed in the fields). `scopeId` is + # zero if the node has no parent, which is normally only the case with files, but should be + # allowed for any kind of node (in order to make runtime type generation easier). + + parameters @32 :List(Parameter); + # If this node is parameterized (generic), the list of parameters. Empty for non-generic types. + + isGeneric @33 :Bool; + # True if this node is generic, meaning that it or one of its parent scopes has a non-empty + # `parameters`. + + struct Parameter { + # Information about one of the node's parameters. + + name @0 :Text; + } + + nestedNodes @4 :List(NestedNode); + # List of nodes nested within this node, along with the names under which they were declared. + + struct NestedNode { + name @0 :Text; + # Unqualified symbol name. Unlike Node.displayName, this *can* be used programmatically. + # + # (On Zooko's triangle, this is the node's petname according to its parent scope.) + + id @1 :Id; + # ID of the nested node. Typically, the target node's scopeId points back to this node, but + # robust code should avoid relying on this. + } + + annotations @5 :List(Annotation); + # Annotations applied to this node. + + union { + # Info specific to each kind of node. + + file @6 :Void; + + struct :group { + dataWordCount @7 :UInt16; + # Size of the data section, in words. + + pointerCount @8 :UInt16; + # Size of the pointer section, in pointers (which are one word each). + + preferredListEncoding @9 :ElementSize; + # The preferred element size to use when encoding a list of this struct. If this is anything + # other than `inlineComposite` then the struct is one word or less in size and is a candidate + # for list packing optimization. + + isGroup @10 :Bool; + # If true, then this "struct" node is actually not an independent node, but merely represents + # some named union or group within a particular parent struct. This node's scopeId refers + # to the parent struct, which may itself be a union/group in yet another struct. + # + # All group nodes share the same dataWordCount and pointerCount as the top-level + # struct, and their fields live in the same ordinal and offset spaces as all other fields in + # the struct. + # + # Note that a named union is considered a special kind of group -- in fact, a named union + # is exactly equivalent to a group that contains nothing but an unnamed union. + + discriminantCount @11 :UInt16; + # Number of fields in this struct which are members of an anonymous union, and thus may + # overlap. If this is non-zero, then a 16-bit discriminant is present indicating which + # of the overlapping fields is active. This can never be 1 -- if it is non-zero, it must be + # two or more. + # + # Note that the fields of an unnamed union are considered fields of the scope containing the + # union -- an unnamed union is not its own group. So, a top-level struct may contain a + # non-zero discriminant count. Named unions, on the other hand, are equivalent to groups + # containing unnamed unions. So, a named union has its own independent schema node, with + # `isGroup` = true. + + discriminantOffset @12 :UInt32; + # If `discriminantCount` is non-zero, this is the offset of the union discriminant, in + # multiples of 16 bits. + + fields @13 :List(Field); + # Fields defined within this scope (either the struct's top-level fields, or the fields of + # a particular group; see `isGroup`). + # + # The fields are sorted by ordinal number, but note that because groups share the same + # ordinal space, the field's index in this list is not necessarily exactly its ordinal. + # On the other hand, the field's position in this list does remain the same even as the + # protocol evolves, since it is not possible to insert or remove an earlier ordinal. + # Therefore, for most use cases, if you want to identify a field by number, it may make the + # most sense to use the field's index in this list rather than its ordinal. + } + + enum :group { + enumerants@14 :List(Enumerant); + # Enumerants ordered by numeric value (ordinal). + } + + interface :group { + methods @15 :List(Method); + # Methods ordered by ordinal. + + superclasses @31 :List(Superclass); + # Superclasses of this interface. + } + + const :group { + type @16 :Type; + value @17 :Value; + } + + annotation :group { + type @18 :Type; + + targetsFile @19 :Bool; + targetsConst @20 :Bool; + targetsEnum @21 :Bool; + targetsEnumerant @22 :Bool; + targetsStruct @23 :Bool; + targetsField @24 :Bool; + targetsUnion @25 :Bool; + targetsGroup @26 :Bool; + targetsInterface @27 :Bool; + targetsMethod @28 :Bool; + targetsParam @29 :Bool; + targetsAnnotation @30 :Bool; + } + } +} + +struct Field { + # Schema for a field of a struct. + + name @0 :Text; + + codeOrder @1 :UInt16; + # Indicates where this member appeared in the code, relative to other members. + # Code ordering may have semantic relevance -- programmers tend to place related fields + # together. So, using code ordering makes sense in human-readable formats where ordering is + # otherwise irrelevant, like JSON. The values of codeOrder are tightly-packed, so the maximum + # value is count(members) - 1. Fields that are members of a union are only ordered relative to + # the other members of that union, so the maximum value there is count(union.members). + + annotations @2 :List(Annotation); + + const noDiscriminant :UInt16 = 0xffff; + + discriminantValue @3 :UInt16 = Field.noDiscriminant; + # If the field is in a union, this is the value which the union's discriminant should take when + # the field is active. If the field is not in a union, this is 0xffff. + + union { + slot :group { + # A regular, non-group, non-fixed-list field. + + offset @4 :UInt32; + # Offset, in units of the field's size, from the beginning of the section in which the field + # resides. E.g. for a UInt32 field, multiply this by 4 to get the byte offset from the + # beginning of the data section. + + type @5 :Type; + defaultValue @6 :Value; + + hadExplicitDefault @10 :Bool; + # Whether the default value was specified explicitly. Non-explicit default values are always + # zero or empty values. Usually, whether the default value was explicit shouldn't matter. + # The main use case for this flag is for structs representing method parameters: + # explicitly-defaulted parameters may be allowed to be omitted when calling the method. + } + + group :group { + # A group. + + typeId @7 :Id; + # The ID of the group's node. + } + } + + ordinal :union { + implicit @8 :Void; + explicit @9 :UInt16; + # The original ordinal number given to the field. You probably should NOT use this; if you need + # a numeric identifier for a field, use its position within the field array for its scope. + # The ordinal is given here mainly just so that the original schema text can be reproduced given + # the compiled version -- i.e. so that `capnp compile -ocapnp` can do its job. + } +} + +struct Enumerant { + # Schema for member of an enum. + + name @0 :Text; + + codeOrder @1 :UInt16; + # Specifies order in which the enumerants were declared in the code. + # Like Struct.Field.codeOrder. + + annotations @2 :List(Annotation); +} + +struct Superclass { + id @0 :Id; + brand @1 :Brand; +} + +struct Method { + # Schema for method of an interface. + + name @0 :Text; + + codeOrder @1 :UInt16; + # Specifies order in which the methods were declared in the code. + # Like Struct.Field.codeOrder. + + implicitParameters @7 :List(Node.Parameter); + # The parameters listed in [] (typically, type / generic parameters), whose bindings are intended + # to be inferred rather than specified explicitly, although not all languages support this. + + paramStructType @2 :Id; + # ID of the parameter struct type. If a named parameter list was specified in the method + # declaration (rather than a single struct parameter type) then a corresponding struct type is + # auto-generated. Such an auto-generated type will not be listed in the interface's + # `nestedNodes` and its `scopeId` will be zero -- it is completely detached from the namespace. + # (Awkwardly, it does of course inherit generic parameters from the method's scope, which makes + # this a situation where you can't just climb the scope chain to find where a particular + # generic parameter was introduced. Making the `scopeId` zero was a mistake.) + + paramBrand @5 :Brand; + # Brand of param struct type. + + resultStructType @3 :Id; + # ID of the return struct type; similar to `paramStructType`. + + resultBrand @6 :Brand; + # Brand of result struct type. + + annotations @4 :List(Annotation); +} + +struct Type { + # Represents a type expression. + + union { + # The ordinals intentionally match those of Value. + + void @0 :Void; + bool @1 :Void; + int8 @2 :Void; + int16 @3 :Void; + int32 @4 :Void; + int64 @5 :Void; + uint8 @6 :Void; + uint16 @7 :Void; + uint32 @8 :Void; + uint64 @9 :Void; + float32 @10 :Void; + float64 @11 :Void; + text @12 :Void; + data @13 :Void; + + list :group { + elementType @14 :Type; + } + + enum :group { + typeId @15 :Id; + brand @21 :Brand; + } + struct :group { + typeId @16 :Id; + brand @22 :Brand; + } + interface :group { + typeId @17 :Id; + brand @23 :Brand; + } + + anyPointer :union { + unconstrained :union { + # A regular AnyPointer. + # + # The name "unconstrained" means as opposed to constraining it to match a type parameter. + # In retrospect this name is probably a poor choice given that it may still be constrained + # to be a struct, list, or capability. + + anyKind @18 :Void; # truly AnyPointer + struct @25 :Void; # AnyStruct + list @26 :Void; # AnyList + capability @27 :Void; # Capability + } + + parameter :group { + # This is actually a reference to a type parameter defined within this scope. + + scopeId @19 :Id; + # ID of the generic type whose parameter we're referencing. This should be a parent of the + # current scope. + + parameterIndex @20 :UInt16; + # Index of the parameter within the generic type's parameter list. + } + + implicitMethodParameter :group { + # This is actually a reference to an implicit (generic) parameter of a method. The only + # legal context for this type to appear is inside Method.paramBrand or Method.resultBrand. + + parameterIndex @24 :UInt16; + } + } + } +} + +struct Brand { + # Specifies bindings for parameters of generics. Since these bindings turn a generic into a + # non-generic, we call it the "brand". + + scopes @0 :List(Scope); + # For each of the target type and each of its parent scopes, a parameterization may be included + # in this list. If no parameterization is included for a particular relevant scope, then either + # that scope has no parameters or all parameters should be considered to be `AnyPointer`. + + struct Scope { + scopeId @0 :Id; + # ID of the scope to which these params apply. + + union { + bind @1 :List(Binding); + # List of parameter bindings. + + inherit @2 :Void; + # The place where this Brand appears is actually within this scope or a sub-scope, + # and the bindings for this scope should be inherited from the reference point. + } + } + + struct Binding { + union { + unbound @0 :Void; + type @1 :Type; + + # TODO(someday): Allow non-type parameters? Unsure if useful. + } + } +} + +struct Value { + # Represents a value, e.g. a field default value, constant value, or annotation value. + + union { + # The ordinals intentionally match those of Type. + + void @0 :Void; + bool @1 :Bool; + int8 @2 :Int8; + int16 @3 :Int16; + int32 @4 :Int32; + int64 @5 :Int64; + uint8 @6 :UInt8; + uint16 @7 :UInt16; + uint32 @8 :UInt32; + uint64 @9 :UInt64; + float32 @10 :Float32; + float64 @11 :Float64; + text @12 :Text; + data @13 :Data; + + list @14 :AnyPointer; + + enum @15 :UInt16; + struct @16 :AnyPointer; + + interface @17 :Void; + # The only interface value that can be represented statically is "null", whose methods always + # throw exceptions. + + anyPointer @18 :AnyPointer; + } +} + +struct Annotation { + # Describes an annotation applied to a declaration. Note AnnotationNode describes the + # annotation's declaration, while this describes a use of the annotation. + + id @0 :Id; + # ID of the annotation node. + + brand @2 :Brand; + # Brand of the annotation. + # + # Note that the annotation itself is not allowed to be parameterized, but its scope might be. + + value @1 :Value; +} + +enum ElementSize { + # Possible element sizes for encoded lists. These correspond exactly to the possible values of + # the 3-bit element size component of a list pointer. + + empty @0; # aka "void", but that's a keyword. + bit @1; + byte @2; + twoBytes @3; + fourBytes @4; + eightBytes @5; + pointer @6; + inlineComposite @7; +} + +struct CapnpVersion { + major @0 :UInt16; + minor @1 :UInt8; + micro @2 :UInt8; +} + +struct CodeGeneratorRequest { + capnpVersion @2 :CapnpVersion; + # Version of the `capnp` executable. Generally, code generators should ignore this, but the code + # generators that ship with `capnp` itself will print a warning if this mismatches since that + # probably indicates something is misconfigured. + # + # The first version of 'capnp' to set this was 0.6.0. So, if it's missing, the compiler version + # is older than that. + + nodes @0 :List(Node); + # All nodes parsed by the compiler, including for the files on the command line and their + # imports. + + requestedFiles @1 :List(RequestedFile); + # Files which were listed on the command line. + + struct RequestedFile { + id @0 :Id; + # ID of the file. + + filename @1 :Text; + # Name of the file as it appeared on the command-line (minus the src-prefix). You may use + # this to decide where to write the output. + + imports @2 :List(Import); + # List of all imported paths seen in this file. + + struct Import { + id @0 :Id; + # ID of the imported file. + + name @1 :Text; + # Name which *this* file used to refer to the foreign file. This may be a relative name. + # This information is provided because it might be useful for code generation, e.g. to + # generate #include directives in C++. We don't put this in Node.file because this + # information is only meaningful at compile time anyway. + # + # (On Zooko's triangle, this is the import's petname according to the importing file.) + } + } +} diff --git a/phonelibs/capnp-cpp/include/capnp/schema.capnp.h b/phonelibs/capnp-cpp/include/capnp/schema.capnp.h new file mode 100644 index 00000000000000..1f116c9f8fe7af --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/schema.capnp.h @@ -0,0 +1,7861 @@ +// Generated by Cap'n Proto compiler, DO NOT EDIT +// source: schema.capnp + +#ifndef CAPNP_INCLUDED_a93fc509624c72d9_ +#define CAPNP_INCLUDED_a93fc509624c72d9_ + +#include + +#if CAPNP_VERSION != 6001 +#error "Version mismatch between generated code and library headers. You must use the same version of the Cap'n Proto compiler and library." +#endif + + +namespace capnp { +namespace schemas { + +CAPNP_DECLARE_SCHEMA(e682ab4cf923a417); +CAPNP_DECLARE_SCHEMA(b9521bccf10fa3b1); +CAPNP_DECLARE_SCHEMA(debf55bbfa0fc242); +CAPNP_DECLARE_SCHEMA(9ea0b19b37fb4435); +CAPNP_DECLARE_SCHEMA(b54ab3364333f598); +CAPNP_DECLARE_SCHEMA(e82753cff0c2218f); +CAPNP_DECLARE_SCHEMA(b18aa5ac7a0d9420); +CAPNP_DECLARE_SCHEMA(ec1619d4400a0290); +CAPNP_DECLARE_SCHEMA(9aad50a41f4af45f); +CAPNP_DECLARE_SCHEMA(97b14cbe7cfec712); +CAPNP_DECLARE_SCHEMA(c42305476bb4746f); +CAPNP_DECLARE_SCHEMA(cafccddb68db1d11); +CAPNP_DECLARE_SCHEMA(bb90d5c287870be6); +CAPNP_DECLARE_SCHEMA(978a7cebdc549a4d); +CAPNP_DECLARE_SCHEMA(a9962a9ed0a4d7f8); +CAPNP_DECLARE_SCHEMA(9500cce23b334d80); +CAPNP_DECLARE_SCHEMA(d07378ede1f9cc60); +CAPNP_DECLARE_SCHEMA(87e739250a60ea97); +CAPNP_DECLARE_SCHEMA(9e0e78711a7f87a9); +CAPNP_DECLARE_SCHEMA(ac3a6f60ef4cc6d3); +CAPNP_DECLARE_SCHEMA(ed8bca69f7fb0cbf); +CAPNP_DECLARE_SCHEMA(c2573fe8a23e49f1); +CAPNP_DECLARE_SCHEMA(8e3b5f79fe593656); +CAPNP_DECLARE_SCHEMA(9dd1f724f4614a85); +CAPNP_DECLARE_SCHEMA(baefc9120c56e274); +CAPNP_DECLARE_SCHEMA(903455f06065422b); +CAPNP_DECLARE_SCHEMA(abd73485a9636bc9); +CAPNP_DECLARE_SCHEMA(c863cd16969ee7fc); +CAPNP_DECLARE_SCHEMA(ce23dcd2d7b00c9b); +CAPNP_DECLARE_SCHEMA(f1c8950dab257542); +CAPNP_DECLARE_SCHEMA(d1958f7dba521926); +enum class ElementSize_d1958f7dba521926: uint16_t { + EMPTY, + BIT, + BYTE, + TWO_BYTES, + FOUR_BYTES, + EIGHT_BYTES, + POINTER, + INLINE_COMPOSITE, +}; +CAPNP_DECLARE_ENUM(ElementSize, d1958f7dba521926); +CAPNP_DECLARE_SCHEMA(d85d305b7d839963); +CAPNP_DECLARE_SCHEMA(bfc546f6210ad7ce); +CAPNP_DECLARE_SCHEMA(cfea0eb02e810062); +CAPNP_DECLARE_SCHEMA(ae504193122357e5); + +} // namespace schemas +} // namespace capnp + +namespace capnp { +namespace schema { + +struct Node { + Node() = delete; + + class Reader; + class Builder; + class Pipeline; + enum Which: uint16_t { + FILE, + STRUCT, + ENUM, + INTERFACE, + CONST, + ANNOTATION, + }; + struct Parameter; + struct NestedNode; + struct Struct; + struct Enum; + struct Interface; + struct Const; + struct Annotation; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(e682ab4cf923a417, 5, 6) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Node::Parameter { + Parameter() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(b9521bccf10fa3b1, 0, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Node::NestedNode { + NestedNode() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(debf55bbfa0fc242, 1, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Node::Struct { + Struct() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(9ea0b19b37fb4435, 5, 6) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Node::Enum { + Enum() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(b54ab3364333f598, 5, 6) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Node::Interface { + Interface() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(e82753cff0c2218f, 5, 6) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Node::Const { + Const() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(b18aa5ac7a0d9420, 5, 6) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Node::Annotation { + Annotation() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(ec1619d4400a0290, 5, 6) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Field { + Field() = delete; + + class Reader; + class Builder; + class Pipeline; + enum Which: uint16_t { + SLOT, + GROUP, + }; + static constexpr ::uint16_t NO_DISCRIMINANT = 65535u; + struct Slot; + struct Group; + struct Ordinal; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(9aad50a41f4af45f, 3, 4) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Field::Slot { + Slot() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(c42305476bb4746f, 3, 4) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Field::Group { + Group() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(cafccddb68db1d11, 3, 4) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Field::Ordinal { + Ordinal() = delete; + + class Reader; + class Builder; + class Pipeline; + enum Which: uint16_t { + IMPLICIT, + EXPLICIT, + }; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(bb90d5c287870be6, 3, 4) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Enumerant { + Enumerant() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(978a7cebdc549a4d, 1, 2) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Superclass { + Superclass() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(a9962a9ed0a4d7f8, 1, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Method { + Method() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(9500cce23b334d80, 3, 5) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Type { + Type() = delete; + + class Reader; + class Builder; + class Pipeline; + enum Which: uint16_t { + VOID, + BOOL, + INT8, + INT16, + INT32, + INT64, + UINT8, + UINT16, + UINT32, + UINT64, + FLOAT32, + FLOAT64, + TEXT, + DATA, + LIST, + ENUM, + STRUCT, + INTERFACE, + ANY_POINTER, + }; + struct List; + struct Enum; + struct Struct; + struct Interface; + struct AnyPointer; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(d07378ede1f9cc60, 3, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Type::List { + List() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(87e739250a60ea97, 3, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Type::Enum { + Enum() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(9e0e78711a7f87a9, 3, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Type::Struct { + Struct() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(ac3a6f60ef4cc6d3, 3, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Type::Interface { + Interface() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(ed8bca69f7fb0cbf, 3, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Type::AnyPointer { + AnyPointer() = delete; + + class Reader; + class Builder; + class Pipeline; + enum Which: uint16_t { + UNCONSTRAINED, + PARAMETER, + IMPLICIT_METHOD_PARAMETER, + }; + struct Unconstrained; + struct Parameter; + struct ImplicitMethodParameter; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(c2573fe8a23e49f1, 3, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Type::AnyPointer::Unconstrained { + Unconstrained() = delete; + + class Reader; + class Builder; + class Pipeline; + enum Which: uint16_t { + ANY_KIND, + STRUCT, + LIST, + CAPABILITY, + }; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(8e3b5f79fe593656, 3, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Type::AnyPointer::Parameter { + Parameter() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(9dd1f724f4614a85, 3, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Type::AnyPointer::ImplicitMethodParameter { + ImplicitMethodParameter() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(baefc9120c56e274, 3, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Brand { + Brand() = delete; + + class Reader; + class Builder; + class Pipeline; + struct Scope; + struct Binding; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(903455f06065422b, 0, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Brand::Scope { + Scope() = delete; + + class Reader; + class Builder; + class Pipeline; + enum Which: uint16_t { + BIND, + INHERIT, + }; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(abd73485a9636bc9, 2, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Brand::Binding { + Binding() = delete; + + class Reader; + class Builder; + class Pipeline; + enum Which: uint16_t { + UNBOUND, + TYPE, + }; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(c863cd16969ee7fc, 1, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Value { + Value() = delete; + + class Reader; + class Builder; + class Pipeline; + enum Which: uint16_t { + VOID, + BOOL, + INT8, + INT16, + INT32, + INT64, + UINT8, + UINT16, + UINT32, + UINT64, + FLOAT32, + FLOAT64, + TEXT, + DATA, + LIST, + ENUM, + STRUCT, + INTERFACE, + ANY_POINTER, + }; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(ce23dcd2d7b00c9b, 2, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Annotation { + Annotation() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(f1c8950dab257542, 1, 2) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +typedef ::capnp::schemas::ElementSize_d1958f7dba521926 ElementSize; + +struct CapnpVersion { + CapnpVersion() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(d85d305b7d839963, 1, 0) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct CodeGeneratorRequest { + CodeGeneratorRequest() = delete; + + class Reader; + class Builder; + class Pipeline; + struct RequestedFile; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(bfc546f6210ad7ce, 0, 3) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct CodeGeneratorRequest::RequestedFile { + RequestedFile() = delete; + + class Reader; + class Builder; + class Pipeline; + struct Import; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(cfea0eb02e810062, 1, 2) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct CodeGeneratorRequest::RequestedFile::Import { + Import() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(ae504193122357e5, 1, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +// ======================================================================================= + +class Node::Reader { +public: + typedef Node Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline Which which() const; + inline ::uint64_t getId() const; + + inline bool hasDisplayName() const; + inline ::capnp::Text::Reader getDisplayName() const; + + inline ::uint32_t getDisplayNamePrefixLength() const; + + inline ::uint64_t getScopeId() const; + + inline bool hasNestedNodes() const; + inline ::capnp::List< ::capnp::schema::Node::NestedNode>::Reader getNestedNodes() const; + + inline bool hasAnnotations() const; + inline ::capnp::List< ::capnp::schema::Annotation>::Reader getAnnotations() const; + + inline bool isFile() const; + inline ::capnp::Void getFile() const; + + inline bool isStruct() const; + inline typename Struct::Reader getStruct() const; + + inline bool isEnum() const; + inline typename Enum::Reader getEnum() const; + + inline bool isInterface() const; + inline typename Interface::Reader getInterface() const; + + inline bool isConst() const; + inline typename Const::Reader getConst() const; + + inline bool isAnnotation() const; + inline typename Annotation::Reader getAnnotation() const; + + inline bool hasParameters() const; + inline ::capnp::List< ::capnp::schema::Node::Parameter>::Reader getParameters() const; + + inline bool getIsGeneric() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Node::Builder { +public: + typedef Node Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline Which which(); + inline ::uint64_t getId(); + inline void setId( ::uint64_t value); + + inline bool hasDisplayName(); + inline ::capnp::Text::Builder getDisplayName(); + inline void setDisplayName( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initDisplayName(unsigned int size); + inline void adoptDisplayName(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownDisplayName(); + + inline ::uint32_t getDisplayNamePrefixLength(); + inline void setDisplayNamePrefixLength( ::uint32_t value); + + inline ::uint64_t getScopeId(); + inline void setScopeId( ::uint64_t value); + + inline bool hasNestedNodes(); + inline ::capnp::List< ::capnp::schema::Node::NestedNode>::Builder getNestedNodes(); + inline void setNestedNodes( ::capnp::List< ::capnp::schema::Node::NestedNode>::Reader value); + inline ::capnp::List< ::capnp::schema::Node::NestedNode>::Builder initNestedNodes(unsigned int size); + inline void adoptNestedNodes(::capnp::Orphan< ::capnp::List< ::capnp::schema::Node::NestedNode>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::capnp::schema::Node::NestedNode>> disownNestedNodes(); + + inline bool hasAnnotations(); + inline ::capnp::List< ::capnp::schema::Annotation>::Builder getAnnotations(); + inline void setAnnotations( ::capnp::List< ::capnp::schema::Annotation>::Reader value); + inline ::capnp::List< ::capnp::schema::Annotation>::Builder initAnnotations(unsigned int size); + inline void adoptAnnotations(::capnp::Orphan< ::capnp::List< ::capnp::schema::Annotation>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::capnp::schema::Annotation>> disownAnnotations(); + + inline bool isFile(); + inline ::capnp::Void getFile(); + inline void setFile( ::capnp::Void value = ::capnp::VOID); + + inline bool isStruct(); + inline typename Struct::Builder getStruct(); + inline typename Struct::Builder initStruct(); + + inline bool isEnum(); + inline typename Enum::Builder getEnum(); + inline typename Enum::Builder initEnum(); + + inline bool isInterface(); + inline typename Interface::Builder getInterface(); + inline typename Interface::Builder initInterface(); + + inline bool isConst(); + inline typename Const::Builder getConst(); + inline typename Const::Builder initConst(); + + inline bool isAnnotation(); + inline typename Annotation::Builder getAnnotation(); + inline typename Annotation::Builder initAnnotation(); + + inline bool hasParameters(); + inline ::capnp::List< ::capnp::schema::Node::Parameter>::Builder getParameters(); + inline void setParameters( ::capnp::List< ::capnp::schema::Node::Parameter>::Reader value); + inline ::capnp::List< ::capnp::schema::Node::Parameter>::Builder initParameters(unsigned int size); + inline void adoptParameters(::capnp::Orphan< ::capnp::List< ::capnp::schema::Node::Parameter>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::capnp::schema::Node::Parameter>> disownParameters(); + + inline bool getIsGeneric(); + inline void setIsGeneric(bool value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Node::Pipeline { +public: + typedef Node Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Node::Parameter::Reader { +public: + typedef Parameter Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasName() const; + inline ::capnp::Text::Reader getName() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Node::Parameter::Builder { +public: + typedef Parameter Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasName(); + inline ::capnp::Text::Builder getName(); + inline void setName( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initName(unsigned int size); + inline void adoptName(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownName(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Node::Parameter::Pipeline { +public: + typedef Parameter Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Node::NestedNode::Reader { +public: + typedef NestedNode Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasName() const; + inline ::capnp::Text::Reader getName() const; + + inline ::uint64_t getId() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Node::NestedNode::Builder { +public: + typedef NestedNode Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasName(); + inline ::capnp::Text::Builder getName(); + inline void setName( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initName(unsigned int size); + inline void adoptName(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownName(); + + inline ::uint64_t getId(); + inline void setId( ::uint64_t value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Node::NestedNode::Pipeline { +public: + typedef NestedNode Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Node::Struct::Reader { +public: + typedef Struct Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline ::uint16_t getDataWordCount() const; + + inline ::uint16_t getPointerCount() const; + + inline ::capnp::schema::ElementSize getPreferredListEncoding() const; + + inline bool getIsGroup() const; + + inline ::uint16_t getDiscriminantCount() const; + + inline ::uint32_t getDiscriminantOffset() const; + + inline bool hasFields() const; + inline ::capnp::List< ::capnp::schema::Field>::Reader getFields() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Node::Struct::Builder { +public: + typedef Struct Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint16_t getDataWordCount(); + inline void setDataWordCount( ::uint16_t value); + + inline ::uint16_t getPointerCount(); + inline void setPointerCount( ::uint16_t value); + + inline ::capnp::schema::ElementSize getPreferredListEncoding(); + inline void setPreferredListEncoding( ::capnp::schema::ElementSize value); + + inline bool getIsGroup(); + inline void setIsGroup(bool value); + + inline ::uint16_t getDiscriminantCount(); + inline void setDiscriminantCount( ::uint16_t value); + + inline ::uint32_t getDiscriminantOffset(); + inline void setDiscriminantOffset( ::uint32_t value); + + inline bool hasFields(); + inline ::capnp::List< ::capnp::schema::Field>::Builder getFields(); + inline void setFields( ::capnp::List< ::capnp::schema::Field>::Reader value); + inline ::capnp::List< ::capnp::schema::Field>::Builder initFields(unsigned int size); + inline void adoptFields(::capnp::Orphan< ::capnp::List< ::capnp::schema::Field>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::capnp::schema::Field>> disownFields(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Node::Struct::Pipeline { +public: + typedef Struct Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Node::Enum::Reader { +public: + typedef Enum Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasEnumerants() const; + inline ::capnp::List< ::capnp::schema::Enumerant>::Reader getEnumerants() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Node::Enum::Builder { +public: + typedef Enum Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasEnumerants(); + inline ::capnp::List< ::capnp::schema::Enumerant>::Builder getEnumerants(); + inline void setEnumerants( ::capnp::List< ::capnp::schema::Enumerant>::Reader value); + inline ::capnp::List< ::capnp::schema::Enumerant>::Builder initEnumerants(unsigned int size); + inline void adoptEnumerants(::capnp::Orphan< ::capnp::List< ::capnp::schema::Enumerant>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::capnp::schema::Enumerant>> disownEnumerants(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Node::Enum::Pipeline { +public: + typedef Enum Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Node::Interface::Reader { +public: + typedef Interface Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasMethods() const; + inline ::capnp::List< ::capnp::schema::Method>::Reader getMethods() const; + + inline bool hasSuperclasses() const; + inline ::capnp::List< ::capnp::schema::Superclass>::Reader getSuperclasses() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Node::Interface::Builder { +public: + typedef Interface Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasMethods(); + inline ::capnp::List< ::capnp::schema::Method>::Builder getMethods(); + inline void setMethods( ::capnp::List< ::capnp::schema::Method>::Reader value); + inline ::capnp::List< ::capnp::schema::Method>::Builder initMethods(unsigned int size); + inline void adoptMethods(::capnp::Orphan< ::capnp::List< ::capnp::schema::Method>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::capnp::schema::Method>> disownMethods(); + + inline bool hasSuperclasses(); + inline ::capnp::List< ::capnp::schema::Superclass>::Builder getSuperclasses(); + inline void setSuperclasses( ::capnp::List< ::capnp::schema::Superclass>::Reader value); + inline ::capnp::List< ::capnp::schema::Superclass>::Builder initSuperclasses(unsigned int size); + inline void adoptSuperclasses(::capnp::Orphan< ::capnp::List< ::capnp::schema::Superclass>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::capnp::schema::Superclass>> disownSuperclasses(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Node::Interface::Pipeline { +public: + typedef Interface Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Node::Const::Reader { +public: + typedef Const Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasType() const; + inline ::capnp::schema::Type::Reader getType() const; + + inline bool hasValue() const; + inline ::capnp::schema::Value::Reader getValue() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Node::Const::Builder { +public: + typedef Const Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasType(); + inline ::capnp::schema::Type::Builder getType(); + inline void setType( ::capnp::schema::Type::Reader value); + inline ::capnp::schema::Type::Builder initType(); + inline void adoptType(::capnp::Orphan< ::capnp::schema::Type>&& value); + inline ::capnp::Orphan< ::capnp::schema::Type> disownType(); + + inline bool hasValue(); + inline ::capnp::schema::Value::Builder getValue(); + inline void setValue( ::capnp::schema::Value::Reader value); + inline ::capnp::schema::Value::Builder initValue(); + inline void adoptValue(::capnp::Orphan< ::capnp::schema::Value>&& value); + inline ::capnp::Orphan< ::capnp::schema::Value> disownValue(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Node::Const::Pipeline { +public: + typedef Const Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::capnp::schema::Type::Pipeline getType(); + inline ::capnp::schema::Value::Pipeline getValue(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Node::Annotation::Reader { +public: + typedef Annotation Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasType() const; + inline ::capnp::schema::Type::Reader getType() const; + + inline bool getTargetsFile() const; + + inline bool getTargetsConst() const; + + inline bool getTargetsEnum() const; + + inline bool getTargetsEnumerant() const; + + inline bool getTargetsStruct() const; + + inline bool getTargetsField() const; + + inline bool getTargetsUnion() const; + + inline bool getTargetsGroup() const; + + inline bool getTargetsInterface() const; + + inline bool getTargetsMethod() const; + + inline bool getTargetsParam() const; + + inline bool getTargetsAnnotation() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Node::Annotation::Builder { +public: + typedef Annotation Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasType(); + inline ::capnp::schema::Type::Builder getType(); + inline void setType( ::capnp::schema::Type::Reader value); + inline ::capnp::schema::Type::Builder initType(); + inline void adoptType(::capnp::Orphan< ::capnp::schema::Type>&& value); + inline ::capnp::Orphan< ::capnp::schema::Type> disownType(); + + inline bool getTargetsFile(); + inline void setTargetsFile(bool value); + + inline bool getTargetsConst(); + inline void setTargetsConst(bool value); + + inline bool getTargetsEnum(); + inline void setTargetsEnum(bool value); + + inline bool getTargetsEnumerant(); + inline void setTargetsEnumerant(bool value); + + inline bool getTargetsStruct(); + inline void setTargetsStruct(bool value); + + inline bool getTargetsField(); + inline void setTargetsField(bool value); + + inline bool getTargetsUnion(); + inline void setTargetsUnion(bool value); + + inline bool getTargetsGroup(); + inline void setTargetsGroup(bool value); + + inline bool getTargetsInterface(); + inline void setTargetsInterface(bool value); + + inline bool getTargetsMethod(); + inline void setTargetsMethod(bool value); + + inline bool getTargetsParam(); + inline void setTargetsParam(bool value); + + inline bool getTargetsAnnotation(); + inline void setTargetsAnnotation(bool value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Node::Annotation::Pipeline { +public: + typedef Annotation Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::capnp::schema::Type::Pipeline getType(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Field::Reader { +public: + typedef Field Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline Which which() const; + inline bool hasName() const; + inline ::capnp::Text::Reader getName() const; + + inline ::uint16_t getCodeOrder() const; + + inline bool hasAnnotations() const; + inline ::capnp::List< ::capnp::schema::Annotation>::Reader getAnnotations() const; + + inline ::uint16_t getDiscriminantValue() const; + + inline bool isSlot() const; + inline typename Slot::Reader getSlot() const; + + inline bool isGroup() const; + inline typename Group::Reader getGroup() const; + + inline typename Ordinal::Reader getOrdinal() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Field::Builder { +public: + typedef Field Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline Which which(); + inline bool hasName(); + inline ::capnp::Text::Builder getName(); + inline void setName( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initName(unsigned int size); + inline void adoptName(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownName(); + + inline ::uint16_t getCodeOrder(); + inline void setCodeOrder( ::uint16_t value); + + inline bool hasAnnotations(); + inline ::capnp::List< ::capnp::schema::Annotation>::Builder getAnnotations(); + inline void setAnnotations( ::capnp::List< ::capnp::schema::Annotation>::Reader value); + inline ::capnp::List< ::capnp::schema::Annotation>::Builder initAnnotations(unsigned int size); + inline void adoptAnnotations(::capnp::Orphan< ::capnp::List< ::capnp::schema::Annotation>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::capnp::schema::Annotation>> disownAnnotations(); + + inline ::uint16_t getDiscriminantValue(); + inline void setDiscriminantValue( ::uint16_t value); + + inline bool isSlot(); + inline typename Slot::Builder getSlot(); + inline typename Slot::Builder initSlot(); + + inline bool isGroup(); + inline typename Group::Builder getGroup(); + inline typename Group::Builder initGroup(); + + inline typename Ordinal::Builder getOrdinal(); + inline typename Ordinal::Builder initOrdinal(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Field::Pipeline { +public: + typedef Field Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline typename Ordinal::Pipeline getOrdinal(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Field::Slot::Reader { +public: + typedef Slot Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline ::uint32_t getOffset() const; + + inline bool hasType() const; + inline ::capnp::schema::Type::Reader getType() const; + + inline bool hasDefaultValue() const; + inline ::capnp::schema::Value::Reader getDefaultValue() const; + + inline bool getHadExplicitDefault() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Field::Slot::Builder { +public: + typedef Slot Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint32_t getOffset(); + inline void setOffset( ::uint32_t value); + + inline bool hasType(); + inline ::capnp::schema::Type::Builder getType(); + inline void setType( ::capnp::schema::Type::Reader value); + inline ::capnp::schema::Type::Builder initType(); + inline void adoptType(::capnp::Orphan< ::capnp::schema::Type>&& value); + inline ::capnp::Orphan< ::capnp::schema::Type> disownType(); + + inline bool hasDefaultValue(); + inline ::capnp::schema::Value::Builder getDefaultValue(); + inline void setDefaultValue( ::capnp::schema::Value::Reader value); + inline ::capnp::schema::Value::Builder initDefaultValue(); + inline void adoptDefaultValue(::capnp::Orphan< ::capnp::schema::Value>&& value); + inline ::capnp::Orphan< ::capnp::schema::Value> disownDefaultValue(); + + inline bool getHadExplicitDefault(); + inline void setHadExplicitDefault(bool value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Field::Slot::Pipeline { +public: + typedef Slot Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::capnp::schema::Type::Pipeline getType(); + inline ::capnp::schema::Value::Pipeline getDefaultValue(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Field::Group::Reader { +public: + typedef Group Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline ::uint64_t getTypeId() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Field::Group::Builder { +public: + typedef Group Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint64_t getTypeId(); + inline void setTypeId( ::uint64_t value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Field::Group::Pipeline { +public: + typedef Group Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Field::Ordinal::Reader { +public: + typedef Ordinal Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline Which which() const; + inline bool isImplicit() const; + inline ::capnp::Void getImplicit() const; + + inline bool isExplicit() const; + inline ::uint16_t getExplicit() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Field::Ordinal::Builder { +public: + typedef Ordinal Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline Which which(); + inline bool isImplicit(); + inline ::capnp::Void getImplicit(); + inline void setImplicit( ::capnp::Void value = ::capnp::VOID); + + inline bool isExplicit(); + inline ::uint16_t getExplicit(); + inline void setExplicit( ::uint16_t value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Field::Ordinal::Pipeline { +public: + typedef Ordinal Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Enumerant::Reader { +public: + typedef Enumerant Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasName() const; + inline ::capnp::Text::Reader getName() const; + + inline ::uint16_t getCodeOrder() const; + + inline bool hasAnnotations() const; + inline ::capnp::List< ::capnp::schema::Annotation>::Reader getAnnotations() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Enumerant::Builder { +public: + typedef Enumerant Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasName(); + inline ::capnp::Text::Builder getName(); + inline void setName( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initName(unsigned int size); + inline void adoptName(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownName(); + + inline ::uint16_t getCodeOrder(); + inline void setCodeOrder( ::uint16_t value); + + inline bool hasAnnotations(); + inline ::capnp::List< ::capnp::schema::Annotation>::Builder getAnnotations(); + inline void setAnnotations( ::capnp::List< ::capnp::schema::Annotation>::Reader value); + inline ::capnp::List< ::capnp::schema::Annotation>::Builder initAnnotations(unsigned int size); + inline void adoptAnnotations(::capnp::Orphan< ::capnp::List< ::capnp::schema::Annotation>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::capnp::schema::Annotation>> disownAnnotations(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Enumerant::Pipeline { +public: + typedef Enumerant Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Superclass::Reader { +public: + typedef Superclass Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline ::uint64_t getId() const; + + inline bool hasBrand() const; + inline ::capnp::schema::Brand::Reader getBrand() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Superclass::Builder { +public: + typedef Superclass Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint64_t getId(); + inline void setId( ::uint64_t value); + + inline bool hasBrand(); + inline ::capnp::schema::Brand::Builder getBrand(); + inline void setBrand( ::capnp::schema::Brand::Reader value); + inline ::capnp::schema::Brand::Builder initBrand(); + inline void adoptBrand(::capnp::Orphan< ::capnp::schema::Brand>&& value); + inline ::capnp::Orphan< ::capnp::schema::Brand> disownBrand(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Superclass::Pipeline { +public: + typedef Superclass Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::capnp::schema::Brand::Pipeline getBrand(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Method::Reader { +public: + typedef Method Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasName() const; + inline ::capnp::Text::Reader getName() const; + + inline ::uint16_t getCodeOrder() const; + + inline ::uint64_t getParamStructType() const; + + inline ::uint64_t getResultStructType() const; + + inline bool hasAnnotations() const; + inline ::capnp::List< ::capnp::schema::Annotation>::Reader getAnnotations() const; + + inline bool hasParamBrand() const; + inline ::capnp::schema::Brand::Reader getParamBrand() const; + + inline bool hasResultBrand() const; + inline ::capnp::schema::Brand::Reader getResultBrand() const; + + inline bool hasImplicitParameters() const; + inline ::capnp::List< ::capnp::schema::Node::Parameter>::Reader getImplicitParameters() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Method::Builder { +public: + typedef Method Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasName(); + inline ::capnp::Text::Builder getName(); + inline void setName( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initName(unsigned int size); + inline void adoptName(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownName(); + + inline ::uint16_t getCodeOrder(); + inline void setCodeOrder( ::uint16_t value); + + inline ::uint64_t getParamStructType(); + inline void setParamStructType( ::uint64_t value); + + inline ::uint64_t getResultStructType(); + inline void setResultStructType( ::uint64_t value); + + inline bool hasAnnotations(); + inline ::capnp::List< ::capnp::schema::Annotation>::Builder getAnnotations(); + inline void setAnnotations( ::capnp::List< ::capnp::schema::Annotation>::Reader value); + inline ::capnp::List< ::capnp::schema::Annotation>::Builder initAnnotations(unsigned int size); + inline void adoptAnnotations(::capnp::Orphan< ::capnp::List< ::capnp::schema::Annotation>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::capnp::schema::Annotation>> disownAnnotations(); + + inline bool hasParamBrand(); + inline ::capnp::schema::Brand::Builder getParamBrand(); + inline void setParamBrand( ::capnp::schema::Brand::Reader value); + inline ::capnp::schema::Brand::Builder initParamBrand(); + inline void adoptParamBrand(::capnp::Orphan< ::capnp::schema::Brand>&& value); + inline ::capnp::Orphan< ::capnp::schema::Brand> disownParamBrand(); + + inline bool hasResultBrand(); + inline ::capnp::schema::Brand::Builder getResultBrand(); + inline void setResultBrand( ::capnp::schema::Brand::Reader value); + inline ::capnp::schema::Brand::Builder initResultBrand(); + inline void adoptResultBrand(::capnp::Orphan< ::capnp::schema::Brand>&& value); + inline ::capnp::Orphan< ::capnp::schema::Brand> disownResultBrand(); + + inline bool hasImplicitParameters(); + inline ::capnp::List< ::capnp::schema::Node::Parameter>::Builder getImplicitParameters(); + inline void setImplicitParameters( ::capnp::List< ::capnp::schema::Node::Parameter>::Reader value); + inline ::capnp::List< ::capnp::schema::Node::Parameter>::Builder initImplicitParameters(unsigned int size); + inline void adoptImplicitParameters(::capnp::Orphan< ::capnp::List< ::capnp::schema::Node::Parameter>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::capnp::schema::Node::Parameter>> disownImplicitParameters(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Method::Pipeline { +public: + typedef Method Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::capnp::schema::Brand::Pipeline getParamBrand(); + inline ::capnp::schema::Brand::Pipeline getResultBrand(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Type::Reader { +public: + typedef Type Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline Which which() const; + inline bool isVoid() const; + inline ::capnp::Void getVoid() const; + + inline bool isBool() const; + inline ::capnp::Void getBool() const; + + inline bool isInt8() const; + inline ::capnp::Void getInt8() const; + + inline bool isInt16() const; + inline ::capnp::Void getInt16() const; + + inline bool isInt32() const; + inline ::capnp::Void getInt32() const; + + inline bool isInt64() const; + inline ::capnp::Void getInt64() const; + + inline bool isUint8() const; + inline ::capnp::Void getUint8() const; + + inline bool isUint16() const; + inline ::capnp::Void getUint16() const; + + inline bool isUint32() const; + inline ::capnp::Void getUint32() const; + + inline bool isUint64() const; + inline ::capnp::Void getUint64() const; + + inline bool isFloat32() const; + inline ::capnp::Void getFloat32() const; + + inline bool isFloat64() const; + inline ::capnp::Void getFloat64() const; + + inline bool isText() const; + inline ::capnp::Void getText() const; + + inline bool isData() const; + inline ::capnp::Void getData() const; + + inline bool isList() const; + inline typename List::Reader getList() const; + + inline bool isEnum() const; + inline typename Enum::Reader getEnum() const; + + inline bool isStruct() const; + inline typename Struct::Reader getStruct() const; + + inline bool isInterface() const; + inline typename Interface::Reader getInterface() const; + + inline bool isAnyPointer() const; + inline typename AnyPointer::Reader getAnyPointer() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Type::Builder { +public: + typedef Type Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline Which which(); + inline bool isVoid(); + inline ::capnp::Void getVoid(); + inline void setVoid( ::capnp::Void value = ::capnp::VOID); + + inline bool isBool(); + inline ::capnp::Void getBool(); + inline void setBool( ::capnp::Void value = ::capnp::VOID); + + inline bool isInt8(); + inline ::capnp::Void getInt8(); + inline void setInt8( ::capnp::Void value = ::capnp::VOID); + + inline bool isInt16(); + inline ::capnp::Void getInt16(); + inline void setInt16( ::capnp::Void value = ::capnp::VOID); + + inline bool isInt32(); + inline ::capnp::Void getInt32(); + inline void setInt32( ::capnp::Void value = ::capnp::VOID); + + inline bool isInt64(); + inline ::capnp::Void getInt64(); + inline void setInt64( ::capnp::Void value = ::capnp::VOID); + + inline bool isUint8(); + inline ::capnp::Void getUint8(); + inline void setUint8( ::capnp::Void value = ::capnp::VOID); + + inline bool isUint16(); + inline ::capnp::Void getUint16(); + inline void setUint16( ::capnp::Void value = ::capnp::VOID); + + inline bool isUint32(); + inline ::capnp::Void getUint32(); + inline void setUint32( ::capnp::Void value = ::capnp::VOID); + + inline bool isUint64(); + inline ::capnp::Void getUint64(); + inline void setUint64( ::capnp::Void value = ::capnp::VOID); + + inline bool isFloat32(); + inline ::capnp::Void getFloat32(); + inline void setFloat32( ::capnp::Void value = ::capnp::VOID); + + inline bool isFloat64(); + inline ::capnp::Void getFloat64(); + inline void setFloat64( ::capnp::Void value = ::capnp::VOID); + + inline bool isText(); + inline ::capnp::Void getText(); + inline void setText( ::capnp::Void value = ::capnp::VOID); + + inline bool isData(); + inline ::capnp::Void getData(); + inline void setData( ::capnp::Void value = ::capnp::VOID); + + inline bool isList(); + inline typename List::Builder getList(); + inline typename List::Builder initList(); + + inline bool isEnum(); + inline typename Enum::Builder getEnum(); + inline typename Enum::Builder initEnum(); + + inline bool isStruct(); + inline typename Struct::Builder getStruct(); + inline typename Struct::Builder initStruct(); + + inline bool isInterface(); + inline typename Interface::Builder getInterface(); + inline typename Interface::Builder initInterface(); + + inline bool isAnyPointer(); + inline typename AnyPointer::Builder getAnyPointer(); + inline typename AnyPointer::Builder initAnyPointer(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Type::Pipeline { +public: + typedef Type Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Type::List::Reader { +public: + typedef List Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasElementType() const; + inline ::capnp::schema::Type::Reader getElementType() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Type::List::Builder { +public: + typedef List Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasElementType(); + inline ::capnp::schema::Type::Builder getElementType(); + inline void setElementType( ::capnp::schema::Type::Reader value); + inline ::capnp::schema::Type::Builder initElementType(); + inline void adoptElementType(::capnp::Orphan< ::capnp::schema::Type>&& value); + inline ::capnp::Orphan< ::capnp::schema::Type> disownElementType(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Type::List::Pipeline { +public: + typedef List Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::capnp::schema::Type::Pipeline getElementType(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Type::Enum::Reader { +public: + typedef Enum Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline ::uint64_t getTypeId() const; + + inline bool hasBrand() const; + inline ::capnp::schema::Brand::Reader getBrand() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Type::Enum::Builder { +public: + typedef Enum Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint64_t getTypeId(); + inline void setTypeId( ::uint64_t value); + + inline bool hasBrand(); + inline ::capnp::schema::Brand::Builder getBrand(); + inline void setBrand( ::capnp::schema::Brand::Reader value); + inline ::capnp::schema::Brand::Builder initBrand(); + inline void adoptBrand(::capnp::Orphan< ::capnp::schema::Brand>&& value); + inline ::capnp::Orphan< ::capnp::schema::Brand> disownBrand(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Type::Enum::Pipeline { +public: + typedef Enum Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::capnp::schema::Brand::Pipeline getBrand(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Type::Struct::Reader { +public: + typedef Struct Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline ::uint64_t getTypeId() const; + + inline bool hasBrand() const; + inline ::capnp::schema::Brand::Reader getBrand() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Type::Struct::Builder { +public: + typedef Struct Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint64_t getTypeId(); + inline void setTypeId( ::uint64_t value); + + inline bool hasBrand(); + inline ::capnp::schema::Brand::Builder getBrand(); + inline void setBrand( ::capnp::schema::Brand::Reader value); + inline ::capnp::schema::Brand::Builder initBrand(); + inline void adoptBrand(::capnp::Orphan< ::capnp::schema::Brand>&& value); + inline ::capnp::Orphan< ::capnp::schema::Brand> disownBrand(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Type::Struct::Pipeline { +public: + typedef Struct Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::capnp::schema::Brand::Pipeline getBrand(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Type::Interface::Reader { +public: + typedef Interface Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline ::uint64_t getTypeId() const; + + inline bool hasBrand() const; + inline ::capnp::schema::Brand::Reader getBrand() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Type::Interface::Builder { +public: + typedef Interface Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint64_t getTypeId(); + inline void setTypeId( ::uint64_t value); + + inline bool hasBrand(); + inline ::capnp::schema::Brand::Builder getBrand(); + inline void setBrand( ::capnp::schema::Brand::Reader value); + inline ::capnp::schema::Brand::Builder initBrand(); + inline void adoptBrand(::capnp::Orphan< ::capnp::schema::Brand>&& value); + inline ::capnp::Orphan< ::capnp::schema::Brand> disownBrand(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Type::Interface::Pipeline { +public: + typedef Interface Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::capnp::schema::Brand::Pipeline getBrand(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Type::AnyPointer::Reader { +public: + typedef AnyPointer Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline Which which() const; + inline bool isUnconstrained() const; + inline typename Unconstrained::Reader getUnconstrained() const; + + inline bool isParameter() const; + inline typename Parameter::Reader getParameter() const; + + inline bool isImplicitMethodParameter() const; + inline typename ImplicitMethodParameter::Reader getImplicitMethodParameter() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Type::AnyPointer::Builder { +public: + typedef AnyPointer Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline Which which(); + inline bool isUnconstrained(); + inline typename Unconstrained::Builder getUnconstrained(); + inline typename Unconstrained::Builder initUnconstrained(); + + inline bool isParameter(); + inline typename Parameter::Builder getParameter(); + inline typename Parameter::Builder initParameter(); + + inline bool isImplicitMethodParameter(); + inline typename ImplicitMethodParameter::Builder getImplicitMethodParameter(); + inline typename ImplicitMethodParameter::Builder initImplicitMethodParameter(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Type::AnyPointer::Pipeline { +public: + typedef AnyPointer Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Type::AnyPointer::Unconstrained::Reader { +public: + typedef Unconstrained Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline Which which() const; + inline bool isAnyKind() const; + inline ::capnp::Void getAnyKind() const; + + inline bool isStruct() const; + inline ::capnp::Void getStruct() const; + + inline bool isList() const; + inline ::capnp::Void getList() const; + + inline bool isCapability() const; + inline ::capnp::Void getCapability() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Type::AnyPointer::Unconstrained::Builder { +public: + typedef Unconstrained Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline Which which(); + inline bool isAnyKind(); + inline ::capnp::Void getAnyKind(); + inline void setAnyKind( ::capnp::Void value = ::capnp::VOID); + + inline bool isStruct(); + inline ::capnp::Void getStruct(); + inline void setStruct( ::capnp::Void value = ::capnp::VOID); + + inline bool isList(); + inline ::capnp::Void getList(); + inline void setList( ::capnp::Void value = ::capnp::VOID); + + inline bool isCapability(); + inline ::capnp::Void getCapability(); + inline void setCapability( ::capnp::Void value = ::capnp::VOID); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Type::AnyPointer::Unconstrained::Pipeline { +public: + typedef Unconstrained Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Type::AnyPointer::Parameter::Reader { +public: + typedef Parameter Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline ::uint64_t getScopeId() const; + + inline ::uint16_t getParameterIndex() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Type::AnyPointer::Parameter::Builder { +public: + typedef Parameter Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint64_t getScopeId(); + inline void setScopeId( ::uint64_t value); + + inline ::uint16_t getParameterIndex(); + inline void setParameterIndex( ::uint16_t value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Type::AnyPointer::Parameter::Pipeline { +public: + typedef Parameter Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Type::AnyPointer::ImplicitMethodParameter::Reader { +public: + typedef ImplicitMethodParameter Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline ::uint16_t getParameterIndex() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Type::AnyPointer::ImplicitMethodParameter::Builder { +public: + typedef ImplicitMethodParameter Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint16_t getParameterIndex(); + inline void setParameterIndex( ::uint16_t value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Type::AnyPointer::ImplicitMethodParameter::Pipeline { +public: + typedef ImplicitMethodParameter Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Brand::Reader { +public: + typedef Brand Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasScopes() const; + inline ::capnp::List< ::capnp::schema::Brand::Scope>::Reader getScopes() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Brand::Builder { +public: + typedef Brand Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasScopes(); + inline ::capnp::List< ::capnp::schema::Brand::Scope>::Builder getScopes(); + inline void setScopes( ::capnp::List< ::capnp::schema::Brand::Scope>::Reader value); + inline ::capnp::List< ::capnp::schema::Brand::Scope>::Builder initScopes(unsigned int size); + inline void adoptScopes(::capnp::Orphan< ::capnp::List< ::capnp::schema::Brand::Scope>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::capnp::schema::Brand::Scope>> disownScopes(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Brand::Pipeline { +public: + typedef Brand Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Brand::Scope::Reader { +public: + typedef Scope Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline Which which() const; + inline ::uint64_t getScopeId() const; + + inline bool isBind() const; + inline bool hasBind() const; + inline ::capnp::List< ::capnp::schema::Brand::Binding>::Reader getBind() const; + + inline bool isInherit() const; + inline ::capnp::Void getInherit() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Brand::Scope::Builder { +public: + typedef Scope Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline Which which(); + inline ::uint64_t getScopeId(); + inline void setScopeId( ::uint64_t value); + + inline bool isBind(); + inline bool hasBind(); + inline ::capnp::List< ::capnp::schema::Brand::Binding>::Builder getBind(); + inline void setBind( ::capnp::List< ::capnp::schema::Brand::Binding>::Reader value); + inline ::capnp::List< ::capnp::schema::Brand::Binding>::Builder initBind(unsigned int size); + inline void adoptBind(::capnp::Orphan< ::capnp::List< ::capnp::schema::Brand::Binding>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::capnp::schema::Brand::Binding>> disownBind(); + + inline bool isInherit(); + inline ::capnp::Void getInherit(); + inline void setInherit( ::capnp::Void value = ::capnp::VOID); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Brand::Scope::Pipeline { +public: + typedef Scope Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Brand::Binding::Reader { +public: + typedef Binding Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline Which which() const; + inline bool isUnbound() const; + inline ::capnp::Void getUnbound() const; + + inline bool isType() const; + inline bool hasType() const; + inline ::capnp::schema::Type::Reader getType() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Brand::Binding::Builder { +public: + typedef Binding Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline Which which(); + inline bool isUnbound(); + inline ::capnp::Void getUnbound(); + inline void setUnbound( ::capnp::Void value = ::capnp::VOID); + + inline bool isType(); + inline bool hasType(); + inline ::capnp::schema::Type::Builder getType(); + inline void setType( ::capnp::schema::Type::Reader value); + inline ::capnp::schema::Type::Builder initType(); + inline void adoptType(::capnp::Orphan< ::capnp::schema::Type>&& value); + inline ::capnp::Orphan< ::capnp::schema::Type> disownType(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Brand::Binding::Pipeline { +public: + typedef Binding Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Value::Reader { +public: + typedef Value Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline Which which() const; + inline bool isVoid() const; + inline ::capnp::Void getVoid() const; + + inline bool isBool() const; + inline bool getBool() const; + + inline bool isInt8() const; + inline ::int8_t getInt8() const; + + inline bool isInt16() const; + inline ::int16_t getInt16() const; + + inline bool isInt32() const; + inline ::int32_t getInt32() const; + + inline bool isInt64() const; + inline ::int64_t getInt64() const; + + inline bool isUint8() const; + inline ::uint8_t getUint8() const; + + inline bool isUint16() const; + inline ::uint16_t getUint16() const; + + inline bool isUint32() const; + inline ::uint32_t getUint32() const; + + inline bool isUint64() const; + inline ::uint64_t getUint64() const; + + inline bool isFloat32() const; + inline float getFloat32() const; + + inline bool isFloat64() const; + inline double getFloat64() const; + + inline bool isText() const; + inline bool hasText() const; + inline ::capnp::Text::Reader getText() const; + + inline bool isData() const; + inline bool hasData() const; + inline ::capnp::Data::Reader getData() const; + + inline bool isList() const; + inline bool hasList() const; + inline ::capnp::AnyPointer::Reader getList() const; + + inline bool isEnum() const; + inline ::uint16_t getEnum() const; + + inline bool isStruct() const; + inline bool hasStruct() const; + inline ::capnp::AnyPointer::Reader getStruct() const; + + inline bool isInterface() const; + inline ::capnp::Void getInterface() const; + + inline bool isAnyPointer() const; + inline bool hasAnyPointer() const; + inline ::capnp::AnyPointer::Reader getAnyPointer() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Value::Builder { +public: + typedef Value Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline Which which(); + inline bool isVoid(); + inline ::capnp::Void getVoid(); + inline void setVoid( ::capnp::Void value = ::capnp::VOID); + + inline bool isBool(); + inline bool getBool(); + inline void setBool(bool value); + + inline bool isInt8(); + inline ::int8_t getInt8(); + inline void setInt8( ::int8_t value); + + inline bool isInt16(); + inline ::int16_t getInt16(); + inline void setInt16( ::int16_t value); + + inline bool isInt32(); + inline ::int32_t getInt32(); + inline void setInt32( ::int32_t value); + + inline bool isInt64(); + inline ::int64_t getInt64(); + inline void setInt64( ::int64_t value); + + inline bool isUint8(); + inline ::uint8_t getUint8(); + inline void setUint8( ::uint8_t value); + + inline bool isUint16(); + inline ::uint16_t getUint16(); + inline void setUint16( ::uint16_t value); + + inline bool isUint32(); + inline ::uint32_t getUint32(); + inline void setUint32( ::uint32_t value); + + inline bool isUint64(); + inline ::uint64_t getUint64(); + inline void setUint64( ::uint64_t value); + + inline bool isFloat32(); + inline float getFloat32(); + inline void setFloat32(float value); + + inline bool isFloat64(); + inline double getFloat64(); + inline void setFloat64(double value); + + inline bool isText(); + inline bool hasText(); + inline ::capnp::Text::Builder getText(); + inline void setText( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initText(unsigned int size); + inline void adoptText(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownText(); + + inline bool isData(); + inline bool hasData(); + inline ::capnp::Data::Builder getData(); + inline void setData( ::capnp::Data::Reader value); + inline ::capnp::Data::Builder initData(unsigned int size); + inline void adoptData(::capnp::Orphan< ::capnp::Data>&& value); + inline ::capnp::Orphan< ::capnp::Data> disownData(); + + inline bool isList(); + inline bool hasList(); + inline ::capnp::AnyPointer::Builder getList(); + inline ::capnp::AnyPointer::Builder initList(); + + inline bool isEnum(); + inline ::uint16_t getEnum(); + inline void setEnum( ::uint16_t value); + + inline bool isStruct(); + inline bool hasStruct(); + inline ::capnp::AnyPointer::Builder getStruct(); + inline ::capnp::AnyPointer::Builder initStruct(); + + inline bool isInterface(); + inline ::capnp::Void getInterface(); + inline void setInterface( ::capnp::Void value = ::capnp::VOID); + + inline bool isAnyPointer(); + inline bool hasAnyPointer(); + inline ::capnp::AnyPointer::Builder getAnyPointer(); + inline ::capnp::AnyPointer::Builder initAnyPointer(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Value::Pipeline { +public: + typedef Value Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Annotation::Reader { +public: + typedef Annotation Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline ::uint64_t getId() const; + + inline bool hasValue() const; + inline ::capnp::schema::Value::Reader getValue() const; + + inline bool hasBrand() const; + inline ::capnp::schema::Brand::Reader getBrand() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Annotation::Builder { +public: + typedef Annotation Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint64_t getId(); + inline void setId( ::uint64_t value); + + inline bool hasValue(); + inline ::capnp::schema::Value::Builder getValue(); + inline void setValue( ::capnp::schema::Value::Reader value); + inline ::capnp::schema::Value::Builder initValue(); + inline void adoptValue(::capnp::Orphan< ::capnp::schema::Value>&& value); + inline ::capnp::Orphan< ::capnp::schema::Value> disownValue(); + + inline bool hasBrand(); + inline ::capnp::schema::Brand::Builder getBrand(); + inline void setBrand( ::capnp::schema::Brand::Reader value); + inline ::capnp::schema::Brand::Builder initBrand(); + inline void adoptBrand(::capnp::Orphan< ::capnp::schema::Brand>&& value); + inline ::capnp::Orphan< ::capnp::schema::Brand> disownBrand(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Annotation::Pipeline { +public: + typedef Annotation Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::capnp::schema::Value::Pipeline getValue(); + inline ::capnp::schema::Brand::Pipeline getBrand(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class CapnpVersion::Reader { +public: + typedef CapnpVersion Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline ::uint16_t getMajor() const; + + inline ::uint8_t getMinor() const; + + inline ::uint8_t getMicro() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class CapnpVersion::Builder { +public: + typedef CapnpVersion Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint16_t getMajor(); + inline void setMajor( ::uint16_t value); + + inline ::uint8_t getMinor(); + inline void setMinor( ::uint8_t value); + + inline ::uint8_t getMicro(); + inline void setMicro( ::uint8_t value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class CapnpVersion::Pipeline { +public: + typedef CapnpVersion Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class CodeGeneratorRequest::Reader { +public: + typedef CodeGeneratorRequest Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasNodes() const; + inline ::capnp::List< ::capnp::schema::Node>::Reader getNodes() const; + + inline bool hasRequestedFiles() const; + inline ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile>::Reader getRequestedFiles() const; + + inline bool hasCapnpVersion() const; + inline ::capnp::schema::CapnpVersion::Reader getCapnpVersion() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class CodeGeneratorRequest::Builder { +public: + typedef CodeGeneratorRequest Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasNodes(); + inline ::capnp::List< ::capnp::schema::Node>::Builder getNodes(); + inline void setNodes( ::capnp::List< ::capnp::schema::Node>::Reader value); + inline ::capnp::List< ::capnp::schema::Node>::Builder initNodes(unsigned int size); + inline void adoptNodes(::capnp::Orphan< ::capnp::List< ::capnp::schema::Node>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::capnp::schema::Node>> disownNodes(); + + inline bool hasRequestedFiles(); + inline ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile>::Builder getRequestedFiles(); + inline void setRequestedFiles( ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile>::Reader value); + inline ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile>::Builder initRequestedFiles(unsigned int size); + inline void adoptRequestedFiles(::capnp::Orphan< ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile>> disownRequestedFiles(); + + inline bool hasCapnpVersion(); + inline ::capnp::schema::CapnpVersion::Builder getCapnpVersion(); + inline void setCapnpVersion( ::capnp::schema::CapnpVersion::Reader value); + inline ::capnp::schema::CapnpVersion::Builder initCapnpVersion(); + inline void adoptCapnpVersion(::capnp::Orphan< ::capnp::schema::CapnpVersion>&& value); + inline ::capnp::Orphan< ::capnp::schema::CapnpVersion> disownCapnpVersion(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class CodeGeneratorRequest::Pipeline { +public: + typedef CodeGeneratorRequest Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::capnp::schema::CapnpVersion::Pipeline getCapnpVersion(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class CodeGeneratorRequest::RequestedFile::Reader { +public: + typedef RequestedFile Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline ::uint64_t getId() const; + + inline bool hasFilename() const; + inline ::capnp::Text::Reader getFilename() const; + + inline bool hasImports() const; + inline ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile::Import>::Reader getImports() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class CodeGeneratorRequest::RequestedFile::Builder { +public: + typedef RequestedFile Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint64_t getId(); + inline void setId( ::uint64_t value); + + inline bool hasFilename(); + inline ::capnp::Text::Builder getFilename(); + inline void setFilename( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initFilename(unsigned int size); + inline void adoptFilename(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownFilename(); + + inline bool hasImports(); + inline ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile::Import>::Builder getImports(); + inline void setImports( ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile::Import>::Reader value); + inline ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile::Import>::Builder initImports(unsigned int size); + inline void adoptImports(::capnp::Orphan< ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile::Import>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile::Import>> disownImports(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class CodeGeneratorRequest::RequestedFile::Pipeline { +public: + typedef RequestedFile Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class CodeGeneratorRequest::RequestedFile::Import::Reader { +public: + typedef Import Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline ::uint64_t getId() const; + + inline bool hasName() const; + inline ::capnp::Text::Reader getName() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class CodeGeneratorRequest::RequestedFile::Import::Builder { +public: + typedef Import Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint64_t getId(); + inline void setId( ::uint64_t value); + + inline bool hasName(); + inline ::capnp::Text::Builder getName(); + inline void setName( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initName(unsigned int size); + inline void adoptName(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownName(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class CodeGeneratorRequest::RequestedFile::Import::Pipeline { +public: + typedef Import Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +// ======================================================================================= + +inline ::capnp::schema::Node::Which Node::Reader::which() const { + return _reader.getDataField( + ::capnp::bounded<6>() * ::capnp::ELEMENTS); +} +inline ::capnp::schema::Node::Which Node::Builder::which() { + return _builder.getDataField( + ::capnp::bounded<6>() * ::capnp::ELEMENTS); +} + +inline ::uint64_t Node::Reader::getId() const { + return _reader.getDataField< ::uint64_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint64_t Node::Builder::getId() { + return _builder.getDataField< ::uint64_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Node::Builder::setId( ::uint64_t value) { + _builder.setDataField< ::uint64_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Node::Reader::hasDisplayName() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Node::Builder::hasDisplayName() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader Node::Reader::getDisplayName() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder Node::Builder::getDisplayName() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Node::Builder::setDisplayName( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder Node::Builder::initDisplayName(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), size); +} +inline void Node::Builder::adoptDisplayName( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> Node::Builder::disownDisplayName() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline ::uint32_t Node::Reader::getDisplayNamePrefixLength() const { + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t Node::Builder::getDisplayNamePrefixLength() { + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} +inline void Node::Builder::setDisplayNamePrefixLength( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, value); +} + +inline ::uint64_t Node::Reader::getScopeId() const { + return _reader.getDataField< ::uint64_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} + +inline ::uint64_t Node::Builder::getScopeId() { + return _builder.getDataField< ::uint64_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} +inline void Node::Builder::setScopeId( ::uint64_t value) { + _builder.setDataField< ::uint64_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, value); +} + +inline bool Node::Reader::hasNestedNodes() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool Node::Builder::hasNestedNodes() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::capnp::schema::Node::NestedNode>::Reader Node::Reader::getNestedNodes() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Node::NestedNode>>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::capnp::schema::Node::NestedNode>::Builder Node::Builder::getNestedNodes() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Node::NestedNode>>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void Node::Builder::setNestedNodes( ::capnp::List< ::capnp::schema::Node::NestedNode>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Node::NestedNode>>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::capnp::schema::Node::NestedNode>::Builder Node::Builder::initNestedNodes(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Node::NestedNode>>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), size); +} +inline void Node::Builder::adoptNestedNodes( + ::capnp::Orphan< ::capnp::List< ::capnp::schema::Node::NestedNode>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Node::NestedNode>>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::capnp::schema::Node::NestedNode>> Node::Builder::disownNestedNodes() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Node::NestedNode>>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline bool Node::Reader::hasAnnotations() const { + return !_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline bool Node::Builder::hasAnnotations() { + return !_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::capnp::schema::Annotation>::Reader Node::Reader::getAnnotations() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Annotation>>::get(_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::capnp::schema::Annotation>::Builder Node::Builder::getAnnotations() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Annotation>>::get(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline void Node::Builder::setAnnotations( ::capnp::List< ::capnp::schema::Annotation>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Annotation>>::set(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::capnp::schema::Annotation>::Builder Node::Builder::initAnnotations(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Annotation>>::init(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), size); +} +inline void Node::Builder::adoptAnnotations( + ::capnp::Orphan< ::capnp::List< ::capnp::schema::Annotation>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Annotation>>::adopt(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::capnp::schema::Annotation>> Node::Builder::disownAnnotations() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Annotation>>::disown(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} + +inline bool Node::Reader::isFile() const { + return which() == Node::FILE; +} +inline bool Node::Builder::isFile() { + return which() == Node::FILE; +} +inline ::capnp::Void Node::Reader::getFile() const { + KJ_IREQUIRE((which() == Node::FILE), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::capnp::Void Node::Builder::getFile() { + KJ_IREQUIRE((which() == Node::FILE), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Node::Builder::setFile( ::capnp::Void value) { + _builder.setDataField( + ::capnp::bounded<6>() * ::capnp::ELEMENTS, Node::FILE); + _builder.setDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Node::Reader::isStruct() const { + return which() == Node::STRUCT; +} +inline bool Node::Builder::isStruct() { + return which() == Node::STRUCT; +} +inline typename Node::Struct::Reader Node::Reader::getStruct() const { + KJ_IREQUIRE((which() == Node::STRUCT), + "Must check which() before get()ing a union member."); + return typename Node::Struct::Reader(_reader); +} +inline typename Node::Struct::Builder Node::Builder::getStruct() { + KJ_IREQUIRE((which() == Node::STRUCT), + "Must check which() before get()ing a union member."); + return typename Node::Struct::Builder(_builder); +} +inline typename Node::Struct::Builder Node::Builder::initStruct() { + _builder.setDataField( + ::capnp::bounded<6>() * ::capnp::ELEMENTS, Node::STRUCT); + _builder.setDataField< ::uint16_t>(::capnp::bounded<7>() * ::capnp::ELEMENTS, 0); + _builder.setDataField< ::uint16_t>(::capnp::bounded<12>() * ::capnp::ELEMENTS, 0); + _builder.setDataField< ::uint16_t>(::capnp::bounded<13>() * ::capnp::ELEMENTS, 0); + _builder.setDataField(::capnp::bounded<224>() * ::capnp::ELEMENTS, 0); + _builder.setDataField< ::uint16_t>(::capnp::bounded<15>() * ::capnp::ELEMENTS, 0); + _builder.setDataField< ::uint32_t>(::capnp::bounded<8>() * ::capnp::ELEMENTS, 0); + _builder.getPointerField(::capnp::bounded<3>() * ::capnp::POINTERS).clear(); + return typename Node::Struct::Builder(_builder); +} +inline bool Node::Reader::isEnum() const { + return which() == Node::ENUM; +} +inline bool Node::Builder::isEnum() { + return which() == Node::ENUM; +} +inline typename Node::Enum::Reader Node::Reader::getEnum() const { + KJ_IREQUIRE((which() == Node::ENUM), + "Must check which() before get()ing a union member."); + return typename Node::Enum::Reader(_reader); +} +inline typename Node::Enum::Builder Node::Builder::getEnum() { + KJ_IREQUIRE((which() == Node::ENUM), + "Must check which() before get()ing a union member."); + return typename Node::Enum::Builder(_builder); +} +inline typename Node::Enum::Builder Node::Builder::initEnum() { + _builder.setDataField( + ::capnp::bounded<6>() * ::capnp::ELEMENTS, Node::ENUM); + _builder.getPointerField(::capnp::bounded<3>() * ::capnp::POINTERS).clear(); + return typename Node::Enum::Builder(_builder); +} +inline bool Node::Reader::isInterface() const { + return which() == Node::INTERFACE; +} +inline bool Node::Builder::isInterface() { + return which() == Node::INTERFACE; +} +inline typename Node::Interface::Reader Node::Reader::getInterface() const { + KJ_IREQUIRE((which() == Node::INTERFACE), + "Must check which() before get()ing a union member."); + return typename Node::Interface::Reader(_reader); +} +inline typename Node::Interface::Builder Node::Builder::getInterface() { + KJ_IREQUIRE((which() == Node::INTERFACE), + "Must check which() before get()ing a union member."); + return typename Node::Interface::Builder(_builder); +} +inline typename Node::Interface::Builder Node::Builder::initInterface() { + _builder.setDataField( + ::capnp::bounded<6>() * ::capnp::ELEMENTS, Node::INTERFACE); + _builder.getPointerField(::capnp::bounded<3>() * ::capnp::POINTERS).clear(); + _builder.getPointerField(::capnp::bounded<4>() * ::capnp::POINTERS).clear(); + return typename Node::Interface::Builder(_builder); +} +inline bool Node::Reader::isConst() const { + return which() == Node::CONST; +} +inline bool Node::Builder::isConst() { + return which() == Node::CONST; +} +inline typename Node::Const::Reader Node::Reader::getConst() const { + KJ_IREQUIRE((which() == Node::CONST), + "Must check which() before get()ing a union member."); + return typename Node::Const::Reader(_reader); +} +inline typename Node::Const::Builder Node::Builder::getConst() { + KJ_IREQUIRE((which() == Node::CONST), + "Must check which() before get()ing a union member."); + return typename Node::Const::Builder(_builder); +} +inline typename Node::Const::Builder Node::Builder::initConst() { + _builder.setDataField( + ::capnp::bounded<6>() * ::capnp::ELEMENTS, Node::CONST); + _builder.getPointerField(::capnp::bounded<3>() * ::capnp::POINTERS).clear(); + _builder.getPointerField(::capnp::bounded<4>() * ::capnp::POINTERS).clear(); + return typename Node::Const::Builder(_builder); +} +inline bool Node::Reader::isAnnotation() const { + return which() == Node::ANNOTATION; +} +inline bool Node::Builder::isAnnotation() { + return which() == Node::ANNOTATION; +} +inline typename Node::Annotation::Reader Node::Reader::getAnnotation() const { + KJ_IREQUIRE((which() == Node::ANNOTATION), + "Must check which() before get()ing a union member."); + return typename Node::Annotation::Reader(_reader); +} +inline typename Node::Annotation::Builder Node::Builder::getAnnotation() { + KJ_IREQUIRE((which() == Node::ANNOTATION), + "Must check which() before get()ing a union member."); + return typename Node::Annotation::Builder(_builder); +} +inline typename Node::Annotation::Builder Node::Builder::initAnnotation() { + _builder.setDataField( + ::capnp::bounded<6>() * ::capnp::ELEMENTS, Node::ANNOTATION); + _builder.setDataField(::capnp::bounded<112>() * ::capnp::ELEMENTS, 0); + _builder.setDataField(::capnp::bounded<113>() * ::capnp::ELEMENTS, 0); + _builder.setDataField(::capnp::bounded<114>() * ::capnp::ELEMENTS, 0); + _builder.setDataField(::capnp::bounded<115>() * ::capnp::ELEMENTS, 0); + _builder.setDataField(::capnp::bounded<116>() * ::capnp::ELEMENTS, 0); + _builder.setDataField(::capnp::bounded<117>() * ::capnp::ELEMENTS, 0); + _builder.setDataField(::capnp::bounded<118>() * ::capnp::ELEMENTS, 0); + _builder.setDataField(::capnp::bounded<119>() * ::capnp::ELEMENTS, 0); + _builder.setDataField(::capnp::bounded<120>() * ::capnp::ELEMENTS, 0); + _builder.setDataField(::capnp::bounded<121>() * ::capnp::ELEMENTS, 0); + _builder.setDataField(::capnp::bounded<122>() * ::capnp::ELEMENTS, 0); + _builder.setDataField(::capnp::bounded<123>() * ::capnp::ELEMENTS, 0); + _builder.getPointerField(::capnp::bounded<3>() * ::capnp::POINTERS).clear(); + return typename Node::Annotation::Builder(_builder); +} +inline bool Node::Reader::hasParameters() const { + return !_reader.getPointerField( + ::capnp::bounded<5>() * ::capnp::POINTERS).isNull(); +} +inline bool Node::Builder::hasParameters() { + return !_builder.getPointerField( + ::capnp::bounded<5>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::capnp::schema::Node::Parameter>::Reader Node::Reader::getParameters() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Node::Parameter>>::get(_reader.getPointerField( + ::capnp::bounded<5>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::capnp::schema::Node::Parameter>::Builder Node::Builder::getParameters() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Node::Parameter>>::get(_builder.getPointerField( + ::capnp::bounded<5>() * ::capnp::POINTERS)); +} +inline void Node::Builder::setParameters( ::capnp::List< ::capnp::schema::Node::Parameter>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Node::Parameter>>::set(_builder.getPointerField( + ::capnp::bounded<5>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::capnp::schema::Node::Parameter>::Builder Node::Builder::initParameters(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Node::Parameter>>::init(_builder.getPointerField( + ::capnp::bounded<5>() * ::capnp::POINTERS), size); +} +inline void Node::Builder::adoptParameters( + ::capnp::Orphan< ::capnp::List< ::capnp::schema::Node::Parameter>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Node::Parameter>>::adopt(_builder.getPointerField( + ::capnp::bounded<5>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::capnp::schema::Node::Parameter>> Node::Builder::disownParameters() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Node::Parameter>>::disown(_builder.getPointerField( + ::capnp::bounded<5>() * ::capnp::POINTERS)); +} + +inline bool Node::Reader::getIsGeneric() const { + return _reader.getDataField( + ::capnp::bounded<288>() * ::capnp::ELEMENTS); +} + +inline bool Node::Builder::getIsGeneric() { + return _builder.getDataField( + ::capnp::bounded<288>() * ::capnp::ELEMENTS); +} +inline void Node::Builder::setIsGeneric(bool value) { + _builder.setDataField( + ::capnp::bounded<288>() * ::capnp::ELEMENTS, value); +} + +inline bool Node::Parameter::Reader::hasName() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Node::Parameter::Builder::hasName() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader Node::Parameter::Reader::getName() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder Node::Parameter::Builder::getName() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Node::Parameter::Builder::setName( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder Node::Parameter::Builder::initName(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), size); +} +inline void Node::Parameter::Builder::adoptName( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> Node::Parameter::Builder::disownName() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool Node::NestedNode::Reader::hasName() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Node::NestedNode::Builder::hasName() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader Node::NestedNode::Reader::getName() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder Node::NestedNode::Builder::getName() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Node::NestedNode::Builder::setName( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder Node::NestedNode::Builder::initName(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), size); +} +inline void Node::NestedNode::Builder::adoptName( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> Node::NestedNode::Builder::disownName() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline ::uint64_t Node::NestedNode::Reader::getId() const { + return _reader.getDataField< ::uint64_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint64_t Node::NestedNode::Builder::getId() { + return _builder.getDataField< ::uint64_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Node::NestedNode::Builder::setId( ::uint64_t value) { + _builder.setDataField< ::uint64_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline ::uint16_t Node::Struct::Reader::getDataWordCount() const { + return _reader.getDataField< ::uint16_t>( + ::capnp::bounded<7>() * ::capnp::ELEMENTS); +} + +inline ::uint16_t Node::Struct::Builder::getDataWordCount() { + return _builder.getDataField< ::uint16_t>( + ::capnp::bounded<7>() * ::capnp::ELEMENTS); +} +inline void Node::Struct::Builder::setDataWordCount( ::uint16_t value) { + _builder.setDataField< ::uint16_t>( + ::capnp::bounded<7>() * ::capnp::ELEMENTS, value); +} + +inline ::uint16_t Node::Struct::Reader::getPointerCount() const { + return _reader.getDataField< ::uint16_t>( + ::capnp::bounded<12>() * ::capnp::ELEMENTS); +} + +inline ::uint16_t Node::Struct::Builder::getPointerCount() { + return _builder.getDataField< ::uint16_t>( + ::capnp::bounded<12>() * ::capnp::ELEMENTS); +} +inline void Node::Struct::Builder::setPointerCount( ::uint16_t value) { + _builder.setDataField< ::uint16_t>( + ::capnp::bounded<12>() * ::capnp::ELEMENTS, value); +} + +inline ::capnp::schema::ElementSize Node::Struct::Reader::getPreferredListEncoding() const { + return _reader.getDataField< ::capnp::schema::ElementSize>( + ::capnp::bounded<13>() * ::capnp::ELEMENTS); +} + +inline ::capnp::schema::ElementSize Node::Struct::Builder::getPreferredListEncoding() { + return _builder.getDataField< ::capnp::schema::ElementSize>( + ::capnp::bounded<13>() * ::capnp::ELEMENTS); +} +inline void Node::Struct::Builder::setPreferredListEncoding( ::capnp::schema::ElementSize value) { + _builder.setDataField< ::capnp::schema::ElementSize>( + ::capnp::bounded<13>() * ::capnp::ELEMENTS, value); +} + +inline bool Node::Struct::Reader::getIsGroup() const { + return _reader.getDataField( + ::capnp::bounded<224>() * ::capnp::ELEMENTS); +} + +inline bool Node::Struct::Builder::getIsGroup() { + return _builder.getDataField( + ::capnp::bounded<224>() * ::capnp::ELEMENTS); +} +inline void Node::Struct::Builder::setIsGroup(bool value) { + _builder.setDataField( + ::capnp::bounded<224>() * ::capnp::ELEMENTS, value); +} + +inline ::uint16_t Node::Struct::Reader::getDiscriminantCount() const { + return _reader.getDataField< ::uint16_t>( + ::capnp::bounded<15>() * ::capnp::ELEMENTS); +} + +inline ::uint16_t Node::Struct::Builder::getDiscriminantCount() { + return _builder.getDataField< ::uint16_t>( + ::capnp::bounded<15>() * ::capnp::ELEMENTS); +} +inline void Node::Struct::Builder::setDiscriminantCount( ::uint16_t value) { + _builder.setDataField< ::uint16_t>( + ::capnp::bounded<15>() * ::capnp::ELEMENTS, value); +} + +inline ::uint32_t Node::Struct::Reader::getDiscriminantOffset() const { + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<8>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t Node::Struct::Builder::getDiscriminantOffset() { + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<8>() * ::capnp::ELEMENTS); +} +inline void Node::Struct::Builder::setDiscriminantOffset( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<8>() * ::capnp::ELEMENTS, value); +} + +inline bool Node::Struct::Reader::hasFields() const { + return !_reader.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS).isNull(); +} +inline bool Node::Struct::Builder::hasFields() { + return !_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::capnp::schema::Field>::Reader Node::Struct::Reader::getFields() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Field>>::get(_reader.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::capnp::schema::Field>::Builder Node::Struct::Builder::getFields() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Field>>::get(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +inline void Node::Struct::Builder::setFields( ::capnp::List< ::capnp::schema::Field>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Field>>::set(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::capnp::schema::Field>::Builder Node::Struct::Builder::initFields(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Field>>::init(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), size); +} +inline void Node::Struct::Builder::adoptFields( + ::capnp::Orphan< ::capnp::List< ::capnp::schema::Field>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Field>>::adopt(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::capnp::schema::Field>> Node::Struct::Builder::disownFields() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Field>>::disown(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} + +inline bool Node::Enum::Reader::hasEnumerants() const { + return !_reader.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS).isNull(); +} +inline bool Node::Enum::Builder::hasEnumerants() { + return !_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::capnp::schema::Enumerant>::Reader Node::Enum::Reader::getEnumerants() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Enumerant>>::get(_reader.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::capnp::schema::Enumerant>::Builder Node::Enum::Builder::getEnumerants() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Enumerant>>::get(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +inline void Node::Enum::Builder::setEnumerants( ::capnp::List< ::capnp::schema::Enumerant>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Enumerant>>::set(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::capnp::schema::Enumerant>::Builder Node::Enum::Builder::initEnumerants(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Enumerant>>::init(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), size); +} +inline void Node::Enum::Builder::adoptEnumerants( + ::capnp::Orphan< ::capnp::List< ::capnp::schema::Enumerant>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Enumerant>>::adopt(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::capnp::schema::Enumerant>> Node::Enum::Builder::disownEnumerants() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Enumerant>>::disown(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} + +inline bool Node::Interface::Reader::hasMethods() const { + return !_reader.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS).isNull(); +} +inline bool Node::Interface::Builder::hasMethods() { + return !_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::capnp::schema::Method>::Reader Node::Interface::Reader::getMethods() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Method>>::get(_reader.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::capnp::schema::Method>::Builder Node::Interface::Builder::getMethods() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Method>>::get(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +inline void Node::Interface::Builder::setMethods( ::capnp::List< ::capnp::schema::Method>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Method>>::set(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::capnp::schema::Method>::Builder Node::Interface::Builder::initMethods(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Method>>::init(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), size); +} +inline void Node::Interface::Builder::adoptMethods( + ::capnp::Orphan< ::capnp::List< ::capnp::schema::Method>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Method>>::adopt(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::capnp::schema::Method>> Node::Interface::Builder::disownMethods() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Method>>::disown(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} + +inline bool Node::Interface::Reader::hasSuperclasses() const { + return !_reader.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS).isNull(); +} +inline bool Node::Interface::Builder::hasSuperclasses() { + return !_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::capnp::schema::Superclass>::Reader Node::Interface::Reader::getSuperclasses() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Superclass>>::get(_reader.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::capnp::schema::Superclass>::Builder Node::Interface::Builder::getSuperclasses() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Superclass>>::get(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS)); +} +inline void Node::Interface::Builder::setSuperclasses( ::capnp::List< ::capnp::schema::Superclass>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Superclass>>::set(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::capnp::schema::Superclass>::Builder Node::Interface::Builder::initSuperclasses(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Superclass>>::init(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS), size); +} +inline void Node::Interface::Builder::adoptSuperclasses( + ::capnp::Orphan< ::capnp::List< ::capnp::schema::Superclass>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Superclass>>::adopt(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::capnp::schema::Superclass>> Node::Interface::Builder::disownSuperclasses() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Superclass>>::disown(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS)); +} + +inline bool Node::Const::Reader::hasType() const { + return !_reader.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS).isNull(); +} +inline bool Node::Const::Builder::hasType() { + return !_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::schema::Type::Reader Node::Const::Reader::getType() const { + return ::capnp::_::PointerHelpers< ::capnp::schema::Type>::get(_reader.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +inline ::capnp::schema::Type::Builder Node::Const::Builder::getType() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Type>::get(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::capnp::schema::Type::Pipeline Node::Const::Pipeline::getType() { + return ::capnp::schema::Type::Pipeline(_typeless.getPointerField(3)); +} +#endif // !CAPNP_LITE +inline void Node::Const::Builder::setType( ::capnp::schema::Type::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::schema::Type>::set(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), value); +} +inline ::capnp::schema::Type::Builder Node::Const::Builder::initType() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Type>::init(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +inline void Node::Const::Builder::adoptType( + ::capnp::Orphan< ::capnp::schema::Type>&& value) { + ::capnp::_::PointerHelpers< ::capnp::schema::Type>::adopt(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::schema::Type> Node::Const::Builder::disownType() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Type>::disown(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} + +inline bool Node::Const::Reader::hasValue() const { + return !_reader.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS).isNull(); +} +inline bool Node::Const::Builder::hasValue() { + return !_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::schema::Value::Reader Node::Const::Reader::getValue() const { + return ::capnp::_::PointerHelpers< ::capnp::schema::Value>::get(_reader.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS)); +} +inline ::capnp::schema::Value::Builder Node::Const::Builder::getValue() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Value>::get(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::capnp::schema::Value::Pipeline Node::Const::Pipeline::getValue() { + return ::capnp::schema::Value::Pipeline(_typeless.getPointerField(4)); +} +#endif // !CAPNP_LITE +inline void Node::Const::Builder::setValue( ::capnp::schema::Value::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::schema::Value>::set(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS), value); +} +inline ::capnp::schema::Value::Builder Node::Const::Builder::initValue() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Value>::init(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS)); +} +inline void Node::Const::Builder::adoptValue( + ::capnp::Orphan< ::capnp::schema::Value>&& value) { + ::capnp::_::PointerHelpers< ::capnp::schema::Value>::adopt(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::schema::Value> Node::Const::Builder::disownValue() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Value>::disown(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS)); +} + +inline bool Node::Annotation::Reader::hasType() const { + return !_reader.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS).isNull(); +} +inline bool Node::Annotation::Builder::hasType() { + return !_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::schema::Type::Reader Node::Annotation::Reader::getType() const { + return ::capnp::_::PointerHelpers< ::capnp::schema::Type>::get(_reader.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +inline ::capnp::schema::Type::Builder Node::Annotation::Builder::getType() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Type>::get(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::capnp::schema::Type::Pipeline Node::Annotation::Pipeline::getType() { + return ::capnp::schema::Type::Pipeline(_typeless.getPointerField(3)); +} +#endif // !CAPNP_LITE +inline void Node::Annotation::Builder::setType( ::capnp::schema::Type::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::schema::Type>::set(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), value); +} +inline ::capnp::schema::Type::Builder Node::Annotation::Builder::initType() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Type>::init(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +inline void Node::Annotation::Builder::adoptType( + ::capnp::Orphan< ::capnp::schema::Type>&& value) { + ::capnp::_::PointerHelpers< ::capnp::schema::Type>::adopt(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::schema::Type> Node::Annotation::Builder::disownType() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Type>::disown(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} + +inline bool Node::Annotation::Reader::getTargetsFile() const { + return _reader.getDataField( + ::capnp::bounded<112>() * ::capnp::ELEMENTS); +} + +inline bool Node::Annotation::Builder::getTargetsFile() { + return _builder.getDataField( + ::capnp::bounded<112>() * ::capnp::ELEMENTS); +} +inline void Node::Annotation::Builder::setTargetsFile(bool value) { + _builder.setDataField( + ::capnp::bounded<112>() * ::capnp::ELEMENTS, value); +} + +inline bool Node::Annotation::Reader::getTargetsConst() const { + return _reader.getDataField( + ::capnp::bounded<113>() * ::capnp::ELEMENTS); +} + +inline bool Node::Annotation::Builder::getTargetsConst() { + return _builder.getDataField( + ::capnp::bounded<113>() * ::capnp::ELEMENTS); +} +inline void Node::Annotation::Builder::setTargetsConst(bool value) { + _builder.setDataField( + ::capnp::bounded<113>() * ::capnp::ELEMENTS, value); +} + +inline bool Node::Annotation::Reader::getTargetsEnum() const { + return _reader.getDataField( + ::capnp::bounded<114>() * ::capnp::ELEMENTS); +} + +inline bool Node::Annotation::Builder::getTargetsEnum() { + return _builder.getDataField( + ::capnp::bounded<114>() * ::capnp::ELEMENTS); +} +inline void Node::Annotation::Builder::setTargetsEnum(bool value) { + _builder.setDataField( + ::capnp::bounded<114>() * ::capnp::ELEMENTS, value); +} + +inline bool Node::Annotation::Reader::getTargetsEnumerant() const { + return _reader.getDataField( + ::capnp::bounded<115>() * ::capnp::ELEMENTS); +} + +inline bool Node::Annotation::Builder::getTargetsEnumerant() { + return _builder.getDataField( + ::capnp::bounded<115>() * ::capnp::ELEMENTS); +} +inline void Node::Annotation::Builder::setTargetsEnumerant(bool value) { + _builder.setDataField( + ::capnp::bounded<115>() * ::capnp::ELEMENTS, value); +} + +inline bool Node::Annotation::Reader::getTargetsStruct() const { + return _reader.getDataField( + ::capnp::bounded<116>() * ::capnp::ELEMENTS); +} + +inline bool Node::Annotation::Builder::getTargetsStruct() { + return _builder.getDataField( + ::capnp::bounded<116>() * ::capnp::ELEMENTS); +} +inline void Node::Annotation::Builder::setTargetsStruct(bool value) { + _builder.setDataField( + ::capnp::bounded<116>() * ::capnp::ELEMENTS, value); +} + +inline bool Node::Annotation::Reader::getTargetsField() const { + return _reader.getDataField( + ::capnp::bounded<117>() * ::capnp::ELEMENTS); +} + +inline bool Node::Annotation::Builder::getTargetsField() { + return _builder.getDataField( + ::capnp::bounded<117>() * ::capnp::ELEMENTS); +} +inline void Node::Annotation::Builder::setTargetsField(bool value) { + _builder.setDataField( + ::capnp::bounded<117>() * ::capnp::ELEMENTS, value); +} + +inline bool Node::Annotation::Reader::getTargetsUnion() const { + return _reader.getDataField( + ::capnp::bounded<118>() * ::capnp::ELEMENTS); +} + +inline bool Node::Annotation::Builder::getTargetsUnion() { + return _builder.getDataField( + ::capnp::bounded<118>() * ::capnp::ELEMENTS); +} +inline void Node::Annotation::Builder::setTargetsUnion(bool value) { + _builder.setDataField( + ::capnp::bounded<118>() * ::capnp::ELEMENTS, value); +} + +inline bool Node::Annotation::Reader::getTargetsGroup() const { + return _reader.getDataField( + ::capnp::bounded<119>() * ::capnp::ELEMENTS); +} + +inline bool Node::Annotation::Builder::getTargetsGroup() { + return _builder.getDataField( + ::capnp::bounded<119>() * ::capnp::ELEMENTS); +} +inline void Node::Annotation::Builder::setTargetsGroup(bool value) { + _builder.setDataField( + ::capnp::bounded<119>() * ::capnp::ELEMENTS, value); +} + +inline bool Node::Annotation::Reader::getTargetsInterface() const { + return _reader.getDataField( + ::capnp::bounded<120>() * ::capnp::ELEMENTS); +} + +inline bool Node::Annotation::Builder::getTargetsInterface() { + return _builder.getDataField( + ::capnp::bounded<120>() * ::capnp::ELEMENTS); +} +inline void Node::Annotation::Builder::setTargetsInterface(bool value) { + _builder.setDataField( + ::capnp::bounded<120>() * ::capnp::ELEMENTS, value); +} + +inline bool Node::Annotation::Reader::getTargetsMethod() const { + return _reader.getDataField( + ::capnp::bounded<121>() * ::capnp::ELEMENTS); +} + +inline bool Node::Annotation::Builder::getTargetsMethod() { + return _builder.getDataField( + ::capnp::bounded<121>() * ::capnp::ELEMENTS); +} +inline void Node::Annotation::Builder::setTargetsMethod(bool value) { + _builder.setDataField( + ::capnp::bounded<121>() * ::capnp::ELEMENTS, value); +} + +inline bool Node::Annotation::Reader::getTargetsParam() const { + return _reader.getDataField( + ::capnp::bounded<122>() * ::capnp::ELEMENTS); +} + +inline bool Node::Annotation::Builder::getTargetsParam() { + return _builder.getDataField( + ::capnp::bounded<122>() * ::capnp::ELEMENTS); +} +inline void Node::Annotation::Builder::setTargetsParam(bool value) { + _builder.setDataField( + ::capnp::bounded<122>() * ::capnp::ELEMENTS, value); +} + +inline bool Node::Annotation::Reader::getTargetsAnnotation() const { + return _reader.getDataField( + ::capnp::bounded<123>() * ::capnp::ELEMENTS); +} + +inline bool Node::Annotation::Builder::getTargetsAnnotation() { + return _builder.getDataField( + ::capnp::bounded<123>() * ::capnp::ELEMENTS); +} +inline void Node::Annotation::Builder::setTargetsAnnotation(bool value) { + _builder.setDataField( + ::capnp::bounded<123>() * ::capnp::ELEMENTS, value); +} + +inline ::capnp::schema::Field::Which Field::Reader::which() const { + return _reader.getDataField( + ::capnp::bounded<4>() * ::capnp::ELEMENTS); +} +inline ::capnp::schema::Field::Which Field::Builder::which() { + return _builder.getDataField( + ::capnp::bounded<4>() * ::capnp::ELEMENTS); +} + +inline bool Field::Reader::hasName() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Field::Builder::hasName() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader Field::Reader::getName() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder Field::Builder::getName() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Field::Builder::setName( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder Field::Builder::initName(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), size); +} +inline void Field::Builder::adoptName( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> Field::Builder::disownName() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline ::uint16_t Field::Reader::getCodeOrder() const { + return _reader.getDataField< ::uint16_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint16_t Field::Builder::getCodeOrder() { + return _builder.getDataField< ::uint16_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Field::Builder::setCodeOrder( ::uint16_t value) { + _builder.setDataField< ::uint16_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Field::Reader::hasAnnotations() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool Field::Builder::hasAnnotations() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::capnp::schema::Annotation>::Reader Field::Reader::getAnnotations() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Annotation>>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::capnp::schema::Annotation>::Builder Field::Builder::getAnnotations() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Annotation>>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void Field::Builder::setAnnotations( ::capnp::List< ::capnp::schema::Annotation>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Annotation>>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::capnp::schema::Annotation>::Builder Field::Builder::initAnnotations(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Annotation>>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), size); +} +inline void Field::Builder::adoptAnnotations( + ::capnp::Orphan< ::capnp::List< ::capnp::schema::Annotation>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Annotation>>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::capnp::schema::Annotation>> Field::Builder::disownAnnotations() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Annotation>>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline ::uint16_t Field::Reader::getDiscriminantValue() const { + return _reader.getDataField< ::uint16_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, 65535u); +} + +inline ::uint16_t Field::Builder::getDiscriminantValue() { + return _builder.getDataField< ::uint16_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, 65535u); +} +inline void Field::Builder::setDiscriminantValue( ::uint16_t value) { + _builder.setDataField< ::uint16_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value, 65535u); +} + +inline bool Field::Reader::isSlot() const { + return which() == Field::SLOT; +} +inline bool Field::Builder::isSlot() { + return which() == Field::SLOT; +} +inline typename Field::Slot::Reader Field::Reader::getSlot() const { + KJ_IREQUIRE((which() == Field::SLOT), + "Must check which() before get()ing a union member."); + return typename Field::Slot::Reader(_reader); +} +inline typename Field::Slot::Builder Field::Builder::getSlot() { + KJ_IREQUIRE((which() == Field::SLOT), + "Must check which() before get()ing a union member."); + return typename Field::Slot::Builder(_builder); +} +inline typename Field::Slot::Builder Field::Builder::initSlot() { + _builder.setDataField( + ::capnp::bounded<4>() * ::capnp::ELEMENTS, Field::SLOT); + _builder.setDataField< ::uint32_t>(::capnp::bounded<1>() * ::capnp::ELEMENTS, 0); + _builder.setDataField(::capnp::bounded<128>() * ::capnp::ELEMENTS, 0); + _builder.getPointerField(::capnp::bounded<2>() * ::capnp::POINTERS).clear(); + _builder.getPointerField(::capnp::bounded<3>() * ::capnp::POINTERS).clear(); + return typename Field::Slot::Builder(_builder); +} +inline bool Field::Reader::isGroup() const { + return which() == Field::GROUP; +} +inline bool Field::Builder::isGroup() { + return which() == Field::GROUP; +} +inline typename Field::Group::Reader Field::Reader::getGroup() const { + KJ_IREQUIRE((which() == Field::GROUP), + "Must check which() before get()ing a union member."); + return typename Field::Group::Reader(_reader); +} +inline typename Field::Group::Builder Field::Builder::getGroup() { + KJ_IREQUIRE((which() == Field::GROUP), + "Must check which() before get()ing a union member."); + return typename Field::Group::Builder(_builder); +} +inline typename Field::Group::Builder Field::Builder::initGroup() { + _builder.setDataField( + ::capnp::bounded<4>() * ::capnp::ELEMENTS, Field::GROUP); + _builder.setDataField< ::uint64_t>(::capnp::bounded<2>() * ::capnp::ELEMENTS, 0); + return typename Field::Group::Builder(_builder); +} +inline typename Field::Ordinal::Reader Field::Reader::getOrdinal() const { + return typename Field::Ordinal::Reader(_reader); +} +inline typename Field::Ordinal::Builder Field::Builder::getOrdinal() { + return typename Field::Ordinal::Builder(_builder); +} +#if !CAPNP_LITE +inline typename Field::Ordinal::Pipeline Field::Pipeline::getOrdinal() { + return typename Field::Ordinal::Pipeline(_typeless.noop()); +} +#endif // !CAPNP_LITE +inline typename Field::Ordinal::Builder Field::Builder::initOrdinal() { + _builder.setDataField< ::uint16_t>(::capnp::bounded<5>() * ::capnp::ELEMENTS, 0); + _builder.setDataField< ::uint16_t>(::capnp::bounded<6>() * ::capnp::ELEMENTS, 0); + return typename Field::Ordinal::Builder(_builder); +} +inline ::uint32_t Field::Slot::Reader::getOffset() const { + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t Field::Slot::Builder::getOffset() { + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void Field::Slot::Builder::setOffset( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline bool Field::Slot::Reader::hasType() const { + return !_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline bool Field::Slot::Builder::hasType() { + return !_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::schema::Type::Reader Field::Slot::Reader::getType() const { + return ::capnp::_::PointerHelpers< ::capnp::schema::Type>::get(_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline ::capnp::schema::Type::Builder Field::Slot::Builder::getType() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Type>::get(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::capnp::schema::Type::Pipeline Field::Slot::Pipeline::getType() { + return ::capnp::schema::Type::Pipeline(_typeless.getPointerField(2)); +} +#endif // !CAPNP_LITE +inline void Field::Slot::Builder::setType( ::capnp::schema::Type::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::schema::Type>::set(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), value); +} +inline ::capnp::schema::Type::Builder Field::Slot::Builder::initType() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Type>::init(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline void Field::Slot::Builder::adoptType( + ::capnp::Orphan< ::capnp::schema::Type>&& value) { + ::capnp::_::PointerHelpers< ::capnp::schema::Type>::adopt(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::schema::Type> Field::Slot::Builder::disownType() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Type>::disown(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} + +inline bool Field::Slot::Reader::hasDefaultValue() const { + return !_reader.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS).isNull(); +} +inline bool Field::Slot::Builder::hasDefaultValue() { + return !_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::schema::Value::Reader Field::Slot::Reader::getDefaultValue() const { + return ::capnp::_::PointerHelpers< ::capnp::schema::Value>::get(_reader.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +inline ::capnp::schema::Value::Builder Field::Slot::Builder::getDefaultValue() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Value>::get(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::capnp::schema::Value::Pipeline Field::Slot::Pipeline::getDefaultValue() { + return ::capnp::schema::Value::Pipeline(_typeless.getPointerField(3)); +} +#endif // !CAPNP_LITE +inline void Field::Slot::Builder::setDefaultValue( ::capnp::schema::Value::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::schema::Value>::set(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), value); +} +inline ::capnp::schema::Value::Builder Field::Slot::Builder::initDefaultValue() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Value>::init(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +inline void Field::Slot::Builder::adoptDefaultValue( + ::capnp::Orphan< ::capnp::schema::Value>&& value) { + ::capnp::_::PointerHelpers< ::capnp::schema::Value>::adopt(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::schema::Value> Field::Slot::Builder::disownDefaultValue() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Value>::disown(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} + +inline bool Field::Slot::Reader::getHadExplicitDefault() const { + return _reader.getDataField( + ::capnp::bounded<128>() * ::capnp::ELEMENTS); +} + +inline bool Field::Slot::Builder::getHadExplicitDefault() { + return _builder.getDataField( + ::capnp::bounded<128>() * ::capnp::ELEMENTS); +} +inline void Field::Slot::Builder::setHadExplicitDefault(bool value) { + _builder.setDataField( + ::capnp::bounded<128>() * ::capnp::ELEMENTS, value); +} + +inline ::uint64_t Field::Group::Reader::getTypeId() const { + return _reader.getDataField< ::uint64_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} + +inline ::uint64_t Field::Group::Builder::getTypeId() { + return _builder.getDataField< ::uint64_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} +inline void Field::Group::Builder::setTypeId( ::uint64_t value) { + _builder.setDataField< ::uint64_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, value); +} + +inline ::capnp::schema::Field::Ordinal::Which Field::Ordinal::Reader::which() const { + return _reader.getDataField( + ::capnp::bounded<5>() * ::capnp::ELEMENTS); +} +inline ::capnp::schema::Field::Ordinal::Which Field::Ordinal::Builder::which() { + return _builder.getDataField( + ::capnp::bounded<5>() * ::capnp::ELEMENTS); +} + +inline bool Field::Ordinal::Reader::isImplicit() const { + return which() == Field::Ordinal::IMPLICIT; +} +inline bool Field::Ordinal::Builder::isImplicit() { + return which() == Field::Ordinal::IMPLICIT; +} +inline ::capnp::Void Field::Ordinal::Reader::getImplicit() const { + KJ_IREQUIRE((which() == Field::Ordinal::IMPLICIT), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::capnp::Void Field::Ordinal::Builder::getImplicit() { + KJ_IREQUIRE((which() == Field::Ordinal::IMPLICIT), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Field::Ordinal::Builder::setImplicit( ::capnp::Void value) { + _builder.setDataField( + ::capnp::bounded<5>() * ::capnp::ELEMENTS, Field::Ordinal::IMPLICIT); + _builder.setDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Field::Ordinal::Reader::isExplicit() const { + return which() == Field::Ordinal::EXPLICIT; +} +inline bool Field::Ordinal::Builder::isExplicit() { + return which() == Field::Ordinal::EXPLICIT; +} +inline ::uint16_t Field::Ordinal::Reader::getExplicit() const { + KJ_IREQUIRE((which() == Field::Ordinal::EXPLICIT), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::uint16_t>( + ::capnp::bounded<6>() * ::capnp::ELEMENTS); +} + +inline ::uint16_t Field::Ordinal::Builder::getExplicit() { + KJ_IREQUIRE((which() == Field::Ordinal::EXPLICIT), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::uint16_t>( + ::capnp::bounded<6>() * ::capnp::ELEMENTS); +} +inline void Field::Ordinal::Builder::setExplicit( ::uint16_t value) { + _builder.setDataField( + ::capnp::bounded<5>() * ::capnp::ELEMENTS, Field::Ordinal::EXPLICIT); + _builder.setDataField< ::uint16_t>( + ::capnp::bounded<6>() * ::capnp::ELEMENTS, value); +} + +inline bool Enumerant::Reader::hasName() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Enumerant::Builder::hasName() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader Enumerant::Reader::getName() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder Enumerant::Builder::getName() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Enumerant::Builder::setName( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder Enumerant::Builder::initName(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), size); +} +inline void Enumerant::Builder::adoptName( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> Enumerant::Builder::disownName() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline ::uint16_t Enumerant::Reader::getCodeOrder() const { + return _reader.getDataField< ::uint16_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint16_t Enumerant::Builder::getCodeOrder() { + return _builder.getDataField< ::uint16_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Enumerant::Builder::setCodeOrder( ::uint16_t value) { + _builder.setDataField< ::uint16_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Enumerant::Reader::hasAnnotations() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool Enumerant::Builder::hasAnnotations() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::capnp::schema::Annotation>::Reader Enumerant::Reader::getAnnotations() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Annotation>>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::capnp::schema::Annotation>::Builder Enumerant::Builder::getAnnotations() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Annotation>>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void Enumerant::Builder::setAnnotations( ::capnp::List< ::capnp::schema::Annotation>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Annotation>>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::capnp::schema::Annotation>::Builder Enumerant::Builder::initAnnotations(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Annotation>>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), size); +} +inline void Enumerant::Builder::adoptAnnotations( + ::capnp::Orphan< ::capnp::List< ::capnp::schema::Annotation>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Annotation>>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::capnp::schema::Annotation>> Enumerant::Builder::disownAnnotations() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Annotation>>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline ::uint64_t Superclass::Reader::getId() const { + return _reader.getDataField< ::uint64_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint64_t Superclass::Builder::getId() { + return _builder.getDataField< ::uint64_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Superclass::Builder::setId( ::uint64_t value) { + _builder.setDataField< ::uint64_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Superclass::Reader::hasBrand() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Superclass::Builder::hasBrand() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::schema::Brand::Reader Superclass::Reader::getBrand() const { + return ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::schema::Brand::Builder Superclass::Builder::getBrand() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::capnp::schema::Brand::Pipeline Superclass::Pipeline::getBrand() { + return ::capnp::schema::Brand::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void Superclass::Builder::setBrand( ::capnp::schema::Brand::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::schema::Brand::Builder Superclass::Builder::initBrand() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Superclass::Builder::adoptBrand( + ::capnp::Orphan< ::capnp::schema::Brand>&& value) { + ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::schema::Brand> Superclass::Builder::disownBrand() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool Method::Reader::hasName() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Method::Builder::hasName() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader Method::Reader::getName() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder Method::Builder::getName() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Method::Builder::setName( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder Method::Builder::initName(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), size); +} +inline void Method::Builder::adoptName( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> Method::Builder::disownName() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline ::uint16_t Method::Reader::getCodeOrder() const { + return _reader.getDataField< ::uint16_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint16_t Method::Builder::getCodeOrder() { + return _builder.getDataField< ::uint16_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Method::Builder::setCodeOrder( ::uint16_t value) { + _builder.setDataField< ::uint16_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline ::uint64_t Method::Reader::getParamStructType() const { + return _reader.getDataField< ::uint64_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline ::uint64_t Method::Builder::getParamStructType() { + return _builder.getDataField< ::uint64_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void Method::Builder::setParamStructType( ::uint64_t value) { + _builder.setDataField< ::uint64_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline ::uint64_t Method::Reader::getResultStructType() const { + return _reader.getDataField< ::uint64_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} + +inline ::uint64_t Method::Builder::getResultStructType() { + return _builder.getDataField< ::uint64_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} +inline void Method::Builder::setResultStructType( ::uint64_t value) { + _builder.setDataField< ::uint64_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, value); +} + +inline bool Method::Reader::hasAnnotations() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool Method::Builder::hasAnnotations() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::capnp::schema::Annotation>::Reader Method::Reader::getAnnotations() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Annotation>>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::capnp::schema::Annotation>::Builder Method::Builder::getAnnotations() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Annotation>>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void Method::Builder::setAnnotations( ::capnp::List< ::capnp::schema::Annotation>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Annotation>>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::capnp::schema::Annotation>::Builder Method::Builder::initAnnotations(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Annotation>>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), size); +} +inline void Method::Builder::adoptAnnotations( + ::capnp::Orphan< ::capnp::List< ::capnp::schema::Annotation>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Annotation>>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::capnp::schema::Annotation>> Method::Builder::disownAnnotations() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Annotation>>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline bool Method::Reader::hasParamBrand() const { + return !_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline bool Method::Builder::hasParamBrand() { + return !_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::schema::Brand::Reader Method::Reader::getParamBrand() const { + return ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::get(_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline ::capnp::schema::Brand::Builder Method::Builder::getParamBrand() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::get(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::capnp::schema::Brand::Pipeline Method::Pipeline::getParamBrand() { + return ::capnp::schema::Brand::Pipeline(_typeless.getPointerField(2)); +} +#endif // !CAPNP_LITE +inline void Method::Builder::setParamBrand( ::capnp::schema::Brand::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::set(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), value); +} +inline ::capnp::schema::Brand::Builder Method::Builder::initParamBrand() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::init(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline void Method::Builder::adoptParamBrand( + ::capnp::Orphan< ::capnp::schema::Brand>&& value) { + ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::adopt(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::schema::Brand> Method::Builder::disownParamBrand() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::disown(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} + +inline bool Method::Reader::hasResultBrand() const { + return !_reader.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS).isNull(); +} +inline bool Method::Builder::hasResultBrand() { + return !_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::schema::Brand::Reader Method::Reader::getResultBrand() const { + return ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::get(_reader.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +inline ::capnp::schema::Brand::Builder Method::Builder::getResultBrand() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::get(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::capnp::schema::Brand::Pipeline Method::Pipeline::getResultBrand() { + return ::capnp::schema::Brand::Pipeline(_typeless.getPointerField(3)); +} +#endif // !CAPNP_LITE +inline void Method::Builder::setResultBrand( ::capnp::schema::Brand::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::set(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), value); +} +inline ::capnp::schema::Brand::Builder Method::Builder::initResultBrand() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::init(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +inline void Method::Builder::adoptResultBrand( + ::capnp::Orphan< ::capnp::schema::Brand>&& value) { + ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::adopt(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::schema::Brand> Method::Builder::disownResultBrand() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::disown(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} + +inline bool Method::Reader::hasImplicitParameters() const { + return !_reader.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS).isNull(); +} +inline bool Method::Builder::hasImplicitParameters() { + return !_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::capnp::schema::Node::Parameter>::Reader Method::Reader::getImplicitParameters() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Node::Parameter>>::get(_reader.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::capnp::schema::Node::Parameter>::Builder Method::Builder::getImplicitParameters() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Node::Parameter>>::get(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS)); +} +inline void Method::Builder::setImplicitParameters( ::capnp::List< ::capnp::schema::Node::Parameter>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Node::Parameter>>::set(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::capnp::schema::Node::Parameter>::Builder Method::Builder::initImplicitParameters(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Node::Parameter>>::init(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS), size); +} +inline void Method::Builder::adoptImplicitParameters( + ::capnp::Orphan< ::capnp::List< ::capnp::schema::Node::Parameter>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Node::Parameter>>::adopt(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::capnp::schema::Node::Parameter>> Method::Builder::disownImplicitParameters() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Node::Parameter>>::disown(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS)); +} + +inline ::capnp::schema::Type::Which Type::Reader::which() const { + return _reader.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline ::capnp::schema::Type::Which Type::Builder::which() { + return _builder.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline bool Type::Reader::isVoid() const { + return which() == Type::VOID; +} +inline bool Type::Builder::isVoid() { + return which() == Type::VOID; +} +inline ::capnp::Void Type::Reader::getVoid() const { + KJ_IREQUIRE((which() == Type::VOID), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::capnp::Void Type::Builder::getVoid() { + KJ_IREQUIRE((which() == Type::VOID), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Type::Builder::setVoid( ::capnp::Void value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Type::VOID); + _builder.setDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Type::Reader::isBool() const { + return which() == Type::BOOL; +} +inline bool Type::Builder::isBool() { + return which() == Type::BOOL; +} +inline ::capnp::Void Type::Reader::getBool() const { + KJ_IREQUIRE((which() == Type::BOOL), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::capnp::Void Type::Builder::getBool() { + KJ_IREQUIRE((which() == Type::BOOL), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Type::Builder::setBool( ::capnp::Void value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Type::BOOL); + _builder.setDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Type::Reader::isInt8() const { + return which() == Type::INT8; +} +inline bool Type::Builder::isInt8() { + return which() == Type::INT8; +} +inline ::capnp::Void Type::Reader::getInt8() const { + KJ_IREQUIRE((which() == Type::INT8), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::capnp::Void Type::Builder::getInt8() { + KJ_IREQUIRE((which() == Type::INT8), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Type::Builder::setInt8( ::capnp::Void value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Type::INT8); + _builder.setDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Type::Reader::isInt16() const { + return which() == Type::INT16; +} +inline bool Type::Builder::isInt16() { + return which() == Type::INT16; +} +inline ::capnp::Void Type::Reader::getInt16() const { + KJ_IREQUIRE((which() == Type::INT16), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::capnp::Void Type::Builder::getInt16() { + KJ_IREQUIRE((which() == Type::INT16), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Type::Builder::setInt16( ::capnp::Void value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Type::INT16); + _builder.setDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Type::Reader::isInt32() const { + return which() == Type::INT32; +} +inline bool Type::Builder::isInt32() { + return which() == Type::INT32; +} +inline ::capnp::Void Type::Reader::getInt32() const { + KJ_IREQUIRE((which() == Type::INT32), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::capnp::Void Type::Builder::getInt32() { + KJ_IREQUIRE((which() == Type::INT32), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Type::Builder::setInt32( ::capnp::Void value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Type::INT32); + _builder.setDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Type::Reader::isInt64() const { + return which() == Type::INT64; +} +inline bool Type::Builder::isInt64() { + return which() == Type::INT64; +} +inline ::capnp::Void Type::Reader::getInt64() const { + KJ_IREQUIRE((which() == Type::INT64), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::capnp::Void Type::Builder::getInt64() { + KJ_IREQUIRE((which() == Type::INT64), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Type::Builder::setInt64( ::capnp::Void value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Type::INT64); + _builder.setDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Type::Reader::isUint8() const { + return which() == Type::UINT8; +} +inline bool Type::Builder::isUint8() { + return which() == Type::UINT8; +} +inline ::capnp::Void Type::Reader::getUint8() const { + KJ_IREQUIRE((which() == Type::UINT8), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::capnp::Void Type::Builder::getUint8() { + KJ_IREQUIRE((which() == Type::UINT8), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Type::Builder::setUint8( ::capnp::Void value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Type::UINT8); + _builder.setDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Type::Reader::isUint16() const { + return which() == Type::UINT16; +} +inline bool Type::Builder::isUint16() { + return which() == Type::UINT16; +} +inline ::capnp::Void Type::Reader::getUint16() const { + KJ_IREQUIRE((which() == Type::UINT16), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::capnp::Void Type::Builder::getUint16() { + KJ_IREQUIRE((which() == Type::UINT16), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Type::Builder::setUint16( ::capnp::Void value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Type::UINT16); + _builder.setDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Type::Reader::isUint32() const { + return which() == Type::UINT32; +} +inline bool Type::Builder::isUint32() { + return which() == Type::UINT32; +} +inline ::capnp::Void Type::Reader::getUint32() const { + KJ_IREQUIRE((which() == Type::UINT32), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::capnp::Void Type::Builder::getUint32() { + KJ_IREQUIRE((which() == Type::UINT32), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Type::Builder::setUint32( ::capnp::Void value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Type::UINT32); + _builder.setDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Type::Reader::isUint64() const { + return which() == Type::UINT64; +} +inline bool Type::Builder::isUint64() { + return which() == Type::UINT64; +} +inline ::capnp::Void Type::Reader::getUint64() const { + KJ_IREQUIRE((which() == Type::UINT64), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::capnp::Void Type::Builder::getUint64() { + KJ_IREQUIRE((which() == Type::UINT64), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Type::Builder::setUint64( ::capnp::Void value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Type::UINT64); + _builder.setDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Type::Reader::isFloat32() const { + return which() == Type::FLOAT32; +} +inline bool Type::Builder::isFloat32() { + return which() == Type::FLOAT32; +} +inline ::capnp::Void Type::Reader::getFloat32() const { + KJ_IREQUIRE((which() == Type::FLOAT32), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::capnp::Void Type::Builder::getFloat32() { + KJ_IREQUIRE((which() == Type::FLOAT32), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Type::Builder::setFloat32( ::capnp::Void value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Type::FLOAT32); + _builder.setDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Type::Reader::isFloat64() const { + return which() == Type::FLOAT64; +} +inline bool Type::Builder::isFloat64() { + return which() == Type::FLOAT64; +} +inline ::capnp::Void Type::Reader::getFloat64() const { + KJ_IREQUIRE((which() == Type::FLOAT64), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::capnp::Void Type::Builder::getFloat64() { + KJ_IREQUIRE((which() == Type::FLOAT64), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Type::Builder::setFloat64( ::capnp::Void value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Type::FLOAT64); + _builder.setDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Type::Reader::isText() const { + return which() == Type::TEXT; +} +inline bool Type::Builder::isText() { + return which() == Type::TEXT; +} +inline ::capnp::Void Type::Reader::getText() const { + KJ_IREQUIRE((which() == Type::TEXT), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::capnp::Void Type::Builder::getText() { + KJ_IREQUIRE((which() == Type::TEXT), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Type::Builder::setText( ::capnp::Void value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Type::TEXT); + _builder.setDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Type::Reader::isData() const { + return which() == Type::DATA; +} +inline bool Type::Builder::isData() { + return which() == Type::DATA; +} +inline ::capnp::Void Type::Reader::getData() const { + KJ_IREQUIRE((which() == Type::DATA), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::capnp::Void Type::Builder::getData() { + KJ_IREQUIRE((which() == Type::DATA), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Type::Builder::setData( ::capnp::Void value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Type::DATA); + _builder.setDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Type::Reader::isList() const { + return which() == Type::LIST; +} +inline bool Type::Builder::isList() { + return which() == Type::LIST; +} +inline typename Type::List::Reader Type::Reader::getList() const { + KJ_IREQUIRE((which() == Type::LIST), + "Must check which() before get()ing a union member."); + return typename Type::List::Reader(_reader); +} +inline typename Type::List::Builder Type::Builder::getList() { + KJ_IREQUIRE((which() == Type::LIST), + "Must check which() before get()ing a union member."); + return typename Type::List::Builder(_builder); +} +inline typename Type::List::Builder Type::Builder::initList() { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Type::LIST); + _builder.getPointerField(::capnp::bounded<0>() * ::capnp::POINTERS).clear(); + return typename Type::List::Builder(_builder); +} +inline bool Type::Reader::isEnum() const { + return which() == Type::ENUM; +} +inline bool Type::Builder::isEnum() { + return which() == Type::ENUM; +} +inline typename Type::Enum::Reader Type::Reader::getEnum() const { + KJ_IREQUIRE((which() == Type::ENUM), + "Must check which() before get()ing a union member."); + return typename Type::Enum::Reader(_reader); +} +inline typename Type::Enum::Builder Type::Builder::getEnum() { + KJ_IREQUIRE((which() == Type::ENUM), + "Must check which() before get()ing a union member."); + return typename Type::Enum::Builder(_builder); +} +inline typename Type::Enum::Builder Type::Builder::initEnum() { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Type::ENUM); + _builder.setDataField< ::uint64_t>(::capnp::bounded<1>() * ::capnp::ELEMENTS, 0); + _builder.getPointerField(::capnp::bounded<0>() * ::capnp::POINTERS).clear(); + return typename Type::Enum::Builder(_builder); +} +inline bool Type::Reader::isStruct() const { + return which() == Type::STRUCT; +} +inline bool Type::Builder::isStruct() { + return which() == Type::STRUCT; +} +inline typename Type::Struct::Reader Type::Reader::getStruct() const { + KJ_IREQUIRE((which() == Type::STRUCT), + "Must check which() before get()ing a union member."); + return typename Type::Struct::Reader(_reader); +} +inline typename Type::Struct::Builder Type::Builder::getStruct() { + KJ_IREQUIRE((which() == Type::STRUCT), + "Must check which() before get()ing a union member."); + return typename Type::Struct::Builder(_builder); +} +inline typename Type::Struct::Builder Type::Builder::initStruct() { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Type::STRUCT); + _builder.setDataField< ::uint64_t>(::capnp::bounded<1>() * ::capnp::ELEMENTS, 0); + _builder.getPointerField(::capnp::bounded<0>() * ::capnp::POINTERS).clear(); + return typename Type::Struct::Builder(_builder); +} +inline bool Type::Reader::isInterface() const { + return which() == Type::INTERFACE; +} +inline bool Type::Builder::isInterface() { + return which() == Type::INTERFACE; +} +inline typename Type::Interface::Reader Type::Reader::getInterface() const { + KJ_IREQUIRE((which() == Type::INTERFACE), + "Must check which() before get()ing a union member."); + return typename Type::Interface::Reader(_reader); +} +inline typename Type::Interface::Builder Type::Builder::getInterface() { + KJ_IREQUIRE((which() == Type::INTERFACE), + "Must check which() before get()ing a union member."); + return typename Type::Interface::Builder(_builder); +} +inline typename Type::Interface::Builder Type::Builder::initInterface() { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Type::INTERFACE); + _builder.setDataField< ::uint64_t>(::capnp::bounded<1>() * ::capnp::ELEMENTS, 0); + _builder.getPointerField(::capnp::bounded<0>() * ::capnp::POINTERS).clear(); + return typename Type::Interface::Builder(_builder); +} +inline bool Type::Reader::isAnyPointer() const { + return which() == Type::ANY_POINTER; +} +inline bool Type::Builder::isAnyPointer() { + return which() == Type::ANY_POINTER; +} +inline typename Type::AnyPointer::Reader Type::Reader::getAnyPointer() const { + KJ_IREQUIRE((which() == Type::ANY_POINTER), + "Must check which() before get()ing a union member."); + return typename Type::AnyPointer::Reader(_reader); +} +inline typename Type::AnyPointer::Builder Type::Builder::getAnyPointer() { + KJ_IREQUIRE((which() == Type::ANY_POINTER), + "Must check which() before get()ing a union member."); + return typename Type::AnyPointer::Builder(_builder); +} +inline typename Type::AnyPointer::Builder Type::Builder::initAnyPointer() { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Type::ANY_POINTER); + _builder.setDataField< ::uint16_t>(::capnp::bounded<4>() * ::capnp::ELEMENTS, 0); + _builder.setDataField< ::uint16_t>(::capnp::bounded<5>() * ::capnp::ELEMENTS, 0); + _builder.setDataField< ::uint64_t>(::capnp::bounded<2>() * ::capnp::ELEMENTS, 0); + return typename Type::AnyPointer::Builder(_builder); +} +inline bool Type::List::Reader::hasElementType() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Type::List::Builder::hasElementType() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::schema::Type::Reader Type::List::Reader::getElementType() const { + return ::capnp::_::PointerHelpers< ::capnp::schema::Type>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::schema::Type::Builder Type::List::Builder::getElementType() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Type>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::capnp::schema::Type::Pipeline Type::List::Pipeline::getElementType() { + return ::capnp::schema::Type::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void Type::List::Builder::setElementType( ::capnp::schema::Type::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::schema::Type>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::schema::Type::Builder Type::List::Builder::initElementType() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Type>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Type::List::Builder::adoptElementType( + ::capnp::Orphan< ::capnp::schema::Type>&& value) { + ::capnp::_::PointerHelpers< ::capnp::schema::Type>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::schema::Type> Type::List::Builder::disownElementType() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Type>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline ::uint64_t Type::Enum::Reader::getTypeId() const { + return _reader.getDataField< ::uint64_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline ::uint64_t Type::Enum::Builder::getTypeId() { + return _builder.getDataField< ::uint64_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void Type::Enum::Builder::setTypeId( ::uint64_t value) { + _builder.setDataField< ::uint64_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline bool Type::Enum::Reader::hasBrand() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Type::Enum::Builder::hasBrand() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::schema::Brand::Reader Type::Enum::Reader::getBrand() const { + return ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::schema::Brand::Builder Type::Enum::Builder::getBrand() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::capnp::schema::Brand::Pipeline Type::Enum::Pipeline::getBrand() { + return ::capnp::schema::Brand::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void Type::Enum::Builder::setBrand( ::capnp::schema::Brand::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::schema::Brand::Builder Type::Enum::Builder::initBrand() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Type::Enum::Builder::adoptBrand( + ::capnp::Orphan< ::capnp::schema::Brand>&& value) { + ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::schema::Brand> Type::Enum::Builder::disownBrand() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline ::uint64_t Type::Struct::Reader::getTypeId() const { + return _reader.getDataField< ::uint64_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline ::uint64_t Type::Struct::Builder::getTypeId() { + return _builder.getDataField< ::uint64_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void Type::Struct::Builder::setTypeId( ::uint64_t value) { + _builder.setDataField< ::uint64_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline bool Type::Struct::Reader::hasBrand() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Type::Struct::Builder::hasBrand() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::schema::Brand::Reader Type::Struct::Reader::getBrand() const { + return ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::schema::Brand::Builder Type::Struct::Builder::getBrand() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::capnp::schema::Brand::Pipeline Type::Struct::Pipeline::getBrand() { + return ::capnp::schema::Brand::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void Type::Struct::Builder::setBrand( ::capnp::schema::Brand::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::schema::Brand::Builder Type::Struct::Builder::initBrand() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Type::Struct::Builder::adoptBrand( + ::capnp::Orphan< ::capnp::schema::Brand>&& value) { + ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::schema::Brand> Type::Struct::Builder::disownBrand() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline ::uint64_t Type::Interface::Reader::getTypeId() const { + return _reader.getDataField< ::uint64_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline ::uint64_t Type::Interface::Builder::getTypeId() { + return _builder.getDataField< ::uint64_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void Type::Interface::Builder::setTypeId( ::uint64_t value) { + _builder.setDataField< ::uint64_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline bool Type::Interface::Reader::hasBrand() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Type::Interface::Builder::hasBrand() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::schema::Brand::Reader Type::Interface::Reader::getBrand() const { + return ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::schema::Brand::Builder Type::Interface::Builder::getBrand() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::capnp::schema::Brand::Pipeline Type::Interface::Pipeline::getBrand() { + return ::capnp::schema::Brand::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void Type::Interface::Builder::setBrand( ::capnp::schema::Brand::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::schema::Brand::Builder Type::Interface::Builder::initBrand() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Type::Interface::Builder::adoptBrand( + ::capnp::Orphan< ::capnp::schema::Brand>&& value) { + ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::schema::Brand> Type::Interface::Builder::disownBrand() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline ::capnp::schema::Type::AnyPointer::Which Type::AnyPointer::Reader::which() const { + return _reader.getDataField( + ::capnp::bounded<4>() * ::capnp::ELEMENTS); +} +inline ::capnp::schema::Type::AnyPointer::Which Type::AnyPointer::Builder::which() { + return _builder.getDataField( + ::capnp::bounded<4>() * ::capnp::ELEMENTS); +} + +inline bool Type::AnyPointer::Reader::isUnconstrained() const { + return which() == Type::AnyPointer::UNCONSTRAINED; +} +inline bool Type::AnyPointer::Builder::isUnconstrained() { + return which() == Type::AnyPointer::UNCONSTRAINED; +} +inline typename Type::AnyPointer::Unconstrained::Reader Type::AnyPointer::Reader::getUnconstrained() const { + KJ_IREQUIRE((which() == Type::AnyPointer::UNCONSTRAINED), + "Must check which() before get()ing a union member."); + return typename Type::AnyPointer::Unconstrained::Reader(_reader); +} +inline typename Type::AnyPointer::Unconstrained::Builder Type::AnyPointer::Builder::getUnconstrained() { + KJ_IREQUIRE((which() == Type::AnyPointer::UNCONSTRAINED), + "Must check which() before get()ing a union member."); + return typename Type::AnyPointer::Unconstrained::Builder(_builder); +} +inline typename Type::AnyPointer::Unconstrained::Builder Type::AnyPointer::Builder::initUnconstrained() { + _builder.setDataField( + ::capnp::bounded<4>() * ::capnp::ELEMENTS, Type::AnyPointer::UNCONSTRAINED); + _builder.setDataField< ::uint16_t>(::capnp::bounded<5>() * ::capnp::ELEMENTS, 0); + return typename Type::AnyPointer::Unconstrained::Builder(_builder); +} +inline bool Type::AnyPointer::Reader::isParameter() const { + return which() == Type::AnyPointer::PARAMETER; +} +inline bool Type::AnyPointer::Builder::isParameter() { + return which() == Type::AnyPointer::PARAMETER; +} +inline typename Type::AnyPointer::Parameter::Reader Type::AnyPointer::Reader::getParameter() const { + KJ_IREQUIRE((which() == Type::AnyPointer::PARAMETER), + "Must check which() before get()ing a union member."); + return typename Type::AnyPointer::Parameter::Reader(_reader); +} +inline typename Type::AnyPointer::Parameter::Builder Type::AnyPointer::Builder::getParameter() { + KJ_IREQUIRE((which() == Type::AnyPointer::PARAMETER), + "Must check which() before get()ing a union member."); + return typename Type::AnyPointer::Parameter::Builder(_builder); +} +inline typename Type::AnyPointer::Parameter::Builder Type::AnyPointer::Builder::initParameter() { + _builder.setDataField( + ::capnp::bounded<4>() * ::capnp::ELEMENTS, Type::AnyPointer::PARAMETER); + _builder.setDataField< ::uint16_t>(::capnp::bounded<5>() * ::capnp::ELEMENTS, 0); + _builder.setDataField< ::uint64_t>(::capnp::bounded<2>() * ::capnp::ELEMENTS, 0); + return typename Type::AnyPointer::Parameter::Builder(_builder); +} +inline bool Type::AnyPointer::Reader::isImplicitMethodParameter() const { + return which() == Type::AnyPointer::IMPLICIT_METHOD_PARAMETER; +} +inline bool Type::AnyPointer::Builder::isImplicitMethodParameter() { + return which() == Type::AnyPointer::IMPLICIT_METHOD_PARAMETER; +} +inline typename Type::AnyPointer::ImplicitMethodParameter::Reader Type::AnyPointer::Reader::getImplicitMethodParameter() const { + KJ_IREQUIRE((which() == Type::AnyPointer::IMPLICIT_METHOD_PARAMETER), + "Must check which() before get()ing a union member."); + return typename Type::AnyPointer::ImplicitMethodParameter::Reader(_reader); +} +inline typename Type::AnyPointer::ImplicitMethodParameter::Builder Type::AnyPointer::Builder::getImplicitMethodParameter() { + KJ_IREQUIRE((which() == Type::AnyPointer::IMPLICIT_METHOD_PARAMETER), + "Must check which() before get()ing a union member."); + return typename Type::AnyPointer::ImplicitMethodParameter::Builder(_builder); +} +inline typename Type::AnyPointer::ImplicitMethodParameter::Builder Type::AnyPointer::Builder::initImplicitMethodParameter() { + _builder.setDataField( + ::capnp::bounded<4>() * ::capnp::ELEMENTS, Type::AnyPointer::IMPLICIT_METHOD_PARAMETER); + _builder.setDataField< ::uint16_t>(::capnp::bounded<5>() * ::capnp::ELEMENTS, 0); + return typename Type::AnyPointer::ImplicitMethodParameter::Builder(_builder); +} +inline ::capnp::schema::Type::AnyPointer::Unconstrained::Which Type::AnyPointer::Unconstrained::Reader::which() const { + return _reader.getDataField( + ::capnp::bounded<5>() * ::capnp::ELEMENTS); +} +inline ::capnp::schema::Type::AnyPointer::Unconstrained::Which Type::AnyPointer::Unconstrained::Builder::which() { + return _builder.getDataField( + ::capnp::bounded<5>() * ::capnp::ELEMENTS); +} + +inline bool Type::AnyPointer::Unconstrained::Reader::isAnyKind() const { + return which() == Type::AnyPointer::Unconstrained::ANY_KIND; +} +inline bool Type::AnyPointer::Unconstrained::Builder::isAnyKind() { + return which() == Type::AnyPointer::Unconstrained::ANY_KIND; +} +inline ::capnp::Void Type::AnyPointer::Unconstrained::Reader::getAnyKind() const { + KJ_IREQUIRE((which() == Type::AnyPointer::Unconstrained::ANY_KIND), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::capnp::Void Type::AnyPointer::Unconstrained::Builder::getAnyKind() { + KJ_IREQUIRE((which() == Type::AnyPointer::Unconstrained::ANY_KIND), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Type::AnyPointer::Unconstrained::Builder::setAnyKind( ::capnp::Void value) { + _builder.setDataField( + ::capnp::bounded<5>() * ::capnp::ELEMENTS, Type::AnyPointer::Unconstrained::ANY_KIND); + _builder.setDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Type::AnyPointer::Unconstrained::Reader::isStruct() const { + return which() == Type::AnyPointer::Unconstrained::STRUCT; +} +inline bool Type::AnyPointer::Unconstrained::Builder::isStruct() { + return which() == Type::AnyPointer::Unconstrained::STRUCT; +} +inline ::capnp::Void Type::AnyPointer::Unconstrained::Reader::getStruct() const { + KJ_IREQUIRE((which() == Type::AnyPointer::Unconstrained::STRUCT), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::capnp::Void Type::AnyPointer::Unconstrained::Builder::getStruct() { + KJ_IREQUIRE((which() == Type::AnyPointer::Unconstrained::STRUCT), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Type::AnyPointer::Unconstrained::Builder::setStruct( ::capnp::Void value) { + _builder.setDataField( + ::capnp::bounded<5>() * ::capnp::ELEMENTS, Type::AnyPointer::Unconstrained::STRUCT); + _builder.setDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Type::AnyPointer::Unconstrained::Reader::isList() const { + return which() == Type::AnyPointer::Unconstrained::LIST; +} +inline bool Type::AnyPointer::Unconstrained::Builder::isList() { + return which() == Type::AnyPointer::Unconstrained::LIST; +} +inline ::capnp::Void Type::AnyPointer::Unconstrained::Reader::getList() const { + KJ_IREQUIRE((which() == Type::AnyPointer::Unconstrained::LIST), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::capnp::Void Type::AnyPointer::Unconstrained::Builder::getList() { + KJ_IREQUIRE((which() == Type::AnyPointer::Unconstrained::LIST), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Type::AnyPointer::Unconstrained::Builder::setList( ::capnp::Void value) { + _builder.setDataField( + ::capnp::bounded<5>() * ::capnp::ELEMENTS, Type::AnyPointer::Unconstrained::LIST); + _builder.setDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Type::AnyPointer::Unconstrained::Reader::isCapability() const { + return which() == Type::AnyPointer::Unconstrained::CAPABILITY; +} +inline bool Type::AnyPointer::Unconstrained::Builder::isCapability() { + return which() == Type::AnyPointer::Unconstrained::CAPABILITY; +} +inline ::capnp::Void Type::AnyPointer::Unconstrained::Reader::getCapability() const { + KJ_IREQUIRE((which() == Type::AnyPointer::Unconstrained::CAPABILITY), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::capnp::Void Type::AnyPointer::Unconstrained::Builder::getCapability() { + KJ_IREQUIRE((which() == Type::AnyPointer::Unconstrained::CAPABILITY), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Type::AnyPointer::Unconstrained::Builder::setCapability( ::capnp::Void value) { + _builder.setDataField( + ::capnp::bounded<5>() * ::capnp::ELEMENTS, Type::AnyPointer::Unconstrained::CAPABILITY); + _builder.setDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline ::uint64_t Type::AnyPointer::Parameter::Reader::getScopeId() const { + return _reader.getDataField< ::uint64_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} + +inline ::uint64_t Type::AnyPointer::Parameter::Builder::getScopeId() { + return _builder.getDataField< ::uint64_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} +inline void Type::AnyPointer::Parameter::Builder::setScopeId( ::uint64_t value) { + _builder.setDataField< ::uint64_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, value); +} + +inline ::uint16_t Type::AnyPointer::Parameter::Reader::getParameterIndex() const { + return _reader.getDataField< ::uint16_t>( + ::capnp::bounded<5>() * ::capnp::ELEMENTS); +} + +inline ::uint16_t Type::AnyPointer::Parameter::Builder::getParameterIndex() { + return _builder.getDataField< ::uint16_t>( + ::capnp::bounded<5>() * ::capnp::ELEMENTS); +} +inline void Type::AnyPointer::Parameter::Builder::setParameterIndex( ::uint16_t value) { + _builder.setDataField< ::uint16_t>( + ::capnp::bounded<5>() * ::capnp::ELEMENTS, value); +} + +inline ::uint16_t Type::AnyPointer::ImplicitMethodParameter::Reader::getParameterIndex() const { + return _reader.getDataField< ::uint16_t>( + ::capnp::bounded<5>() * ::capnp::ELEMENTS); +} + +inline ::uint16_t Type::AnyPointer::ImplicitMethodParameter::Builder::getParameterIndex() { + return _builder.getDataField< ::uint16_t>( + ::capnp::bounded<5>() * ::capnp::ELEMENTS); +} +inline void Type::AnyPointer::ImplicitMethodParameter::Builder::setParameterIndex( ::uint16_t value) { + _builder.setDataField< ::uint16_t>( + ::capnp::bounded<5>() * ::capnp::ELEMENTS, value); +} + +inline bool Brand::Reader::hasScopes() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Brand::Builder::hasScopes() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::capnp::schema::Brand::Scope>::Reader Brand::Reader::getScopes() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Brand::Scope>>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::capnp::schema::Brand::Scope>::Builder Brand::Builder::getScopes() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Brand::Scope>>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Brand::Builder::setScopes( ::capnp::List< ::capnp::schema::Brand::Scope>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Brand::Scope>>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::capnp::schema::Brand::Scope>::Builder Brand::Builder::initScopes(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Brand::Scope>>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), size); +} +inline void Brand::Builder::adoptScopes( + ::capnp::Orphan< ::capnp::List< ::capnp::schema::Brand::Scope>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Brand::Scope>>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::capnp::schema::Brand::Scope>> Brand::Builder::disownScopes() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Brand::Scope>>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline ::capnp::schema::Brand::Scope::Which Brand::Scope::Reader::which() const { + return _reader.getDataField( + ::capnp::bounded<4>() * ::capnp::ELEMENTS); +} +inline ::capnp::schema::Brand::Scope::Which Brand::Scope::Builder::which() { + return _builder.getDataField( + ::capnp::bounded<4>() * ::capnp::ELEMENTS); +} + +inline ::uint64_t Brand::Scope::Reader::getScopeId() const { + return _reader.getDataField< ::uint64_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint64_t Brand::Scope::Builder::getScopeId() { + return _builder.getDataField< ::uint64_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Brand::Scope::Builder::setScopeId( ::uint64_t value) { + _builder.setDataField< ::uint64_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Brand::Scope::Reader::isBind() const { + return which() == Brand::Scope::BIND; +} +inline bool Brand::Scope::Builder::isBind() { + return which() == Brand::Scope::BIND; +} +inline bool Brand::Scope::Reader::hasBind() const { + if (which() != Brand::Scope::BIND) return false; + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Brand::Scope::Builder::hasBind() { + if (which() != Brand::Scope::BIND) return false; + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::capnp::schema::Brand::Binding>::Reader Brand::Scope::Reader::getBind() const { + KJ_IREQUIRE((which() == Brand::Scope::BIND), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Brand::Binding>>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::capnp::schema::Brand::Binding>::Builder Brand::Scope::Builder::getBind() { + KJ_IREQUIRE((which() == Brand::Scope::BIND), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Brand::Binding>>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Brand::Scope::Builder::setBind( ::capnp::List< ::capnp::schema::Brand::Binding>::Reader value) { + _builder.setDataField( + ::capnp::bounded<4>() * ::capnp::ELEMENTS, Brand::Scope::BIND); + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Brand::Binding>>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::capnp::schema::Brand::Binding>::Builder Brand::Scope::Builder::initBind(unsigned int size) { + _builder.setDataField( + ::capnp::bounded<4>() * ::capnp::ELEMENTS, Brand::Scope::BIND); + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Brand::Binding>>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), size); +} +inline void Brand::Scope::Builder::adoptBind( + ::capnp::Orphan< ::capnp::List< ::capnp::schema::Brand::Binding>>&& value) { + _builder.setDataField( + ::capnp::bounded<4>() * ::capnp::ELEMENTS, Brand::Scope::BIND); + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Brand::Binding>>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::capnp::schema::Brand::Binding>> Brand::Scope::Builder::disownBind() { + KJ_IREQUIRE((which() == Brand::Scope::BIND), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Brand::Binding>>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool Brand::Scope::Reader::isInherit() const { + return which() == Brand::Scope::INHERIT; +} +inline bool Brand::Scope::Builder::isInherit() { + return which() == Brand::Scope::INHERIT; +} +inline ::capnp::Void Brand::Scope::Reader::getInherit() const { + KJ_IREQUIRE((which() == Brand::Scope::INHERIT), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::capnp::Void Brand::Scope::Builder::getInherit() { + KJ_IREQUIRE((which() == Brand::Scope::INHERIT), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Brand::Scope::Builder::setInherit( ::capnp::Void value) { + _builder.setDataField( + ::capnp::bounded<4>() * ::capnp::ELEMENTS, Brand::Scope::INHERIT); + _builder.setDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline ::capnp::schema::Brand::Binding::Which Brand::Binding::Reader::which() const { + return _reader.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline ::capnp::schema::Brand::Binding::Which Brand::Binding::Builder::which() { + return _builder.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline bool Brand::Binding::Reader::isUnbound() const { + return which() == Brand::Binding::UNBOUND; +} +inline bool Brand::Binding::Builder::isUnbound() { + return which() == Brand::Binding::UNBOUND; +} +inline ::capnp::Void Brand::Binding::Reader::getUnbound() const { + KJ_IREQUIRE((which() == Brand::Binding::UNBOUND), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::capnp::Void Brand::Binding::Builder::getUnbound() { + KJ_IREQUIRE((which() == Brand::Binding::UNBOUND), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Brand::Binding::Builder::setUnbound( ::capnp::Void value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Brand::Binding::UNBOUND); + _builder.setDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Brand::Binding::Reader::isType() const { + return which() == Brand::Binding::TYPE; +} +inline bool Brand::Binding::Builder::isType() { + return which() == Brand::Binding::TYPE; +} +inline bool Brand::Binding::Reader::hasType() const { + if (which() != Brand::Binding::TYPE) return false; + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Brand::Binding::Builder::hasType() { + if (which() != Brand::Binding::TYPE) return false; + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::schema::Type::Reader Brand::Binding::Reader::getType() const { + KJ_IREQUIRE((which() == Brand::Binding::TYPE), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::schema::Type>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::schema::Type::Builder Brand::Binding::Builder::getType() { + KJ_IREQUIRE((which() == Brand::Binding::TYPE), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::schema::Type>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Brand::Binding::Builder::setType( ::capnp::schema::Type::Reader value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Brand::Binding::TYPE); + ::capnp::_::PointerHelpers< ::capnp::schema::Type>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::schema::Type::Builder Brand::Binding::Builder::initType() { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Brand::Binding::TYPE); + return ::capnp::_::PointerHelpers< ::capnp::schema::Type>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Brand::Binding::Builder::adoptType( + ::capnp::Orphan< ::capnp::schema::Type>&& value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Brand::Binding::TYPE); + ::capnp::_::PointerHelpers< ::capnp::schema::Type>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::schema::Type> Brand::Binding::Builder::disownType() { + KJ_IREQUIRE((which() == Brand::Binding::TYPE), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::schema::Type>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline ::capnp::schema::Value::Which Value::Reader::which() const { + return _reader.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline ::capnp::schema::Value::Which Value::Builder::which() { + return _builder.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline bool Value::Reader::isVoid() const { + return which() == Value::VOID; +} +inline bool Value::Builder::isVoid() { + return which() == Value::VOID; +} +inline ::capnp::Void Value::Reader::getVoid() const { + KJ_IREQUIRE((which() == Value::VOID), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::capnp::Void Value::Builder::getVoid() { + KJ_IREQUIRE((which() == Value::VOID), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Value::Builder::setVoid( ::capnp::Void value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Value::VOID); + _builder.setDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Value::Reader::isBool() const { + return which() == Value::BOOL; +} +inline bool Value::Builder::isBool() { + return which() == Value::BOOL; +} +inline bool Value::Reader::getBool() const { + KJ_IREQUIRE((which() == Value::BOOL), + "Must check which() before get()ing a union member."); + return _reader.getDataField( + ::capnp::bounded<16>() * ::capnp::ELEMENTS); +} + +inline bool Value::Builder::getBool() { + KJ_IREQUIRE((which() == Value::BOOL), + "Must check which() before get()ing a union member."); + return _builder.getDataField( + ::capnp::bounded<16>() * ::capnp::ELEMENTS); +} +inline void Value::Builder::setBool(bool value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Value::BOOL); + _builder.setDataField( + ::capnp::bounded<16>() * ::capnp::ELEMENTS, value); +} + +inline bool Value::Reader::isInt8() const { + return which() == Value::INT8; +} +inline bool Value::Builder::isInt8() { + return which() == Value::INT8; +} +inline ::int8_t Value::Reader::getInt8() const { + KJ_IREQUIRE((which() == Value::INT8), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::int8_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} + +inline ::int8_t Value::Builder::getInt8() { + KJ_IREQUIRE((which() == Value::INT8), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::int8_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} +inline void Value::Builder::setInt8( ::int8_t value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Value::INT8); + _builder.setDataField< ::int8_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, value); +} + +inline bool Value::Reader::isInt16() const { + return which() == Value::INT16; +} +inline bool Value::Builder::isInt16() { + return which() == Value::INT16; +} +inline ::int16_t Value::Reader::getInt16() const { + KJ_IREQUIRE((which() == Value::INT16), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::int16_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline ::int16_t Value::Builder::getInt16() { + KJ_IREQUIRE((which() == Value::INT16), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::int16_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void Value::Builder::setInt16( ::int16_t value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Value::INT16); + _builder.setDataField< ::int16_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline bool Value::Reader::isInt32() const { + return which() == Value::INT32; +} +inline bool Value::Builder::isInt32() { + return which() == Value::INT32; +} +inline ::int32_t Value::Reader::getInt32() const { + KJ_IREQUIRE((which() == Value::INT32), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::int32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline ::int32_t Value::Builder::getInt32() { + KJ_IREQUIRE((which() == Value::INT32), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::int32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void Value::Builder::setInt32( ::int32_t value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Value::INT32); + _builder.setDataField< ::int32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline bool Value::Reader::isInt64() const { + return which() == Value::INT64; +} +inline bool Value::Builder::isInt64() { + return which() == Value::INT64; +} +inline ::int64_t Value::Reader::getInt64() const { + KJ_IREQUIRE((which() == Value::INT64), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::int64_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline ::int64_t Value::Builder::getInt64() { + KJ_IREQUIRE((which() == Value::INT64), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::int64_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void Value::Builder::setInt64( ::int64_t value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Value::INT64); + _builder.setDataField< ::int64_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline bool Value::Reader::isUint8() const { + return which() == Value::UINT8; +} +inline bool Value::Builder::isUint8() { + return which() == Value::UINT8; +} +inline ::uint8_t Value::Reader::getUint8() const { + KJ_IREQUIRE((which() == Value::UINT8), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::uint8_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} + +inline ::uint8_t Value::Builder::getUint8() { + KJ_IREQUIRE((which() == Value::UINT8), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::uint8_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} +inline void Value::Builder::setUint8( ::uint8_t value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Value::UINT8); + _builder.setDataField< ::uint8_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, value); +} + +inline bool Value::Reader::isUint16() const { + return which() == Value::UINT16; +} +inline bool Value::Builder::isUint16() { + return which() == Value::UINT16; +} +inline ::uint16_t Value::Reader::getUint16() const { + KJ_IREQUIRE((which() == Value::UINT16), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::uint16_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline ::uint16_t Value::Builder::getUint16() { + KJ_IREQUIRE((which() == Value::UINT16), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::uint16_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void Value::Builder::setUint16( ::uint16_t value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Value::UINT16); + _builder.setDataField< ::uint16_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline bool Value::Reader::isUint32() const { + return which() == Value::UINT32; +} +inline bool Value::Builder::isUint32() { + return which() == Value::UINT32; +} +inline ::uint32_t Value::Reader::getUint32() const { + KJ_IREQUIRE((which() == Value::UINT32), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t Value::Builder::getUint32() { + KJ_IREQUIRE((which() == Value::UINT32), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void Value::Builder::setUint32( ::uint32_t value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Value::UINT32); + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline bool Value::Reader::isUint64() const { + return which() == Value::UINT64; +} +inline bool Value::Builder::isUint64() { + return which() == Value::UINT64; +} +inline ::uint64_t Value::Reader::getUint64() const { + KJ_IREQUIRE((which() == Value::UINT64), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::uint64_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline ::uint64_t Value::Builder::getUint64() { + KJ_IREQUIRE((which() == Value::UINT64), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::uint64_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void Value::Builder::setUint64( ::uint64_t value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Value::UINT64); + _builder.setDataField< ::uint64_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline bool Value::Reader::isFloat32() const { + return which() == Value::FLOAT32; +} +inline bool Value::Builder::isFloat32() { + return which() == Value::FLOAT32; +} +inline float Value::Reader::getFloat32() const { + KJ_IREQUIRE((which() == Value::FLOAT32), + "Must check which() before get()ing a union member."); + return _reader.getDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline float Value::Builder::getFloat32() { + KJ_IREQUIRE((which() == Value::FLOAT32), + "Must check which() before get()ing a union member."); + return _builder.getDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void Value::Builder::setFloat32(float value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Value::FLOAT32); + _builder.setDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline bool Value::Reader::isFloat64() const { + return which() == Value::FLOAT64; +} +inline bool Value::Builder::isFloat64() { + return which() == Value::FLOAT64; +} +inline double Value::Reader::getFloat64() const { + KJ_IREQUIRE((which() == Value::FLOAT64), + "Must check which() before get()ing a union member."); + return _reader.getDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline double Value::Builder::getFloat64() { + KJ_IREQUIRE((which() == Value::FLOAT64), + "Must check which() before get()ing a union member."); + return _builder.getDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void Value::Builder::setFloat64(double value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Value::FLOAT64); + _builder.setDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline bool Value::Reader::isText() const { + return which() == Value::TEXT; +} +inline bool Value::Builder::isText() { + return which() == Value::TEXT; +} +inline bool Value::Reader::hasText() const { + if (which() != Value::TEXT) return false; + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Value::Builder::hasText() { + if (which() != Value::TEXT) return false; + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader Value::Reader::getText() const { + KJ_IREQUIRE((which() == Value::TEXT), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder Value::Builder::getText() { + KJ_IREQUIRE((which() == Value::TEXT), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Value::Builder::setText( ::capnp::Text::Reader value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Value::TEXT); + ::capnp::_::PointerHelpers< ::capnp::Text>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder Value::Builder::initText(unsigned int size) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Value::TEXT); + return ::capnp::_::PointerHelpers< ::capnp::Text>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), size); +} +inline void Value::Builder::adoptText( + ::capnp::Orphan< ::capnp::Text>&& value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Value::TEXT); + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> Value::Builder::disownText() { + KJ_IREQUIRE((which() == Value::TEXT), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool Value::Reader::isData() const { + return which() == Value::DATA; +} +inline bool Value::Builder::isData() { + return which() == Value::DATA; +} +inline bool Value::Reader::hasData() const { + if (which() != Value::DATA) return false; + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Value::Builder::hasData() { + if (which() != Value::DATA) return false; + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Data::Reader Value::Reader::getData() const { + KJ_IREQUIRE((which() == Value::DATA), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::Data>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::Data::Builder Value::Builder::getData() { + KJ_IREQUIRE((which() == Value::DATA), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::Data>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Value::Builder::setData( ::capnp::Data::Reader value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Value::DATA); + ::capnp::_::PointerHelpers< ::capnp::Data>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::Data::Builder Value::Builder::initData(unsigned int size) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Value::DATA); + return ::capnp::_::PointerHelpers< ::capnp::Data>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), size); +} +inline void Value::Builder::adoptData( + ::capnp::Orphan< ::capnp::Data>&& value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Value::DATA); + ::capnp::_::PointerHelpers< ::capnp::Data>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Data> Value::Builder::disownData() { + KJ_IREQUIRE((which() == Value::DATA), + "Must check which() before get()ing a union member."); + return ::capnp::_::PointerHelpers< ::capnp::Data>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool Value::Reader::isList() const { + return which() == Value::LIST; +} +inline bool Value::Builder::isList() { + return which() == Value::LIST; +} +inline bool Value::Reader::hasList() const { + if (which() != Value::LIST) return false; + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Value::Builder::hasList() { + if (which() != Value::LIST) return false; + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::AnyPointer::Reader Value::Reader::getList() const { + KJ_IREQUIRE((which() == Value::LIST), + "Must check which() before get()ing a union member."); + return ::capnp::AnyPointer::Reader(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::AnyPointer::Builder Value::Builder::getList() { + KJ_IREQUIRE((which() == Value::LIST), + "Must check which() before get()ing a union member."); + return ::capnp::AnyPointer::Builder(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::AnyPointer::Builder Value::Builder::initList() { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Value::LIST); + auto result = ::capnp::AnyPointer::Builder(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); + result.clear(); + return result; +} + +inline bool Value::Reader::isEnum() const { + return which() == Value::ENUM; +} +inline bool Value::Builder::isEnum() { + return which() == Value::ENUM; +} +inline ::uint16_t Value::Reader::getEnum() const { + KJ_IREQUIRE((which() == Value::ENUM), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::uint16_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline ::uint16_t Value::Builder::getEnum() { + KJ_IREQUIRE((which() == Value::ENUM), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::uint16_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void Value::Builder::setEnum( ::uint16_t value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Value::ENUM); + _builder.setDataField< ::uint16_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline bool Value::Reader::isStruct() const { + return which() == Value::STRUCT; +} +inline bool Value::Builder::isStruct() { + return which() == Value::STRUCT; +} +inline bool Value::Reader::hasStruct() const { + if (which() != Value::STRUCT) return false; + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Value::Builder::hasStruct() { + if (which() != Value::STRUCT) return false; + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::AnyPointer::Reader Value::Reader::getStruct() const { + KJ_IREQUIRE((which() == Value::STRUCT), + "Must check which() before get()ing a union member."); + return ::capnp::AnyPointer::Reader(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::AnyPointer::Builder Value::Builder::getStruct() { + KJ_IREQUIRE((which() == Value::STRUCT), + "Must check which() before get()ing a union member."); + return ::capnp::AnyPointer::Builder(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::AnyPointer::Builder Value::Builder::initStruct() { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Value::STRUCT); + auto result = ::capnp::AnyPointer::Builder(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); + result.clear(); + return result; +} + +inline bool Value::Reader::isInterface() const { + return which() == Value::INTERFACE; +} +inline bool Value::Builder::isInterface() { + return which() == Value::INTERFACE; +} +inline ::capnp::Void Value::Reader::getInterface() const { + KJ_IREQUIRE((which() == Value::INTERFACE), + "Must check which() before get()ing a union member."); + return _reader.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::capnp::Void Value::Builder::getInterface() { + KJ_IREQUIRE((which() == Value::INTERFACE), + "Must check which() before get()ing a union member."); + return _builder.getDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Value::Builder::setInterface( ::capnp::Void value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Value::INTERFACE); + _builder.setDataField< ::capnp::Void>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Value::Reader::isAnyPointer() const { + return which() == Value::ANY_POINTER; +} +inline bool Value::Builder::isAnyPointer() { + return which() == Value::ANY_POINTER; +} +inline bool Value::Reader::hasAnyPointer() const { + if (which() != Value::ANY_POINTER) return false; + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Value::Builder::hasAnyPointer() { + if (which() != Value::ANY_POINTER) return false; + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::AnyPointer::Reader Value::Reader::getAnyPointer() const { + KJ_IREQUIRE((which() == Value::ANY_POINTER), + "Must check which() before get()ing a union member."); + return ::capnp::AnyPointer::Reader(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::AnyPointer::Builder Value::Builder::getAnyPointer() { + KJ_IREQUIRE((which() == Value::ANY_POINTER), + "Must check which() before get()ing a union member."); + return ::capnp::AnyPointer::Builder(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::AnyPointer::Builder Value::Builder::initAnyPointer() { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, Value::ANY_POINTER); + auto result = ::capnp::AnyPointer::Builder(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); + result.clear(); + return result; +} + +inline ::uint64_t Annotation::Reader::getId() const { + return _reader.getDataField< ::uint64_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint64_t Annotation::Builder::getId() { + return _builder.getDataField< ::uint64_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Annotation::Builder::setId( ::uint64_t value) { + _builder.setDataField< ::uint64_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Annotation::Reader::hasValue() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Annotation::Builder::hasValue() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::schema::Value::Reader Annotation::Reader::getValue() const { + return ::capnp::_::PointerHelpers< ::capnp::schema::Value>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::schema::Value::Builder Annotation::Builder::getValue() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Value>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::capnp::schema::Value::Pipeline Annotation::Pipeline::getValue() { + return ::capnp::schema::Value::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void Annotation::Builder::setValue( ::capnp::schema::Value::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::schema::Value>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::schema::Value::Builder Annotation::Builder::initValue() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Value>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Annotation::Builder::adoptValue( + ::capnp::Orphan< ::capnp::schema::Value>&& value) { + ::capnp::_::PointerHelpers< ::capnp::schema::Value>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::schema::Value> Annotation::Builder::disownValue() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Value>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool Annotation::Reader::hasBrand() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool Annotation::Builder::hasBrand() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::schema::Brand::Reader Annotation::Reader::getBrand() const { + return ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::schema::Brand::Builder Annotation::Builder::getBrand() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::capnp::schema::Brand::Pipeline Annotation::Pipeline::getBrand() { + return ::capnp::schema::Brand::Pipeline(_typeless.getPointerField(1)); +} +#endif // !CAPNP_LITE +inline void Annotation::Builder::setBrand( ::capnp::schema::Brand::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::schema::Brand::Builder Annotation::Builder::initBrand() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void Annotation::Builder::adoptBrand( + ::capnp::Orphan< ::capnp::schema::Brand>&& value) { + ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::schema::Brand> Annotation::Builder::disownBrand() { + return ::capnp::_::PointerHelpers< ::capnp::schema::Brand>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline ::uint16_t CapnpVersion::Reader::getMajor() const { + return _reader.getDataField< ::uint16_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint16_t CapnpVersion::Builder::getMajor() { + return _builder.getDataField< ::uint16_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void CapnpVersion::Builder::setMajor( ::uint16_t value) { + _builder.setDataField< ::uint16_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline ::uint8_t CapnpVersion::Reader::getMinor() const { + return _reader.getDataField< ::uint8_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} + +inline ::uint8_t CapnpVersion::Builder::getMinor() { + return _builder.getDataField< ::uint8_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} +inline void CapnpVersion::Builder::setMinor( ::uint8_t value) { + _builder.setDataField< ::uint8_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, value); +} + +inline ::uint8_t CapnpVersion::Reader::getMicro() const { + return _reader.getDataField< ::uint8_t>( + ::capnp::bounded<3>() * ::capnp::ELEMENTS); +} + +inline ::uint8_t CapnpVersion::Builder::getMicro() { + return _builder.getDataField< ::uint8_t>( + ::capnp::bounded<3>() * ::capnp::ELEMENTS); +} +inline void CapnpVersion::Builder::setMicro( ::uint8_t value) { + _builder.setDataField< ::uint8_t>( + ::capnp::bounded<3>() * ::capnp::ELEMENTS, value); +} + +inline bool CodeGeneratorRequest::Reader::hasNodes() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool CodeGeneratorRequest::Builder::hasNodes() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::capnp::schema::Node>::Reader CodeGeneratorRequest::Reader::getNodes() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Node>>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::capnp::schema::Node>::Builder CodeGeneratorRequest::Builder::getNodes() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Node>>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void CodeGeneratorRequest::Builder::setNodes( ::capnp::List< ::capnp::schema::Node>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Node>>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::capnp::schema::Node>::Builder CodeGeneratorRequest::Builder::initNodes(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Node>>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), size); +} +inline void CodeGeneratorRequest::Builder::adoptNodes( + ::capnp::Orphan< ::capnp::List< ::capnp::schema::Node>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Node>>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::capnp::schema::Node>> CodeGeneratorRequest::Builder::disownNodes() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::Node>>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool CodeGeneratorRequest::Reader::hasRequestedFiles() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool CodeGeneratorRequest::Builder::hasRequestedFiles() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile>::Reader CodeGeneratorRequest::Reader::getRequestedFiles() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile>>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile>::Builder CodeGeneratorRequest::Builder::getRequestedFiles() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile>>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void CodeGeneratorRequest::Builder::setRequestedFiles( ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile>>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile>::Builder CodeGeneratorRequest::Builder::initRequestedFiles(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile>>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), size); +} +inline void CodeGeneratorRequest::Builder::adoptRequestedFiles( + ::capnp::Orphan< ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile>>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile>> CodeGeneratorRequest::Builder::disownRequestedFiles() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile>>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline bool CodeGeneratorRequest::Reader::hasCapnpVersion() const { + return !_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline bool CodeGeneratorRequest::Builder::hasCapnpVersion() { + return !_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::schema::CapnpVersion::Reader CodeGeneratorRequest::Reader::getCapnpVersion() const { + return ::capnp::_::PointerHelpers< ::capnp::schema::CapnpVersion>::get(_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline ::capnp::schema::CapnpVersion::Builder CodeGeneratorRequest::Builder::getCapnpVersion() { + return ::capnp::_::PointerHelpers< ::capnp::schema::CapnpVersion>::get(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::capnp::schema::CapnpVersion::Pipeline CodeGeneratorRequest::Pipeline::getCapnpVersion() { + return ::capnp::schema::CapnpVersion::Pipeline(_typeless.getPointerField(2)); +} +#endif // !CAPNP_LITE +inline void CodeGeneratorRequest::Builder::setCapnpVersion( ::capnp::schema::CapnpVersion::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::schema::CapnpVersion>::set(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), value); +} +inline ::capnp::schema::CapnpVersion::Builder CodeGeneratorRequest::Builder::initCapnpVersion() { + return ::capnp::_::PointerHelpers< ::capnp::schema::CapnpVersion>::init(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline void CodeGeneratorRequest::Builder::adoptCapnpVersion( + ::capnp::Orphan< ::capnp::schema::CapnpVersion>&& value) { + ::capnp::_::PointerHelpers< ::capnp::schema::CapnpVersion>::adopt(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::schema::CapnpVersion> CodeGeneratorRequest::Builder::disownCapnpVersion() { + return ::capnp::_::PointerHelpers< ::capnp::schema::CapnpVersion>::disown(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} + +inline ::uint64_t CodeGeneratorRequest::RequestedFile::Reader::getId() const { + return _reader.getDataField< ::uint64_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint64_t CodeGeneratorRequest::RequestedFile::Builder::getId() { + return _builder.getDataField< ::uint64_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void CodeGeneratorRequest::RequestedFile::Builder::setId( ::uint64_t value) { + _builder.setDataField< ::uint64_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool CodeGeneratorRequest::RequestedFile::Reader::hasFilename() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool CodeGeneratorRequest::RequestedFile::Builder::hasFilename() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader CodeGeneratorRequest::RequestedFile::Reader::getFilename() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder CodeGeneratorRequest::RequestedFile::Builder::getFilename() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void CodeGeneratorRequest::RequestedFile::Builder::setFilename( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder CodeGeneratorRequest::RequestedFile::Builder::initFilename(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), size); +} +inline void CodeGeneratorRequest::RequestedFile::Builder::adoptFilename( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> CodeGeneratorRequest::RequestedFile::Builder::disownFilename() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool CodeGeneratorRequest::RequestedFile::Reader::hasImports() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool CodeGeneratorRequest::RequestedFile::Builder::hasImports() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile::Import>::Reader CodeGeneratorRequest::RequestedFile::Reader::getImports() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile::Import>>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile::Import>::Builder CodeGeneratorRequest::RequestedFile::Builder::getImports() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile::Import>>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void CodeGeneratorRequest::RequestedFile::Builder::setImports( ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile::Import>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile::Import>>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile::Import>::Builder CodeGeneratorRequest::RequestedFile::Builder::initImports(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile::Import>>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), size); +} +inline void CodeGeneratorRequest::RequestedFile::Builder::adoptImports( + ::capnp::Orphan< ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile::Import>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile::Import>>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile::Import>> CodeGeneratorRequest::RequestedFile::Builder::disownImports() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::schema::CodeGeneratorRequest::RequestedFile::Import>>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline ::uint64_t CodeGeneratorRequest::RequestedFile::Import::Reader::getId() const { + return _reader.getDataField< ::uint64_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint64_t CodeGeneratorRequest::RequestedFile::Import::Builder::getId() { + return _builder.getDataField< ::uint64_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void CodeGeneratorRequest::RequestedFile::Import::Builder::setId( ::uint64_t value) { + _builder.setDataField< ::uint64_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool CodeGeneratorRequest::RequestedFile::Import::Reader::hasName() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool CodeGeneratorRequest::RequestedFile::Import::Builder::hasName() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader CodeGeneratorRequest::RequestedFile::Import::Reader::getName() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder CodeGeneratorRequest::RequestedFile::Import::Builder::getName() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void CodeGeneratorRequest::RequestedFile::Import::Builder::setName( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder CodeGeneratorRequest::RequestedFile::Import::Builder::initName(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), size); +} +inline void CodeGeneratorRequest::RequestedFile::Import::Builder::adoptName( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> CodeGeneratorRequest::RequestedFile::Import::Builder::disownName() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +} // namespace +} // namespace + +#endif // CAPNP_INCLUDED_a93fc509624c72d9_ diff --git a/phonelibs/capnp-cpp/include/capnp/schema.h b/phonelibs/capnp-cpp/include/capnp/schema.h new file mode 100644 index 00000000000000..d59fa7523668d3 --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/schema.h @@ -0,0 +1,934 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef CAPNP_SCHEMA_H_ +#define CAPNP_SCHEMA_H_ + +#if defined(__GNUC__) && !defined(CAPNP_HEADER_WARNINGS) +#pragma GCC system_header +#endif + +#if CAPNP_LITE +#error "Reflection APIs, including this header, are not available in lite mode." +#endif + +#include + +namespace capnp { + +class Schema; +class StructSchema; +class EnumSchema; +class InterfaceSchema; +class ConstSchema; +class ListSchema; +class Type; + +template ()> struct SchemaType_ { typedef Schema Type; }; +template struct SchemaType_ { typedef schema::Type::Which Type; }; +template struct SchemaType_ { typedef schema::Type::Which Type; }; +template struct SchemaType_ { typedef EnumSchema Type; }; +template struct SchemaType_ { typedef StructSchema Type; }; +template struct SchemaType_ { typedef InterfaceSchema Type; }; +template struct SchemaType_ { typedef ListSchema Type; }; + +template +using SchemaType = typename SchemaType_::Type; +// SchemaType is the type of T's schema, e.g. StructSchema if T is a struct. + +namespace _ { // private +extern const RawSchema NULL_SCHEMA; +extern const RawSchema NULL_STRUCT_SCHEMA; +extern const RawSchema NULL_ENUM_SCHEMA; +extern const RawSchema NULL_INTERFACE_SCHEMA; +extern const RawSchema NULL_CONST_SCHEMA; +// The schema types default to these null (empty) schemas in case of error, especially when +// exceptions are disabled. +} // namespace _ (private) + +class Schema { + // Convenience wrapper around capnp::schema::Node. + +public: + inline Schema(): raw(&_::NULL_SCHEMA.defaultBrand) {} + + template + static inline SchemaType from() { return SchemaType::template fromImpl(); } + // Get the Schema for a particular compiled-in type. + + schema::Node::Reader getProto() const; + // Get the underlying Cap'n Proto representation of the schema node. (Note that this accessor + // has performance comparable to accessors of struct-typed fields on Reader classes.) + + kj::ArrayPtr asUncheckedMessage() const; + // Get the encoded schema node content as a single message segment. It is safe to read as an + // unchecked message. + + Schema getDependency(uint64_t id) const KJ_DEPRECATED("Does not handle generics correctly."); + // DEPRECATED: This method cannot correctly account for generic type parameter bindings that + // may apply to the dependency. Instead of using this method, use a method of the Schema API + // that corresponds to the exact kind of dependency. For example, to get a field type, use + // StructSchema::Field::getType(). + // + // Gets the Schema for one of this Schema's dependencies. For example, if this Schema is for a + // struct, you could look up the schema for one of its fields' types. Throws an exception if this + // schema doesn't actually depend on the given id. + // + // Note that not all type IDs found in the schema node are considered "dependencies" -- only the + // ones that are needed to implement the dynamic API are. That includes: + // - Field types. + // - Group types. + // - scopeId for group nodes, but NOT otherwise. + // - Method parameter and return types. + // + // The following are NOT considered dependencies: + // - Nested nodes. + // - scopeId for a non-group node. + // - Annotations. + // + // To obtain schemas for those, you would need a SchemaLoader. + + bool isBranded() const; + // Returns true if this schema represents a non-default parameterization of this type. + + Schema getGeneric() const; + // Get the version of this schema with any brands removed. + + class BrandArgumentList; + BrandArgumentList getBrandArgumentsAtScope(uint64_t scopeId) const; + // Gets the values bound to the brand parameters at the given scope. + + StructSchema asStruct() const; + EnumSchema asEnum() const; + InterfaceSchema asInterface() const; + ConstSchema asConst() const; + // Cast the Schema to a specific type. Throws an exception if the type doesn't match. Use + // getProto() to determine type, e.g. getProto().isStruct(). + + inline bool operator==(const Schema& other) const { return raw == other.raw; } + inline bool operator!=(const Schema& other) const { return raw != other.raw; } + // Determine whether two Schemas are wrapping the exact same underlying data, by identity. If + // you want to check if two Schemas represent the same type (but possibly different versions of + // it), compare their IDs instead. + + template + void requireUsableAs() const; + // Throws an exception if a value with this Schema cannot safely be cast to a native value of + // the given type. This passes if either: + // - *this == from() + // - This schema was loaded with SchemaLoader, the type ID matches typeId(), and + // loadCompiledTypeAndDependencies() was called on the SchemaLoader. + + kj::StringPtr getShortDisplayName() const; + // Get the short version of the node's display name. + +private: + const _::RawBrandedSchema* raw; + + inline explicit Schema(const _::RawBrandedSchema* raw): raw(raw) { + KJ_IREQUIRE(raw->lazyInitializer == nullptr, + "Must call ensureInitialized() on RawSchema before constructing Schema."); + } + + template static inline Schema fromImpl() { + return Schema(&_::rawSchema()); + } + + void requireUsableAs(const _::RawSchema* expected) const; + + uint32_t getSchemaOffset(const schema::Value::Reader& value) const; + + Type getBrandBinding(uint64_t scopeId, uint index) const; + // Look up the binding for a brand parameter used by this Schema. Returns `AnyPointer` if the + // parameter is not bound. + // + // TODO(someday): Public interface for iterating over all bindings? + + Schema getDependency(uint64_t id, uint location) const; + // Look up schema for a particular dependency of this schema. `location` is the dependency + // location number as defined in _::RawBrandedSchema. + + Type interpretType(schema::Type::Reader proto, uint location) const; + // Interpret a schema::Type in the given location within the schema, compiling it into a + // Type object. + + friend class StructSchema; + friend class EnumSchema; + friend class InterfaceSchema; + friend class ConstSchema; + friend class ListSchema; + friend class SchemaLoader; + friend class Type; + friend kj::StringTree _::structString( + _::StructReader reader, const _::RawBrandedSchema& schema); + friend kj::String _::enumString(uint16_t value, const _::RawBrandedSchema& schema); +}; + +kj::StringPtr KJ_STRINGIFY(const Schema& schema); + +class Schema::BrandArgumentList { + // A list of generic parameter bindings for parameters of some particular type. Note that since + // parameters on an outer type apply to all inner types as well, a deeply-nested type can have + // multiple BrandArgumentLists that apply to it. + // + // A BrandArgumentList only represents the arguments that the client of the type specified. Since + // new parameters can be added over time, this list may not cover all defined parameters for the + // type. Missing parameters should be treated as AnyPointer. This class's implementation of + // operator[] already does this for you; out-of-bounds access will safely return AnyPointer. + +public: + inline BrandArgumentList(): scopeId(0), size_(0), bindings(nullptr) {} + + inline uint size() const { return size_; } + Type operator[](uint index) const; + + typedef _::IndexingIterator Iterator; + inline Iterator begin() const { return Iterator(this, 0); } + inline Iterator end() const { return Iterator(this, size()); } + +private: + uint64_t scopeId; + uint size_; + bool isUnbound; + const _::RawBrandedSchema::Binding* bindings; + + inline BrandArgumentList(uint64_t scopeId, bool isUnbound) + : scopeId(scopeId), size_(0), isUnbound(isUnbound), bindings(nullptr) {} + inline BrandArgumentList(uint64_t scopeId, uint size, + const _::RawBrandedSchema::Binding* bindings) + : scopeId(scopeId), size_(size), isUnbound(false), bindings(bindings) {} + + friend class Schema; +}; + +// ------------------------------------------------------------------- + +class StructSchema: public Schema { +public: + inline StructSchema(): Schema(&_::NULL_STRUCT_SCHEMA.defaultBrand) {} + + class Field; + class FieldList; + class FieldSubset; + + FieldList getFields() const; + // List top-level fields of this struct. This list will contain top-level groups (including + // named unions) but not the members of those groups. The list does, however, contain the + // members of the unnamed union, if there is one. + + FieldSubset getUnionFields() const; + // If the field contains an unnamed union, get a list of fields in the union, ordered by + // ordinal. Since discriminant values are assigned sequentially by ordinal, you may index this + // list by discriminant value. + + FieldSubset getNonUnionFields() const; + // Get the fields of this struct which are not in an unnamed union, ordered by ordinal. + + kj::Maybe findFieldByName(kj::StringPtr name) const; + // Find the field with the given name, or return null if there is no such field. If the struct + // contains an unnamed union, then this will find fields of that union in addition to fields + // of the outer struct, since they exist in the same namespace. It will not, however, find + // members of groups (including named unions) -- you must first look up the group itself, + // then dig into its type. + + Field getFieldByName(kj::StringPtr name) const; + // Like findFieldByName() but throws an exception on failure. + + kj::Maybe getFieldByDiscriminant(uint16_t discriminant) const; + // Finds the field whose `discriminantValue` is equal to the given value, or returns null if + // there is no such field. (If the schema does not represent a union or a struct containing + // an unnamed union, then this always returns null.) + +private: + StructSchema(Schema base): Schema(base) {} + template static inline StructSchema fromImpl() { + return StructSchema(Schema(&_::rawBrandedSchema())); + } + friend class Schema; + friend class Type; +}; + +class StructSchema::Field { +public: + Field() = default; + + inline schema::Field::Reader getProto() const { return proto; } + inline StructSchema getContainingStruct() const { return parent; } + + inline uint getIndex() const { return index; } + // Get the index of this field within the containing struct or union. + + Type getType() const; + // Get the type of this field. Note that this is preferred over getProto().getType() as this + // method will apply generics. + + uint32_t getDefaultValueSchemaOffset() const; + // For struct, list, and object fields, returns the offset, in words, within the first segment of + // the struct's schema, where this field's default value pointer is located. The schema is + // always stored as a single-segment unchecked message, which in turn means that the default + // value pointer itself can be treated as the root of an unchecked message -- if you know where + // to find it, which is what this method helps you with. + // + // For blobs, returns the offset of the beginning of the blob's content within the first segment + // of the struct's schema. + // + // This is primarily useful for code generators. The C++ code generator, for example, embeds + // the entire schema as a raw word array within the generated code. Of course, to implement + // field accessors, it needs access to those fields' default values. Embedding separate copies + // of those default values would be redundant since they are already included in the schema, but + // seeking through the schema at runtime to find the default values would be ugly. Instead, + // the code generator can use getDefaultValueSchemaOffset() to find the offset of the default + // value within the schema, and can simply apply that offset at runtime. + // + // If the above does not make sense, you probably don't need this method. + + inline bool operator==(const Field& other) const; + inline bool operator!=(const Field& other) const { return !(*this == other); } + +private: + StructSchema parent; + uint index; + schema::Field::Reader proto; + + inline Field(StructSchema parent, uint index, schema::Field::Reader proto) + : parent(parent), index(index), proto(proto) {} + + friend class StructSchema; +}; + +kj::StringPtr KJ_STRINGIFY(const StructSchema::Field& field); + +class StructSchema::FieldList { +public: + FieldList() = default; // empty list + + inline uint size() const { return list.size(); } + inline Field operator[](uint index) const { return Field(parent, index, list[index]); } + + typedef _::IndexingIterator Iterator; + inline Iterator begin() const { return Iterator(this, 0); } + inline Iterator end() const { return Iterator(this, size()); } + +private: + StructSchema parent; + List::Reader list; + + inline FieldList(StructSchema parent, List::Reader list) + : parent(parent), list(list) {} + + friend class StructSchema; +}; + +class StructSchema::FieldSubset { +public: + FieldSubset() = default; // empty list + + inline uint size() const { return size_; } + inline Field operator[](uint index) const { + return Field(parent, indices[index], list[indices[index]]); + } + + typedef _::IndexingIterator Iterator; + inline Iterator begin() const { return Iterator(this, 0); } + inline Iterator end() const { return Iterator(this, size()); } + +private: + StructSchema parent; + List::Reader list; + const uint16_t* indices; + uint size_; + + inline FieldSubset(StructSchema parent, List::Reader list, + const uint16_t* indices, uint size) + : parent(parent), list(list), indices(indices), size_(size) {} + + friend class StructSchema; +}; + +// ------------------------------------------------------------------- + +class EnumSchema: public Schema { +public: + inline EnumSchema(): Schema(&_::NULL_ENUM_SCHEMA.defaultBrand) {} + + class Enumerant; + class EnumerantList; + + EnumerantList getEnumerants() const; + + kj::Maybe findEnumerantByName(kj::StringPtr name) const; + + Enumerant getEnumerantByName(kj::StringPtr name) const; + // Like findEnumerantByName() but throws an exception on failure. + +private: + EnumSchema(Schema base): Schema(base) {} + template static inline EnumSchema fromImpl() { + return EnumSchema(Schema(&_::rawBrandedSchema())); + } + friend class Schema; + friend class Type; +}; + +class EnumSchema::Enumerant { +public: + Enumerant() = default; + + inline schema::Enumerant::Reader getProto() const { return proto; } + inline EnumSchema getContainingEnum() const { return parent; } + + inline uint16_t getOrdinal() const { return ordinal; } + inline uint getIndex() const { return ordinal; } + + inline bool operator==(const Enumerant& other) const; + inline bool operator!=(const Enumerant& other) const { return !(*this == other); } + +private: + EnumSchema parent; + uint16_t ordinal; + schema::Enumerant::Reader proto; + + inline Enumerant(EnumSchema parent, uint16_t ordinal, schema::Enumerant::Reader proto) + : parent(parent), ordinal(ordinal), proto(proto) {} + + friend class EnumSchema; +}; + +class EnumSchema::EnumerantList { +public: + EnumerantList() = default; // empty list + + inline uint size() const { return list.size(); } + inline Enumerant operator[](uint index) const { return Enumerant(parent, index, list[index]); } + + typedef _::IndexingIterator Iterator; + inline Iterator begin() const { return Iterator(this, 0); } + inline Iterator end() const { return Iterator(this, size()); } + +private: + EnumSchema parent; + List::Reader list; + + inline EnumerantList(EnumSchema parent, List::Reader list) + : parent(parent), list(list) {} + + friend class EnumSchema; +}; + +// ------------------------------------------------------------------- + +class InterfaceSchema: public Schema { +public: + inline InterfaceSchema(): Schema(&_::NULL_INTERFACE_SCHEMA.defaultBrand) {} + + class Method; + class MethodList; + + MethodList getMethods() const; + + kj::Maybe findMethodByName(kj::StringPtr name) const; + + Method getMethodByName(kj::StringPtr name) const; + // Like findMethodByName() but throws an exception on failure. + + class SuperclassList; + + SuperclassList getSuperclasses() const; + // Get the immediate superclasses of this type, after applying generics. + + bool extends(InterfaceSchema other) const; + // Returns true if `other` is a superclass of this interface (including if `other == *this`). + + kj::Maybe findSuperclass(uint64_t typeId) const; + // Find the superclass of this interface with the given type ID. Returns null if the interface + // extends no such type. + +private: + InterfaceSchema(Schema base): Schema(base) {} + template static inline InterfaceSchema fromImpl() { + return InterfaceSchema(Schema(&_::rawBrandedSchema())); + } + friend class Schema; + friend class Type; + + kj::Maybe findMethodByName(kj::StringPtr name, uint& counter) const; + bool extends(InterfaceSchema other, uint& counter) const; + kj::Maybe findSuperclass(uint64_t typeId, uint& counter) const; + // We protect against malicious schemas with large or cyclic hierarchies by cutting off the + // search when the counter reaches a threshold. +}; + +class InterfaceSchema::Method { +public: + Method() = default; + + inline schema::Method::Reader getProto() const { return proto; } + inline InterfaceSchema getContainingInterface() const { return parent; } + + inline uint16_t getOrdinal() const { return ordinal; } + inline uint getIndex() const { return ordinal; } + + StructSchema getParamType() const; + StructSchema getResultType() const; + // Get the parameter and result types, including substituting generic parameters. + + inline bool operator==(const Method& other) const; + inline bool operator!=(const Method& other) const { return !(*this == other); } + +private: + InterfaceSchema parent; + uint16_t ordinal; + schema::Method::Reader proto; + + inline Method(InterfaceSchema parent, uint16_t ordinal, + schema::Method::Reader proto) + : parent(parent), ordinal(ordinal), proto(proto) {} + + friend class InterfaceSchema; +}; + +class InterfaceSchema::MethodList { +public: + MethodList() = default; // empty list + + inline uint size() const { return list.size(); } + inline Method operator[](uint index) const { return Method(parent, index, list[index]); } + + typedef _::IndexingIterator Iterator; + inline Iterator begin() const { return Iterator(this, 0); } + inline Iterator end() const { return Iterator(this, size()); } + +private: + InterfaceSchema parent; + List::Reader list; + + inline MethodList(InterfaceSchema parent, List::Reader list) + : parent(parent), list(list) {} + + friend class InterfaceSchema; +}; + +class InterfaceSchema::SuperclassList { +public: + SuperclassList() = default; // empty list + + inline uint size() const { return list.size(); } + InterfaceSchema operator[](uint index) const; + + typedef _::IndexingIterator Iterator; + inline Iterator begin() const { return Iterator(this, 0); } + inline Iterator end() const { return Iterator(this, size()); } + +private: + InterfaceSchema parent; + List::Reader list; + + inline SuperclassList(InterfaceSchema parent, List::Reader list) + : parent(parent), list(list) {} + + friend class InterfaceSchema; +}; + +// ------------------------------------------------------------------- + +class ConstSchema: public Schema { + // Represents a constant declaration. + // + // `ConstSchema` can be implicitly cast to DynamicValue to read its value. + +public: + inline ConstSchema(): Schema(&_::NULL_CONST_SCHEMA.defaultBrand) {} + + template + ReaderFor as() const; + // Read the constant's value. This is a convenience method equivalent to casting the ConstSchema + // to a DynamicValue and then calling its `as()` method. For dependency reasons, this method + // is defined in , which you must #include explicitly. + + uint32_t getValueSchemaOffset() const; + // Much like StructSchema::Field::getDefaultValueSchemaOffset(), if the constant has pointer + // type, this gets the offset from the beginning of the constant's schema node to a pointer + // representing the constant value. + + Type getType() const; + +private: + ConstSchema(Schema base): Schema(base) {} + friend class Schema; +}; + +// ------------------------------------------------------------------- + +class Type { +public: + struct BrandParameter { + uint64_t scopeId; + uint index; + }; + struct ImplicitParameter { + uint index; + }; + + inline Type(); + inline Type(schema::Type::Which primitive); + inline Type(StructSchema schema); + inline Type(EnumSchema schema); + inline Type(InterfaceSchema schema); + inline Type(ListSchema schema); + inline Type(schema::Type::AnyPointer::Unconstrained::Which anyPointerKind); + inline Type(BrandParameter param); + inline Type(ImplicitParameter param); + + template + inline static Type from(); + + inline schema::Type::Which which() const; + + StructSchema asStruct() const; + EnumSchema asEnum() const; + InterfaceSchema asInterface() const; + ListSchema asList() const; + // Each of these methods may only be called if which() returns the corresponding type. + + kj::Maybe getBrandParameter() const; + // Only callable if which() returns ANY_POINTER. Returns null if the type is just a regular + // AnyPointer and not a parameter. + + kj::Maybe getImplicitParameter() const; + // Only callable if which() returns ANY_POINTER. Returns null if the type is just a regular + // AnyPointer and not a parameter. "Implicit parameters" refer to type parameters on methods. + + inline schema::Type::AnyPointer::Unconstrained::Which whichAnyPointerKind() const; + // Only callable if which() returns ANY_POINTER. + + inline bool isVoid() const; + inline bool isBool() const; + inline bool isInt8() const; + inline bool isInt16() const; + inline bool isInt32() const; + inline bool isInt64() const; + inline bool isUInt8() const; + inline bool isUInt16() const; + inline bool isUInt32() const; + inline bool isUInt64() const; + inline bool isFloat32() const; + inline bool isFloat64() const; + inline bool isText() const; + inline bool isData() const; + inline bool isList() const; + inline bool isEnum() const; + inline bool isStruct() const; + inline bool isInterface() const; + inline bool isAnyPointer() const; + + bool operator==(const Type& other) const; + inline bool operator!=(const Type& other) const { return !(*this == other); } + + size_t hashCode() const; + + inline Type wrapInList(uint depth = 1) const; + // Return the Type formed by wrapping this type in List() `depth` times. + + inline Type(schema::Type::Which derived, const _::RawBrandedSchema* schema); + // For internal use. + +private: + schema::Type::Which baseType; // type not including applications of List() + uint8_t listDepth; // 0 for T, 1 for List(T), 2 for List(List(T)), ... + + bool isImplicitParam; + // If true, this refers to an implicit method parameter. baseType must be ANY_POINTER, scopeId + // must be zero, and paramIndex indicates the parameter index. + + union { + uint16_t paramIndex; + // If baseType is ANY_POINTER but this Type actually refers to a type parameter, this is the + // index of the parameter among the parameters at its scope, and `scopeId` below is the type ID + // of the scope where the parameter was defined. + + schema::Type::AnyPointer::Unconstrained::Which anyPointerKind; + // If scopeId is zero and isImplicitParam is false. + }; + + union { + const _::RawBrandedSchema* schema; // if type is struct, enum, interface... + uint64_t scopeId; // if type is AnyPointer but it's actually a type parameter... + }; + + Type(schema::Type::Which baseType, uint8_t listDepth, const _::RawBrandedSchema* schema) + : baseType(baseType), listDepth(listDepth), schema(schema) { + KJ_IREQUIRE(baseType != schema::Type::ANY_POINTER); + } + + void requireUsableAs(Type expected) const; + + friend class ListSchema; // only for requireUsableAs() +}; + +// ------------------------------------------------------------------- + +class ListSchema { + // ListSchema is a little different because list types are not described by schema nodes. So, + // ListSchema doesn't subclass Schema. + +public: + ListSchema() = default; + + static ListSchema of(schema::Type::Which primitiveType); + static ListSchema of(StructSchema elementType); + static ListSchema of(EnumSchema elementType); + static ListSchema of(InterfaceSchema elementType); + static ListSchema of(ListSchema elementType); + static ListSchema of(Type elementType); + // Construct the schema for a list of the given type. + + static ListSchema of(schema::Type::Reader elementType, Schema context) + KJ_DEPRECATED("Does not handle generics correctly."); + // DEPRECATED: This method cannot correctly account for generic type parameter bindings that + // may apply to the input type. Instead of using this method, use a method of the Schema API + // that corresponds to the exact kind of dependency. For example, to get a field type, use + // StructSchema::Field::getType(). + // + // Construct from an element type schema. Requires a context which can handle getDependency() + // requests for any type ID found in the schema. + + Type getElementType() const; + + inline schema::Type::Which whichElementType() const; + // Get the element type's "which()". ListSchema does not actually store a schema::Type::Reader + // describing the element type, but if it did, this would be equivalent to calling + // .getBody().which() on that type. + + StructSchema getStructElementType() const; + EnumSchema getEnumElementType() const; + InterfaceSchema getInterfaceElementType() const; + ListSchema getListElementType() const; + // Get the schema for complex element types. Each of these throws an exception if the element + // type is not of the requested kind. + + inline bool operator==(const ListSchema& other) const { return elementType == other.elementType; } + inline bool operator!=(const ListSchema& other) const { return elementType != other.elementType; } + + template + void requireUsableAs() const; + +private: + Type elementType; + + inline explicit ListSchema(Type elementType): elementType(elementType) {} + + template + struct FromImpl; + template static inline ListSchema fromImpl() { + return FromImpl::get(); + } + + void requireUsableAs(ListSchema expected) const; + + friend class Schema; +}; + +// ======================================================================================= +// inline implementation + +template <> inline schema::Type::Which Schema::from() { return schema::Type::VOID; } +template <> inline schema::Type::Which Schema::from() { return schema::Type::BOOL; } +template <> inline schema::Type::Which Schema::from() { return schema::Type::INT8; } +template <> inline schema::Type::Which Schema::from() { return schema::Type::INT16; } +template <> inline schema::Type::Which Schema::from() { return schema::Type::INT32; } +template <> inline schema::Type::Which Schema::from() { return schema::Type::INT64; } +template <> inline schema::Type::Which Schema::from() { return schema::Type::UINT8; } +template <> inline schema::Type::Which Schema::from() { return schema::Type::UINT16; } +template <> inline schema::Type::Which Schema::from() { return schema::Type::UINT32; } +template <> inline schema::Type::Which Schema::from() { return schema::Type::UINT64; } +template <> inline schema::Type::Which Schema::from() { return schema::Type::FLOAT32; } +template <> inline schema::Type::Which Schema::from() { return schema::Type::FLOAT64; } +template <> inline schema::Type::Which Schema::from() { return schema::Type::TEXT; } +template <> inline schema::Type::Which Schema::from() { return schema::Type::DATA; } + +inline Schema Schema::getDependency(uint64_t id) const { + return getDependency(id, 0); +} + +inline bool Schema::isBranded() const { + return raw != &raw->generic->defaultBrand; +} + +inline Schema Schema::getGeneric() const { + return Schema(&raw->generic->defaultBrand); +} + +template +inline void Schema::requireUsableAs() const { + requireUsableAs(&_::rawSchema()); +} + +inline bool StructSchema::Field::operator==(const Field& other) const { + return parent == other.parent && index == other.index; +} +inline bool EnumSchema::Enumerant::operator==(const Enumerant& other) const { + return parent == other.parent && ordinal == other.ordinal; +} +inline bool InterfaceSchema::Method::operator==(const Method& other) const { + return parent == other.parent && ordinal == other.ordinal; +} + +inline ListSchema ListSchema::of(StructSchema elementType) { + return ListSchema(Type(elementType)); +} +inline ListSchema ListSchema::of(EnumSchema elementType) { + return ListSchema(Type(elementType)); +} +inline ListSchema ListSchema::of(InterfaceSchema elementType) { + return ListSchema(Type(elementType)); +} +inline ListSchema ListSchema::of(ListSchema elementType) { + return ListSchema(Type(elementType)); +} +inline ListSchema ListSchema::of(Type elementType) { + return ListSchema(elementType); +} + +inline Type ListSchema::getElementType() const { + return elementType; +} + +inline schema::Type::Which ListSchema::whichElementType() const { + return elementType.which(); +} + +inline StructSchema ListSchema::getStructElementType() const { + return elementType.asStruct(); +} + +inline EnumSchema ListSchema::getEnumElementType() const { + return elementType.asEnum(); +} + +inline InterfaceSchema ListSchema::getInterfaceElementType() const { + return elementType.asInterface(); +} + +inline ListSchema ListSchema::getListElementType() const { + return elementType.asList(); +} + +template +inline void ListSchema::requireUsableAs() const { + static_assert(kind() == Kind::LIST, + "ListSchema::requireUsableAs() requires T is a list type."); + requireUsableAs(Schema::from()); +} + +inline void ListSchema::requireUsableAs(ListSchema expected) const { + elementType.requireUsableAs(expected.elementType); +} + +template +struct ListSchema::FromImpl> { + static inline ListSchema get() { return of(Schema::from()); } +}; + +inline Type::Type(): baseType(schema::Type::VOID), listDepth(0), schema(nullptr) {} +inline Type::Type(schema::Type::Which primitive) + : baseType(primitive), listDepth(0), isImplicitParam(false) { + KJ_IREQUIRE(primitive != schema::Type::STRUCT && + primitive != schema::Type::ENUM && + primitive != schema::Type::INTERFACE && + primitive != schema::Type::LIST); + if (primitive == schema::Type::ANY_POINTER) { + scopeId = 0; + anyPointerKind = schema::Type::AnyPointer::Unconstrained::ANY_KIND; + } else { + schema = nullptr; + } +} +inline Type::Type(schema::Type::Which derived, const _::RawBrandedSchema* schema) + : baseType(derived), listDepth(0), isImplicitParam(false), schema(schema) { + KJ_IREQUIRE(derived == schema::Type::STRUCT || + derived == schema::Type::ENUM || + derived == schema::Type::INTERFACE); +} + +inline Type::Type(StructSchema schema) + : baseType(schema::Type::STRUCT), listDepth(0), schema(schema.raw) {} +inline Type::Type(EnumSchema schema) + : baseType(schema::Type::ENUM), listDepth(0), schema(schema.raw) {} +inline Type::Type(InterfaceSchema schema) + : baseType(schema::Type::INTERFACE), listDepth(0), schema(schema.raw) {} +inline Type::Type(ListSchema schema) + : Type(schema.getElementType()) { ++listDepth; } +inline Type::Type(schema::Type::AnyPointer::Unconstrained::Which anyPointerKind) + : baseType(schema::Type::ANY_POINTER), listDepth(0), isImplicitParam(false), + anyPointerKind(anyPointerKind), scopeId(0) {} +inline Type::Type(BrandParameter param) + : baseType(schema::Type::ANY_POINTER), listDepth(0), isImplicitParam(false), + paramIndex(param.index), scopeId(param.scopeId) {} +inline Type::Type(ImplicitParameter param) + : baseType(schema::Type::ANY_POINTER), listDepth(0), isImplicitParam(true), + paramIndex(param.index), scopeId(0) {} + +inline schema::Type::Which Type::which() const { + return listDepth > 0 ? schema::Type::LIST : baseType; +} + +inline schema::Type::AnyPointer::Unconstrained::Which Type::whichAnyPointerKind() const { + KJ_IREQUIRE(baseType == schema::Type::ANY_POINTER); + return !isImplicitParam && scopeId == 0 ? anyPointerKind + : schema::Type::AnyPointer::Unconstrained::ANY_KIND; +} + +template +inline Type Type::from() { return Type(Schema::from()); } + +inline bool Type::isVoid () const { return baseType == schema::Type::VOID && listDepth == 0; } +inline bool Type::isBool () const { return baseType == schema::Type::BOOL && listDepth == 0; } +inline bool Type::isInt8 () const { return baseType == schema::Type::INT8 && listDepth == 0; } +inline bool Type::isInt16 () const { return baseType == schema::Type::INT16 && listDepth == 0; } +inline bool Type::isInt32 () const { return baseType == schema::Type::INT32 && listDepth == 0; } +inline bool Type::isInt64 () const { return baseType == schema::Type::INT64 && listDepth == 0; } +inline bool Type::isUInt8 () const { return baseType == schema::Type::UINT8 && listDepth == 0; } +inline bool Type::isUInt16 () const { return baseType == schema::Type::UINT16 && listDepth == 0; } +inline bool Type::isUInt32 () const { return baseType == schema::Type::UINT32 && listDepth == 0; } +inline bool Type::isUInt64 () const { return baseType == schema::Type::UINT64 && listDepth == 0; } +inline bool Type::isFloat32() const { return baseType == schema::Type::FLOAT32 && listDepth == 0; } +inline bool Type::isFloat64() const { return baseType == schema::Type::FLOAT64 && listDepth == 0; } +inline bool Type::isText () const { return baseType == schema::Type::TEXT && listDepth == 0; } +inline bool Type::isData () const { return baseType == schema::Type::DATA && listDepth == 0; } +inline bool Type::isList () const { return listDepth > 0; } +inline bool Type::isEnum () const { return baseType == schema::Type::ENUM && listDepth == 0; } +inline bool Type::isStruct () const { return baseType == schema::Type::STRUCT && listDepth == 0; } +inline bool Type::isInterface() const { + return baseType == schema::Type::INTERFACE && listDepth == 0; +} +inline bool Type::isAnyPointer() const { + return baseType == schema::Type::ANY_POINTER && listDepth == 0; +} + +inline Type Type::wrapInList(uint depth) const { + Type result = *this; + result.listDepth += depth; + return result; +} + +} // namespace capnp + +#endif // CAPNP_SCHEMA_H_ diff --git a/phonelibs/capnp-cpp/include/capnp/serialize-async.h b/phonelibs/capnp-cpp/include/capnp/serialize-async.h new file mode 100644 index 00000000000000..a16bfd8975a6c7 --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/serialize-async.h @@ -0,0 +1,64 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef CAPNP_SERIALIZE_ASYNC_H_ +#define CAPNP_SERIALIZE_ASYNC_H_ + +#if defined(__GNUC__) && !defined(CAPNP_HEADER_WARNINGS) +#pragma GCC system_header +#endif + +#include +#include "message.h" + +namespace capnp { + +kj::Promise> readMessage( + kj::AsyncInputStream& input, ReaderOptions options = ReaderOptions(), + kj::ArrayPtr scratchSpace = nullptr); +// Read a message asynchronously. +// +// `input` must remain valid until the returned promise resolves (or is canceled). +// +// `scratchSpace`, if provided, must remain valid until the returned MessageReader is destroyed. + +kj::Promise>> tryReadMessage( + kj::AsyncInputStream& input, ReaderOptions options = ReaderOptions(), + kj::ArrayPtr scratchSpace = nullptr); +// Like `readMessage` but returns null on EOF. + +kj::Promise writeMessage(kj::AsyncOutputStream& output, + kj::ArrayPtr> segments) + KJ_WARN_UNUSED_RESULT; +kj::Promise writeMessage(kj::AsyncOutputStream& output, MessageBuilder& builder) + KJ_WARN_UNUSED_RESULT; +// Write asynchronously. The parameters must remain valid until the returned promise resolves. + +// ======================================================================================= +// inline implementation details + +inline kj::Promise writeMessage(kj::AsyncOutputStream& output, MessageBuilder& builder) { + return writeMessage(output, builder.getSegmentsForOutput()); +} + +} // namespace capnp + +#endif // CAPNP_SERIALIZE_ASYNC_H_ diff --git a/phonelibs/capnp-cpp/include/capnp/serialize-packed.h b/phonelibs/capnp-cpp/include/capnp/serialize-packed.h new file mode 100644 index 00000000000000..a71260ce1dd4c1 --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/serialize-packed.h @@ -0,0 +1,130 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef CAPNP_SERIALIZE_PACKED_H_ +#define CAPNP_SERIALIZE_PACKED_H_ + +#if defined(__GNUC__) && !defined(CAPNP_HEADER_WARNINGS) +#pragma GCC system_header +#endif + +#include "serialize.h" + +namespace capnp { + +namespace _ { // private + +class PackedInputStream: public kj::InputStream { + // An input stream that unpacks packed data with a picky constraint: The caller must read data + // in the exact same size and sequence as the data was written to PackedOutputStream. + +public: + explicit PackedInputStream(kj::BufferedInputStream& inner); + KJ_DISALLOW_COPY(PackedInputStream); + ~PackedInputStream() noexcept(false); + + // implements InputStream ------------------------------------------ + size_t tryRead(void* buffer, size_t minBytes, size_t maxBytes) override; + void skip(size_t bytes) override; + +private: + kj::BufferedInputStream& inner; +}; + +class PackedOutputStream: public kj::OutputStream { +public: + explicit PackedOutputStream(kj::BufferedOutputStream& inner); + KJ_DISALLOW_COPY(PackedOutputStream); + ~PackedOutputStream() noexcept(false); + + // implements OutputStream ----------------------------------------- + void write(const void* buffer, size_t bytes) override; + +private: + kj::BufferedOutputStream& inner; +}; + +} // namespace _ (private) + +class PackedMessageReader: private _::PackedInputStream, public InputStreamMessageReader { +public: + PackedMessageReader(kj::BufferedInputStream& inputStream, ReaderOptions options = ReaderOptions(), + kj::ArrayPtr scratchSpace = nullptr); + KJ_DISALLOW_COPY(PackedMessageReader); + ~PackedMessageReader() noexcept(false); +}; + +class PackedFdMessageReader: private kj::FdInputStream, private kj::BufferedInputStreamWrapper, + public PackedMessageReader { +public: + PackedFdMessageReader(int fd, ReaderOptions options = ReaderOptions(), + kj::ArrayPtr scratchSpace = nullptr); + // Read message from a file descriptor, without taking ownership of the descriptor. + // Note that if you want to reuse the descriptor after the reader is destroyed, you'll need to + // seek it, since otherwise the position is unspecified. + + PackedFdMessageReader(kj::AutoCloseFd fd, ReaderOptions options = ReaderOptions(), + kj::ArrayPtr scratchSpace = nullptr); + // Read a message from a file descriptor, taking ownership of the descriptor. + + KJ_DISALLOW_COPY(PackedFdMessageReader); + + ~PackedFdMessageReader() noexcept(false); +}; + +void writePackedMessage(kj::BufferedOutputStream& output, MessageBuilder& builder); +void writePackedMessage(kj::BufferedOutputStream& output, + kj::ArrayPtr> segments); +// Write a packed message to a buffered output stream. + +void writePackedMessage(kj::OutputStream& output, MessageBuilder& builder); +void writePackedMessage(kj::OutputStream& output, + kj::ArrayPtr> segments); +// Write a packed message to an unbuffered output stream. If you intend to write multiple messages +// in succession, consider wrapping your output in a buffered stream in order to reduce system +// call overhead. + +void writePackedMessageToFd(int fd, MessageBuilder& builder); +void writePackedMessageToFd(int fd, kj::ArrayPtr> segments); +// Write a single packed message to the file descriptor. + +size_t computeUnpackedSizeInWords(kj::ArrayPtr packedBytes); +// Computes the number of words to which the given packed bytes will unpack. Not intended for use +// in performance-sensitive situations. + +// ======================================================================================= +// inline stuff + +inline void writePackedMessage(kj::BufferedOutputStream& output, MessageBuilder& builder) { + writePackedMessage(output, builder.getSegmentsForOutput()); +} + +inline void writePackedMessage(kj::OutputStream& output, MessageBuilder& builder) { + writePackedMessage(output, builder.getSegmentsForOutput()); +} + +inline void writePackedMessageToFd(int fd, MessageBuilder& builder) { + writePackedMessageToFd(fd, builder.getSegmentsForOutput()); +} + +} // namespace capnp + +#endif // CAPNP_SERIALIZE_PACKED_H_ diff --git a/phonelibs/capnp-cpp/include/capnp/serialize-text.h b/phonelibs/capnp-cpp/include/capnp/serialize-text.h new file mode 100644 index 00000000000000..d86fc2c00ec8a5 --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/serialize-text.h @@ -0,0 +1,96 @@ +// Copyright (c) 2015 Philip Quinn. +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef CAPNP_SERIALIZE_TEXT_H_ +#define CAPNP_SERIALIZE_TEXT_H_ + +#if defined(__GNUC__) && !defined(CAPNP_HEADER_WARNINGS) +#pragma GCC system_header +#endif + +#include +#include "dynamic.h" +#include "orphan.h" +#include "schema.h" + +namespace capnp { + +class TextCodec { + // Reads and writes Cap'n Proto objects in a plain text format (as used in the schema + // language for constants, and read/written by the 'decode' and 'encode' commands of + // the capnp tool). + // + // This format is useful for debugging or human input, but it is not a robust alternative + // to the binary format. Changes to a schema's types or names that are permitted in a + // schema's binary evolution will likely break messages stored in this format. + // + // Note that definitions or references (to constants, other fields, or files) are not + // permitted in this format. To evaluate declarations with the full expressiveness of the + // schema language, see `capnp::SchemaParser`. + // + // Requires linking with the capnpc library. + +public: + TextCodec(); + ~TextCodec() noexcept(true); + + void setPrettyPrint(bool enabled); + // If enabled, pads the output of `encode()` with spaces and newlines to make it more + // human-readable. + + template + kj::String encode(T&& value) const; + kj::String encode(DynamicValue::Reader value) const; + // Encode any Cap'n Proto value. + + template + Orphan decode(kj::StringPtr input, Orphanage orphanage) const; + // Decode a text message into a Cap'n Proto object of type T, allocated in the given + // orphanage. Any errors parsing the input or assigning the fields of T are thrown as + // exceptions. + + void decode(kj::StringPtr input, DynamicStruct::Builder output) const; + // Decode a text message for a struct into the given builder. Any errors parsing the + // input or assigning the fields of the output are thrown as exceptions. + + // TODO(someday): expose some control over the error handling? +private: + Orphan decode(kj::StringPtr input, Type type, Orphanage orphanage) const; + + bool prettyPrint; +}; + +// ======================================================================================= +// inline stuff + +template +inline kj::String TextCodec::encode(T&& value) const { + return encode(DynamicValue::Reader(ReaderFor>(kj::fwd(value)))); +} + +template +inline Orphan TextCodec::decode(kj::StringPtr input, Orphanage orphanage) const { + return decode(input, Type::from(), orphanage).template releaseAs(); +} + +} // namespace capnp + +#endif // CAPNP_SERIALIZE_TEXT_H_ diff --git a/phonelibs/capnp-cpp/include/capnp/serialize.h b/phonelibs/capnp-cpp/include/capnp/serialize.h new file mode 100644 index 00000000000000..797db517662abd --- /dev/null +++ b/phonelibs/capnp-cpp/include/capnp/serialize.h @@ -0,0 +1,237 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +// This file implements a simple serialization format for Cap'n Proto messages. The format +// is as follows: +// +// * 32-bit little-endian segment count (4 bytes). +// * 32-bit little-endian size of each segment (4*(segment count) bytes). +// * Padding so that subsequent data is 64-bit-aligned (0 or 4 bytes). (I.e., if there are an even +// number of segments, there are 4 bytes of zeros here, otherwise there is no padding.) +// * Data from each segment, in order (8*sum(segment sizes) bytes) +// +// This format has some important properties: +// - It is self-delimiting, so multiple messages may be written to a stream without any external +// delimiter. +// - The total size and position of each segment can be determined by reading only the first part +// of the message, allowing lazy and random-access reading of the segment data. +// - A message is always at least 8 bytes. +// - A single-segment message can be read entirely in two system calls with no buffering. +// - A multi-segment message can be read entirely in three system calls with no buffering. +// - The format is appropriate for mmap()ing since all data is aligned. + +#ifndef CAPNP_SERIALIZE_H_ +#define CAPNP_SERIALIZE_H_ + +#if defined(__GNUC__) && !defined(CAPNP_HEADER_WARNINGS) +#pragma GCC system_header +#endif + +#include "message.h" +#include + +namespace capnp { + +class FlatArrayMessageReader: public MessageReader { + // Parses a message from a flat array. Note that it makes sense to use this together with mmap() + // for extremely fast parsing. + +public: + FlatArrayMessageReader(kj::ArrayPtr array, ReaderOptions options = ReaderOptions()); + // The array must remain valid until the MessageReader is destroyed. + + kj::ArrayPtr getSegment(uint id) override; + + const word* getEnd() const { return end; } + // Get a pointer just past the end of the message as determined by reading the message header. + // This could actually be before the end of the input array. This pointer is useful e.g. if + // you know that the input array has extra stuff appended after the message and you want to + // get at it. + +private: + // Optimize for single-segment case. + kj::ArrayPtr segment0; + kj::Array> moreSegments; + const word* end; +}; + +kj::ArrayPtr initMessageBuilderFromFlatArrayCopy( + kj::ArrayPtr array, MessageBuilder& target, + ReaderOptions options = ReaderOptions()); +// Convenience function which reads a message using `FlatArrayMessageReader` then copies the +// content into the target `MessageBuilder`, verifying that the message structure is valid +// (although not necessarily that it matches the desired schema). +// +// Returns an ArrayPtr containing any words left over in the array after consuming the whole +// message. This is useful when reading multiple messages that have been concatenated. See also +// FlatArrayMessageReader::getEnd(). +// +// (Note that it's also possible to initialize a `MessageBuilder` directly without a copy using one +// of `MessageBuilder`'s constructors. However, this approach skips the validation step and is not +// safe to use on untrusted input. Therefore, we do not provide a convenience method for it.) + +kj::Array messageToFlatArray(MessageBuilder& builder); +// Constructs a flat array containing the entire content of the given message. +// +// To output the message as bytes, use `.asBytes()` on the returned word array. Keep in mind that +// `asBytes()` returns an ArrayPtr, so you have to save the Array as well to prevent it from being +// deleted. For example: +// +// kj::Array words = messageToFlatArray(myMessage); +// kj::ArrayPtr bytes = words.asBytes(); +// write(fd, bytes.begin(), bytes.size()); + +kj::Array messageToFlatArray(kj::ArrayPtr> segments); +// Version of messageToFlatArray that takes a raw segment array. + +size_t computeSerializedSizeInWords(MessageBuilder& builder); +// Returns the size, in words, that will be needed to serialize the message, including the header. + +size_t computeSerializedSizeInWords(kj::ArrayPtr> segments); +// Version of computeSerializedSizeInWords that takes a raw segment array. + +size_t expectedSizeInWordsFromPrefix(kj::ArrayPtr messagePrefix); +// Given a prefix of a serialized message, try to determine the expected total size of the message, +// in words. The returned size is based on the information known so far; it may be an underestimate +// if the prefix doesn't contain the full segment table. +// +// If the returned value is greater than `messagePrefix.size()`, then the message is not yet +// complete and the app cannot parse it yet. If the returned value is less than or equal to +// `messagePrefix.size()`, then the returned value is the exact total size of the message; any +// remaining bytes are part of the next message. +// +// This function is useful when reading messages from a stream in an asynchronous way, but when +// using the full KJ async infrastructure would be too difficult. Each time bytes are received, +// use this function to determine if an entire message is ready to be parsed. + +// ======================================================================================= + +class InputStreamMessageReader: public MessageReader { + // A MessageReader that reads from an abstract kj::InputStream. See also StreamFdMessageReader + // for a subclass specific to file descriptors. + +public: + InputStreamMessageReader(kj::InputStream& inputStream, + ReaderOptions options = ReaderOptions(), + kj::ArrayPtr scratchSpace = nullptr); + ~InputStreamMessageReader() noexcept(false); + + // implements MessageReader ---------------------------------------- + kj::ArrayPtr getSegment(uint id) override; + +private: + kj::InputStream& inputStream; + byte* readPos; + + // Optimize for single-segment case. + kj::ArrayPtr segment0; + kj::Array> moreSegments; + + kj::Array ownedSpace; + // Only if scratchSpace wasn't big enough. + + kj::UnwindDetector unwindDetector; +}; + +void readMessageCopy(kj::InputStream& input, MessageBuilder& target, + ReaderOptions options = ReaderOptions(), + kj::ArrayPtr scratchSpace = nullptr); +// Convenience function which reads a message using `InputStreamMessageReader` then copies the +// content into the target `MessageBuilder`, verifying that the message structure is valid +// (although not necessarily that it matches the desired schema). +// +// (Note that it's also possible to initialize a `MessageBuilder` directly without a copy using one +// of `MessageBuilder`'s constructors. However, this approach skips the validation step and is not +// safe to use on untrusted input. Therefore, we do not provide a convenience method for it.) + +void writeMessage(kj::OutputStream& output, MessageBuilder& builder); +// Write the message to the given output stream. + +void writeMessage(kj::OutputStream& output, kj::ArrayPtr> segments); +// Write the segment array to the given output stream. + +// ======================================================================================= +// Specializations for reading from / writing to file descriptors. + +class StreamFdMessageReader: private kj::FdInputStream, public InputStreamMessageReader { + // A MessageReader that reads from a steam-based file descriptor. + +public: + StreamFdMessageReader(int fd, ReaderOptions options = ReaderOptions(), + kj::ArrayPtr scratchSpace = nullptr) + : FdInputStream(fd), InputStreamMessageReader(*this, options, scratchSpace) {} + // Read message from a file descriptor, without taking ownership of the descriptor. + + StreamFdMessageReader(kj::AutoCloseFd fd, ReaderOptions options = ReaderOptions(), + kj::ArrayPtr scratchSpace = nullptr) + : FdInputStream(kj::mv(fd)), InputStreamMessageReader(*this, options, scratchSpace) {} + // Read a message from a file descriptor, taking ownership of the descriptor. + + ~StreamFdMessageReader() noexcept(false); +}; + +void readMessageCopyFromFd(int fd, MessageBuilder& target, + ReaderOptions options = ReaderOptions(), + kj::ArrayPtr scratchSpace = nullptr); +// Convenience function which reads a message using `StreamFdMessageReader` then copies the +// content into the target `MessageBuilder`, verifying that the message structure is valid +// (although not necessarily that it matches the desired schema). +// +// (Note that it's also possible to initialize a `MessageBuilder` directly without a copy using one +// of `MessageBuilder`'s constructors. However, this approach skips the validation step and is not +// safe to use on untrusted input. Therefore, we do not provide a convenience method for it.) + +void writeMessageToFd(int fd, MessageBuilder& builder); +// Write the message to the given file descriptor. +// +// This function throws an exception on any I/O error. If your code is not exception-safe, be sure +// you catch this exception at the call site. If throwing an exception is not acceptable, you +// can implement your own OutputStream with arbitrary error handling and then use writeMessage(). + +void writeMessageToFd(int fd, kj::ArrayPtr> segments); +// Write the segment array to the given file descriptor. +// +// This function throws an exception on any I/O error. If your code is not exception-safe, be sure +// you catch this exception at the call site. If throwing an exception is not acceptable, you +// can implement your own OutputStream with arbitrary error handling and then use writeMessage(). + +// ======================================================================================= +// inline stuff + +inline kj::Array messageToFlatArray(MessageBuilder& builder) { + return messageToFlatArray(builder.getSegmentsForOutput()); +} + +inline size_t computeSerializedSizeInWords(MessageBuilder& builder) { + return computeSerializedSizeInWords(builder.getSegmentsForOutput()); +} + +inline void writeMessage(kj::OutputStream& output, MessageBuilder& builder) { + writeMessage(output, builder.getSegmentsForOutput()); +} + +inline void writeMessageToFd(int fd, MessageBuilder& builder) { + writeMessageToFd(fd, builder.getSegmentsForOutput()); +} + +} // namespace capnp + +#endif // SERIALIZE_H_ diff --git a/phonelibs/capnp-cpp/include/kj/arena.h b/phonelibs/capnp-cpp/include/kj/arena.h new file mode 100644 index 00000000000000..32c1f61c51626f --- /dev/null +++ b/phonelibs/capnp-cpp/include/kj/arena.h @@ -0,0 +1,213 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef KJ_ARENA_H_ +#define KJ_ARENA_H_ + +#if defined(__GNUC__) && !KJ_HEADER_WARNINGS +#pragma GCC system_header +#endif + +#include "memory.h" +#include "array.h" +#include "string.h" + +namespace kj { + +class Arena { + // A class which allows several objects to be allocated in contiguous chunks of memory, then + // frees them all at once. + // + // Allocating from the same Arena in multiple threads concurrently is NOT safe, because making + // it safe would require atomic operations that would slow down allocation even when + // single-threaded. If you need to use arena allocation in a multithreaded context, consider + // allocating thread-local arenas. + +public: + explicit Arena(size_t chunkSizeHint = 1024); + // Create an Arena. `chunkSizeHint` hints at where to start when allocating chunks, but is only + // a hint -- the Arena will, for example, allocate progressively larger chunks as time goes on, + // in order to reduce overall allocation overhead. + + explicit Arena(ArrayPtr scratch); + // Allocates from the given scratch space first, only resorting to the heap when it runs out. + + KJ_DISALLOW_COPY(Arena); + ~Arena() noexcept(false); + + template + T& allocate(Params&&... params); + template + ArrayPtr allocateArray(size_t size); + // Allocate an object or array of type T. If T has a non-trivial destructor, that destructor + // will be run during the Arena's destructor. Such destructors are run in opposite order of + // allocation. Note that these methods must maintain a list of destructors to call, which has + // overhead, but this overhead only applies if T has a non-trivial destructor. + + template + Own allocateOwn(Params&&... params); + template + Array allocateOwnArray(size_t size); + template + ArrayBuilder allocateOwnArrayBuilder(size_t capacity); + // Allocate an object or array of type T. Destructors are executed when the returned Own + // or Array goes out-of-scope, which must happen before the Arena is destroyed. This variant + // is useful when you need to control when the destructor is called. This variant also avoids + // the need for the Arena itself to keep track of destructors to call later, which may make it + // slightly more efficient. + + template + inline T& copy(T&& value) { return allocate>(kj::fwd(value)); } + // Allocate a copy of the given value in the arena. This is just a shortcut for calling the + // type's copy (or move) constructor. + + StringPtr copyString(StringPtr content); + // Make a copy of the given string inside the arena, and return a pointer to the copy. + +private: + struct ChunkHeader { + ChunkHeader* next; + byte* pos; // first unallocated byte in this chunk + byte* end; // end of this chunk + }; + struct ObjectHeader { + void (*destructor)(void*); + ObjectHeader* next; + }; + + size_t nextChunkSize; + ChunkHeader* chunkList = nullptr; + ObjectHeader* objectList = nullptr; + + ChunkHeader* currentChunk = nullptr; + + void cleanup(); + // Run all destructors, leaving the above pointers null. If a destructor throws, the State is + // left in a consistent state, such that if cleanup() is called again, it will pick up where + // it left off. + + void* allocateBytes(size_t amount, uint alignment, bool hasDisposer); + // Allocate the given number of bytes. `hasDisposer` must be true if `setDisposer()` may be + // called on this pointer later. + + void* allocateBytesInternal(size_t amount, uint alignment); + // Try to allocate the given number of bytes without taking a lock. Fails if and only if there + // is no space left in the current chunk. + + void setDestructor(void* ptr, void (*destructor)(void*)); + // Schedule the given destructor to be executed when the Arena is destroyed. `ptr` must be a + // pointer previously returned by an `allocateBytes()` call for which `hasDisposer` was true. + + template + static void destroyArray(void* pointer) { + size_t elementCount = *reinterpret_cast(pointer); + constexpr size_t prefixSize = kj::max(alignof(T), sizeof(size_t)); + DestructorOnlyArrayDisposer::instance.disposeImpl( + reinterpret_cast(pointer) + prefixSize, + sizeof(T), elementCount, elementCount, &destroyObject); + } + + template + static void destroyObject(void* pointer) { + dtor(*reinterpret_cast(pointer)); + } +}; + +// ======================================================================================= +// Inline implementation details + +template +T& Arena::allocate(Params&&... params) { + T& result = *reinterpret_cast(allocateBytes( + sizeof(T), alignof(T), !__has_trivial_destructor(T))); + if (!__has_trivial_constructor(T) || sizeof...(Params) > 0) { + ctor(result, kj::fwd(params)...); + } + if (!__has_trivial_destructor(T)) { + setDestructor(&result, &destroyObject); + } + return result; +} + +template +ArrayPtr Arena::allocateArray(size_t size) { + if (__has_trivial_destructor(T)) { + ArrayPtr result = + arrayPtr(reinterpret_cast(allocateBytes( + sizeof(T) * size, alignof(T), false)), size); + if (!__has_trivial_constructor(T)) { + for (size_t i = 0; i < size; i++) { + ctor(result[i]); + } + } + return result; + } else { + // Allocate with a 64-bit prefix in which we store the array size. + constexpr size_t prefixSize = kj::max(alignof(T), sizeof(size_t)); + void* base = allocateBytes(sizeof(T) * size + prefixSize, alignof(T), true); + size_t& tag = *reinterpret_cast(base); + ArrayPtr result = + arrayPtr(reinterpret_cast(reinterpret_cast(base) + prefixSize), size); + setDestructor(base, &destroyArray); + + if (__has_trivial_constructor(T)) { + tag = size; + } else { + // In case of constructor exceptions, we need the tag to end up storing the number of objects + // that were successfully constructed, so that they'll be properly destroyed. + tag = 0; + for (size_t i = 0; i < size; i++) { + ctor(result[i]); + tag = i + 1; + } + } + return result; + } +} + +template +Own Arena::allocateOwn(Params&&... params) { + T& result = *reinterpret_cast(allocateBytes(sizeof(T), alignof(T), false)); + if (!__has_trivial_constructor(T) || sizeof...(Params) > 0) { + ctor(result, kj::fwd(params)...); + } + return Own(&result, DestructorOnlyDisposer::instance); +} + +template +Array Arena::allocateOwnArray(size_t size) { + ArrayBuilder result = allocateOwnArrayBuilder(size); + for (size_t i = 0; i < size; i++) { + result.add(); + } + return result.finish(); +} + +template +ArrayBuilder Arena::allocateOwnArrayBuilder(size_t capacity) { + return ArrayBuilder( + reinterpret_cast(allocateBytes(sizeof(T) * capacity, alignof(T), false)), + capacity, DestructorOnlyArrayDisposer::instance); +} + +} // namespace kj + +#endif // KJ_ARENA_H_ diff --git a/phonelibs/capnp-cpp/include/kj/array.h b/phonelibs/capnp-cpp/include/kj/array.h new file mode 100644 index 00000000000000..51b5dcf31949ab --- /dev/null +++ b/phonelibs/capnp-cpp/include/kj/array.h @@ -0,0 +1,813 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef KJ_ARRAY_H_ +#define KJ_ARRAY_H_ + +#if defined(__GNUC__) && !KJ_HEADER_WARNINGS +#pragma GCC system_header +#endif + +#include "common.h" +#include +#include + +namespace kj { + +// ======================================================================================= +// ArrayDisposer -- Implementation details. + +class ArrayDisposer { + // Much like Disposer from memory.h. + +protected: + // Do not declare a destructor, as doing so will force a global initializer for + // HeapArrayDisposer::instance. + + virtual void disposeImpl(void* firstElement, size_t elementSize, size_t elementCount, + size_t capacity, void (*destroyElement)(void*)) const = 0; + // Disposes of the array. `destroyElement` invokes the destructor of each element, or is nullptr + // if the elements have trivial destructors. `capacity` is the amount of space that was + // allocated while `elementCount` is the number of elements that were actually constructed; + // these are always the same number for Array but may be different when using ArrayBuilder. + +public: + + template + void dispose(T* firstElement, size_t elementCount, size_t capacity) const; + // Helper wrapper around disposeImpl(). + // + // Callers must not call dispose() on the same array twice, even if the first call throws + // an exception. + +private: + template + struct Dispose_; +}; + +class ExceptionSafeArrayUtil { + // Utility class that assists in constructing or destroying elements of an array, where the + // constructor or destructor could throw exceptions. In case of an exception, + // ExceptionSafeArrayUtil's destructor will call destructors on all elements that have been + // constructed but not destroyed. Remember that destructors that throw exceptions are required + // to use UnwindDetector to detect unwind and avoid exceptions in this case. Therefore, no more + // than one exception will be thrown (and the program will not terminate). + +public: + inline ExceptionSafeArrayUtil(void* ptr, size_t elementSize, size_t constructedElementCount, + void (*destroyElement)(void*)) + : pos(reinterpret_cast(ptr) + elementSize * constructedElementCount), + elementSize(elementSize), constructedElementCount(constructedElementCount), + destroyElement(destroyElement) {} + KJ_DISALLOW_COPY(ExceptionSafeArrayUtil); + + inline ~ExceptionSafeArrayUtil() noexcept(false) { + if (constructedElementCount > 0) destroyAll(); + } + + void construct(size_t count, void (*constructElement)(void*)); + // Construct the given number of elements. + + void destroyAll(); + // Destroy all elements. Call this immediately before ExceptionSafeArrayUtil goes out-of-scope + // to ensure that one element throwing an exception does not prevent the others from being + // destroyed. + + void release() { constructedElementCount = 0; } + // Prevent ExceptionSafeArrayUtil's destructor from destroying the constructed elements. + // Call this after you've successfully finished constructing. + +private: + byte* pos; + size_t elementSize; + size_t constructedElementCount; + void (*destroyElement)(void*); +}; + +class DestructorOnlyArrayDisposer: public ArrayDisposer { +public: + static const DestructorOnlyArrayDisposer instance; + + void disposeImpl(void* firstElement, size_t elementSize, size_t elementCount, + size_t capacity, void (*destroyElement)(void*)) const override; +}; + +class NullArrayDisposer: public ArrayDisposer { + // An ArrayDisposer that does nothing. Can be used to construct a fake Arrays that doesn't + // actually own its content. + +public: + static const NullArrayDisposer instance; + + void disposeImpl(void* firstElement, size_t elementSize, size_t elementCount, + size_t capacity, void (*destroyElement)(void*)) const override; +}; + +// ======================================================================================= +// Array + +template +class Array { + // An owned array which will automatically be disposed of (using an ArrayDisposer) in the + // destructor. Can be moved, but not copied. Much like Own, but for arrays rather than + // single objects. + +public: + inline Array(): ptr(nullptr), size_(0), disposer(nullptr) {} + inline Array(decltype(nullptr)): ptr(nullptr), size_(0), disposer(nullptr) {} + inline Array(Array&& other) noexcept + : ptr(other.ptr), size_(other.size_), disposer(other.disposer) { + other.ptr = nullptr; + other.size_ = 0; + } + inline Array(Array>&& other) noexcept + : ptr(other.ptr), size_(other.size_), disposer(other.disposer) { + other.ptr = nullptr; + other.size_ = 0; + } + inline Array(T* firstElement, size_t size, const ArrayDisposer& disposer) + : ptr(firstElement), size_(size), disposer(&disposer) {} + + KJ_DISALLOW_COPY(Array); + inline ~Array() noexcept { dispose(); } + + inline operator ArrayPtr() { + return ArrayPtr(ptr, size_); + } + inline operator ArrayPtr() const { + return ArrayPtr(ptr, size_); + } + inline ArrayPtr asPtr() { + return ArrayPtr(ptr, size_); + } + inline ArrayPtr asPtr() const { + return ArrayPtr(ptr, size_); + } + + inline size_t size() const { return size_; } + inline T& operator[](size_t index) const { + KJ_IREQUIRE(index < size_, "Out-of-bounds Array access."); + return ptr[index]; + } + + inline const T* begin() const { return ptr; } + inline const T* end() const { return ptr + size_; } + inline const T& front() const { return *ptr; } + inline const T& back() const { return *(ptr + size_ - 1); } + inline T* begin() { return ptr; } + inline T* end() { return ptr + size_; } + inline T& front() { return *ptr; } + inline T& back() { return *(ptr + size_ - 1); } + + inline ArrayPtr slice(size_t start, size_t end) { + KJ_IREQUIRE(start <= end && end <= size_, "Out-of-bounds Array::slice()."); + return ArrayPtr(ptr + start, end - start); + } + inline ArrayPtr slice(size_t start, size_t end) const { + KJ_IREQUIRE(start <= end && end <= size_, "Out-of-bounds Array::slice()."); + return ArrayPtr(ptr + start, end - start); + } + + inline ArrayPtr asBytes() const { return asPtr().asBytes(); } + inline ArrayPtr> asBytes() { return asPtr().asBytes(); } + inline ArrayPtr asChars() const { return asPtr().asChars(); } + inline ArrayPtr> asChars() { return asPtr().asChars(); } + + inline Array> releaseAsBytes() { + // Like asBytes() but transfers ownership. + static_assert(sizeof(T) == sizeof(byte), + "releaseAsBytes() only possible on arrays with byte-size elements (e.g. chars)."); + Array> result( + reinterpret_cast*>(ptr), size_, *disposer); + ptr = nullptr; + size_ = 0; + return result; + } + inline Array> releaseAsChars() { + // Like asChars() but transfers ownership. + static_assert(sizeof(T) == sizeof(PropagateConst), + "releaseAsChars() only possible on arrays with char-size elements (e.g. bytes)."); + Array> result( + reinterpret_cast*>(ptr), size_, *disposer); + ptr = nullptr; + size_ = 0; + return result; + } + + inline bool operator==(decltype(nullptr)) const { return size_ == 0; } + inline bool operator!=(decltype(nullptr)) const { return size_ != 0; } + + inline Array& operator=(decltype(nullptr)) { + dispose(); + return *this; + } + + inline Array& operator=(Array&& other) { + dispose(); + ptr = other.ptr; + size_ = other.size_; + disposer = other.disposer; + other.ptr = nullptr; + other.size_ = 0; + return *this; + } + +private: + T* ptr; + size_t size_; + const ArrayDisposer* disposer; + + inline void dispose() { + // Make sure that if an exception is thrown, we are left with a null ptr, so we won't possibly + // dispose again. + T* ptrCopy = ptr; + size_t sizeCopy = size_; + if (ptrCopy != nullptr) { + ptr = nullptr; + size_ = 0; + disposer->dispose(ptrCopy, sizeCopy, sizeCopy); + } + } + + template + friend class Array; +}; + +static_assert(!canMemcpy>(), "canMemcpy<>() is broken"); + +namespace _ { // private + +class HeapArrayDisposer final: public ArrayDisposer { +public: + template + static T* allocate(size_t count); + template + static T* allocateUninitialized(size_t count); + + static const HeapArrayDisposer instance; + +private: + static void* allocateImpl(size_t elementSize, size_t elementCount, size_t capacity, + void (*constructElement)(void*), void (*destroyElement)(void*)); + // Allocates and constructs the array. Both function pointers are null if the constructor is + // trivial, otherwise destroyElement is null if the constructor doesn't throw. + + virtual void disposeImpl(void* firstElement, size_t elementSize, size_t elementCount, + size_t capacity, void (*destroyElement)(void*)) const override; + + template + struct Allocate_; +}; + +} // namespace _ (private) + +template +inline Array heapArray(size_t size) { + // Much like `heap()` from memory.h, allocates a new array on the heap. + + return Array(_::HeapArrayDisposer::allocate(size), size, + _::HeapArrayDisposer::instance); +} + +template Array heapArray(const T* content, size_t size); +template Array heapArray(ArrayPtr content); +template Array heapArray(ArrayPtr content); +template Array heapArray(Iterator begin, Iterator end); +template Array heapArray(std::initializer_list init); +// Allocate a heap array containing a copy of the given content. + +template +Array heapArrayFromIterable(Container&& a) { return heapArray(a.begin(), a.end()); } +template +Array heapArrayFromIterable(Array&& a) { return mv(a); } + +// ======================================================================================= +// ArrayBuilder + +template +class ArrayBuilder { + // Class which lets you build an Array specifying the exact constructor arguments for each + // element, rather than starting by default-constructing them. + +public: + ArrayBuilder(): ptr(nullptr), pos(nullptr), endPtr(nullptr) {} + ArrayBuilder(decltype(nullptr)): ptr(nullptr), pos(nullptr), endPtr(nullptr) {} + explicit ArrayBuilder(RemoveConst* firstElement, size_t capacity, + const ArrayDisposer& disposer) + : ptr(firstElement), pos(firstElement), endPtr(firstElement + capacity), + disposer(&disposer) {} + ArrayBuilder(ArrayBuilder&& other) + : ptr(other.ptr), pos(other.pos), endPtr(other.endPtr), disposer(other.disposer) { + other.ptr = nullptr; + other.pos = nullptr; + other.endPtr = nullptr; + } + KJ_DISALLOW_COPY(ArrayBuilder); + inline ~ArrayBuilder() noexcept(false) { dispose(); } + + inline operator ArrayPtr() { + return arrayPtr(ptr, pos); + } + inline operator ArrayPtr() const { + return arrayPtr(ptr, pos); + } + inline ArrayPtr asPtr() { + return arrayPtr(ptr, pos); + } + inline ArrayPtr asPtr() const { + return arrayPtr(ptr, pos); + } + + inline size_t size() const { return pos - ptr; } + inline size_t capacity() const { return endPtr - ptr; } + inline T& operator[](size_t index) const { + KJ_IREQUIRE(index < implicitCast(pos - ptr), "Out-of-bounds Array access."); + return ptr[index]; + } + + inline const T* begin() const { return ptr; } + inline const T* end() const { return pos; } + inline const T& front() const { return *ptr; } + inline const T& back() const { return *(pos - 1); } + inline T* begin() { return ptr; } + inline T* end() { return pos; } + inline T& front() { return *ptr; } + inline T& back() { return *(pos - 1); } + + ArrayBuilder& operator=(ArrayBuilder&& other) { + dispose(); + ptr = other.ptr; + pos = other.pos; + endPtr = other.endPtr; + disposer = other.disposer; + other.ptr = nullptr; + other.pos = nullptr; + other.endPtr = nullptr; + return *this; + } + ArrayBuilder& operator=(decltype(nullptr)) { + dispose(); + return *this; + } + + template + T& add(Params&&... params) { + KJ_IREQUIRE(pos < endPtr, "Added too many elements to ArrayBuilder."); + ctor(*pos, kj::fwd(params)...); + return *pos++; + } + + template + void addAll(Container&& container) { + addAll()>( + container.begin(), container.end()); + } + + template + void addAll(Iterator start, Iterator end); + + void removeLast() { + KJ_IREQUIRE(pos > ptr, "No elements present to remove."); + kj::dtor(*--pos); + } + + void truncate(size_t size) { + KJ_IREQUIRE(size <= this->size(), "can't use truncate() to expand"); + + T* target = ptr + size; + if (__has_trivial_destructor(T)) { + pos = target; + } else { + while (pos > target) { + kj::dtor(*--pos); + } + } + } + + void resize(size_t size) { + KJ_IREQUIRE(size <= capacity(), "can't resize past capacity"); + + T* target = ptr + size; + if (target > pos) { + // expand + if (__has_trivial_constructor(T)) { + pos = target; + } else { + while (pos < target) { + kj::ctor(*pos++); + } + } + } else { + // truncate + if (__has_trivial_destructor(T)) { + pos = target; + } else { + while (pos > target) { + kj::dtor(*--pos); + } + } + } + } + + Array finish() { + // We could safely remove this check if we assume that the disposer implementation doesn't + // need to know the original capacity, as is thes case with HeapArrayDisposer since it uses + // operator new() or if we created a custom disposer for ArrayBuilder which stores the capacity + // in a prefix. But that would make it hard to write cleverer heap allocators, and anyway this + // check might catch bugs. Probably people should use Vector if they want to build arrays + // without knowing the final size in advance. + KJ_IREQUIRE(pos == endPtr, "ArrayBuilder::finish() called prematurely."); + Array result(reinterpret_cast(ptr), pos - ptr, *disposer); + ptr = nullptr; + pos = nullptr; + endPtr = nullptr; + return result; + } + + inline bool isFull() const { + return pos == endPtr; + } + +private: + T* ptr; + RemoveConst* pos; + T* endPtr; + const ArrayDisposer* disposer; + + inline void dispose() { + // Make sure that if an exception is thrown, we are left with a null ptr, so we won't possibly + // dispose again. + T* ptrCopy = ptr; + T* posCopy = pos; + T* endCopy = endPtr; + if (ptrCopy != nullptr) { + ptr = nullptr; + pos = nullptr; + endPtr = nullptr; + disposer->dispose(ptrCopy, posCopy - ptrCopy, endCopy - ptrCopy); + } + } +}; + +template +inline ArrayBuilder heapArrayBuilder(size_t size) { + // Like `heapArray()` but does not default-construct the elements. You must construct them + // manually by calling `add()`. + + return ArrayBuilder(_::HeapArrayDisposer::allocateUninitialized>(size), + size, _::HeapArrayDisposer::instance); +} + +// ======================================================================================= +// Inline Arrays + +template +class FixedArray { + // A fixed-width array whose storage is allocated inline rather than on the heap. + +public: + inline size_t size() const { return fixedSize; } + inline T* begin() { return content; } + inline T* end() { return content + fixedSize; } + inline const T* begin() const { return content; } + inline const T* end() const { return content + fixedSize; } + + inline operator ArrayPtr() { + return arrayPtr(content, fixedSize); + } + inline operator ArrayPtr() const { + return arrayPtr(content, fixedSize); + } + + inline T& operator[](size_t index) { return content[index]; } + inline const T& operator[](size_t index) const { return content[index]; } + +private: + T content[fixedSize]; +}; + +template +class CappedArray { + // Like `FixedArray` but can be dynamically resized as long as the size does not exceed the limit + // specified by the template parameter. + // + // TODO(someday): Don't construct elements past currentSize? + +public: + inline KJ_CONSTEXPR() CappedArray(): currentSize(fixedSize) {} + inline explicit constexpr CappedArray(size_t s): currentSize(s) {} + + inline size_t size() const { return currentSize; } + inline void setSize(size_t s) { KJ_IREQUIRE(s <= fixedSize); currentSize = s; } + inline T* begin() { return content; } + inline T* end() { return content + currentSize; } + inline const T* begin() const { return content; } + inline const T* end() const { return content + currentSize; } + + inline operator ArrayPtr() { + return arrayPtr(content, currentSize); + } + inline operator ArrayPtr() const { + return arrayPtr(content, currentSize); + } + + inline T& operator[](size_t index) { return content[index]; } + inline const T& operator[](size_t index) const { return content[index]; } + +private: + size_t currentSize; + T content[fixedSize]; +}; + +// ======================================================================================= +// KJ_MAP + +#define KJ_MAP(elementName, array) \ + ::kj::_::Mapper(array) * \ + [&](typename ::kj::_::Mapper::Element elementName) +// Applies some function to every element of an array, returning an Array of the results, with +// nice syntax. Example: +// +// StringPtr foo = "abcd"; +// Array bar = KJ_MAP(c, foo) -> char { return c + 1; }; +// KJ_ASSERT(str(bar) == "bcde"); + +namespace _ { // private + +template +struct Mapper { + T array; + Mapper(T&& array): array(kj::fwd(array)) {} + template + auto operator*(Func&& func) -> Array { + auto builder = heapArrayBuilder(array.size()); + for (auto iter = array.begin(); iter != array.end(); ++iter) { + builder.add(func(*iter)); + } + return builder.finish(); + } + typedef decltype(*kj::instance().begin()) Element; +}; + +template +struct Mapper { + T* array; + Mapper(T* array): array(array) {} + template + auto operator*(Func&& func) -> Array { + auto builder = heapArrayBuilder(s); + for (size_t i = 0; i < s; i++) { + builder.add(func(array[i])); + } + return builder.finish(); + } + typedef decltype(*array)& Element; +}; + +} // namespace _ (private) + +// ======================================================================================= +// Inline implementation details + +template +struct ArrayDisposer::Dispose_ { + static void dispose(T* firstElement, size_t elementCount, size_t capacity, + const ArrayDisposer& disposer) { + disposer.disposeImpl(const_cast*>(firstElement), + sizeof(T), elementCount, capacity, nullptr); + } +}; +template +struct ArrayDisposer::Dispose_ { + static void destruct(void* ptr) { + kj::dtor(*reinterpret_cast(ptr)); + } + + static void dispose(T* firstElement, size_t elementCount, size_t capacity, + const ArrayDisposer& disposer) { + disposer.disposeImpl(firstElement, sizeof(T), elementCount, capacity, &destruct); + } +}; + +template +void ArrayDisposer::dispose(T* firstElement, size_t elementCount, size_t capacity) const { + Dispose_::dispose(firstElement, elementCount, capacity, *this); +} + +namespace _ { // private + +template +struct HeapArrayDisposer::Allocate_ { + static T* allocate(size_t elementCount, size_t capacity) { + return reinterpret_cast(allocateImpl( + sizeof(T), elementCount, capacity, nullptr, nullptr)); + } +}; +template +struct HeapArrayDisposer::Allocate_ { + static void construct(void* ptr) { + kj::ctor(*reinterpret_cast(ptr)); + } + static T* allocate(size_t elementCount, size_t capacity) { + return reinterpret_cast(allocateImpl( + sizeof(T), elementCount, capacity, &construct, nullptr)); + } +}; +template +struct HeapArrayDisposer::Allocate_ { + static void construct(void* ptr) { + kj::ctor(*reinterpret_cast(ptr)); + } + static void destruct(void* ptr) { + kj::dtor(*reinterpret_cast(ptr)); + } + static T* allocate(size_t elementCount, size_t capacity) { + return reinterpret_cast(allocateImpl( + sizeof(T), elementCount, capacity, &construct, &destruct)); + } +}; + +template +T* HeapArrayDisposer::allocate(size_t count) { + return Allocate_::allocate(count, count); +} + +template +T* HeapArrayDisposer::allocateUninitialized(size_t count) { + return Allocate_::allocate(0, count); +} + +template ()> +struct CopyConstructArray_; + +template +struct CopyConstructArray_ { + static inline T* apply(T* __restrict__ pos, T* start, T* end) { + memcpy(pos, start, reinterpret_cast(end) - reinterpret_cast(start)); + return pos + (end - start); + } +}; + +template +struct CopyConstructArray_ { + static inline T* apply(T* __restrict__ pos, const T* start, const T* end) { + memcpy(pos, start, reinterpret_cast(end) - reinterpret_cast(start)); + return pos + (end - start); + } +}; + +template +struct CopyConstructArray_ { + static inline T* apply(T* __restrict__ pos, Iterator start, Iterator end) { + // Since both the copy constructor and assignment operator are trivial, we know that assignment + // is equivalent to copy-constructing. So we can make this case somewhat easier for the + // compiler to optimize. + while (start != end) { + *pos++ = *start++; + } + return pos; + } +}; + +template +struct CopyConstructArray_ { + struct ExceptionGuard { + T* start; + T* pos; + inline explicit ExceptionGuard(T* pos): start(pos), pos(pos) {} + ~ExceptionGuard() noexcept(false) { + while (pos > start) { + dtor(*--pos); + } + } + }; + + static T* apply(T* __restrict__ pos, Iterator start, Iterator end) { + // Verify that T can be *implicitly* constructed from the source values. + if (false) implicitCast(*start); + + if (noexcept(T(*start))) { + while (start != end) { + ctor(*pos++, *start++); + } + return pos; + } else { + // Crap. This is complicated. + ExceptionGuard guard(pos); + while (start != end) { + ctor(*guard.pos, *start++); + ++guard.pos; + } + guard.start = guard.pos; + return guard.pos; + } + } +}; + +template +struct CopyConstructArray_ { + // Actually move-construct. + + struct ExceptionGuard { + T* start; + T* pos; + inline explicit ExceptionGuard(T* pos): start(pos), pos(pos) {} + ~ExceptionGuard() noexcept(false) { + while (pos > start) { + dtor(*--pos); + } + } + }; + + static T* apply(T* __restrict__ pos, Iterator start, Iterator end) { + // Verify that T can be *implicitly* constructed from the source values. + if (false) implicitCast(kj::mv(*start)); + + if (noexcept(T(kj::mv(*start)))) { + while (start != end) { + ctor(*pos++, kj::mv(*start++)); + } + return pos; + } else { + // Crap. This is complicated. + ExceptionGuard guard(pos); + while (start != end) { + ctor(*guard.pos, kj::mv(*start++)); + ++guard.pos; + } + guard.start = guard.pos; + return guard.pos; + } + } +}; + +} // namespace _ (private) + +template +template +void ArrayBuilder::addAll(Iterator start, Iterator end) { + pos = _::CopyConstructArray_, Decay, move>::apply(pos, start, end); +} + +template +Array heapArray(const T* content, size_t size) { + ArrayBuilder builder = heapArrayBuilder(size); + builder.addAll(content, content + size); + return builder.finish(); +} + +template +Array heapArray(T* content, size_t size) { + ArrayBuilder builder = heapArrayBuilder(size); + builder.addAll(content, content + size); + return builder.finish(); +} + +template +Array heapArray(ArrayPtr content) { + ArrayBuilder builder = heapArrayBuilder(content.size()); + builder.addAll(content); + return builder.finish(); +} + +template +Array heapArray(ArrayPtr content) { + ArrayBuilder builder = heapArrayBuilder(content.size()); + builder.addAll(content); + return builder.finish(); +} + +template Array +heapArray(Iterator begin, Iterator end) { + ArrayBuilder builder = heapArrayBuilder(end - begin); + builder.addAll(begin, end); + return builder.finish(); +} + +template +inline Array heapArray(std::initializer_list init) { + return heapArray(init.begin(), init.end()); +} + +} // namespace kj + +#endif // KJ_ARRAY_H_ diff --git a/phonelibs/capnp-cpp/include/kj/async-inl.h b/phonelibs/capnp-cpp/include/kj/async-inl.h new file mode 100644 index 00000000000000..f11e4fcd5b9f74 --- /dev/null +++ b/phonelibs/capnp-cpp/include/kj/async-inl.h @@ -0,0 +1,1112 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +// This file contains extended inline implementation details that are required along with async.h. +// We move this all into a separate file to make async.h more readable. +// +// Non-inline declarations here are defined in async.c++. + +#ifndef KJ_ASYNC_H_ +#error "Do not include this directly; include kj/async.h." +#include "async.h" // help IDE parse this file +#endif + +#ifndef KJ_ASYNC_INL_H_ +#define KJ_ASYNC_INL_H_ + +#if defined(__GNUC__) && !KJ_HEADER_WARNINGS +#pragma GCC system_header +#endif + +namespace kj { +namespace _ { // private + +template +class ExceptionOr; + +class ExceptionOrValue { +public: + ExceptionOrValue(bool, Exception&& exception): exception(kj::mv(exception)) {} + KJ_DISALLOW_COPY(ExceptionOrValue); + + void addException(Exception&& exception) { + if (this->exception == nullptr) { + this->exception = kj::mv(exception); + } + } + + template + ExceptionOr& as() { return *static_cast*>(this); } + template + const ExceptionOr& as() const { return *static_cast*>(this); } + + Maybe exception; + +protected: + // Allow subclasses to have move constructor / assignment. + ExceptionOrValue() = default; + ExceptionOrValue(ExceptionOrValue&& other) = default; + ExceptionOrValue& operator=(ExceptionOrValue&& other) = default; +}; + +template +class ExceptionOr: public ExceptionOrValue { +public: + ExceptionOr() = default; + ExceptionOr(T&& value): value(kj::mv(value)) {} + ExceptionOr(bool, Exception&& exception): ExceptionOrValue(false, kj::mv(exception)) {} + ExceptionOr(ExceptionOr&&) = default; + ExceptionOr& operator=(ExceptionOr&&) = default; + + Maybe value; +}; + +class Event { + // An event waiting to be executed. Not for direct use by applications -- promises use this + // internally. + +public: + Event(); + ~Event() noexcept(false); + KJ_DISALLOW_COPY(Event); + + void armDepthFirst(); + // Enqueue this event so that `fire()` will be called from the event loop soon. + // + // Events scheduled in this way are executed in depth-first order: if an event callback arms + // more events, those events are placed at the front of the queue (in the order in which they + // were armed), so that they run immediately after the first event's callback returns. + // + // Depth-first event scheduling is appropriate for events that represent simple continuations + // of a previous event that should be globbed together for performance. Depth-first scheduling + // can lead to starvation, so any long-running task must occasionally yield with + // `armBreadthFirst()`. (Promise::then() uses depth-first whereas evalLater() uses + // breadth-first.) + // + // To use breadth-first scheduling instead, use `armBreadthFirst()`. + + void armBreadthFirst(); + // Like `armDepthFirst()` except that the event is placed at the end of the queue. + + kj::String trace(); + // Dump debug info about this event. + + virtual _::PromiseNode* getInnerForTrace(); + // If this event wraps a PromiseNode, get that node. Used for debug tracing. + // Default implementation returns nullptr. + +protected: + virtual Maybe> fire() = 0; + // Fire the event. Possibly returns a pointer to itself, which will be discarded by the + // caller. This is the only way that an event can delete itself as a result of firing, as + // doing so from within fire() will throw an exception. + +private: + friend class kj::EventLoop; + EventLoop& loop; + Event* next; + Event** prev; + bool firing = false; +}; + +class PromiseNode { + // A Promise contains a chain of PromiseNodes tracking the pending transformations. + // + // To reduce generated code bloat, PromiseNode is not a template. Instead, it makes very hacky + // use of pointers to ExceptionOrValue which actually point to ExceptionOr, but are only + // so down-cast in the few places that really need to be templated. Luckily this is all + // internal implementation details. + +public: + virtual void onReady(Event& event) noexcept = 0; + // Arms the given event when ready. + + virtual void setSelfPointer(Own* selfPtr) noexcept; + // Tells the node that `selfPtr` is the pointer that owns this node, and will continue to own + // this node until it is destroyed or setSelfPointer() is called again. ChainPromiseNode uses + // this to shorten redundant chains. The default implementation does nothing; only + // ChainPromiseNode should implement this. + + virtual void get(ExceptionOrValue& output) noexcept = 0; + // Get the result. `output` points to an ExceptionOr into which the result will be written. + // Can only be called once, and only after the node is ready. Must be called directly from the + // event loop, with no application code on the stack. + + virtual PromiseNode* getInnerForTrace(); + // If this node wraps some other PromiseNode, get the wrapped node. Used for debug tracing. + // Default implementation returns nullptr. + +protected: + class OnReadyEvent { + // Helper class for implementing onReady(). + + public: + void init(Event& newEvent); + // Returns true if arm() was already called. + + void arm(); + // Arms the event if init() has already been called and makes future calls to init() return + // true. + + private: + Event* event = nullptr; + }; +}; + +// ------------------------------------------------------------------- + +class ImmediatePromiseNodeBase: public PromiseNode { +public: + ImmediatePromiseNodeBase(); + ~ImmediatePromiseNodeBase() noexcept(false); + + void onReady(Event& event) noexcept override; +}; + +template +class ImmediatePromiseNode final: public ImmediatePromiseNodeBase { + // A promise that has already been resolved to an immediate value or exception. + +public: + ImmediatePromiseNode(ExceptionOr&& result): result(kj::mv(result)) {} + + void get(ExceptionOrValue& output) noexcept override { + output.as() = kj::mv(result); + } + +private: + ExceptionOr result; +}; + +class ImmediateBrokenPromiseNode final: public ImmediatePromiseNodeBase { +public: + ImmediateBrokenPromiseNode(Exception&& exception); + + void get(ExceptionOrValue& output) noexcept override; + +private: + Exception exception; +}; + +// ------------------------------------------------------------------- + +class AttachmentPromiseNodeBase: public PromiseNode { +public: + AttachmentPromiseNodeBase(Own&& dependency); + + void onReady(Event& event) noexcept override; + void get(ExceptionOrValue& output) noexcept override; + PromiseNode* getInnerForTrace() override; + +private: + Own dependency; + + void dropDependency(); + + template + friend class AttachmentPromiseNode; +}; + +template +class AttachmentPromiseNode final: public AttachmentPromiseNodeBase { + // A PromiseNode that holds on to some object (usually, an Own, but could be any movable + // object) until the promise resolves. + +public: + AttachmentPromiseNode(Own&& dependency, Attachment&& attachment) + : AttachmentPromiseNodeBase(kj::mv(dependency)), + attachment(kj::mv(attachment)) {} + + ~AttachmentPromiseNode() noexcept(false) { + // We need to make sure the dependency is deleted before we delete the attachment because the + // dependency may be using the attachment. + dropDependency(); + } + +private: + Attachment attachment; +}; + +// ------------------------------------------------------------------- + +class PtmfHelper { + // This class is a private helper for GetFunctorStartAddress. The class represents the internal + // representation of a pointer-to-member-function. + + template + friend struct GetFunctorStartAddress; + +#if __GNUG__ + + void* ptr; + ptrdiff_t adj; + // Layout of a pointer-to-member-function used by GCC and compatible compilers. + + void* apply(void* obj) { +#if defined(__arm__) || defined(__mips__) || defined(__aarch64__) + if (adj & 1) { + ptrdiff_t voff = (ptrdiff_t)ptr; +#else + ptrdiff_t voff = (ptrdiff_t)ptr; + if (voff & 1) { + voff &= ~1; +#endif + return *(void**)(*(char**)obj + voff); + } else { + return ptr; + } + } + +#define BODY \ + PtmfHelper result; \ + static_assert(sizeof(p) == sizeof(result), "unknown ptmf layout"); \ + memcpy(&result, &p, sizeof(result)); \ + return result + +#else // __GNUG__ + + void* apply(void* obj) { return nullptr; } + // TODO(port): PTMF instruction address extraction + +#define BODY return PtmfHelper{} + +#endif // __GNUG__, else + + template + static PtmfHelper from(F p) { BODY; } + // Create a PtmfHelper from some arbitrary pointer-to-member-function which is not + // overloaded nor a template. In this case the compiler is able to deduce the full function + // signature directly given the name since there is only one function with that name. + + template + static PtmfHelper from(R (C::*p)(NoInfer

...)) { BODY; } + template + static PtmfHelper from(R (C::*p)(NoInfer

...) const) { BODY; } + // Create a PtmfHelper from some poniter-to-member-function which is a template. In this case + // the function must match exactly the containing type C, return type R, and parameter types P... + // GetFunctorStartAddress normally specifies exactly the correct C and R, but can only make a + // guess at P. Luckily, if the function parameters are template parameters then it's not + // necessary to be precise about P. +#undef BODY +}; + +template +struct GetFunctorStartAddress { + // Given a functor (any object defining operator()), return the start address of the function, + // suitable for passing to addr2line to obtain a source file/line for debugging purposes. + // + // This turns out to be incredibly hard to implement in the presence of overloaded or templated + // functors. Therefore, we impose these specific restrictions, specific to our use case: + // - Overloading is not allowed, but templating is. (Generally we only intend to support lambdas + // anyway.) + // - The template parameters to GetFunctorStartAddress specify a hint as to the expected + // parameter types. If the functor is templated, its parameters must match exactly these types. + // (If it's not templated, ParamTypes are ignored.) + + template + static void* apply(Func&& func) { + typedef decltype(func(instance()...)) ReturnType; + return PtmfHelper::from, ParamTypes...>( + &Decay::operator()).apply(&func); + } +}; + +template <> +struct GetFunctorStartAddress: public GetFunctorStartAddress<> {}; +// Hack for TransformPromiseNode use case: an input type of `Void` indicates that the function +// actually has no parameters. + +class TransformPromiseNodeBase: public PromiseNode { +public: + TransformPromiseNodeBase(Own&& dependency, void* continuationTracePtr); + + void onReady(Event& event) noexcept override; + void get(ExceptionOrValue& output) noexcept override; + PromiseNode* getInnerForTrace() override; + +private: + Own dependency; + void* continuationTracePtr; + + void dropDependency(); + void getDepResult(ExceptionOrValue& output); + + virtual void getImpl(ExceptionOrValue& output) = 0; + + template + friend class TransformPromiseNode; +}; + +template +class TransformPromiseNode final: public TransformPromiseNodeBase { + // A PromiseNode that transforms the result of another PromiseNode through an application-provided + // function (implements `then()`). + +public: + TransformPromiseNode(Own&& dependency, Func&& func, ErrorFunc&& errorHandler) + : TransformPromiseNodeBase(kj::mv(dependency), + GetFunctorStartAddress::apply(func)), + func(kj::fwd(func)), errorHandler(kj::fwd(errorHandler)) {} + + ~TransformPromiseNode() noexcept(false) { + // We need to make sure the dependency is deleted before we delete the continuations because it + // is a common pattern for the continuations to hold ownership of objects that might be in-use + // by the dependency. + dropDependency(); + } + +private: + Func func; + ErrorFunc errorHandler; + + void getImpl(ExceptionOrValue& output) override { + ExceptionOr depResult; + getDepResult(depResult); + KJ_IF_MAYBE(depException, depResult.exception) { + output.as() = handle( + MaybeVoidCaller>>::apply( + errorHandler, kj::mv(*depException))); + } else KJ_IF_MAYBE(depValue, depResult.value) { + output.as() = handle(MaybeVoidCaller::apply(func, kj::mv(*depValue))); + } + } + + ExceptionOr handle(T&& value) { + return kj::mv(value); + } + ExceptionOr handle(PropagateException::Bottom&& value) { + return ExceptionOr(false, value.asException()); + } +}; + +// ------------------------------------------------------------------- + +class ForkHubBase; + +class ForkBranchBase: public PromiseNode { +public: + ForkBranchBase(Own&& hub); + ~ForkBranchBase() noexcept(false); + + void hubReady() noexcept; + // Called by the hub to indicate that it is ready. + + // implements PromiseNode ------------------------------------------ + void onReady(Event& event) noexcept override; + PromiseNode* getInnerForTrace() override; + +protected: + inline ExceptionOrValue& getHubResultRef(); + + void releaseHub(ExceptionOrValue& output); + // Release the hub. If an exception is thrown, add it to `output`. + +private: + OnReadyEvent onReadyEvent; + + Own hub; + ForkBranchBase* next = nullptr; + ForkBranchBase** prevPtr = nullptr; + + friend class ForkHubBase; +}; + +template T copyOrAddRef(T& t) { return t; } +template Own copyOrAddRef(Own& t) { return t->addRef(); } + +template +class ForkBranch final: public ForkBranchBase { + // A PromiseNode that implements one branch of a fork -- i.e. one of the branches that receives + // a const reference. + +public: + ForkBranch(Own&& hub): ForkBranchBase(kj::mv(hub)) {} + + void get(ExceptionOrValue& output) noexcept override { + ExceptionOr& hubResult = getHubResultRef().template as(); + KJ_IF_MAYBE(value, hubResult.value) { + output.as().value = copyOrAddRef(*value); + } else { + output.as().value = nullptr; + } + output.exception = hubResult.exception; + releaseHub(output); + } +}; + +template +class SplitBranch final: public ForkBranchBase { + // A PromiseNode that implements one branch of a fork -- i.e. one of the branches that receives + // a const reference. + +public: + SplitBranch(Own&& hub): ForkBranchBase(kj::mv(hub)) {} + + typedef kj::Decay(kj::instance()))> Element; + + void get(ExceptionOrValue& output) noexcept override { + ExceptionOr& hubResult = getHubResultRef().template as(); + KJ_IF_MAYBE(value, hubResult.value) { + output.as().value = kj::mv(kj::get(*value)); + } else { + output.as().value = nullptr; + } + output.exception = hubResult.exception; + releaseHub(output); + } +}; + +// ------------------------------------------------------------------- + +class ForkHubBase: public Refcounted, protected Event { +public: + ForkHubBase(Own&& inner, ExceptionOrValue& resultRef); + + inline ExceptionOrValue& getResultRef() { return resultRef; } + +private: + Own inner; + ExceptionOrValue& resultRef; + + ForkBranchBase* headBranch = nullptr; + ForkBranchBase** tailBranch = &headBranch; + // Tail becomes null once the inner promise is ready and all branches have been notified. + + Maybe> fire() override; + _::PromiseNode* getInnerForTrace() override; + + friend class ForkBranchBase; +}; + +template +class ForkHub final: public ForkHubBase { + // A PromiseNode that implements the hub of a fork. The first call to Promise::fork() replaces + // the promise's outer node with a ForkHub, and subsequent calls add branches to that hub (if + // possible). + +public: + ForkHub(Own&& inner): ForkHubBase(kj::mv(inner), result) {} + + Promise<_::UnfixVoid> addBranch() { + return Promise<_::UnfixVoid>(false, kj::heap>(addRef(*this))); + } + + _::SplitTuplePromise split() { + return splitImpl(MakeIndexes()>()); + } + +private: + ExceptionOr result; + + template + _::SplitTuplePromise splitImpl(Indexes) { + return kj::tuple(addSplit()...); + } + + template + Promise::Element>> addSplit() { + return Promise::Element>>( + false, maybeChain(kj::heap>(addRef(*this)), + implicitCast::Element*>(nullptr))); + } +}; + +inline ExceptionOrValue& ForkBranchBase::getHubResultRef() { + return hub->getResultRef(); +} + +// ------------------------------------------------------------------- + +class ChainPromiseNode final: public PromiseNode, public Event { + // Promise node which reduces Promise> to Promise. + // + // `Event` is only a public base class because otherwise we can't cast Own to + // Own. Ugh, templates and private... + +public: + explicit ChainPromiseNode(Own inner); + ~ChainPromiseNode() noexcept(false); + + void onReady(Event& event) noexcept override; + void setSelfPointer(Own* selfPtr) noexcept override; + void get(ExceptionOrValue& output) noexcept override; + PromiseNode* getInnerForTrace() override; + +private: + enum State { + STEP1, + STEP2 + }; + + State state; + + Own inner; + // In STEP1, a PromiseNode for a Promise. + // In STEP2, a PromiseNode for a T. + + Event* onReadyEvent = nullptr; + Own* selfPtr = nullptr; + + Maybe> fire() override; +}; + +template +Own maybeChain(Own&& node, Promise*) { + return heap(kj::mv(node)); +} + +template +Own&& maybeChain(Own&& node, T*) { + return kj::mv(node); +} + +// ------------------------------------------------------------------- + +class ExclusiveJoinPromiseNode final: public PromiseNode { +public: + ExclusiveJoinPromiseNode(Own left, Own right); + ~ExclusiveJoinPromiseNode() noexcept(false); + + void onReady(Event& event) noexcept override; + void get(ExceptionOrValue& output) noexcept override; + PromiseNode* getInnerForTrace() override; + +private: + class Branch: public Event { + public: + Branch(ExclusiveJoinPromiseNode& joinNode, Own dependency); + ~Branch() noexcept(false); + + bool get(ExceptionOrValue& output); + // Returns true if this is the side that finished. + + Maybe> fire() override; + _::PromiseNode* getInnerForTrace() override; + + private: + ExclusiveJoinPromiseNode& joinNode; + Own dependency; + }; + + Branch left; + Branch right; + OnReadyEvent onReadyEvent; +}; + +// ------------------------------------------------------------------- + +class ArrayJoinPromiseNodeBase: public PromiseNode { +public: + ArrayJoinPromiseNodeBase(Array> promises, + ExceptionOrValue* resultParts, size_t partSize); + ~ArrayJoinPromiseNodeBase() noexcept(false); + + void onReady(Event& event) noexcept override final; + void get(ExceptionOrValue& output) noexcept override final; + PromiseNode* getInnerForTrace() override final; + +protected: + virtual void getNoError(ExceptionOrValue& output) noexcept = 0; + // Called to compile the result only in the case where there were no errors. + +private: + uint countLeft; + OnReadyEvent onReadyEvent; + + class Branch final: public Event { + public: + Branch(ArrayJoinPromiseNodeBase& joinNode, Own dependency, + ExceptionOrValue& output); + ~Branch() noexcept(false); + + Maybe> fire() override; + _::PromiseNode* getInnerForTrace() override; + + Maybe getPart(); + // Calls dependency->get(output). If there was an exception, return it. + + private: + ArrayJoinPromiseNodeBase& joinNode; + Own dependency; + ExceptionOrValue& output; + }; + + Array branches; +}; + +template +class ArrayJoinPromiseNode final: public ArrayJoinPromiseNodeBase { +public: + ArrayJoinPromiseNode(Array> promises, + Array> resultParts) + : ArrayJoinPromiseNodeBase(kj::mv(promises), resultParts.begin(), sizeof(ExceptionOr)), + resultParts(kj::mv(resultParts)) {} + +protected: + void getNoError(ExceptionOrValue& output) noexcept override { + auto builder = heapArrayBuilder(resultParts.size()); + for (auto& part: resultParts) { + KJ_IASSERT(part.value != nullptr, + "Bug in KJ promise framework: Promise result had neither value no exception."); + builder.add(kj::mv(*_::readMaybe(part.value))); + } + output.as>() = builder.finish(); + } + +private: + Array> resultParts; +}; + +template <> +class ArrayJoinPromiseNode final: public ArrayJoinPromiseNodeBase { +public: + ArrayJoinPromiseNode(Array> promises, + Array> resultParts); + ~ArrayJoinPromiseNode(); + +protected: + void getNoError(ExceptionOrValue& output) noexcept override; + +private: + Array> resultParts; +}; + +// ------------------------------------------------------------------- + +class EagerPromiseNodeBase: public PromiseNode, protected Event { + // A PromiseNode that eagerly evaluates its dependency even if its dependent does not eagerly + // evaluate it. + +public: + EagerPromiseNodeBase(Own&& dependency, ExceptionOrValue& resultRef); + + void onReady(Event& event) noexcept override; + PromiseNode* getInnerForTrace() override; + +private: + Own dependency; + OnReadyEvent onReadyEvent; + + ExceptionOrValue& resultRef; + + Maybe> fire() override; +}; + +template +class EagerPromiseNode final: public EagerPromiseNodeBase { +public: + EagerPromiseNode(Own&& dependency) + : EagerPromiseNodeBase(kj::mv(dependency), result) {} + + void get(ExceptionOrValue& output) noexcept override { + output.as() = kj::mv(result); + } + +private: + ExceptionOr result; +}; + +template +Own spark(Own&& node) { + // Forces evaluation of the given node to begin as soon as possible, even if no one is waiting + // on it. + return heap>(kj::mv(node)); +} + +// ------------------------------------------------------------------- + +class AdapterPromiseNodeBase: public PromiseNode { +public: + void onReady(Event& event) noexcept override; + +protected: + inline void setReady() { + onReadyEvent.arm(); + } + +private: + OnReadyEvent onReadyEvent; +}; + +template +class AdapterPromiseNode final: public AdapterPromiseNodeBase, + private PromiseFulfiller> { + // A PromiseNode that wraps a PromiseAdapter. + +public: + template + AdapterPromiseNode(Params&&... params) + : adapter(static_cast>&>(*this), kj::fwd(params)...) {} + + void get(ExceptionOrValue& output) noexcept override { + KJ_IREQUIRE(!isWaiting()); + output.as() = kj::mv(result); + } + +private: + ExceptionOr result; + bool waiting = true; + Adapter adapter; + + void fulfill(T&& value) override { + if (waiting) { + waiting = false; + result = ExceptionOr(kj::mv(value)); + setReady(); + } + } + + void reject(Exception&& exception) override { + if (waiting) { + waiting = false; + result = ExceptionOr(false, kj::mv(exception)); + setReady(); + } + } + + bool isWaiting() override { + return waiting; + } +}; + +} // namespace _ (private) + +// ======================================================================================= + +template +Promise::Promise(_::FixVoid value) + : PromiseBase(heap<_::ImmediatePromiseNode<_::FixVoid>>(kj::mv(value))) {} + +template +Promise::Promise(kj::Exception&& exception) + : PromiseBase(heap<_::ImmediateBrokenPromiseNode>(kj::mv(exception))) {} + +template +template +PromiseForResult Promise::then(Func&& func, ErrorFunc&& errorHandler) { + typedef _::FixVoid<_::ReturnType> ResultT; + + Own<_::PromiseNode> intermediate = + heap<_::TransformPromiseNode, Func, ErrorFunc>>( + kj::mv(node), kj::fwd(func), kj::fwd(errorHandler)); + return PromiseForResult(false, + _::maybeChain(kj::mv(intermediate), implicitCast(nullptr))); +} + +namespace _ { // private + +template +struct IdentityFunc { + inline T operator()(T&& value) const { + return kj::mv(value); + } +}; +template +struct IdentityFunc> { + inline Promise operator()(T&& value) const { + return kj::mv(value); + } +}; +template <> +struct IdentityFunc { + inline void operator()() const {} +}; +template <> +struct IdentityFunc> { + Promise operator()() const; + // This can't be inline because it will make the translation unit depend on kj-async. Awkwardly, + // Cap'n Proto relies on being able to include this header without creating such a link-time + // dependency. +}; + +} // namespace _ (private) + +template +template +Promise Promise::catch_(ErrorFunc&& errorHandler) { + // then()'s ErrorFunc can only return a Promise if Func also returns a Promise. In this case, + // Func is being filled in automatically. We want to make sure ErrorFunc can return a Promise, + // but we don't want the extra overhead of promise chaining if ErrorFunc doesn't actually + // return a promise. So we make our Func return match ErrorFunc. + return then(_::IdentityFunc()))>(), + kj::fwd(errorHandler)); +} + +template +T Promise::wait(WaitScope& waitScope) { + _::ExceptionOr<_::FixVoid> result; + + waitImpl(kj::mv(node), result, waitScope); + + KJ_IF_MAYBE(value, result.value) { + KJ_IF_MAYBE(exception, result.exception) { + throwRecoverableException(kj::mv(*exception)); + } + return _::returnMaybeVoid(kj::mv(*value)); + } else KJ_IF_MAYBE(exception, result.exception) { + throwFatalException(kj::mv(*exception)); + } else { + // Result contained neither a value nor an exception? + KJ_UNREACHABLE; + } +} + +template <> +inline void Promise::wait(WaitScope& waitScope) { + // Override case to use throwRecoverableException(). + + _::ExceptionOr<_::Void> result; + + waitImpl(kj::mv(node), result, waitScope); + + if (result.value != nullptr) { + KJ_IF_MAYBE(exception, result.exception) { + throwRecoverableException(kj::mv(*exception)); + } + } else KJ_IF_MAYBE(exception, result.exception) { + throwRecoverableException(kj::mv(*exception)); + } else { + // Result contained neither a value nor an exception? + KJ_UNREACHABLE; + } +} + +template +ForkedPromise Promise::fork() { + return ForkedPromise(false, refcounted<_::ForkHub<_::FixVoid>>(kj::mv(node))); +} + +template +Promise ForkedPromise::addBranch() { + return hub->addBranch(); +} + +template +_::SplitTuplePromise Promise::split() { + return refcounted<_::ForkHub<_::FixVoid>>(kj::mv(node))->split(); +} + +template +Promise Promise::exclusiveJoin(Promise&& other) { + return Promise(false, heap<_::ExclusiveJoinPromiseNode>(kj::mv(node), kj::mv(other.node))); +} + +template +template +Promise Promise::attach(Attachments&&... attachments) { + return Promise(false, kj::heap<_::AttachmentPromiseNode>>( + kj::mv(node), kj::tuple(kj::fwd(attachments)...))); +} + +template +template +Promise Promise::eagerlyEvaluate(ErrorFunc&& errorHandler) { + // See catch_() for commentary. + return Promise(false, _::spark<_::FixVoid>(then( + _::IdentityFunc()))>(), + kj::fwd(errorHandler)).node)); +} + +template +Promise Promise::eagerlyEvaluate(decltype(nullptr)) { + return Promise(false, _::spark<_::FixVoid>(kj::mv(node))); +} + +template +kj::String Promise::trace() { + return PromiseBase::trace(); +} + +template +inline PromiseForResult evalLater(Func&& func) { + return _::yield().then(kj::fwd(func), _::PropagateException()); +} + +template +inline PromiseForResult evalNow(Func&& func) { + PromiseForResult result = nullptr; + KJ_IF_MAYBE(e, kj::runCatchingExceptions([&]() { + result = func(); + })) { + result = kj::mv(*e); + } + return result; +} + +template +template +void Promise::detach(ErrorFunc&& errorHandler) { + return _::detach(then([](T&&) {}, kj::fwd(errorHandler))); +} + +template <> +template +void Promise::detach(ErrorFunc&& errorHandler) { + return _::detach(then([]() {}, kj::fwd(errorHandler))); +} + +template +Promise> joinPromises(Array>&& promises) { + return Promise>(false, kj::heap<_::ArrayJoinPromiseNode>( + KJ_MAP(p, promises) { return kj::mv(p.node); }, + heapArray<_::ExceptionOr>(promises.size()))); +} + +// ======================================================================================= + +namespace _ { // private + +template +class WeakFulfiller final: public PromiseFulfiller, private kj::Disposer { + // A wrapper around PromiseFulfiller which can be detached. + // + // There are a couple non-trivialities here: + // - If the WeakFulfiller is discarded, we want the promise it fulfills to be implicitly + // rejected. + // - We cannot destroy the WeakFulfiller until the application has discarded it *and* it has been + // detached from the underlying fulfiller, because otherwise the later detach() call will go + // to a dangling pointer. Essentially, WeakFulfiller is reference counted, although the + // refcount never goes over 2 and we manually implement the refcounting because we need to do + // other special things when each side detaches anyway. To this end, WeakFulfiller is its own + // Disposer -- dispose() is called when the application discards its owned pointer to the + // fulfiller and detach() is called when the promise is destroyed. + +public: + KJ_DISALLOW_COPY(WeakFulfiller); + + static kj::Own make() { + WeakFulfiller* ptr = new WeakFulfiller; + return Own(ptr, *ptr); + } + + void fulfill(FixVoid&& value) override { + if (inner != nullptr) { + inner->fulfill(kj::mv(value)); + } + } + + void reject(Exception&& exception) override { + if (inner != nullptr) { + inner->reject(kj::mv(exception)); + } + } + + bool isWaiting() override { + return inner != nullptr && inner->isWaiting(); + } + + void attach(PromiseFulfiller& newInner) { + inner = &newInner; + } + + void detach(PromiseFulfiller& from) { + if (inner == nullptr) { + // Already disposed. + delete this; + } else { + KJ_IREQUIRE(inner == &from); + inner = nullptr; + } + } + +private: + mutable PromiseFulfiller* inner; + + WeakFulfiller(): inner(nullptr) {} + + void disposeImpl(void* pointer) const override { + // TODO(perf): Factor some of this out so it isn't regenerated for every fulfiller type? + + if (inner == nullptr) { + // Already detached. + delete this; + } else { + if (inner->isWaiting()) { + inner->reject(kj::Exception(kj::Exception::Type::FAILED, __FILE__, __LINE__, + kj::heapString("PromiseFulfiller was destroyed without fulfilling the promise."))); + } + inner = nullptr; + } + } +}; + +template +class PromiseAndFulfillerAdapter { +public: + PromiseAndFulfillerAdapter(PromiseFulfiller& fulfiller, + WeakFulfiller& wrapper) + : fulfiller(fulfiller), wrapper(wrapper) { + wrapper.attach(fulfiller); + } + + ~PromiseAndFulfillerAdapter() noexcept(false) { + wrapper.detach(fulfiller); + } + +private: + PromiseFulfiller& fulfiller; + WeakFulfiller& wrapper; +}; + +} // namespace _ (private) + +template +template +bool PromiseFulfiller::rejectIfThrows(Func&& func) { + KJ_IF_MAYBE(exception, kj::runCatchingExceptions(kj::mv(func))) { + reject(kj::mv(*exception)); + return false; + } else { + return true; + } +} + +template +bool PromiseFulfiller::rejectIfThrows(Func&& func) { + KJ_IF_MAYBE(exception, kj::runCatchingExceptions(kj::mv(func))) { + reject(kj::mv(*exception)); + return false; + } else { + return true; + } +} + +template +Promise newAdaptedPromise(Params&&... adapterConstructorParams) { + return Promise(false, heap<_::AdapterPromiseNode<_::FixVoid, Adapter>>( + kj::fwd(adapterConstructorParams)...)); +} + +template +PromiseFulfillerPair newPromiseAndFulfiller() { + auto wrapper = _::WeakFulfiller::make(); + + Own<_::PromiseNode> intermediate( + heap<_::AdapterPromiseNode<_::FixVoid, _::PromiseAndFulfillerAdapter>>(*wrapper)); + Promise<_::JoinPromises> promise(false, + _::maybeChain(kj::mv(intermediate), implicitCast(nullptr))); + + return PromiseFulfillerPair { kj::mv(promise), kj::mv(wrapper) }; +} + +} // namespace kj + +#endif // KJ_ASYNC_INL_H_ diff --git a/phonelibs/capnp-cpp/include/kj/async-io.h b/phonelibs/capnp-cpp/include/kj/async-io.h new file mode 100644 index 00000000000000..2804ed7289603d --- /dev/null +++ b/phonelibs/capnp-cpp/include/kj/async-io.h @@ -0,0 +1,561 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef KJ_ASYNC_IO_H_ +#define KJ_ASYNC_IO_H_ + +#if defined(__GNUC__) && !KJ_HEADER_WARNINGS +#pragma GCC system_header +#endif + +#include "async.h" +#include "function.h" +#include "thread.h" +#include "time.h" + +struct sockaddr; + +namespace kj { + +#if _WIN32 +class Win32EventPort; +#else +class UnixEventPort; +#endif + +class NetworkAddress; +class AsyncOutputStream; + +// ======================================================================================= +// Streaming I/O + +class AsyncInputStream { + // Asynchronous equivalent of InputStream (from io.h). + +public: + virtual Promise read(void* buffer, size_t minBytes, size_t maxBytes); + virtual Promise tryRead(void* buffer, size_t minBytes, size_t maxBytes) = 0; + + Promise read(void* buffer, size_t bytes); + + virtual Maybe tryGetLength(); + // Get the remaining number of bytes that will be produced by this stream, if known. + // + // This is used e.g. to fill in the Content-Length header of an HTTP message. If unknown, the + // HTTP implementation may need to fall back to Transfer-Encoding: chunked. + // + // The default implementation always returns null. + + virtual Promise pumpTo( + AsyncOutputStream& output, uint64_t amount = kj::maxValue); + // Read `amount` bytes from this stream (or to EOF) and write them to `output`, returning the + // total bytes actually pumped (which is only less than `amount` if EOF was reached). + // + // Override this if your stream type knows how to pump itself to certain kinds of output + // streams more efficiently than via the naive approach. You can use + // kj::dynamicDowncastIfAvailable() to test for stream types you recognize, and if none match, + // delegate to the default implementation. + // + // The default implementation first tries calling output.tryPumpFrom(), but if that fails, it + // performs a naive pump by allocating a buffer and reading to it / writing from it in a loop. + + Promise> readAllBytes(); + Promise readAllText(); + // Read until EOF and return as one big byte array or string. +}; + +class AsyncOutputStream { + // Asynchronous equivalent of OutputStream (from io.h). + +public: + virtual Promise write(const void* buffer, size_t size) KJ_WARN_UNUSED_RESULT = 0; + virtual Promise write(ArrayPtr> pieces) + KJ_WARN_UNUSED_RESULT = 0; + + virtual Maybe> tryPumpFrom( + AsyncInputStream& input, uint64_t amount = kj::maxValue); + // Implements double-dispatch for AsyncInputStream::pumpTo(). + // + // This method should only be called from within an implementation of pumpTo(). + // + // This method examines the type of `input` to find optimized ways to pump data from it to this + // output stream. If it finds one, it performs the pump. Otherwise, it returns null. + // + // The default implementation always returns null. +}; + +class AsyncIoStream: public AsyncInputStream, public AsyncOutputStream { + // A combination input and output stream. + +public: + virtual void shutdownWrite() = 0; + // Cleanly shut down just the write end of the stream, while keeping the read end open. + + virtual void abortRead() {} + // Similar to shutdownWrite, but this will shut down the read end of the stream, and should only + // be called when an error has occurred. + + virtual void getsockopt(int level, int option, void* value, uint* length); + virtual void setsockopt(int level, int option, const void* value, uint length); + // Corresponds to getsockopt() and setsockopt() syscalls. Will throw an "unimplemented" exception + // if the stream is not a socket or the option is not appropriate for the socket type. The + // default implementations always throw "unimplemented". + + virtual void getsockname(struct sockaddr* addr, uint* length); + virtual void getpeername(struct sockaddr* addr, uint* length); + // Corresponds to getsockname() and getpeername() syscalls. Will throw an "unimplemented" + // exception if the stream is not a socket. The default implementations always throw + // "unimplemented". + // + // Note that we don't provide methods that return NetworkAddress because it usually wouldn't + // be useful. You can't connect() to or listen() on these addresses, obviously, because they are + // ephemeral addresses for a single connection. +}; + +struct OneWayPipe { + // A data pipe with an input end and an output end. (Typically backed by pipe() system call.) + + Own in; + Own out; +}; + +struct TwoWayPipe { + // A data pipe that supports sending in both directions. Each end's output sends data to the + // other end's input. (Typically backed by socketpair() system call.) + + Own ends[2]; +}; + +class ConnectionReceiver { + // Represents a server socket listening on a port. + +public: + virtual Promise> accept() = 0; + // Accept the next incoming connection. + + virtual uint getPort() = 0; + // Gets the port number, if applicable (i.e. if listening on IP). This is useful if you didn't + // specify a port when constructing the NetworkAddress -- one will have been assigned + // automatically. + + virtual void getsockopt(int level, int option, void* value, uint* length); + virtual void setsockopt(int level, int option, const void* value, uint length); + // Same as the methods of AsyncIoStream. +}; + +// ======================================================================================= +// Datagram I/O + +class AncillaryMessage { + // Represents an ancillary message (aka control message) received using the recvmsg() system + // call (or equivalent). Most apps will not use this. + +public: + inline AncillaryMessage(int level, int type, ArrayPtr data); + AncillaryMessage() = default; + + inline int getLevel() const; + // Originating protocol / socket level. + + inline int getType() const; + // Protocol-specific message type. + + template + inline Maybe as(); + // Interpret the ancillary message as the given struct type. Most ancillary messages are some + // sort of struct, so this is a convenient way to access it. Returns nullptr if the message + // is smaller than the struct -- this can happen if the message was truncated due to + // insufficient ancillary buffer space. + + template + inline ArrayPtr asArray(); + // Interpret the ancillary message as an array of items. If the message size does not evenly + // divide into elements of type T, the remainder is discarded -- this can happen if the message + // was truncated due to insufficient ancillary buffer space. + +private: + int level; + int type; + ArrayPtr data; + // Message data. In most cases you should use `as()` or `asArray()`. +}; + +class DatagramReceiver { + // Class encapsulating the recvmsg() system call. You must specify the DatagramReceiver's + // capacity in advance; if a received packet is larger than the capacity, it will be truncated. + +public: + virtual Promise receive() = 0; + // Receive a new message, overwriting this object's content. + // + // receive() may reuse the same buffers for content and ancillary data with each call. + + template + struct MaybeTruncated { + T value; + + bool isTruncated; + // True if the Receiver's capacity was insufficient to receive the value and therefore the + // value is truncated. + }; + + virtual MaybeTruncated> getContent() = 0; + // Get the content of the datagram. + + virtual MaybeTruncated> getAncillary() = 0; + // Ancilarry messages received with the datagram. See the recvmsg() system call and the cmsghdr + // struct. Most apps don't need this. + // + // If the returned value is truncated, then the last message in the array may itself be + // truncated, meaning its as() method will return nullptr or its asArray() method will + // return fewer elements than expected. Truncation can also mean that additional messages were + // available but discarded. + + virtual NetworkAddress& getSource() = 0; + // Get the datagram sender's address. + + struct Capacity { + size_t content = 8192; + // How much space to allocate for the datagram content. If a datagram is received that is + // larger than this, it will be truncated, with no way to recover the tail. + + size_t ancillary = 0; + // How much space to allocate for ancillary messages. As with content, if the ancillary data + // is larger than this, it will be truncated. + }; +}; + +class DatagramPort { +public: + virtual Promise send(const void* buffer, size_t size, NetworkAddress& destination) = 0; + virtual Promise send(ArrayPtr> pieces, + NetworkAddress& destination) = 0; + + virtual Own makeReceiver( + DatagramReceiver::Capacity capacity = DatagramReceiver::Capacity()) = 0; + // Create a new `Receiver` that can be used to receive datagrams. `capacity` specifies how much + // space to allocate for the received message. The `DatagramPort` must outlive the `Receiver`. + + virtual uint getPort() = 0; + // Gets the port number, if applicable (i.e. if listening on IP). This is useful if you didn't + // specify a port when constructing the NetworkAddress -- one will have been assigned + // automatically. + + virtual void getsockopt(int level, int option, void* value, uint* length); + virtual void setsockopt(int level, int option, const void* value, uint length); + // Same as the methods of AsyncIoStream. +}; + +// ======================================================================================= +// Networks + +class NetworkAddress { + // Represents a remote address to which the application can connect. + +public: + virtual Promise> connect() = 0; + // Make a new connection to this address. + // + // The address must not be a wildcard ("*"). If it is an IP address, it must have a port number. + + virtual Own listen() = 0; + // Listen for incoming connections on this address. + // + // The address must be local. + + virtual Own bindDatagramPort(); + // Open this address as a datagram (e.g. UDP) port. + // + // The address must be local. + + virtual Own clone() = 0; + // Returns an equivalent copy of this NetworkAddress. + + virtual String toString() = 0; + // Produce a human-readable string which hopefully can be passed to Network::parseAddress() + // to reproduce this address, although whether or not that works of course depends on the Network + // implementation. This should be called only to display the address to human users, who will + // hopefully know what they are able to do with it. +}; + +class Network { + // Factory for NetworkAddress instances, representing the network services offered by the + // operating system. + // + // This interface typically represents broad authority, and well-designed code should limit its + // use to high-level startup code and user interaction. Low-level APIs should accept + // NetworkAddress instances directly and work from there, if at all possible. + +public: + virtual Promise> parseAddress(StringPtr addr, uint portHint = 0) = 0; + // Construct a network address from a user-provided string. The format of the address + // strings is not specified at the API level, and application code should make no assumptions + // about them. These strings should always be provided by humans, and said humans will know + // what format to use in their particular context. + // + // `portHint`, if provided, specifies the "standard" IP port number for the application-level + // service in play. If the address turns out to be an IP address (v4 or v6), and it lacks a + // port number, this port will be used. If `addr` lacks a port number *and* `portHint` is + // omitted, then the returned address will only support listen() and bindDatagramPort() + // (not connect()), and an unused port will be chosen each time one of those methods is called. + + virtual Own getSockaddr(const void* sockaddr, uint len) = 0; + // Construct a network address from a legacy struct sockaddr. +}; + +// ======================================================================================= +// I/O Provider + +class AsyncIoProvider { + // Class which constructs asynchronous wrappers around the operating system's I/O facilities. + // + // Generally, the implementation of this interface must integrate closely with a particular + // `EventLoop` implementation. Typically, the EventLoop implementation itself will provide + // an AsyncIoProvider. + +public: + virtual OneWayPipe newOneWayPipe() = 0; + // Creates an input/output stream pair representing the ends of a one-way pipe (e.g. created with + // the pipe(2) system call). + + virtual TwoWayPipe newTwoWayPipe() = 0; + // Creates two AsyncIoStreams representing the two ends of a two-way pipe (e.g. created with + // socketpair(2) system call). Data written to one end can be read from the other. + + virtual Network& getNetwork() = 0; + // Creates a new `Network` instance representing the networks exposed by the operating system. + // + // DO NOT CALL THIS except at the highest levels of your code, ideally in the main() function. If + // you call this from low-level code, then you are preventing higher-level code from injecting an + // alternative implementation. Instead, if your code needs to use network functionality, it + // should ask for a `Network` as a constructor or method parameter, so that higher-level code can + // chose what implementation to use. The system network is essentially a singleton. See: + // http://www.object-oriented-security.org/lets-argue/singletons + // + // Code that uses the system network should not make any assumptions about what kinds of + // addresses it will parse, as this could differ across platforms. String addresses should come + // strictly from the user, who will know how to write them correctly for their system. + // + // With that said, KJ currently supports the following string address formats: + // - IPv4: "1.2.3.4", "1.2.3.4:80" + // - IPv6: "1234:5678::abcd", "[1234:5678::abcd]:80" + // - Local IP wildcard (covers both v4 and v6): "*", "*:80" + // - Symbolic names: "example.com", "example.com:80", "example.com:http", "1.2.3.4:http" + // - Unix domain: "unix:/path/to/socket" + + struct PipeThread { + // A combination of a thread and a two-way pipe that communicates with that thread. + // + // The fields are intentionally ordered so that the pipe will be destroyed (and therefore + // disconnected) before the thread is destroyed (and therefore joined). Thus if the thread + // arranges to exit when it detects disconnect, destruction should be clean. + + Own thread; + Own pipe; + }; + + virtual PipeThread newPipeThread( + Function startFunc) = 0; + // Create a new thread and set up a two-way pipe (socketpair) which can be used to communicate + // with it. One end of the pipe is passed to the thread's start function and the other end of + // the pipe is returned. The new thread also gets its own `AsyncIoProvider` instance and will + // already have an active `EventLoop` when `startFunc` is called. + // + // TODO(someday): I'm not entirely comfortable with this interface. It seems to be doing too + // much at once but I'm not sure how to cleanly break it down. + + virtual Timer& getTimer() = 0; + // Returns a `Timer` based on real time. Time does not pass while event handlers are running -- + // it only updates when the event loop polls for system events. This means that calling `now()` + // on this timer does not require a system call. + // + // This timer is not affected by changes to the system date. It is unspecified whether the timer + // continues to count while the system is suspended. +}; + +class LowLevelAsyncIoProvider { + // Similar to `AsyncIoProvider`, but represents a lower-level interface that may differ on + // different operating systems. You should prefer to use `AsyncIoProvider` over this interface + // whenever possible, as `AsyncIoProvider` is portable and friendlier to dependency-injection. + // + // On Unix, this interface can be used to import native file descriptors into the async framework. + // Different implementations of this interface might work on top of different event handling + // primitives, such as poll vs. epoll vs. kqueue vs. some higher-level event library. + // + // On Windows, this interface can be used to import native HANDLEs into the async framework. + // Different implementations of this interface might work on top of different event handling + // primitives, such as I/O completion ports vs. completion routines. + // + // TODO(port): Actually implement Windows support. + +public: + // --------------------------------------------------------------------------- + // Unix-specific stuff + + enum Flags { + // Flags controlling how to wrap a file descriptor. + + TAKE_OWNERSHIP = 1 << 0, + // The returned object should own the file descriptor, automatically closing it when destroyed. + // The close-on-exec flag will be set on the descriptor if it is not already. + // + // If this flag is not used, then the file descriptor is not automatically closed and the + // close-on-exec flag is not modified. + +#if !_WIN32 + ALREADY_CLOEXEC = 1 << 1, + // Indicates that the close-on-exec flag is known already to be set, so need not be set again. + // Only relevant when combined with TAKE_OWNERSHIP. + // + // On Linux, all system calls which yield new file descriptors have flags or variants which + // set the close-on-exec flag immediately. Unfortunately, other OS's do not. + + ALREADY_NONBLOCK = 1 << 2 + // Indicates that the file descriptor is known already to be in non-blocking mode, so the flag + // need not be set again. Otherwise, all wrap*Fd() methods will enable non-blocking mode + // automatically. + // + // On Linux, all system calls which yield new file descriptors have flags or variants which + // enable non-blocking mode immediately. Unfortunately, other OS's do not. +#endif + }; + +#if _WIN32 + typedef uintptr_t Fd; + // On Windows, the `fd` parameter to each of these methods must be a SOCKET, and must have the + // flag WSA_FLAG_OVERLAPPED (which socket() uses by default, but WSASocket() wants you to specify + // explicitly). +#else + typedef int Fd; + // On Unix, any arbitrary file descriptor is supported. +#endif + + virtual Own wrapInputFd(Fd fd, uint flags = 0) = 0; + // Create an AsyncInputStream wrapping a file descriptor. + // + // `flags` is a bitwise-OR of the values of the `Flags` enum. + + virtual Own wrapOutputFd(Fd fd, uint flags = 0) = 0; + // Create an AsyncOutputStream wrapping a file descriptor. + // + // `flags` is a bitwise-OR of the values of the `Flags` enum. + + virtual Own wrapSocketFd(Fd fd, uint flags = 0) = 0; + // Create an AsyncIoStream wrapping a socket file descriptor. + // + // `flags` is a bitwise-OR of the values of the `Flags` enum. + + virtual Promise> wrapConnectingSocketFd( + Fd fd, const struct sockaddr* addr, uint addrlen, uint flags = 0) = 0; + // Create an AsyncIoStream wrapping a socket and initiate a connection to the given address. + // The returned promise does not resolve until connection has completed. + // + // `flags` is a bitwise-OR of the values of the `Flags` enum. + + virtual Own wrapListenSocketFd(Fd fd, uint flags = 0) = 0; + // Create an AsyncIoStream wrapping a listen socket file descriptor. This socket should already + // have had `bind()` and `listen()` called on it, so it's ready for `accept()`. + // + // `flags` is a bitwise-OR of the values of the `Flags` enum. + + virtual Own wrapDatagramSocketFd(Fd fd, uint flags = 0); + + virtual Timer& getTimer() = 0; + // Returns a `Timer` based on real time. Time does not pass while event handlers are running -- + // it only updates when the event loop polls for system events. This means that calling `now()` + // on this timer does not require a system call. + // + // This timer is not affected by changes to the system date. It is unspecified whether the timer + // continues to count while the system is suspended. +}; + +Own newAsyncIoProvider(LowLevelAsyncIoProvider& lowLevel); +// Make a new AsyncIoProvider wrapping a `LowLevelAsyncIoProvider`. + +struct AsyncIoContext { + Own lowLevelProvider; + Own provider; + WaitScope& waitScope; + +#if _WIN32 + Win32EventPort& win32EventPort; +#else + UnixEventPort& unixEventPort; + // TEMPORARY: Direct access to underlying UnixEventPort, mainly for waiting on signals. This + // field will go away at some point when we have a chance to improve these interfaces. +#endif +}; + +AsyncIoContext setupAsyncIo(); +// Convenience method which sets up the current thread with everything it needs to do async I/O. +// The returned objects contain an `EventLoop` which is wrapping an appropriate `EventPort` for +// doing I/O on the host system, so everything is ready for the thread to start making async calls +// and waiting on promises. +// +// You would typically call this in your main() loop or in the start function of a thread. +// Example: +// +// int main() { +// auto ioContext = kj::setupAsyncIo(); +// +// // Now we can call an async function. +// Promise textPromise = getHttp(*ioContext.provider, "http://example.com"); +// +// // And we can wait for the promise to complete. Note that you can only use `wait()` +// // from the top level, not from inside a promise callback. +// String text = textPromise.wait(ioContext.waitScope); +// print(text); +// return 0; +// } +// +// WARNING: An AsyncIoContext can only be used in the thread and process that created it. In +// particular, note that after a fork(), an AsyncIoContext created in the parent process will +// not work correctly in the child, even if the parent ceases to use its copy. In particular +// note that this means that server processes which daemonize themselves at startup must wait +// until after daemonization to create an AsyncIoContext. + +// ======================================================================================= +// inline implementation details + +inline AncillaryMessage::AncillaryMessage( + int level, int type, ArrayPtr data) + : level(level), type(type), data(data) {} + +inline int AncillaryMessage::getLevel() const { return level; } +inline int AncillaryMessage::getType() const { return type; } + +template +inline Maybe AncillaryMessage::as() { + if (data.size() >= sizeof(T)) { + return *reinterpret_cast(data.begin()); + } else { + return nullptr; + } +} + +template +inline ArrayPtr AncillaryMessage::asArray() { + return arrayPtr(reinterpret_cast(data.begin()), data.size() / sizeof(T)); +} + +} // namespace kj + +#endif // KJ_ASYNC_IO_H_ diff --git a/phonelibs/capnp-cpp/include/kj/async-prelude.h b/phonelibs/capnp-cpp/include/kj/async-prelude.h new file mode 100644 index 00000000000000..0a5843f88a4d77 --- /dev/null +++ b/phonelibs/capnp-cpp/include/kj/async-prelude.h @@ -0,0 +1,218 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +// This file contains a bunch of internal declarations that must appear before async.h can start. +// We don't define these directly in async.h because it makes the file hard to read. + +#ifndef KJ_ASYNC_PRELUDE_H_ +#define KJ_ASYNC_PRELUDE_H_ + +#if defined(__GNUC__) && !KJ_HEADER_WARNINGS +#pragma GCC system_header +#endif + +#include "exception.h" +#include "tuple.h" + +namespace kj { + +class EventLoop; +template +class Promise; +class WaitScope; + +template +Promise> joinPromises(Array>&& promises); +Promise joinPromises(Array>&& promises); + +namespace _ { // private + +template struct JoinPromises_ { typedef T Type; }; +template struct JoinPromises_> { typedef T Type; }; + +template +using JoinPromises = typename JoinPromises_::Type; +// If T is Promise, resolves to U, otherwise resolves to T. +// +// TODO(cleanup): Rename to avoid confusion with joinPromises() call which is completely +// unrelated. + +class PropagateException { + // A functor which accepts a kj::Exception as a parameter and returns a broken promise of + // arbitrary type which simply propagates the exception. +public: + class Bottom { + public: + Bottom(Exception&& exception): exception(kj::mv(exception)) {} + + Exception asException() { return kj::mv(exception); } + + private: + Exception exception; + }; + + Bottom operator()(Exception&& e) { + return Bottom(kj::mv(e)); + } + Bottom operator()(const Exception& e) { + return Bottom(kj::cp(e)); + } +}; + +template +struct ReturnType_ { typedef decltype(instance()(instance())) Type; }; +template +struct ReturnType_ { typedef decltype(instance()()) Type; }; + +template +using ReturnType = typename ReturnType_::Type; +// The return type of functor Func given a parameter of type T, with the special exception that if +// T is void, this is the return type of Func called with no arguments. + +template struct SplitTuplePromise_ { typedef Promise Type; }; +template +struct SplitTuplePromise_> { + typedef kj::Tuple>...> Type; +}; + +template +using SplitTuplePromise = typename SplitTuplePromise_::Type; +// T -> Promise +// Tuple -> Tuple> + +struct Void {}; +// Application code should NOT refer to this! See `kj::READY_NOW` instead. + +template struct FixVoid_ { typedef T Type; }; +template <> struct FixVoid_ { typedef Void Type; }; +template using FixVoid = typename FixVoid_::Type; +// FixVoid is just T unless T is void in which case it is _::Void (an empty struct). + +template struct UnfixVoid_ { typedef T Type; }; +template <> struct UnfixVoid_ { typedef void Type; }; +template using UnfixVoid = typename UnfixVoid_::Type; +// UnfixVoid is the opposite of FixVoid. + +template +struct MaybeVoidCaller { + // Calls the function converting a Void input to an empty parameter list and a void return + // value to a Void output. + + template + static inline Out apply(Func& func, In&& in) { + return func(kj::mv(in)); + } +}; +template +struct MaybeVoidCaller { + template + static inline Out apply(Func& func, In& in) { + return func(in); + } +}; +template +struct MaybeVoidCaller { + template + static inline Out apply(Func& func, Void&& in) { + return func(); + } +}; +template +struct MaybeVoidCaller { + template + static inline Void apply(Func& func, In&& in) { + func(kj::mv(in)); + return Void(); + } +}; +template +struct MaybeVoidCaller { + template + static inline Void apply(Func& func, In& in) { + func(in); + return Void(); + } +}; +template <> +struct MaybeVoidCaller { + template + static inline Void apply(Func& func, Void&& in) { + func(); + return Void(); + } +}; + +template +inline T&& returnMaybeVoid(T&& t) { + return kj::fwd(t); +} +inline void returnMaybeVoid(Void&& v) {} + +class ExceptionOrValue; +class PromiseNode; +class ChainPromiseNode; +template +class ForkHub; + +class TaskSetImpl; + +class Event; + +class PromiseBase { +public: + kj::String trace(); + // Dump debug info about this promise. + +private: + Own node; + + PromiseBase() = default; + PromiseBase(Own&& node): node(kj::mv(node)) {} + + friend class kj::EventLoop; + friend class ChainPromiseNode; + template + friend class kj::Promise; + friend class TaskSetImpl; + template + friend Promise> kj::joinPromises(Array>&& promises); + friend Promise kj::joinPromises(Array>&& promises); +}; + +void detach(kj::Promise&& promise); +void waitImpl(Own<_::PromiseNode>&& node, _::ExceptionOrValue& result, WaitScope& waitScope); +Promise yield(); +Own neverDone(); + +class NeverDone { +public: + template + operator Promise() const { + return Promise(false, neverDone()); + } + + KJ_NORETURN(void wait(WaitScope& waitScope) const); +}; + +} // namespace _ (private) +} // namespace kj + +#endif // KJ_ASYNC_PRELUDE_H_ diff --git a/phonelibs/capnp-cpp/include/kj/async-unix.h b/phonelibs/capnp-cpp/include/kj/async-unix.h new file mode 100644 index 00000000000000..06f128a50eeddb --- /dev/null +++ b/phonelibs/capnp-cpp/include/kj/async-unix.h @@ -0,0 +1,274 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef KJ_ASYNC_UNIX_H_ +#define KJ_ASYNC_UNIX_H_ + +#if _WIN32 +#error "This file is Unix-specific. On Windows, include async-win32.h instead." +#endif + +#if defined(__GNUC__) && !KJ_HEADER_WARNINGS +#pragma GCC system_header +#endif + +#include "async.h" +#include "time.h" +#include "vector.h" +#include "io.h" +#include + +#if __linux__ && !__BIONIC__ && !defined(KJ_USE_EPOLL) +// Default to epoll on Linux, except on Bionic (Android) which doesn't have signalfd.h. +#define KJ_USE_EPOLL 1 +#endif + +namespace kj { + +class UnixEventPort: public EventPort { + // An EventPort implementation which can wait for events on file descriptors as well as signals. + // This API only makes sense on Unix. + // + // The implementation uses `poll()` or possibly a platform-specific API (e.g. epoll, kqueue). + // To also wait on signals without race conditions, the implementation may block signals until + // just before `poll()` while using a signal handler which `siglongjmp()`s back to just before + // the signal was unblocked, or it may use a nicer platform-specific API like signalfd. + // + // The implementation reserves a signal for internal use. By default, it uses SIGUSR1. If you + // need to use SIGUSR1 for something else, you must offer a different signal by calling + // setReservedSignal() at startup. + // + // WARNING: A UnixEventPort can only be used in the thread and process that created it. In + // particular, note that after a fork(), a UnixEventPort created in the parent process will + // not work correctly in the child, even if the parent ceases to use its copy. In particular + // note that this means that server processes which daemonize themselves at startup must wait + // until after daemonization to create a UnixEventPort. + +public: + UnixEventPort(); + ~UnixEventPort() noexcept(false); + + class FdObserver; + // Class that watches an fd for readability or writability. See definition below. + + Promise onSignal(int signum); + // When the given signal is delivered to this thread, return the corresponding siginfo_t. + // The signal must have been captured using `captureSignal()`. + // + // If `onSignal()` has not been called, the signal will remain blocked in this thread. + // Therefore, a signal which arrives before `onSignal()` was called will not be "missed" -- the + // next call to 'onSignal()' will receive it. Also, you can control which thread receives a + // process-wide signal by only calling `onSignal()` on that thread's event loop. + // + // The result of waiting on the same signal twice at once is undefined. + + static void captureSignal(int signum); + // Arranges for the given signal to be captured and handled via UnixEventPort, so that you may + // then pass it to `onSignal()`. This method is static because it registers a signal handler + // which applies process-wide. If any other threads exist in the process when `captureSignal()` + // is called, you *must* set the signal mask in those threads to block this signal, otherwise + // terrible things will happen if the signal happens to be delivered to those threads. If at + // all possible, call `captureSignal()` *before* creating threads, so that threads you create in + // the future will inherit the proper signal mask. + // + // To un-capture a signal, simply install a different signal handler and then un-block it from + // the signal mask. + + static void setReservedSignal(int signum); + // Sets the signal number which `UnixEventPort` reserves for internal use. If your application + // needs to use SIGUSR1, call this at startup (before any calls to `captureSignal()` and before + // constructing an `UnixEventPort`) to offer a different signal. + + Timer& getTimer() { return timerImpl; } + + // implements EventPort ------------------------------------------------------ + bool wait() override; + bool poll() override; + void wake() const override; + +private: + struct TimerSet; // Defined in source file to avoid STL include. + class TimerPromiseAdapter; + class SignalPromiseAdapter; + + TimerImpl timerImpl; + + SignalPromiseAdapter* signalHead = nullptr; + SignalPromiseAdapter** signalTail = &signalHead; + + TimePoint readClock(); + void gotSignal(const siginfo_t& siginfo); + + friend class TimerPromiseAdapter; + +#if KJ_USE_EPOLL + AutoCloseFd epollFd; + AutoCloseFd signalFd; + AutoCloseFd eventFd; // Used for cross-thread wakeups. + + sigset_t signalFdSigset; + // Signal mask as currently set on the signalFd. Tracked so we can detect whether or not it + // needs updating. + + bool doEpollWait(int timeout); + +#else + class PollContext; + + FdObserver* observersHead = nullptr; + FdObserver** observersTail = &observersHead; + + unsigned long long threadId; // actually pthread_t +#endif +}; + +class UnixEventPort::FdObserver { + // Object which watches a file descriptor to determine when it is readable or writable. + // + // For listen sockets, "readable" means that there is a connection to accept(). For everything + // else, it means that read() (or recv()) will return data. + // + // The presence of out-of-band data should NOT fire this event. However, the event may + // occasionally fire spuriously (when there is actually no data to read), and one thing that can + // cause such spurious events is the arrival of OOB data on certain platforms whose event + // interfaces fail to distinguish between regular and OOB data (e.g. Mac OSX). + // + // WARNING: The exact behavior of this class differs across systems, since event interfaces + // vary wildly. Be sure to read the documentation carefully and avoid depending on unspecified + // behavior. If at all possible, use the higher-level AsyncInputStream interface instead. + +public: + enum Flags { + OBSERVE_READ = 1, + OBSERVE_WRITE = 2, + OBSERVE_URGENT = 4, + OBSERVE_READ_WRITE = OBSERVE_READ | OBSERVE_WRITE + }; + + FdObserver(UnixEventPort& eventPort, int fd, uint flags); + // Begin watching the given file descriptor for readability. Only one ReadObserver may exist + // for a given file descriptor at a time. + + ~FdObserver() noexcept(false); + + KJ_DISALLOW_COPY(FdObserver); + + Promise whenBecomesReadable(); + // Resolves the next time the file descriptor transitions from having no data to read to having + // some data to read. + // + // KJ uses "edge-triggered" event notification whenever possible. As a result, it is an error + // to call this method when there is already data in the read buffer which has been there since + // prior to the last turn of the event loop or prior to creation FdWatcher. In this case, it is + // unspecified whether the promise will ever resolve -- it depends on the underlying event + // mechanism being used. + // + // In order to avoid this problem, make sure that you only call `whenBecomesReadable()` + // only at times when you know the buffer is empty. You know this for sure when one of the + // following happens: + // * read() or recv() fails with EAGAIN or EWOULDBLOCK. (You MUST have non-blocking mode + // enabled on the fd!) + // * The file descriptor is a regular byte-oriented object (like a socket or pipe), + // read() or recv() returns fewer than the number of bytes requested, and `atEndHint()` + // returns false. This can only happen if the buffer is empty but EOF is not reached. (Note, + // though, that for record-oriented file descriptors like Linux's inotify interface, this + // rule does not hold, because it could simply be that the next record did not fit into the + // space available.) + // + // It is an error to call `whenBecomesReadable()` again when the promise returned previously + // has not yet resolved. If you do this, the previous promise may throw an exception. + + inline Maybe atEndHint() { return atEnd; } + // Returns true if the event system has indicated that EOF has been received. There may still + // be data in the read buffer, but once that is gone, there's nothing left. + // + // Returns false if the event system has indicated that EOF had NOT been received as of the + // last turn of the event loop. + // + // Returns nullptr if the event system does not know whether EOF has been reached. In this + // case, the only way to know for sure is to call read() or recv() and check if it returns + // zero. + // + // This hint may be useful as an optimization to avoid an unnecessary system call. + + Promise whenBecomesWritable(); + // Resolves the next time the file descriptor transitions from having no space available in the + // write buffer to having some space available. + // + // KJ uses "edge-triggered" event notification whenever possible. As a result, it is an error + // to call this method when there is already space in the write buffer which has been there + // since prior to the last turn of the event loop or prior to creation FdWatcher. In this case, + // it is unspecified whether the promise will ever resolve -- it depends on the underlying + // event mechanism being used. + // + // In order to avoid this problem, make sure that you only call `whenBecomesWritable()` + // only at times when you know the buffer is full. You know this for sure when one of the + // following happens: + // * write() or send() fails with EAGAIN or EWOULDBLOCK. (You MUST have non-blocking mode + // enabled on the fd!) + // * write() or send() succeeds but accepts fewer than the number of bytes provided. This can + // only happen if the buffer is full. + // + // It is an error to call `whenBecomesWritable()` again when the promise returned previously + // has not yet resolved. If you do this, the previous promise may throw an exception. + + Promise whenUrgentDataAvailable(); + // Resolves the next time the file descriptor's read buffer contains "urgent" data. + // + // The conditions for availability of urgent data are specific to the file descriptor's + // underlying implementation. + // + // It is an error to call `whenUrgentDataAvailable()` again when the promise returned previously + // has not yet resolved. If you do this, the previous promise may throw an exception. + // + // WARNING: This has some known weird behavior on macOS. See + // https://github.com/sandstorm-io/capnproto/issues/374. + +private: + UnixEventPort& eventPort; + int fd; + uint flags; + + kj::Maybe>> readFulfiller; + kj::Maybe>> writeFulfiller; + kj::Maybe>> urgentFulfiller; + // Replaced each time `whenBecomesReadable()` or `whenBecomesWritable()` is called. Reverted to + // null every time an event is fired. + + Maybe atEnd; + + void fire(short events); + +#if !KJ_USE_EPOLL + FdObserver* next; + FdObserver** prev; + // Linked list of observers which currently have a non-null readFulfiller or writeFulfiller. + // If `prev` is null then the observer is not currently in the list. + + short getEventMask(); +#endif + + friend class UnixEventPort; +}; + +} // namespace kj + +#endif // KJ_ASYNC_UNIX_H_ diff --git a/phonelibs/capnp-cpp/include/kj/async-win32.h b/phonelibs/capnp-cpp/include/kj/async-win32.h new file mode 100644 index 00000000000000..b70c42e016c5ba --- /dev/null +++ b/phonelibs/capnp-cpp/include/kj/async-win32.h @@ -0,0 +1,234 @@ +// Copyright (c) 2016 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef KJ_ASYNC_WIN32_H_ +#define KJ_ASYNC_WIN32_H_ + +#if !_WIN32 +#error "This file is Windows-specific. On Unix, include async-unix.h instead." +#endif + +#include "async.h" +#include "time.h" +#include "io.h" +#include +#include + +// Include windows.h as lean as possible. (If you need more of the Windows API for your app, +// #include windows.h yourself before including this header.) +#define WIN32_LEAN_AND_MEAN 1 +#define NOSERVICE 1 +#define NOMCX 1 +#define NOIME 1 +#include +#include "windows-sanity.h" + +namespace kj { + +class Win32EventPort: public EventPort { + // Abstract base interface for EventPorts that can listen on Win32 event types. Due to the + // absurd complexity of the Win32 API, it's not possible to standardize on a single + // implementation of EventPort. In particular, there is no way for a single thread to use I/O + // completion ports (the most efficient way of handling I/O) while at the same time waiting for + // signalable handles or UI messages. + // + // Note that UI messages are not supported at all by this interface because the message queue + // is implemented by user32.dll and we want libkj to depend only on kernel32.dll. A separate + // compat library could provide a Win32EventPort implementation that works with the UI message + // queue. + +public: + // --------------------------------------------------------------------------- + // overlapped I/O + + struct IoResult { + DWORD errorCode; + DWORD bytesTransferred; + }; + + class IoOperation { + public: + virtual LPOVERLAPPED getOverlapped() = 0; + // Gets the OVERLAPPED structure to pass to the Win32 I/O call. Do NOT modify it; just pass it + // on. + + virtual Promise onComplete() = 0; + // After making the Win32 call, if the return value indicates that the operation was + // successfully queued (i.e. the completion event will definitely occur), call this to wait + // for completion. + // + // You MUST call this if the operation was successfully queued, and you MUST NOT call this + // otherwise. If the Win32 call failed (without queuing any operation or event) then you should + // simply drop the IoOperation object. + // + // Dropping the returned Promise cancels the operation via Win32's CancelIoEx(). The destructor + // will wait for the cancellation to complete, such that after dropping the proimse it is safe + // to free the buffer that the operation was reading from / writing to. + // + // You may safely drop the `IoOperation` while still waiting for this promise. You may not, + // however, drop the `IoObserver`. + }; + + class IoObserver { + public: + virtual Own newOperation(uint64_t offset) = 0; + // Begin an I/O operation. For file operations, `offset` is the offset within the file at + // which the operation will start. For stream operations, `offset` is ignored. + }; + + virtual Own observeIo(HANDLE handle) = 0; + // Given a handle which supports overlapped I/O, arrange to receive I/O completion events via + // this EventPort. + // + // Different Win32EventPort implementations may handle this in different ways, such as by using + // completion routines (APCs) or by using I/O completion ports. The caller should not assume + // any particular technique. + // + // WARNING: It is only safe to call observeIo() on a particular handle once during its lifetime. + // You cannot observe the same handle from multiple Win32EventPorts, even if not at the same + // time. This is because the Win32 API provides no way to disassociate a handle from an I/O + // completion port once it is associated. + + // --------------------------------------------------------------------------- + // signalable handles + // + // Warning: Due to limitations in the Win32 API, implementations of EventPort may be forced to + // spawn additional threads to wait for signaled objects. This is necessary if the EventPort + // implementation is based on I/O completion ports, or if you need to wait on more than 64 + // handles at once. + + class SignalObserver { + public: + virtual Promise onSignaled() = 0; + // Returns a promise that completes the next time the handle enters the signaled state. + // + // Depending on the type of handle, the handle may automatically be reset to a non-signaled + // state before the promise resolves. The underlying implementaiton uses WaitForSingleObject() + // or an equivalent wait call, so check the documentation for that to understand the semantics. + // + // If the handle is a mutex and it is abandoned without being unlocked, the promise breaks with + // an exception. + + virtual Promise onSignaledOrAbandoned() = 0; + // Like onSingaled(), but instead of throwing when a mutex is abandoned, resolves to `true`. + // Resolves to `false` for non-abandoned signals. + }; + + virtual Own observeSignalState(HANDLE handle) = 0; + // Given a handle that supports waiting for it to become "signaled" via WaitForSingleObject(), + // return an object that can wait for this state using the EventPort. + + // --------------------------------------------------------------------------- + // APCs + + virtual void allowApc() = 0; + // If this is ever called, the Win32EventPort will switch modes so that APCs can be scheduled + // on the thread, e.g. through the Win32 QueueUserAPC() call. In the future, this may be enabled + // by default. However, as of this writing, Wine does not support the necessary + // GetQueuedCompletionStatusEx() call, thus allowApc() breaks Wine support. (Tested on Wine + // 1.8.7.) + // + // If the event port implementation can't support APCs for some reason, this throws. + + // --------------------------------------------------------------------------- + // time + + virtual Timer& getTimer() = 0; +}; + +class Win32WaitObjectThreadPool { + // Helper class that implements Win32EventPort::observeSignalState() by spawning additional + // threads as needed to perform the actual waiting. + // + // This class is intended to be used to assist in building Win32EventPort implementations. + +public: + Win32WaitObjectThreadPool(uint mainThreadCount = 0); + // `mainThreadCount` indicates the number of objects the main thread is able to listen on + // directly. Typically this would be zero (e.g. if the main thread watches an I/O completion + // port) or MAXIMUM_WAIT_OBJECTS (e.g. if the main thread is a UI thread but can use + // MsgWaitForMultipleObjectsEx() to wait on some handles at the same time as messages). + + Own observeSignalState(HANDLE handle); + // Implemetns Win32EventPort::observeSignalState(). + + uint prepareMainThreadWait(HANDLE* handles[]); + // Call immediately before invoking WaitForMultipleObjects() or similar in the main thread. + // Fills in `handles` with the handle pointers to wait on, and returns the number of handles + // in this array. (The array should be allocated to be at least the size passed to the + // constructor). + // + // There's no need to call this if `mainThreadCount` as passed to the constructor was zero. + + bool finishedMainThreadWait(DWORD returnCode); + // Call immediately after invoking WaitForMultipleObjects() or similar in the main thread, + // passing the value returend by that call. Returns true if the event indicated by `returnCode` + // has been handled (i.e. it was WAIT_OBJECT_n or WAIT_ABANDONED_n where n is in-range for the + // last call to prepareMainThreadWait()). +}; + +class Win32IocpEventPort final: public Win32EventPort { + // An EventPort implementation which uses Windows I/O completion ports to listen for events. + // + // With this implementation, observeSignalState() requires spawning a separate thread. + +public: + Win32IocpEventPort(); + ~Win32IocpEventPort() noexcept(false); + + // implements EventPort ------------------------------------------------------ + bool wait() override; + bool poll() override; + void wake() const override; + + // implements Win32IocpEventPort --------------------------------------------- + Own observeIo(HANDLE handle) override; + Own observeSignalState(HANDLE handle) override; + Timer& getTimer() override { return timerImpl; } + void allowApc() override { isAllowApc = true; } + +private: + class IoPromiseAdapter; + class IoOperationImpl; + class IoObserverImpl; + + AutoCloseHandle iocp; + AutoCloseHandle thread; + Win32WaitObjectThreadPool waitThreads; + TimerImpl timerImpl; + mutable std::atomic sentWake {false}; + bool isAllowApc = false; + + static TimePoint readClock(); + + void waitIocp(DWORD timeoutMs); + // Wait on the I/O completion port for up to timeoutMs and pump events. Does not advance the + // timer; caller must do that. + + bool receivedWake(); + + static AutoCloseHandle newIocpHandle(); + static AutoCloseHandle openCurrentThread(); +}; + +} // namespace kj + +#endif // KJ_ASYNC_WIN32_H_ diff --git a/phonelibs/capnp-cpp/include/kj/async.h b/phonelibs/capnp-cpp/include/kj/async.h new file mode 100644 index 00000000000000..5a9d9bdae717dc --- /dev/null +++ b/phonelibs/capnp-cpp/include/kj/async.h @@ -0,0 +1,682 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef KJ_ASYNC_H_ +#define KJ_ASYNC_H_ + +#if defined(__GNUC__) && !KJ_HEADER_WARNINGS +#pragma GCC system_header +#endif + +#include "async-prelude.h" +#include "exception.h" +#include "refcount.h" + +namespace kj { + +class EventLoop; +class WaitScope; + +template +class Promise; +template +class ForkedPromise; +template +class PromiseFulfiller; +template +struct PromiseFulfillerPair; + +template +using PromiseForResult = Promise<_::JoinPromises<_::ReturnType>>; +// Evaluates to the type of Promise for the result of calling functor type Func with parameter type +// T. If T is void, then the promise is for the result of calling Func with no arguments. If +// Func itself returns a promise, the promises are joined, so you never get Promise>. + +// ======================================================================================= +// Promises + +template +class Promise: protected _::PromiseBase { + // The basic primitive of asynchronous computation in KJ. Similar to "futures", but designed + // specifically for event loop concurrency. Similar to E promises and JavaScript Promises/A. + // + // A Promise represents a promise to produce a value of type T some time in the future. Once + // that value has been produced, the promise is "fulfilled". Alternatively, a promise can be + // "broken", with an Exception describing what went wrong. You may implicitly convert a value of + // type T to an already-fulfilled Promise. You may implicitly convert the constant + // `kj::READY_NOW` to an already-fulfilled Promise. You may also implicitly convert a + // `kj::Exception` to an already-broken promise of any type. + // + // Promises are linear types -- they are moveable but not copyable. If a Promise is destroyed + // or goes out of scope (without being moved elsewhere), any ongoing asynchronous operations + // meant to fulfill the promise will be canceled if possible. All methods of `Promise` (unless + // otherwise noted) actually consume the promise in the sense of move semantics. (Arguably they + // should be rvalue-qualified, but at the time this interface was created compilers didn't widely + // support that yet and anyway it would be pretty ugly typing kj::mv(promise).whatever().) If + // you want to use one Promise in two different places, you must fork it with `fork()`. + // + // To use the result of a Promise, you must call `then()` and supply a callback function to + // call with the result. `then()` returns another promise, for the result of the callback. + // Any time that this would result in Promise>, the promises are collapsed into a + // simple Promise that first waits for the outer promise, then the inner. Example: + // + // // Open a remote file, read the content, and then count the + // // number of lines of text. + // // Note that none of the calls here block. `file`, `content` + // // and `lineCount` are all initialized immediately before any + // // asynchronous operations occur. The lambda callbacks are + // // called later. + // Promise> file = openFtp("ftp://host/foo/bar"); + // Promise content = file.then( + // [](Own file) -> Promise { + // return file.readAll(); + // }); + // Promise lineCount = content.then( + // [](String text) -> int { + // uint count = 0; + // for (char c: text) count += (c == '\n'); + // return count; + // }); + // + // For `then()` to work, the current thread must have an active `EventLoop`. Each callback + // is scheduled to execute in that loop. Since `then()` schedules callbacks only on the current + // thread's event loop, you do not need to worry about two callbacks running at the same time. + // You will need to set up at least one `EventLoop` at the top level of your program before you + // can use promises. + // + // To adapt a non-Promise-based asynchronous API to promises, use `newAdaptedPromise()`. + // + // Systems using promises should consider supporting the concept of "pipelining". Pipelining + // means allowing a caller to start issuing method calls against a promised object before the + // promise has actually been fulfilled. This is particularly useful if the promise is for a + // remote object living across a network, as this can avoid round trips when chaining a series + // of calls. It is suggested that any class T which supports pipelining implement a subclass of + // Promise which adds "eventual send" methods -- methods which, when called, say "please + // invoke the corresponding method on the promised value once it is available". These methods + // should in turn return promises for the eventual results of said invocations. Cap'n Proto, + // for example, implements the type `RemotePromise` which supports pipelining RPC requests -- see + // `capnp/capability.h`. + // + // KJ Promises are based on E promises: + // http://wiki.erights.org/wiki/Walnut/Distributed_Computing#Promises + // + // KJ Promises are also inspired in part by the evolving standards for JavaScript/ECMAScript + // promises, which are themselves influenced by E promises: + // http://promisesaplus.com/ + // https://github.com/domenic/promises-unwrapping + +public: + Promise(_::FixVoid value); + // Construct an already-fulfilled Promise from a value of type T. For non-void promises, the + // parameter type is simply T. So, e.g., in a function that returns `Promise`, you can + // say `return 123;` to return a promise that is already fulfilled to 123. + // + // For void promises, use `kj::READY_NOW` as the value, e.g. `return kj::READY_NOW`. + + Promise(kj::Exception&& e); + // Construct an already-broken Promise. + + inline Promise(decltype(nullptr)) {} + + template + PromiseForResult then(Func&& func, ErrorFunc&& errorHandler = _::PropagateException()) + KJ_WARN_UNUSED_RESULT; + // Register a continuation function to be executed when the promise completes. The continuation + // (`func`) takes the promised value (an rvalue of type `T`) as its parameter. The continuation + // may return a new value; `then()` itself returns a promise for the continuation's eventual + // result. If the continuation itself returns a `Promise`, then `then()` shall also return + // a `Promise` which first waits for the original promise, then executes the continuation, + // then waits for the inner promise (i.e. it automatically "unwraps" the promise). + // + // In all cases, `then()` returns immediately. The continuation is executed later. The + // continuation is always executed on the same EventLoop (and, therefore, the same thread) which + // called `then()`, therefore no synchronization is necessary on state shared by the continuation + // and the surrounding scope. If no EventLoop is running on the current thread, `then()` throws + // an exception. + // + // You may also specify an error handler continuation as the second parameter. `errorHandler` + // must be a functor taking a parameter of type `kj::Exception&&`. It must return the same + // type as `func` returns (except when `func` returns `Promise`, in which case `errorHandler` + // may return either `Promise` or just `U`). The default error handler simply propagates the + // exception to the returned promise. + // + // Either `func` or `errorHandler` may, of course, throw an exception, in which case the promise + // is broken. When compiled with -fno-exceptions, the framework will still detect when a + // recoverable exception was thrown inside of a continuation and will consider the promise + // broken even though a (presumably garbage) result was returned. + // + // If the returned promise is destroyed before the callback runs, the callback will be canceled + // (it will never run). + // + // Note that `then()` -- like all other Promise methods -- consumes the promise on which it is + // called, in the sense of move semantics. After returning, the original promise is no longer + // valid, but `then()` returns a new promise. + // + // *Advanced implementation tips:* Most users will never need to worry about the below, but + // it is good to be aware of. + // + // As an optimization, if the callback function `func` does _not_ return another promise, then + // execution of `func` itself may be delayed until its result is known to be needed. The + // expectation here is that `func` is just doing some transformation on the results, not + // scheduling any other actions, therefore the system doesn't need to be proactive about + // evaluating it. This way, a chain of trivial then() transformations can be executed all at + // once without repeatedly re-scheduling through the event loop. Use the `eagerlyEvaluate()` + // method to suppress this behavior. + // + // On the other hand, if `func` _does_ return another promise, then the system evaluates `func` + // as soon as possible, because the promise it returns might be for a newly-scheduled + // long-running asynchronous task. + // + // As another optimization, when a callback function registered with `then()` is actually + // scheduled, it is scheduled to occur immediately, preempting other work in the event queue. + // This allows a long chain of `then`s to execute all at once, improving cache locality by + // clustering operations on the same data. However, this implies that starvation can occur + // if a chain of `then()`s takes a very long time to execute without ever stopping to wait for + // actual I/O. To solve this, use `kj::evalLater()` to yield control; this way, all other events + // in the queue will get a chance to run before your callback is executed. + + Promise ignoreResult() KJ_WARN_UNUSED_RESULT { return then([](T&&) {}); } + // Convenience method to convert the promise to a void promise by ignoring the return value. + // + // You must still wait on the returned promise if you want the task to execute. + + template + Promise catch_(ErrorFunc&& errorHandler) KJ_WARN_UNUSED_RESULT; + // Equivalent to `.then(identityFunc, errorHandler)`, where `identifyFunc` is a function that + // just returns its input. + + T wait(WaitScope& waitScope); + // Run the event loop until the promise is fulfilled, then return its result. If the promise + // is rejected, throw an exception. + // + // wait() is primarily useful at the top level of a program -- typically, within the function + // that allocated the EventLoop. For example, a program that performs one or two RPCs and then + // exits would likely use wait() in its main() function to wait on each RPC. On the other hand, + // server-side code generally cannot use wait(), because it has to be able to accept multiple + // requests at once. + // + // If the promise is rejected, `wait()` throws an exception. If the program was compiled without + // exceptions (-fno-exceptions), this will usually abort. In this case you really should first + // use `then()` to set an appropriate handler for the exception case, so that the promise you + // actually wait on never throws. + // + // `waitScope` is an object proving that the caller is in a scope where wait() is allowed. By + // convention, any function which might call wait(), or which might call another function which + // might call wait(), must take `WaitScope&` as one of its parameters. This is needed for two + // reasons: + // * `wait()` is not allowed during an event callback, because event callbacks are themselves + // called during some other `wait()`, and such recursive `wait()`s would only be able to + // complete in LIFO order, which might mean that the outer `wait()` ends up waiting longer + // than it is supposed to. To prevent this, a `WaitScope` cannot be constructed or used during + // an event callback. + // * Since `wait()` runs the event loop, unrelated event callbacks may execute before `wait()` + // returns. This means that anyone calling `wait()` must be reentrant -- state may change + // around them in arbitrary ways. Therefore, callers really need to know if a function they + // are calling might wait(), and the `WaitScope&` parameter makes this clear. + // + // TODO(someday): Implement fibers, and let them call wait() even when they are handling an + // event. + + ForkedPromise fork() KJ_WARN_UNUSED_RESULT; + // Forks the promise, so that multiple different clients can independently wait on the result. + // `T` must be copy-constructable for this to work. Or, in the special case where `T` is + // `Own`, `U` must have a method `Own addRef()` which returns a new reference to the same + // (or an equivalent) object (probably implemented via reference counting). + + _::SplitTuplePromise split(); + // Split a promise for a tuple into a tuple of promises. + // + // E.g. if you have `Promise>`, `split()` returns + // `kj::Tuple, Promise>`. + + Promise exclusiveJoin(Promise&& other) KJ_WARN_UNUSED_RESULT; + // Return a new promise that resolves when either the original promise resolves or `other` + // resolves (whichever comes first). The promise that didn't resolve first is canceled. + + // TODO(someday): inclusiveJoin(), or perhaps just join(), which waits for both completions + // and produces a tuple? + + template + Promise attach(Attachments&&... attachments) KJ_WARN_UNUSED_RESULT; + // "Attaches" one or more movable objects (often, Owns) to the promise, such that they will + // be destroyed when the promise resolves. This is useful when a promise's callback contains + // pointers into some object and you want to make sure the object still exists when the callback + // runs -- after calling then(), use attach() to add necessary objects to the result. + + template + Promise eagerlyEvaluate(ErrorFunc&& errorHandler) KJ_WARN_UNUSED_RESULT; + Promise eagerlyEvaluate(decltype(nullptr)) KJ_WARN_UNUSED_RESULT; + // Force eager evaluation of this promise. Use this if you are going to hold on to the promise + // for awhile without consuming the result, but you want to make sure that the system actually + // processes it. + // + // `errorHandler` is a function that takes `kj::Exception&&`, like the second parameter to + // `then()`, except that it must return void. We make you specify this because otherwise it's + // easy to forget to handle errors in a promise that you never use. You may specify nullptr for + // the error handler if you are sure that ignoring errors is fine, or if you know that you'll + // eventually wait on the promise somewhere. + + template + void detach(ErrorFunc&& errorHandler); + // Allows the promise to continue running in the background until it completes or the + // `EventLoop` is destroyed. Be careful when using this: since you can no longer cancel this + // promise, you need to make sure that the promise owns all the objects it touches or make sure + // those objects outlive the EventLoop. + // + // `errorHandler` is a function that takes `kj::Exception&&`, like the second parameter to + // `then()`, except that it must return void. + // + // This function exists mainly to implement the Cap'n Proto requirement that RPC calls cannot be + // canceled unless the callee explicitly permits it. + + kj::String trace(); + // Returns a dump of debug info about this promise. Not for production use. Requires RTTI. + // This method does NOT consume the promise as other methods do. + +private: + Promise(bool, Own<_::PromiseNode>&& node): PromiseBase(kj::mv(node)) {} + // Second parameter prevent ambiguity with immediate-value constructor. + + template + friend class Promise; + friend class EventLoop; + template + friend Promise newAdaptedPromise(Params&&... adapterConstructorParams); + template + friend PromiseFulfillerPair newPromiseAndFulfiller(); + template + friend class _::ForkHub; + friend class _::TaskSetImpl; + friend Promise _::yield(); + friend class _::NeverDone; + template + friend Promise> joinPromises(Array>&& promises); + friend Promise joinPromises(Array>&& promises); +}; + +template +class ForkedPromise { + // The result of `Promise::fork()` and `EventLoop::fork()`. Allows branches to be created. + // Like `Promise`, this is a pass-by-move type. + +public: + inline ForkedPromise(decltype(nullptr)) {} + + Promise addBranch(); + // Add a new branch to the fork. The branch is equivalent to the original promise. + +private: + Own<_::ForkHub<_::FixVoid>> hub; + + inline ForkedPromise(bool, Own<_::ForkHub<_::FixVoid>>&& hub): hub(kj::mv(hub)) {} + + friend class Promise; + friend class EventLoop; +}; + +constexpr _::Void READY_NOW = _::Void(); +// Use this when you need a Promise that is already fulfilled -- this value can be implicitly +// cast to `Promise`. + +constexpr _::NeverDone NEVER_DONE = _::NeverDone(); +// The opposite of `READY_NOW`, return this when the promise should never resolve. This can be +// implicitly converted to any promise type. You may also call `NEVER_DONE.wait()` to wait +// forever (useful for servers). + +template +PromiseForResult evalLater(Func&& func) KJ_WARN_UNUSED_RESULT; +// Schedule for the given zero-parameter function to be executed in the event loop at some +// point in the near future. Returns a Promise for its result -- or, if `func()` itself returns +// a promise, `evalLater()` returns a Promise for the result of resolving that promise. +// +// Example usage: +// Promise x = evalLater([]() { return 123; }); +// +// The above is exactly equivalent to: +// Promise x = Promise(READY_NOW).then([]() { return 123; }); +// +// If the returned promise is destroyed before the callback runs, the callback will be canceled +// (never called). +// +// If you schedule several evaluations with `evalLater` during the same callback, they are +// guaranteed to be executed in order. + +template +PromiseForResult evalNow(Func&& func) KJ_WARN_UNUSED_RESULT; +// Run `func()` and return a promise for its result. `func()` executes before `evalNow()` returns. +// If `func()` throws an exception, the exception is caught and wrapped in a promise -- this is the +// main reason why `evalNow()` is useful. + +template +Promise> joinPromises(Array>&& promises); +// Join an array of promises into a promise for an array. + +// ======================================================================================= +// Hack for creating a lambda that holds an owned pointer. + +template +class CaptureByMove { +public: + inline CaptureByMove(Func&& func, MovedParam&& param) + : func(kj::mv(func)), param(kj::mv(param)) {} + + template + inline auto operator()(Params&&... params) + -> decltype(kj::instance()(kj::instance(), kj::fwd(params)...)) { + return func(kj::mv(param), kj::fwd(params)...); + } + +private: + Func func; + MovedParam param; +}; + +template +inline CaptureByMove> mvCapture(MovedParam&& param, Func&& func) { + // Hack to create a "lambda" which captures a variable by moving it rather than copying or + // referencing. C++14 generalized captures should make this obsolete, but for now in C++11 this + // is commonly needed for Promise continuations that own their state. Example usage: + // + // Own ptr = makeFoo(); + // Promise promise = callRpc(); + // promise.then(mvCapture(ptr, [](Own&& ptr, int result) { + // return ptr->finish(result); + // })); + + return CaptureByMove>(kj::fwd(func), kj::mv(param)); +} + +// ======================================================================================= +// Advanced promise construction + +template +class PromiseFulfiller { + // A callback which can be used to fulfill a promise. Only the first call to fulfill() or + // reject() matters; subsequent calls are ignored. + +public: + virtual void fulfill(T&& value) = 0; + // Fulfill the promise with the given value. + + virtual void reject(Exception&& exception) = 0; + // Reject the promise with an error. + + virtual bool isWaiting() = 0; + // Returns true if the promise is still unfulfilled and someone is potentially waiting for it. + // Returns false if fulfill()/reject() has already been called *or* if the promise to be + // fulfilled has been discarded and therefore the result will never be used anyway. + + template + bool rejectIfThrows(Func&& func); + // Call the function (with no arguments) and return true. If an exception is thrown, call + // `fulfiller.reject()` and then return false. When compiled with exceptions disabled, + // non-fatal exceptions are still detected and handled correctly. +}; + +template <> +class PromiseFulfiller { + // Specialization of PromiseFulfiller for void promises. See PromiseFulfiller. + +public: + virtual void fulfill(_::Void&& value = _::Void()) = 0; + // Call with zero parameters. The parameter is a dummy that only exists so that subclasses don't + // have to specialize for . + + virtual void reject(Exception&& exception) = 0; + virtual bool isWaiting() = 0; + + template + bool rejectIfThrows(Func&& func); +}; + +template +Promise newAdaptedPromise(Params&&... adapterConstructorParams); +// Creates a new promise which owns an instance of `Adapter` which encapsulates the operation +// that will eventually fulfill the promise. This is primarily useful for adapting non-KJ +// asynchronous APIs to use promises. +// +// An instance of `Adapter` will be allocated and owned by the returned `Promise`. A +// `PromiseFulfiller&` will be passed as the first parameter to the adapter's constructor, +// and `adapterConstructorParams` will be forwarded as the subsequent parameters. The adapter +// is expected to perform some asynchronous operation and call the `PromiseFulfiller` once +// it is finished. +// +// The adapter is destroyed when its owning Promise is destroyed. This may occur before the +// Promise has been fulfilled. In this case, the adapter's destructor should cancel the +// asynchronous operation. Once the adapter is destroyed, the fulfillment callback cannot be +// called. +// +// An adapter implementation should be carefully written to ensure that it cannot accidentally +// be left unfulfilled permanently because of an exception. Consider making liberal use of +// `PromiseFulfiller::rejectIfThrows()`. + +template +struct PromiseFulfillerPair { + Promise<_::JoinPromises> promise; + Own> fulfiller; +}; + +template +PromiseFulfillerPair newPromiseAndFulfiller(); +// Construct a Promise and a separate PromiseFulfiller which can be used to fulfill the promise. +// If the PromiseFulfiller is destroyed before either of its methods are called, the Promise is +// implicitly rejected. +// +// Although this function is easier to use than `newAdaptedPromise()`, it has the serious drawback +// that there is no way to handle cancellation (i.e. detect when the Promise is discarded). +// +// You can arrange to fulfill a promise with another promise by using a promise type for T. E.g. +// `newPromiseAndFulfiller>()` will produce a promise of type `Promise` but the +// fulfiller will be of type `PromiseFulfiller>`. Thus you pass a `Promise` to the +// `fulfill()` callback, and the promises are chained. + +// ======================================================================================= +// TaskSet + +class TaskSet { + // Holds a collection of Promises and ensures that each executes to completion. Memory + // associated with each promise is automatically freed when the promise completes. Destroying + // the TaskSet itself automatically cancels all unfinished promises. + // + // This is useful for "daemon" objects that perform background tasks which aren't intended to + // fulfill any particular external promise, but which may need to be canceled (and thus can't + // use `Promise::detach()`). The daemon object holds a TaskSet to collect these tasks it is + // working on. This way, if the daemon itself is destroyed, the TaskSet is detroyed as well, + // and everything the daemon is doing is canceled. + +public: + class ErrorHandler { + public: + virtual void taskFailed(kj::Exception&& exception) = 0; + }; + + TaskSet(ErrorHandler& errorHandler); + // `loop` will be used to wait on promises. `errorHandler` will be executed any time a task + // throws an exception, and will execute within the given EventLoop. + + ~TaskSet() noexcept(false); + + void add(Promise&& promise); + + kj::String trace(); + // Return debug info about all promises currently in the TaskSet. + +private: + Own<_::TaskSetImpl> impl; +}; + +// ======================================================================================= +// The EventLoop class + +class EventPort { + // Interfaces between an `EventLoop` and events originating from outside of the loop's thread. + // All such events come in through the `EventPort` implementation. + // + // An `EventPort` implementation may interface with low-level operating system APIs and/or other + // threads. You can also write an `EventPort` which wraps some other (non-KJ) event loop + // framework, allowing the two to coexist in a single thread. + +public: + virtual bool wait() = 0; + // Wait for an external event to arrive, sleeping if necessary. Once at least one event has + // arrived, queue it to the event loop (e.g. by fulfilling a promise) and return. + // + // This is called during `Promise::wait()` whenever the event queue becomes empty, in order to + // wait for new events to populate the queue. + // + // It is safe to return even if nothing has actually been queued, so long as calling `wait()` in + // a loop will eventually sleep. (That is to say, false positives are fine.) + // + // Returns true if wake() has been called from another thread. (Precisely, returns true if + // no previous call to wait `wait()` nor `poll()` has returned true since `wake()` was last + // called.) + + virtual bool poll() = 0; + // Check if any external events have arrived, but do not sleep. If any events have arrived, + // add them to the event queue (e.g. by fulfilling promises) before returning. + // + // This may be called during `Promise::wait()` when the EventLoop has been executing for a while + // without a break but is still non-empty. + // + // Returns true if wake() has been called from another thread. (Precisely, returns true if + // no previous call to wait `wait()` nor `poll()` has returned true since `wake()` was last + // called.) + + virtual void setRunnable(bool runnable); + // Called to notify the `EventPort` when the `EventLoop` has work to do; specifically when it + // transitions from empty -> runnable or runnable -> empty. This is typically useful when + // integrating with an external event loop; if the loop is currently runnable then you should + // arrange to call run() on it soon. The default implementation does nothing. + + virtual void wake() const; + // Wake up the EventPort's thread from another thread. + // + // Unlike all other methods on this interface, `wake()` may be called from another thread, hence + // it is `const`. + // + // Technically speaking, `wake()` causes the target thread to cease sleeping and not to sleep + // again until `wait()` or `poll()` has returned true at least once. + // + // The default implementation throws an UNIMPLEMENTED exception. +}; + +class EventLoop { + // Represents a queue of events being executed in a loop. Most code won't interact with + // EventLoop directly, but instead use `Promise`s to interact with it indirectly. See the + // documentation for `Promise`. + // + // Each thread can have at most one current EventLoop. To make an `EventLoop` current for + // the thread, create a `WaitScope`. Async APIs require that the thread has a current EventLoop, + // or they will throw exceptions. APIs that use `Promise::wait()` additionally must explicitly + // be passed a reference to the `WaitScope` to make the caller aware that they might block. + // + // Generally, you will want to construct an `EventLoop` at the top level of your program, e.g. + // in the main() function, or in the start function of a thread. You can then use it to + // construct some promises and wait on the result. Example: + // + // int main() { + // // `loop` becomes the official EventLoop for the thread. + // MyEventPort eventPort; + // EventLoop loop(eventPort); + // + // // Now we can call an async function. + // Promise textPromise = getHttp("http://example.com"); + // + // // And we can wait for the promise to complete. Note that you can only use `wait()` + // // from the top level, not from inside a promise callback. + // String text = textPromise.wait(); + // print(text); + // return 0; + // } + // + // Most applications that do I/O will prefer to use `setupAsyncIo()` from `async-io.h` rather + // than allocate an `EventLoop` directly. + +public: + EventLoop(); + // Construct an `EventLoop` which does not receive external events at all. + + explicit EventLoop(EventPort& port); + // Construct an `EventLoop` which receives external events through the given `EventPort`. + + ~EventLoop() noexcept(false); + + void run(uint maxTurnCount = maxValue); + // Run the event loop for `maxTurnCount` turns or until there is nothing left to be done, + // whichever comes first. This never calls the `EventPort`'s `sleep()` or `poll()`. It will + // call the `EventPort`'s `setRunnable(false)` if the queue becomes empty. + + bool isRunnable(); + // Returns true if run() would currently do anything, or false if the queue is empty. + +private: + EventPort& port; + + bool running = false; + // True while looping -- wait() is then not allowed. + + bool lastRunnableState = false; + // What did we last pass to port.setRunnable()? + + _::Event* head = nullptr; + _::Event** tail = &head; + _::Event** depthFirstInsertPoint = &head; + + Own<_::TaskSetImpl> daemons; + + bool turn(); + void setRunnable(bool runnable); + void enterScope(); + void leaveScope(); + + friend void _::detach(kj::Promise&& promise); + friend void _::waitImpl(Own<_::PromiseNode>&& node, _::ExceptionOrValue& result, + WaitScope& waitScope); + friend class _::Event; + friend class WaitScope; +}; + +class WaitScope { + // Represents a scope in which asynchronous programming can occur. A `WaitScope` should usually + // be allocated on the stack and serves two purposes: + // * While the `WaitScope` exists, its `EventLoop` is registered as the current loop for the + // thread. Most operations dealing with `Promise` (including all of its methods) do not work + // unless the thread has a current `EventLoop`. + // * `WaitScope` may be passed to `Promise::wait()` to synchronously wait for a particular + // promise to complete. See `Promise::wait()` for an extended discussion. + +public: + inline explicit WaitScope(EventLoop& loop): loop(loop) { loop.enterScope(); } + inline ~WaitScope() { loop.leaveScope(); } + KJ_DISALLOW_COPY(WaitScope); + +private: + EventLoop& loop; + friend class EventLoop; + friend void _::waitImpl(Own<_::PromiseNode>&& node, _::ExceptionOrValue& result, + WaitScope& waitScope); +}; + +} // namespace kj + +#include "async-inl.h" + +#endif // KJ_ASYNC_H_ diff --git a/phonelibs/capnp-cpp/include/kj/common.h b/phonelibs/capnp-cpp/include/kj/common.h new file mode 100644 index 00000000000000..4a908ae0007fd7 --- /dev/null +++ b/phonelibs/capnp-cpp/include/kj/common.h @@ -0,0 +1,1400 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +// Header that should be #included by everyone. +// +// This defines very simple utilities that are widely applicable. + +#ifndef KJ_COMMON_H_ +#define KJ_COMMON_H_ + +#if defined(__GNUC__) && !KJ_HEADER_WARNINGS +#pragma GCC system_header +#endif + +#ifndef KJ_NO_COMPILER_CHECK +#if __cplusplus < 201103L && !__CDT_PARSER__ && !_MSC_VER + #error "This code requires C++11. Either your compiler does not support it or it is not enabled." + #ifdef __GNUC__ + // Compiler claims compatibility with GCC, so presumably supports -std. + #error "Pass -std=c++11 on the compiler command line to enable C++11." + #endif +#endif + +#ifdef __GNUC__ + #if __clang__ + #if __clang_major__ < 3 || (__clang_major__ == 3 && __clang_minor__ < 2) + #warning "This library requires at least Clang 3.2." + #elif defined(__apple_build_version__) && __apple_build_version__ <= 4250028 + #warning "This library requires at least Clang 3.2. XCode 4.6's Clang, which claims to be "\ + "version 4.2 (wat?), is actually built from some random SVN revision between 3.1 "\ + "and 3.2. Unfortunately, it is insufficient for compiling this library. You can "\ + "download the real Clang 3.2 (or newer) from the Clang web site. Step-by-step "\ + "instructions can be found in Cap'n Proto's documentation: "\ + "http://kentonv.github.io/capnproto/install.html#clang_32_on_mac_osx" + #elif __cplusplus >= 201103L && !__has_include() + #warning "Your compiler supports C++11 but your C++ standard library does not. If your "\ + "system has libc++ installed (as should be the case on e.g. Mac OSX), try adding "\ + "-stdlib=libc++ to your CXXFLAGS." + #endif + #else + #if __GNUC__ < 4 || (__GNUC__ == 4 && __GNUC_MINOR__ < 7) + #warning "This library requires at least GCC 4.7." + #endif + #endif +#elif defined(_MSC_VER) + #if _MSC_VER < 1900 + #error "You need Visual Studio 2015 or better to compile this code." + #endif +#else + #warning "I don't recognize your compiler. As of this writing, Clang and GCC are the only "\ + "known compilers with enough C++11 support for this library. "\ + "#define KJ_NO_COMPILER_CHECK to make this warning go away." +#endif +#endif + +#include +#include + +#if __linux__ && __cplusplus > 201200L +// Hack around stdlib bug with C++14 that exists on some Linux systems. +// Apparently in this mode the C library decides not to define gets() but the C++ library still +// tries to import it into the std namespace. This bug has been fixed at the source but is still +// widely present in the wild e.g. on Ubuntu 14.04. +#undef _GLIBCXX_HAVE_GETS +#endif + +#if defined(_MSC_VER) +#ifndef NOMINMAX +#define NOMINMAX 1 +#endif +#include // __popcnt +#endif + +// ======================================================================================= + +namespace kj { + +typedef unsigned int uint; +typedef unsigned char byte; + +// ======================================================================================= +// Common macros, especially for common yet compiler-specific features. + +// Detect whether RTTI and exceptions are enabled, assuming they are unless we have specific +// evidence to the contrary. Clients can always define KJ_NO_RTTI or KJ_NO_EXCEPTIONS explicitly +// to override these checks. +#ifdef __GNUC__ + #if !defined(KJ_NO_RTTI) && !__GXX_RTTI + #define KJ_NO_RTTI 1 + #endif + #if !defined(KJ_NO_EXCEPTIONS) && !__EXCEPTIONS + #define KJ_NO_EXCEPTIONS 1 + #endif +#elif defined(_MSC_VER) + #if !defined(KJ_NO_RTTI) && !defined(_CPPRTTI) + #define KJ_NO_RTTI 1 + #endif + #if !defined(KJ_NO_EXCEPTIONS) && !defined(_CPPUNWIND) + #define KJ_NO_EXCEPTIONS 1 + #endif +#endif + +#if !defined(KJ_DEBUG) && !defined(KJ_NDEBUG) +// Heuristically decide whether to enable debug mode. If DEBUG or NDEBUG is defined, use that. +// Otherwise, fall back to checking whether optimization is enabled. +#if defined(DEBUG) || defined(_DEBUG) +#define KJ_DEBUG +#elif defined(NDEBUG) +#define KJ_NDEBUG +#elif __OPTIMIZE__ +#define KJ_NDEBUG +#else +#define KJ_DEBUG +#endif +#endif + +#define KJ_DISALLOW_COPY(classname) \ + classname(const classname&) = delete; \ + classname& operator=(const classname&) = delete +// Deletes the implicit copy constructor and assignment operator. + +#ifdef __GNUC__ +#define KJ_LIKELY(condition) __builtin_expect(condition, true) +#define KJ_UNLIKELY(condition) __builtin_expect(condition, false) +// Branch prediction macros. Evaluates to the condition given, but also tells the compiler that we +// expect the condition to be true/false enough of the time that it's worth hard-coding branch +// prediction. +#else +#define KJ_LIKELY(condition) (condition) +#define KJ_UNLIKELY(condition) (condition) +#endif + +#if defined(KJ_DEBUG) || __NO_INLINE__ +#define KJ_ALWAYS_INLINE(...) inline __VA_ARGS__ +// Don't force inline in debug mode. +#else +#if defined(_MSC_VER) +#define KJ_ALWAYS_INLINE(...) __forceinline __VA_ARGS__ +#else +#define KJ_ALWAYS_INLINE(...) inline __VA_ARGS__ __attribute__((always_inline)) +#endif +// Force a function to always be inlined. Apply only to the prototype, not to the definition. +#endif + +#if defined(_MSC_VER) +#define KJ_NOINLINE __declspec(noinline) +#else +#define KJ_NOINLINE __attribute__((noinline)) +#endif + +#if defined(_MSC_VER) +#define KJ_NORETURN(prototype) __declspec(noreturn) prototype +#define KJ_UNUSED +#define KJ_WARN_UNUSED_RESULT +// TODO(msvc): KJ_WARN_UNUSED_RESULT can use _Check_return_ on MSVC, but it's a prefix, so +// wrapping the whole prototype is needed. http://msdn.microsoft.com/en-us/library/jj159529.aspx +// Similarly, KJ_UNUSED could use __pragma(warning(suppress:...)), but again that's a prefix. +#else +#define KJ_NORETURN(prototype) prototype __attribute__((noreturn)) +#define KJ_UNUSED __attribute__((unused)) +#define KJ_WARN_UNUSED_RESULT __attribute__((warn_unused_result)) +#endif + +#if __clang__ +#define KJ_UNUSED_MEMBER __attribute__((unused)) +// Inhibits "unused" warning for member variables. Only Clang produces such a warning, while GCC +// complains if the attribute is set on members. +#else +#define KJ_UNUSED_MEMBER +#endif + +#if __clang__ +#define KJ_DEPRECATED(reason) \ + __attribute__((deprecated(reason))) +#define KJ_UNAVAILABLE(reason) \ + __attribute__((unavailable(reason))) +#elif __GNUC__ +#define KJ_DEPRECATED(reason) \ + __attribute__((deprecated)) +#define KJ_UNAVAILABLE(reason) +#else +#define KJ_DEPRECATED(reason) +#define KJ_UNAVAILABLE(reason) +// TODO(msvc): Again, here, MSVC prefers a prefix, __declspec(deprecated). +#endif + +namespace _ { // private + +KJ_NORETURN(void inlineRequireFailure( + const char* file, int line, const char* expectation, const char* macroArgs, + const char* message = nullptr)); + +KJ_NORETURN(void unreachable()); + +} // namespace _ (private) + +#ifdef KJ_DEBUG +#if _MSC_VER +#define KJ_IREQUIRE(condition, ...) \ + if (KJ_LIKELY(condition)); else ::kj::_::inlineRequireFailure( \ + __FILE__, __LINE__, #condition, "" #__VA_ARGS__, __VA_ARGS__) +// Version of KJ_DREQUIRE() which is safe to use in headers that are #included by users. Used to +// check preconditions inside inline methods. KJ_IREQUIRE is particularly useful in that +// it will be enabled depending on whether the application is compiled in debug mode rather than +// whether libkj is. +#else +#define KJ_IREQUIRE(condition, ...) \ + if (KJ_LIKELY(condition)); else ::kj::_::inlineRequireFailure( \ + __FILE__, __LINE__, #condition, #__VA_ARGS__, ##__VA_ARGS__) +// Version of KJ_DREQUIRE() which is safe to use in headers that are #included by users. Used to +// check preconditions inside inline methods. KJ_IREQUIRE is particularly useful in that +// it will be enabled depending on whether the application is compiled in debug mode rather than +// whether libkj is. +#endif +#else +#define KJ_IREQUIRE(condition, ...) +#endif + +#define KJ_IASSERT KJ_IREQUIRE + +#define KJ_UNREACHABLE ::kj::_::unreachable(); +// Put this on code paths that cannot be reached to suppress compiler warnings about missing +// returns. + +#if __clang__ +#define KJ_CLANG_KNOWS_THIS_IS_UNREACHABLE_BUT_GCC_DOESNT +#else +#define KJ_CLANG_KNOWS_THIS_IS_UNREACHABLE_BUT_GCC_DOESNT KJ_UNREACHABLE +#endif + +// #define KJ_STACK_ARRAY(type, name, size, minStack, maxStack) +// +// Allocate an array, preferably on the stack, unless it is too big. On GCC this will use +// variable-sized arrays. For other compilers we could just use a fixed-size array. `minStack` +// is the stack array size to use if variable-width arrays are not supported. `maxStack` is the +// maximum stack array size if variable-width arrays *are* supported. +#if __GNUC__ && !__clang__ +#define KJ_STACK_ARRAY(type, name, size, minStack, maxStack) \ + size_t name##_size = (size); \ + bool name##_isOnStack = name##_size <= (maxStack); \ + type name##_stack[name##_isOnStack ? size : 0]; \ + ::kj::Array name##_heap = name##_isOnStack ? \ + nullptr : kj::heapArray(name##_size); \ + ::kj::ArrayPtr name = name##_isOnStack ? \ + kj::arrayPtr(name##_stack, name##_size) : name##_heap +#else +#define KJ_STACK_ARRAY(type, name, size, minStack, maxStack) \ + size_t name##_size = (size); \ + bool name##_isOnStack = name##_size <= (minStack); \ + type name##_stack[minStack]; \ + ::kj::Array name##_heap = name##_isOnStack ? \ + nullptr : kj::heapArray(name##_size); \ + ::kj::ArrayPtr name = name##_isOnStack ? \ + kj::arrayPtr(name##_stack, name##_size) : name##_heap +#endif + +#define KJ_CONCAT_(x, y) x##y +#define KJ_CONCAT(x, y) KJ_CONCAT_(x, y) +#define KJ_UNIQUE_NAME(prefix) KJ_CONCAT(prefix, __LINE__) +// Create a unique identifier name. We use concatenate __LINE__ rather than __COUNTER__ so that +// the name can be used multiple times in the same macro. + +#if _MSC_VER + +#define KJ_CONSTEXPR(...) __VA_ARGS__ +// Use in cases where MSVC barfs on constexpr. A replacement keyword (e.g. "const") can be +// provided, or just leave blank to remove the keyword entirely. +// +// TODO(msvc): Remove this hack once MSVC fully supports constexpr. + +#ifndef __restrict__ +#define __restrict__ __restrict +// TODO(msvc): Would it be better to define a KJ_RESTRICT macro? +#endif + +#pragma warning(disable: 4521 4522) +// This warning complains when there are two copy constructors, one for a const reference and +// one for a non-const reference. It is often quite necessary to do this in wrapper templates, +// therefore this warning is dumb and we disable it. + +#pragma warning(disable: 4458) +// Warns when a parameter name shadows a class member. Unfortunately my code does this a lot, +// since I don't use a special name format for members. + +#else // _MSC_VER +#define KJ_CONSTEXPR(...) constexpr +#endif + +// ======================================================================================= +// Template metaprogramming helpers. + +template struct NoInfer_ { typedef T Type; }; +template using NoInfer = typename NoInfer_::Type; +// Use NoInfer::Type in place of T for a template function parameter to prevent inference of +// the type based on the parameter value. + +template struct RemoveConst_ { typedef T Type; }; +template struct RemoveConst_ { typedef T Type; }; +template using RemoveConst = typename RemoveConst_::Type; + +template struct IsLvalueReference_ { static constexpr bool value = false; }; +template struct IsLvalueReference_ { static constexpr bool value = true; }; +template +inline constexpr bool isLvalueReference() { return IsLvalueReference_::value; } + +template struct Decay_ { typedef T Type; }; +template struct Decay_ { typedef typename Decay_::Type Type; }; +template struct Decay_ { typedef typename Decay_::Type Type; }; +template struct Decay_ { typedef typename Decay_::Type Type; }; +template struct Decay_ { typedef typename Decay_::Type Type; }; +template struct Decay_ { typedef typename Decay_::Type Type; }; +template struct Decay_ { typedef typename Decay_::Type Type; }; +template struct Decay_ { typedef typename Decay_::Type Type; }; +template struct Decay_ { typedef typename Decay_::Type Type; }; +template using Decay = typename Decay_::Type; + +template struct EnableIf_; +template <> struct EnableIf_ { typedef void Type; }; +template using EnableIf = typename EnableIf_::Type; +// Use like: +// +// template ()> +// void func(T&& t); + +template struct VoidSfinae_ { using Type = void; }; +template using VoidSfinae = typename VoidSfinae_::Type; +// Note: VoidSfinae is std::void_t from C++17. + +template +T instance() noexcept; +// Like std::declval, but doesn't transform T into an rvalue reference. If you want that, specify +// instance(). + +struct DisallowConstCopy { + // Inherit from this, or declare a member variable of this type, to prevent the class from being + // copyable from a const reference -- instead, it will only be copyable from non-const references. + // This is useful for enforcing transitive constness of contained pointers. + // + // For example, say you have a type T which contains a pointer. T has non-const methods which + // modify the value at that pointer, but T's const methods are designed to allow reading only. + // Unfortunately, if T has a regular copy constructor, someone can simply make a copy of T and + // then use it to modify the pointed-to value. However, if T inherits DisallowConstCopy, then + // callers will only be able to copy non-const instances of T. Ideally, there is some + // parallel type ImmutableT which is like a version of T that only has const methods, and can + // be copied from a const T. + // + // Note that due to C++ rules about implicit copy constructors and assignment operators, any + // type that contains or inherits from a type that disallows const copies will also automatically + // disallow const copies. Hey, cool, that's exactly what we want. + +#if CAPNP_DEBUG_TYPES + // Alas! Declaring a defaulted non-const copy constructor tickles a bug which causes GCC and + // Clang to disagree on ABI, using different calling conventions to pass this type, leading to + // immediate segfaults. See: + // https://bugs.llvm.org/show_bug.cgi?id=23764 + // https://gcc.gnu.org/bugzilla/show_bug.cgi?id=58074 + // + // Because of this, we can't use this technique. We guard it by CAPNP_DEBUG_TYPES so that it + // still applies to the Cap'n Proto developers during internal testing. + + DisallowConstCopy() = default; + DisallowConstCopy(DisallowConstCopy&) = default; + DisallowConstCopy(DisallowConstCopy&&) = default; + DisallowConstCopy& operator=(DisallowConstCopy&) = default; + DisallowConstCopy& operator=(DisallowConstCopy&&) = default; +#endif +}; + +#if _MSC_VER + +#define KJ_CPCAP(obj) obj=::kj::cp(obj) +// TODO(msvc): MSVC refuses to invoke non-const versions of copy constructors in by-value lambda +// captures. Wrap your captured object in this macro to force the compiler to perform a copy. +// Example: +// +// struct Foo: DisallowConstCopy {}; +// Foo foo; +// auto lambda = [KJ_CPCAP(foo)] {}; + +#else + +#define KJ_CPCAP(obj) obj +// Clang and gcc both already perform copy capturing correctly with non-const copy constructors. + +#endif + +template +struct DisallowConstCopyIfNotConst: public DisallowConstCopy { + // Inherit from this when implementing a template that contains a pointer to T and which should + // enforce transitive constness. If T is a const type, this has no effect. Otherwise, it is + // an alias for DisallowConstCopy. +}; + +template +struct DisallowConstCopyIfNotConst {}; + +template struct IsConst_ { static constexpr bool value = false; }; +template struct IsConst_ { static constexpr bool value = true; }; +template constexpr bool isConst() { return IsConst_::value; } + +template struct EnableIfNotConst_ { typedef T Type; }; +template struct EnableIfNotConst_; +template using EnableIfNotConst = typename EnableIfNotConst_::Type; + +template struct EnableIfConst_; +template struct EnableIfConst_ { typedef T Type; }; +template using EnableIfConst = typename EnableIfConst_::Type; + +template struct RemoveConstOrDisable_ { struct Type; }; +template struct RemoveConstOrDisable_ { typedef T Type; }; +template using RemoveConstOrDisable = typename RemoveConstOrDisable_::Type; + +template struct IsReference_ { static constexpr bool value = false; }; +template struct IsReference_ { static constexpr bool value = true; }; +template constexpr bool isReference() { return IsReference_::value; } + +template +struct PropagateConst_ { typedef To Type; }; +template +struct PropagateConst_ { typedef const To Type; }; +template +using PropagateConst = typename PropagateConst_::Type; + +namespace _ { // private + +template +T refIfLvalue(T&&); + +} // namespace _ (private) + +#define KJ_DECLTYPE_REF(exp) decltype(::kj::_::refIfLvalue(exp)) +// Like decltype(exp), but if exp is an lvalue, produces a reference type. +// +// int i; +// decltype(i) i1(i); // i1 has type int. +// KJ_DECLTYPE_REF(i + 1) i2(i + 1); // i2 has type int. +// KJ_DECLTYPE_REF(i) i3(i); // i3 has type int&. +// KJ_DECLTYPE_REF(kj::mv(i)) i4(kj::mv(i)); // i4 has type int. + +template +struct CanConvert_ { + static int sfinae(T); + static bool sfinae(...); +}; + +template +constexpr bool canConvert() { + return sizeof(CanConvert_::sfinae(instance())) == sizeof(int); +} + +#if __GNUC__ && !__clang__ && __GNUC__ < 5 +template +constexpr bool canMemcpy() { + // Returns true if T can be copied using memcpy instead of using the copy constructor or + // assignment operator. + + // GCC 4 does not have __is_trivially_constructible and friends, and there doesn't seem to be + // any reliable alternative. __has_trivial_copy() and __has_trivial_assign() return the right + // thing at one point but later on they changed such that a deleted copy constructor was + // considered "trivial" (apparently technically correct, though useless). So, on GCC 4 we give up + // and assume we can't memcpy() at all, and must explicitly copy-construct everything. + return false; +} +#define KJ_ASSERT_CAN_MEMCPY(T) +#else +template +constexpr bool canMemcpy() { + // Returns true if T can be copied using memcpy instead of using the copy constructor or + // assignment operator. + + return __is_trivially_constructible(T, const T&) && __is_trivially_assignable(T, const T&); +} +#define KJ_ASSERT_CAN_MEMCPY(T) \ + static_assert(kj::canMemcpy(), "this code expects this type to be memcpy()-able"); +#endif + +// ======================================================================================= +// Equivalents to std::move() and std::forward(), since these are very commonly needed and the +// std header pulls in lots of other stuff. +// +// We use abbreviated names mv and fwd because these helpers (especially mv) are so commonly used +// that the cost of typing more letters outweighs the cost of being slightly harder to understand +// when first encountered. + +template constexpr T&& mv(T& t) noexcept { return static_cast(t); } +template constexpr T&& fwd(NoInfer& t) noexcept { return static_cast(t); } + +template constexpr T cp(T& t) noexcept { return t; } +template constexpr T cp(const T& t) noexcept { return t; } +// Useful to force a copy, particularly to pass into a function that expects T&&. + +template struct ChooseType_; +template struct ChooseType_ { typedef T Type; }; +template struct ChooseType_ { typedef T Type; }; +template struct ChooseType_ { typedef U Type; }; + +template +using WiderType = typename ChooseType_= sizeof(U)>::Type; + +template +inline constexpr auto min(T&& a, U&& b) -> WiderType, Decay> { + return a < b ? WiderType, Decay>(a) : WiderType, Decay>(b); +} + +template +inline constexpr auto max(T&& a, U&& b) -> WiderType, Decay> { + return a > b ? WiderType, Decay>(a) : WiderType, Decay>(b); +} + +template +inline constexpr size_t size(T (&arr)[s]) { return s; } +template +inline constexpr size_t size(T&& arr) { return arr.size(); } +// Returns the size of the parameter, whether the parameter is a regular C array or a container +// with a `.size()` method. + +class MaxValue_ { +private: + template + inline constexpr T maxSigned() const { + return (1ull << (sizeof(T) * 8 - 1)) - 1; + } + template + inline constexpr T maxUnsigned() const { + return ~static_cast(0u); + } + +public: +#define _kJ_HANDLE_TYPE(T) \ + inline constexpr operator signed T() const { return MaxValue_::maxSigned < signed T>(); } \ + inline constexpr operator unsigned T() const { return MaxValue_::maxUnsigned(); } + _kJ_HANDLE_TYPE(char) + _kJ_HANDLE_TYPE(short) + _kJ_HANDLE_TYPE(int) + _kJ_HANDLE_TYPE(long) + _kJ_HANDLE_TYPE(long long) +#undef _kJ_HANDLE_TYPE + + inline constexpr operator char() const { + // `char` is different from both `signed char` and `unsigned char`, and may be signed or + // unsigned on different platforms. Ugh. + return char(-1) < 0 ? MaxValue_::maxSigned() + : MaxValue_::maxUnsigned(); + } +}; + +class MinValue_ { +private: + template + inline constexpr T minSigned() const { + return 1ull << (sizeof(T) * 8 - 1); + } + template + inline constexpr T minUnsigned() const { + return 0u; + } + +public: +#define _kJ_HANDLE_TYPE(T) \ + inline constexpr operator signed T() const { return MinValue_::minSigned < signed T>(); } \ + inline constexpr operator unsigned T() const { return MinValue_::minUnsigned(); } + _kJ_HANDLE_TYPE(char) + _kJ_HANDLE_TYPE(short) + _kJ_HANDLE_TYPE(int) + _kJ_HANDLE_TYPE(long) + _kJ_HANDLE_TYPE(long long) +#undef _kJ_HANDLE_TYPE + + inline constexpr operator char() const { + // `char` is different from both `signed char` and `unsigned char`, and may be signed or + // unsigned on different platforms. Ugh. + return char(-1) < 0 ? MinValue_::minSigned() + : MinValue_::minUnsigned(); + } +}; + +static KJ_CONSTEXPR(const) MaxValue_ maxValue = MaxValue_(); +// A special constant which, when cast to an integer type, takes on the maximum possible value of +// that type. This is useful to use as e.g. a parameter to a function because it will be robust +// in the face of changes to the parameter's type. +// +// `char` is not supported, but `signed char` and `unsigned char` are. + +static KJ_CONSTEXPR(const) MinValue_ minValue = MinValue_(); +// A special constant which, when cast to an integer type, takes on the minimum possible value +// of that type. This is useful to use as e.g. a parameter to a function because it will be robust +// in the face of changes to the parameter's type. +// +// `char` is not supported, but `signed char` and `unsigned char` are. + +template +inline bool operator==(T t, MaxValue_) { return t == Decay(maxValue); } +template +inline bool operator==(T t, MinValue_) { return t == Decay(minValue); } + +template +inline constexpr unsigned long long maxValueForBits() { + // Get the maximum integer representable in the given number of bits. + + // 1ull << 64 is unfortunately undefined. + return (bits == 64 ? 0 : (1ull << bits)) - 1; +} + +struct ThrowOverflow { + // Functor which throws an exception complaining about integer overflow. Usually this is used + // with the interfaces in units.h, but is defined here because Cap'n Proto wants to avoid + // including units.h when not using CAPNP_DEBUG_TYPES. + void operator()() const; +}; + +#if __GNUC__ +inline constexpr float inf() { return __builtin_huge_valf(); } +inline constexpr float nan() { return __builtin_nanf(""); } + +#elif _MSC_VER + +// Do what MSVC math.h does +#pragma warning(push) +#pragma warning(disable: 4756) // "overflow in constant arithmetic" +inline constexpr float inf() { return (float)(1e300 * 1e300); } +#pragma warning(pop) + +float nan(); +// Unfortunatley, inf() * 0.0f produces a NaN with the sign bit set, whereas our preferred +// canonical NaN should not have the sign bit set. std::numeric_limits::quiet_NaN() +// returns the correct NaN, but we don't want to #include that here. So, we give up and make +// this out-of-line on MSVC. +// +// TODO(msvc): Can we do better? + +#else +#error "Not sure how to support your compiler." +#endif + +inline constexpr bool isNaN(float f) { return f != f; } +inline constexpr bool isNaN(double f) { return f != f; } + +inline int popCount(unsigned int x) { +#if defined(_MSC_VER) + return __popcnt(x); + // Note: __popcnt returns unsigned int, but the value is clearly guaranteed to fit into an int +#else + return __builtin_popcount(x); +#endif +} + +// ======================================================================================= +// Useful fake containers + +template +class Range { +public: + inline constexpr Range(const T& begin, const T& end): begin_(begin), end_(end) {} + inline explicit constexpr Range(const T& end): begin_(0), end_(end) {} + + class Iterator { + public: + Iterator() = default; + inline Iterator(const T& value): value(value) {} + + inline const T& operator* () const { return value; } + inline const T& operator[](size_t index) const { return value + index; } + inline Iterator& operator++() { ++value; return *this; } + inline Iterator operator++(int) { return Iterator(value++); } + inline Iterator& operator--() { --value; return *this; } + inline Iterator operator--(int) { return Iterator(value--); } + inline Iterator& operator+=(ptrdiff_t amount) { value += amount; return *this; } + inline Iterator& operator-=(ptrdiff_t amount) { value -= amount; return *this; } + inline Iterator operator+ (ptrdiff_t amount) const { return Iterator(value + amount); } + inline Iterator operator- (ptrdiff_t amount) const { return Iterator(value - amount); } + inline ptrdiff_t operator- (const Iterator& other) const { return value - other.value; } + + inline bool operator==(const Iterator& other) const { return value == other.value; } + inline bool operator!=(const Iterator& other) const { return value != other.value; } + inline bool operator<=(const Iterator& other) const { return value <= other.value; } + inline bool operator>=(const Iterator& other) const { return value >= other.value; } + inline bool operator< (const Iterator& other) const { return value < other.value; } + inline bool operator> (const Iterator& other) const { return value > other.value; } + + private: + T value; + }; + + inline Iterator begin() const { return Iterator(begin_); } + inline Iterator end() const { return Iterator(end_); } + + inline auto size() const -> decltype(instance() - instance()) { return end_ - begin_; } + +private: + T begin_; + T end_; +}; + +template +inline constexpr Range, Decay>> range(T begin, U end) { + return Range, Decay>>(begin, end); +} + +template +inline constexpr Range> range(T begin, T end) { return Range>(begin, end); } +// Returns a fake iterable container containing all values of T from `begin` (inclusive) to `end` +// (exclusive). Example: +// +// // Prints 1, 2, 3, 4, 5, 6, 7, 8, 9. +// for (int i: kj::range(1, 10)) { print(i); } + +template +inline constexpr Range> zeroTo(T end) { return Range>(end); } +// Returns a fake iterable container containing all values of T from zero (inclusive) to `end` +// (exclusive). Example: +// +// // Prints 0, 1, 2, 3, 4, 5, 6, 7, 8, 9. +// for (int i: kj::zeroTo(10)) { print(i); } + +template +inline constexpr Range indices(T&& container) { + // Shortcut for iterating over the indices of a container: + // + // for (size_t i: kj::indices(myArray)) { handle(myArray[i]); } + + return range(0, kj::size(container)); +} + +template +class Repeat { +public: + inline constexpr Repeat(const T& value, size_t count): value(value), count(count) {} + + class Iterator { + public: + Iterator() = default; + inline Iterator(const T& value, size_t index): value(value), index(index) {} + + inline const T& operator* () const { return value; } + inline const T& operator[](ptrdiff_t index) const { return value; } + inline Iterator& operator++() { ++index; return *this; } + inline Iterator operator++(int) { return Iterator(value, index++); } + inline Iterator& operator--() { --index; return *this; } + inline Iterator operator--(int) { return Iterator(value, index--); } + inline Iterator& operator+=(ptrdiff_t amount) { index += amount; return *this; } + inline Iterator& operator-=(ptrdiff_t amount) { index -= amount; return *this; } + inline Iterator operator+ (ptrdiff_t amount) const { return Iterator(value, index + amount); } + inline Iterator operator- (ptrdiff_t amount) const { return Iterator(value, index - amount); } + inline ptrdiff_t operator- (const Iterator& other) const { return index - other.index; } + + inline bool operator==(const Iterator& other) const { return index == other.index; } + inline bool operator!=(const Iterator& other) const { return index != other.index; } + inline bool operator<=(const Iterator& other) const { return index <= other.index; } + inline bool operator>=(const Iterator& other) const { return index >= other.index; } + inline bool operator< (const Iterator& other) const { return index < other.index; } + inline bool operator> (const Iterator& other) const { return index > other.index; } + + private: + T value; + size_t index; + }; + + inline Iterator begin() const { return Iterator(value, 0); } + inline Iterator end() const { return Iterator(value, count); } + + inline size_t size() const { return count; } + inline const T& operator[](ptrdiff_t) const { return value; } + +private: + T value; + size_t count; +}; + +template +inline constexpr Repeat> repeat(T&& value, size_t count) { + // Returns a fake iterable which contains `count` repeats of `value`. Useful for e.g. creating + // a bunch of spaces: `kj::repeat(' ', indent * 2)` + + return Repeat>(value, count); +} + +// ======================================================================================= +// Manually invoking constructors and destructors +// +// ctor(x, ...) and dtor(x) invoke x's constructor or destructor, respectively. + +// We want placement new, but we don't want to #include . operator new cannot be defined in +// a namespace, and defining it globally conflicts with the definition in . So we have to +// define a dummy type and an operator new that uses it. + +namespace _ { // private +struct PlacementNew {}; +} // namespace _ (private) +} // namespace kj + +inline void* operator new(size_t, kj::_::PlacementNew, void* __p) noexcept { + return __p; +} + +inline void operator delete(void*, kj::_::PlacementNew, void* __p) noexcept {} + +namespace kj { + +template +inline void ctor(T& location, Params&&... params) { + new (_::PlacementNew(), &location) T(kj::fwd(params)...); +} + +template +inline void dtor(T& location) { + location.~T(); +} + +// ======================================================================================= +// Maybe +// +// Use in cases where you want to indicate that a value may be null. Using Maybe instead of T* +// forces the caller to handle the null case in order to satisfy the compiler, thus reliably +// preventing null pointer dereferences at runtime. +// +// Maybe can be implicitly constructed from T and from nullptr. Additionally, it can be +// implicitly constructed from T*, in which case the pointer is checked for nullness at runtime. +// To read the value of a Maybe, do: +// +// KJ_IF_MAYBE(value, someFuncReturningMaybe()) { +// doSomething(*value); +// } else { +// maybeWasNull(); +// } +// +// KJ_IF_MAYBE's first parameter is a variable name which will be defined within the following +// block. The variable will behave like a (guaranteed non-null) pointer to the Maybe's value, +// though it may or may not actually be a pointer. +// +// Note that Maybe actually just wraps a pointer, whereas Maybe wraps a T and a boolean +// indicating nullness. + +template +class Maybe; + +namespace _ { // private + +template +class NullableValue { + // Class whose interface behaves much like T*, but actually contains an instance of T and a + // boolean flag indicating nullness. + +public: + inline NullableValue(NullableValue&& other) noexcept(noexcept(T(instance()))) + : isSet(other.isSet) { + if (isSet) { + ctor(value, kj::mv(other.value)); + } + } + inline NullableValue(const NullableValue& other) + : isSet(other.isSet) { + if (isSet) { + ctor(value, other.value); + } + } + inline NullableValue(NullableValue& other) + : isSet(other.isSet) { + if (isSet) { + ctor(value, other.value); + } + } + inline ~NullableValue() +#if _MSC_VER + // TODO(msvc): MSVC has a hard time with noexcept specifier expressions that are more complex + // than `true` or `false`. We had a workaround for VS2015, but VS2017 regressed. + noexcept(false) +#else + noexcept(noexcept(instance().~T())) +#endif + { + if (isSet) { + dtor(value); + } + } + + inline T& operator*() & { return value; } + inline const T& operator*() const & { return value; } + inline T&& operator*() && { return kj::mv(value); } + inline const T&& operator*() const && { return kj::mv(value); } + inline T* operator->() { return &value; } + inline const T* operator->() const { return &value; } + inline operator T*() { return isSet ? &value : nullptr; } + inline operator const T*() const { return isSet ? &value : nullptr; } + + template + inline T& emplace(Params&&... params) { + if (isSet) { + isSet = false; + dtor(value); + } + ctor(value, kj::fwd(params)...); + isSet = true; + return value; + } + +private: // internal interface used by friends only + inline NullableValue() noexcept: isSet(false) {} + inline NullableValue(T&& t) noexcept(noexcept(T(instance()))) + : isSet(true) { + ctor(value, kj::mv(t)); + } + inline NullableValue(T& t) + : isSet(true) { + ctor(value, t); + } + inline NullableValue(const T& t) + : isSet(true) { + ctor(value, t); + } + inline NullableValue(const T* t) + : isSet(t != nullptr) { + if (isSet) ctor(value, *t); + } + template + inline NullableValue(NullableValue&& other) noexcept(noexcept(T(instance()))) + : isSet(other.isSet) { + if (isSet) { + ctor(value, kj::mv(other.value)); + } + } + template + inline NullableValue(const NullableValue& other) + : isSet(other.isSet) { + if (isSet) { + ctor(value, other.value); + } + } + template + inline NullableValue(const NullableValue& other) + : isSet(other.isSet) { + if (isSet) { + ctor(value, *other.ptr); + } + } + inline NullableValue(decltype(nullptr)): isSet(false) {} + + inline NullableValue& operator=(NullableValue&& other) { + if (&other != this) { + // Careful about throwing destructors/constructors here. + if (isSet) { + isSet = false; + dtor(value); + } + if (other.isSet) { + ctor(value, kj::mv(other.value)); + isSet = true; + } + } + return *this; + } + + inline NullableValue& operator=(NullableValue& other) { + if (&other != this) { + // Careful about throwing destructors/constructors here. + if (isSet) { + isSet = false; + dtor(value); + } + if (other.isSet) { + ctor(value, other.value); + isSet = true; + } + } + return *this; + } + + inline NullableValue& operator=(const NullableValue& other) { + if (&other != this) { + // Careful about throwing destructors/constructors here. + if (isSet) { + isSet = false; + dtor(value); + } + if (other.isSet) { + ctor(value, other.value); + isSet = true; + } + } + return *this; + } + + inline bool operator==(decltype(nullptr)) const { return !isSet; } + inline bool operator!=(decltype(nullptr)) const { return isSet; } + +private: + bool isSet; + +#if _MSC_VER +#pragma warning(push) +#pragma warning(disable: 4624) +// Warns that the anonymous union has a deleted destructor when T is non-trivial. This warning +// seems broken. +#endif + + union { + T value; + }; + +#if _MSC_VER +#pragma warning(pop) +#endif + + friend class kj::Maybe; + template + friend NullableValue&& readMaybe(Maybe&& maybe); +}; + +template +inline NullableValue&& readMaybe(Maybe&& maybe) { return kj::mv(maybe.ptr); } +template +inline T* readMaybe(Maybe& maybe) { return maybe.ptr; } +template +inline const T* readMaybe(const Maybe& maybe) { return maybe.ptr; } +template +inline T* readMaybe(Maybe&& maybe) { return maybe.ptr; } +template +inline T* readMaybe(const Maybe& maybe) { return maybe.ptr; } + +template +inline T* readMaybe(T* ptr) { return ptr; } +// Allow KJ_IF_MAYBE to work on regular pointers. + +} // namespace _ (private) + +#define KJ_IF_MAYBE(name, exp) if (auto name = ::kj::_::readMaybe(exp)) + +template +class Maybe { + // A T, or nullptr. + + // IF YOU CHANGE THIS CLASS: Note that there is a specialization of it in memory.h. + +public: + Maybe(): ptr(nullptr) {} + Maybe(T&& t) noexcept(noexcept(T(instance()))): ptr(kj::mv(t)) {} + Maybe(T& t): ptr(t) {} + Maybe(const T& t): ptr(t) {} + Maybe(const T* t) noexcept: ptr(t) {} + Maybe(Maybe&& other) noexcept(noexcept(T(instance()))): ptr(kj::mv(other.ptr)) {} + Maybe(const Maybe& other): ptr(other.ptr) {} + Maybe(Maybe& other): ptr(other.ptr) {} + + template + Maybe(Maybe&& other) noexcept(noexcept(T(instance()))) { + KJ_IF_MAYBE(val, kj::mv(other)) { + ptr.emplace(kj::mv(*val)); + } + } + template + Maybe(const Maybe& other) { + KJ_IF_MAYBE(val, other) { + ptr.emplace(*val); + } + } + + Maybe(decltype(nullptr)) noexcept: ptr(nullptr) {} + + template + inline T& emplace(Params&&... params) { + // Replace this Maybe's content with a new value constructed by passing the given parametrs to + // T's constructor. This can be used to initialize a Maybe without copying or even moving a T. + // Returns a reference to the newly-constructed value. + + return ptr.emplace(kj::fwd(params)...); + } + + inline Maybe& operator=(Maybe&& other) { ptr = kj::mv(other.ptr); return *this; } + inline Maybe& operator=(Maybe& other) { ptr = other.ptr; return *this; } + inline Maybe& operator=(const Maybe& other) { ptr = other.ptr; return *this; } + + inline bool operator==(decltype(nullptr)) const { return ptr == nullptr; } + inline bool operator!=(decltype(nullptr)) const { return ptr != nullptr; } + + T& orDefault(T& defaultValue) { + if (ptr == nullptr) { + return defaultValue; + } else { + return *ptr; + } + } + const T& orDefault(const T& defaultValue) const { + if (ptr == nullptr) { + return defaultValue; + } else { + return *ptr; + } + } + + template + auto map(Func&& f) & -> Maybe()))> { + if (ptr == nullptr) { + return nullptr; + } else { + return f(*ptr); + } + } + + template + auto map(Func&& f) const & -> Maybe()))> { + if (ptr == nullptr) { + return nullptr; + } else { + return f(*ptr); + } + } + + template + auto map(Func&& f) && -> Maybe()))> { + if (ptr == nullptr) { + return nullptr; + } else { + return f(kj::mv(*ptr)); + } + } + + template + auto map(Func&& f) const && -> Maybe()))> { + if (ptr == nullptr) { + return nullptr; + } else { + return f(kj::mv(*ptr)); + } + } + +private: + _::NullableValue ptr; + + template + friend class Maybe; + template + friend _::NullableValue&& _::readMaybe(Maybe&& maybe); + template + friend U* _::readMaybe(Maybe& maybe); + template + friend const U* _::readMaybe(const Maybe& maybe); +}; + +template +class Maybe: public DisallowConstCopyIfNotConst { +public: + Maybe() noexcept: ptr(nullptr) {} + Maybe(T& t) noexcept: ptr(&t) {} + Maybe(T* t) noexcept: ptr(t) {} + + template + inline Maybe(Maybe& other) noexcept: ptr(other.ptr) {} + template + inline Maybe(const Maybe& other) noexcept: ptr(other.ptr) {} + inline Maybe(decltype(nullptr)) noexcept: ptr(nullptr) {} + + inline Maybe& operator=(T& other) noexcept { ptr = &other; return *this; } + inline Maybe& operator=(T* other) noexcept { ptr = other; return *this; } + template + inline Maybe& operator=(Maybe& other) noexcept { ptr = other.ptr; return *this; } + template + inline Maybe& operator=(const Maybe& other) noexcept { ptr = other.ptr; return *this; } + + inline bool operator==(decltype(nullptr)) const { return ptr == nullptr; } + inline bool operator!=(decltype(nullptr)) const { return ptr != nullptr; } + + T& orDefault(T& defaultValue) { + if (ptr == nullptr) { + return defaultValue; + } else { + return *ptr; + } + } + const T& orDefault(const T& defaultValue) const { + if (ptr == nullptr) { + return defaultValue; + } else { + return *ptr; + } + } + + template + auto map(Func&& f) -> Maybe()))> { + if (ptr == nullptr) { + return nullptr; + } else { + return f(*ptr); + } + } + +private: + T* ptr; + + template + friend class Maybe; + template + friend U* _::readMaybe(Maybe&& maybe); + template + friend U* _::readMaybe(const Maybe& maybe); +}; + +// ======================================================================================= +// ArrayPtr +// +// So common that we put it in common.h rather than array.h. + +template +class ArrayPtr: public DisallowConstCopyIfNotConst { + // A pointer to an array. Includes a size. Like any pointer, it doesn't own the target data, + // and passing by value only copies the pointer, not the target. + +public: + inline constexpr ArrayPtr(): ptr(nullptr), size_(0) {} + inline constexpr ArrayPtr(decltype(nullptr)): ptr(nullptr), size_(0) {} + inline constexpr ArrayPtr(T* ptr, size_t size): ptr(ptr), size_(size) {} + inline constexpr ArrayPtr(T* begin, T* end): ptr(begin), size_(end - begin) {} + inline KJ_CONSTEXPR() ArrayPtr(::std::initializer_list> init) + : ptr(init.begin()), size_(init.size()) {} + + template + inline constexpr ArrayPtr(T (&native)[size]): ptr(native), size_(size) {} + // Construct an ArrayPtr from a native C-style array. + + inline operator ArrayPtr() const { + return ArrayPtr(ptr, size_); + } + inline ArrayPtr asConst() const { + return ArrayPtr(ptr, size_); + } + + inline size_t size() const { return size_; } + inline const T& operator[](size_t index) const { + KJ_IREQUIRE(index < size_, "Out-of-bounds ArrayPtr access."); + return ptr[index]; + } + inline T& operator[](size_t index) { + KJ_IREQUIRE(index < size_, "Out-of-bounds ArrayPtr access."); + return ptr[index]; + } + + inline T* begin() { return ptr; } + inline T* end() { return ptr + size_; } + inline T& front() { return *ptr; } + inline T& back() { return *(ptr + size_ - 1); } + inline const T* begin() const { return ptr; } + inline const T* end() const { return ptr + size_; } + inline const T& front() const { return *ptr; } + inline const T& back() const { return *(ptr + size_ - 1); } + + inline ArrayPtr slice(size_t start, size_t end) const { + KJ_IREQUIRE(start <= end && end <= size_, "Out-of-bounds ArrayPtr::slice()."); + return ArrayPtr(ptr + start, end - start); + } + inline ArrayPtr slice(size_t start, size_t end) { + KJ_IREQUIRE(start <= end && end <= size_, "Out-of-bounds ArrayPtr::slice()."); + return ArrayPtr(ptr + start, end - start); + } + + inline ArrayPtr> asBytes() const { + // Reinterpret the array as a byte array. This is explicitly legal under C++ aliasing + // rules. + return { reinterpret_cast*>(ptr), size_ * sizeof(T) }; + } + inline ArrayPtr> asChars() const { + // Reinterpret the array as a char array. This is explicitly legal under C++ aliasing + // rules. + return { reinterpret_cast*>(ptr), size_ * sizeof(T) }; + } + + inline bool operator==(decltype(nullptr)) const { return size_ == 0; } + inline bool operator!=(decltype(nullptr)) const { return size_ != 0; } + + inline bool operator==(const ArrayPtr& other) const { + if (size_ != other.size_) return false; + for (size_t i = 0; i < size_; i++) { + if (ptr[i] != other[i]) return false; + } + return true; + } + inline bool operator!=(const ArrayPtr& other) const { return !(*this == other); } + +private: + T* ptr; + size_t size_; +}; + +template +inline constexpr ArrayPtr arrayPtr(T* ptr, size_t size) { + // Use this function to construct ArrayPtrs without writing out the type name. + return ArrayPtr(ptr, size); +} + +template +inline constexpr ArrayPtr arrayPtr(T* begin, T* end) { + // Use this function to construct ArrayPtrs without writing out the type name. + return ArrayPtr(begin, end); +} + +// ======================================================================================= +// Casts + +template +To implicitCast(From&& from) { + // `implicitCast(value)` casts `value` to type `T` only if the conversion is implicit. Useful + // for e.g. resolving ambiguous overloads without sacrificing type-safety. + return kj::fwd(from); +} + +template +Maybe dynamicDowncastIfAvailable(From& from) { + // If RTTI is disabled, always returns nullptr. Otherwise, works like dynamic_cast. Useful + // in situations where dynamic_cast could allow an optimization, but isn't strictly necessary + // for correctness. It is highly recommended that you try to arrange all your dynamic_casts + // this way, as a dynamic_cast that is necessary for correctness implies a flaw in the interface + // design. + + // Force a compile error if To is not a subtype of From. Cross-casting is rare; if it is needed + // we should have a separate cast function like dynamicCrosscastIfAvailable(). + if (false) { + kj::implicitCast(kj::implicitCast(nullptr)); + } + +#if KJ_NO_RTTI + return nullptr; +#else + return dynamic_cast(&from); +#endif +} + +template +To& downcast(From& from) { + // Down-cast a value to a sub-type, asserting that the cast is valid. In opt mode this is a + // static_cast, but in debug mode (when RTTI is enabled) a dynamic_cast will be used to verify + // that the value really has the requested type. + + // Force a compile error if To is not a subtype of From. + if (false) { + kj::implicitCast(kj::implicitCast(nullptr)); + } + +#if !KJ_NO_RTTI + KJ_IREQUIRE(dynamic_cast(&from) != nullptr, "Value cannot be downcast() to requested type."); +#endif + + return static_cast(from); +} + +// ======================================================================================= +// Defer + +namespace _ { // private + +template +class Deferred { +public: + inline Deferred(Func&& func): func(kj::fwd(func)), canceled(false) {} + inline ~Deferred() noexcept(false) { if (!canceled) func(); } + KJ_DISALLOW_COPY(Deferred); + + // This move constructor is usually optimized away by the compiler. + inline Deferred(Deferred&& other): func(kj::mv(other.func)), canceled(false) { + other.canceled = true; + } +private: + Func func; + bool canceled; +}; + +} // namespace _ (private) + +template +_::Deferred defer(Func&& func) { + // Returns an object which will invoke the given functor in its destructor. The object is not + // copyable but is movable with the semantics you'd expect. Since the return type is private, + // you need to assign to an `auto` variable. + // + // The KJ_DEFER macro provides slightly more convenient syntax for the common case where you + // want some code to run at current scope exit. + + return _::Deferred(kj::fwd(func)); +} + +#define KJ_DEFER(code) auto KJ_UNIQUE_NAME(_kjDefer) = ::kj::defer([&](){code;}) +// Run the given code when the function exits, whether by return or exception. + +} // namespace kj + +#endif // KJ_COMMON_H_ diff --git a/phonelibs/capnp-cpp/include/kj/compat/gtest.h b/phonelibs/capnp-cpp/include/kj/compat/gtest.h new file mode 100644 index 00000000000000..016dbdfac322ee --- /dev/null +++ b/phonelibs/capnp-cpp/include/kj/compat/gtest.h @@ -0,0 +1,122 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef KJ_COMPAT_GTEST_H_ +#define KJ_COMPAT_GTEST_H_ +// This file defines compatibility macros converting Google Test tests into KJ tests. +// +// This is only intended to cover the most common functionality. Many tests will likely need +// additional tweaks. For instance: +// - Using operator<< to print information on failure is not supported. Instead, switch to +// KJ_ASSERT/KJ_EXPECT and pass in stuff to print as additional parameters. +// - Test fixtures are not supported. Allocate your "test fixture" on the stack instead. Do setup +// in the constructor, teardown in the destructor. + +#include "../test.h" + +namespace kj { + +namespace _ { // private + +template +T abs(T value) { return value < 0 ? -value : value; } + +inline bool floatAlmostEqual(float a, float b) { + return a == b || abs(a - b) < (abs(a) + abs(b)) * 1e-5; +} + +inline bool doubleAlmostEqual(double a, double b) { + return a == b || abs(a - b) < (abs(a) + abs(b)) * 1e-12; +} + +} // namespace _ (private) + +#define EXPECT_FALSE(x) KJ_EXPECT(!(x)) +#define EXPECT_TRUE(x) KJ_EXPECT(x) +#define EXPECT_EQ(x, y) KJ_EXPECT((x) == (y), x, y) +#define EXPECT_NE(x, y) KJ_EXPECT((x) != (y), x, y) +#define EXPECT_LE(x, y) KJ_EXPECT((x) <= (y), x, y) +#define EXPECT_GE(x, y) KJ_EXPECT((x) >= (y), x, y) +#define EXPECT_LT(x, y) KJ_EXPECT((x) < (y), x, y) +#define EXPECT_GT(x, y) KJ_EXPECT((x) > (y), x, y) +#define EXPECT_STREQ(x, y) KJ_EXPECT(::strcmp(x, y) == 0, x, y) +#define EXPECT_FLOAT_EQ(x, y) KJ_EXPECT(::kj::_::floatAlmostEqual(y, x), y, x); +#define EXPECT_DOUBLE_EQ(x, y) KJ_EXPECT(::kj::_::doubleAlmostEqual(y, x), y, x); + +#define ASSERT_FALSE(x) KJ_ASSERT(!(x)) +#define ASSERT_TRUE(x) KJ_ASSERT(x) +#define ASSERT_EQ(x, y) KJ_ASSERT((x) == (y), x, y) +#define ASSERT_NE(x, y) KJ_ASSERT((x) != (y), x, y) +#define ASSERT_LE(x, y) KJ_ASSERT((x) <= (y), x, y) +#define ASSERT_GE(x, y) KJ_ASSERT((x) >= (y), x, y) +#define ASSERT_LT(x, y) KJ_ASSERT((x) < (y), x, y) +#define ASSERT_GT(x, y) KJ_ASSERT((x) > (y), x, y) +#define ASSERT_STREQ(x, y) KJ_ASSERT(::strcmp(x, y) == 0, x, y) +#define ASSERT_FLOAT_EQ(x, y) KJ_ASSERT(::kj::_::floatAlmostEqual(y, x), y, x); +#define ASSERT_DOUBLE_EQ(x, y) KJ_ASSERT(::kj::_::doubleAlmostEqual(y, x), y, x); + +class AddFailureAdapter { +public: + AddFailureAdapter(const char* file, int line): file(file), line(line) {} + + ~AddFailureAdapter() { + if (!handled) { + _::Debug::log(file, line, LogSeverity::ERROR, "expectation failed"); + } + } + + template + void operator<<(T&& info) { + handled = true; + _::Debug::log(file, line, LogSeverity::ERROR, "\"expectation failed\", info", + "expectation failed", kj::fwd(info)); + } + +private: + bool handled = false; + const char* file; + int line; +}; + +#define ADD_FAILURE() ::kj::AddFailureAdapter(__FILE__, __LINE__) + +#if KJ_NO_EXCEPTIONS +#define EXPECT_ANY_THROW(code) \ + KJ_EXPECT(::kj::_::expectFatalThrow(nullptr, nullptr, [&]() { code; })) +#else +#define EXPECT_ANY_THROW(code) \ + KJ_EXPECT(::kj::runCatchingExceptions([&]() { code; }) != nullptr) +#endif + +#define EXPECT_NONFATAL_FAILURE(code) \ + EXPECT_TRUE(kj::runCatchingExceptions([&]() { code; }) != nullptr); + +#ifdef KJ_DEBUG +#define EXPECT_DEBUG_ANY_THROW EXPECT_ANY_THROW +#else +#define EXPECT_DEBUG_ANY_THROW(EXP) +#endif + +#define TEST(x, y) KJ_TEST("legacy test: " #x "/" #y) + +} // namespace kj + +#endif // KJ_COMPAT_GTEST_H_ diff --git a/phonelibs/capnp-cpp/include/kj/compat/http.h b/phonelibs/capnp-cpp/include/kj/compat/http.h new file mode 100644 index 00000000000000..8d455cc2588543 --- /dev/null +++ b/phonelibs/capnp-cpp/include/kj/compat/http.h @@ -0,0 +1,636 @@ +// Copyright (c) 2017 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef KJ_COMPAT_HTTP_H_ +#define KJ_COMPAT_HTTP_H_ +// The KJ HTTP client/server library. +// +// This is a simple library which can be used to implement an HTTP client or server. Properties +// of this library include: +// - Uses KJ async framework. +// - Agnostic to transport layer -- you can provide your own. +// - Header parsing is zero-copy -- it results in strings that point directly into the buffer +// received off the wire. +// - Application code which reads and writes headers refers to headers by symbolic names, not by +// string literals, with lookups being array-index-based, not map-based. To make this possible, +// the application announces what headers it cares about in advance, in order to assign numeric +// values to them. +// - Methods are identified by an enum. + +#include +#include +#include +#include +#include + +namespace kj { + +#define KJ_HTTP_FOR_EACH_METHOD(MACRO) \ + MACRO(GET) \ + MACRO(HEAD) \ + MACRO(POST) \ + MACRO(PUT) \ + MACRO(DELETE) \ + MACRO(PATCH) \ + MACRO(PURGE) \ + MACRO(OPTIONS) \ + MACRO(TRACE) \ + /* standard methods */ \ + /* */ \ + /* (CONNECT is intentionally omitted since it is handled specially in HttpHandler) */ \ + \ + MACRO(COPY) \ + MACRO(LOCK) \ + MACRO(MKCOL) \ + MACRO(MOVE) \ + MACRO(PROPFIND) \ + MACRO(PROPPATCH) \ + MACRO(SEARCH) \ + MACRO(UNLOCK) \ + /* WebDAV */ \ + \ + MACRO(REPORT) \ + MACRO(MKACTIVITY) \ + MACRO(CHECKOUT) \ + MACRO(MERGE) \ + /* Subversion */ \ + \ + MACRO(MSEARCH) \ + MACRO(NOTIFY) \ + MACRO(SUBSCRIBE) \ + MACRO(UNSUBSCRIBE) + /* UPnP */ + +#define KJ_HTTP_FOR_EACH_CONNECTION_HEADER(MACRO) \ + MACRO(connection, "Connection") \ + MACRO(contentLength, "Content-Length") \ + MACRO(keepAlive, "Keep-Alive") \ + MACRO(te, "TE") \ + MACRO(trailer, "Trailer") \ + MACRO(transferEncoding, "Transfer-Encoding") \ + MACRO(upgrade, "Upgrade") + +enum class HttpMethod { + // Enum of known HTTP methods. + // + // We use an enum rather than a string to allow for faster parsing and switching and to reduce + // ambiguity. + +#define DECLARE_METHOD(id) id, +KJ_HTTP_FOR_EACH_METHOD(DECLARE_METHOD) +#undef DECLARE_METHOD +}; + +kj::StringPtr KJ_STRINGIFY(HttpMethod method); +kj::Maybe tryParseHttpMethod(kj::StringPtr name); + +class HttpHeaderTable; + +class HttpHeaderId { + // Identifies an HTTP header by numeric ID that indexes into an HttpHeaderTable. + // + // The KJ HTTP API prefers that headers be identified by these IDs for a few reasons: + // - Integer lookups are much more efficient than string lookups. + // - Case-insensitivity is awkward to deal with when const strings are being passed to the lookup + // method. + // - Writing out strings less often means fewer typos. + // + // See HttpHeaderTable for usage hints. + +public: + HttpHeaderId() = default; + + inline bool operator==(const HttpHeaderId& other) const { return id == other.id; } + inline bool operator!=(const HttpHeaderId& other) const { return id != other.id; } + inline bool operator< (const HttpHeaderId& other) const { return id < other.id; } + inline bool operator> (const HttpHeaderId& other) const { return id > other.id; } + inline bool operator<=(const HttpHeaderId& other) const { return id <= other.id; } + inline bool operator>=(const HttpHeaderId& other) const { return id >= other.id; } + + inline size_t hashCode() const { return id; } + + kj::StringPtr toString() const; + + void requireFrom(HttpHeaderTable& table) const; + // In debug mode, throws an exception if the HttpHeaderId is not from the given table. + // + // In opt mode, no-op. + +#define KJ_HTTP_FOR_EACH_BUILTIN_HEADER(MACRO) \ + MACRO(HOST, "Host") \ + MACRO(DATE, "Date") \ + MACRO(LOCATION, "Location") \ + MACRO(CONTENT_TYPE, "Content-Type") + // For convenience, these very-common headers are valid for all HttpHeaderTables. You can refer + // to them like: + // + // HttpHeaderId::HOST + // + // TODO(0.7): Fill this out with more common headers. + +#define DECLARE_HEADER(id, name) \ + static const HttpHeaderId id; + // Declare a constant for each builtin header, e.g.: HttpHeaderId::CONNECTION + + KJ_HTTP_FOR_EACH_BUILTIN_HEADER(DECLARE_HEADER); +#undef DECLARE_HEADER + +private: + HttpHeaderTable* table; + uint id; + + inline explicit constexpr HttpHeaderId(HttpHeaderTable* table, uint id): table(table), id(id) {} + friend class HttpHeaderTable; + friend class HttpHeaders; +}; + +class HttpHeaderTable { + // Construct an HttpHeaderTable to declare which headers you'll be interested in later on, and + // to manufacture IDs for them. + // + // Example: + // + // // Build a header table with the headers we are interested in. + // kj::HttpHeaderTable::Builder builder; + // const HttpHeaderId accept = builder.add("Accept"); + // const HttpHeaderId contentType = builder.add("Content-Type"); + // kj::HttpHeaderTable table(kj::mv(builder)); + // + // // Create an HTTP client. + // auto client = kj::newHttpClient(table, network); + // + // // Get http://example.com. + // HttpHeaders headers(table); + // headers.set(accept, "text/html"); + // auto response = client->send(kj::HttpMethod::GET, "http://example.com", headers) + // .wait(waitScope); + // auto msg = kj::str("Response content type: ", response.headers.get(contentType)); + + struct IdsByNameMap; + +public: + HttpHeaderTable(); + // Constructs a table that only contains the builtin headers. + + class Builder { + public: + Builder(); + HttpHeaderId add(kj::StringPtr name); + Own build(); + + HttpHeaderTable& getFutureTable(); + // Get the still-unbuilt header table. You cannot actually use it until build() has been + // called. + // + // This method exists to help when building a shared header table -- the Builder may be passed + // to several components, each of which will register the headers they need and get a reference + // to the future table. + + private: + kj::Own table; + }; + + KJ_DISALLOW_COPY(HttpHeaderTable); // Can't copy because HttpHeaderId points to the table. + ~HttpHeaderTable() noexcept(false); + + uint idCount(); + // Return the number of IDs in the table. + + kj::Maybe stringToId(kj::StringPtr name); + // Try to find an ID for the given name. The matching is case-insensitive, per the HTTP spec. + // + // Note: if `name` contains characters that aren't allowed in HTTP header names, this may return + // a bogus value rather than null, due to optimizations used in case-insensitive matching. + + kj::StringPtr idToString(HttpHeaderId id); + // Get the canonical string name for the given ID. + +private: + kj::Vector namesById; + kj::Own idsByName; +}; + +class HttpHeaders { + // Represents a set of HTTP headers. + // + // This class guards against basic HTTP header injection attacks: Trying to set a header name or + // value containing a newline, carriage return, or other invalid character will throw an + // exception. + +public: + explicit HttpHeaders(HttpHeaderTable& table); + + KJ_DISALLOW_COPY(HttpHeaders); + HttpHeaders(HttpHeaders&&) = default; + HttpHeaders& operator=(HttpHeaders&&) = default; + + void clear(); + // Clears all contents, as if the object was freshly-allocated. However, calling this rather + // than actually re-allocating the object may avoid re-allocation of internal objects. + + HttpHeaders clone() const; + // Creates a deep clone of the HttpHeaders. The returned object owns all strings it references. + + HttpHeaders cloneShallow() const; + // Creates a shallow clone of the HttpHeaders. The returned object references the same strings + // as the original, owning none of them. + + kj::Maybe get(HttpHeaderId id) const; + // Read a header. + + template + void forEach(Func&& func) const; + // Calls `func(name, value)` for each header in the set -- including headers that aren't mapped + // to IDs in the header table. Both inputs are of type kj::StringPtr. + + void set(HttpHeaderId id, kj::StringPtr value); + void set(HttpHeaderId id, kj::String&& value); + // Sets a header value, overwriting the existing value. + // + // The String&& version is equivalent to calling the other version followed by takeOwnership(). + // + // WARNING: It is the caller's responsibility to ensure that `value` remains valid until the + // HttpHeaders object is destroyed. This allows string literals to be passed without making a + // copy, but complicates the use of dynamic values. Hint: Consider using `takeOwnership()`. + + void add(kj::StringPtr name, kj::StringPtr value); + void add(kj::StringPtr name, kj::String&& value); + void add(kj::String&& name, kj::String&& value); + // Append a header. `name` will be looked up in the header table, but if it's not mapped, the + // header will be added to the list of unmapped headers. + // + // The String&& versions are equivalent to calling the other version followed by takeOwnership(). + // + // WARNING: It is the caller's responsibility to ensure that `name` and `value` remain valid + // until the HttpHeaders object is destroyed. This allows string literals to be passed without + // making a copy, but complicates the use of dynamic values. Hint: Consider using + // `takeOwnership()`. + + void unset(HttpHeaderId id); + // Removes a header. + // + // It's not possible to remove a header by string name because non-indexed headers would take + // O(n) time to remove. Instead, construct a new HttpHeaders object and copy contents. + + void takeOwnership(kj::String&& string); + void takeOwnership(kj::Array&& chars); + void takeOwnership(HttpHeaders&& otherHeaders); + // Takes overship of a string so that it lives until the HttpHeaders object is destroyed. Useful + // when you've passed a dynamic value to set() or add() or parse*(). + + struct ConnectionHeaders { + // These headers govern details of the specific HTTP connection or framing of the content. + // Hence, they are managed internally within the HTTP library, and never appear in an + // HttpHeaders structure. + +#define DECLARE_HEADER(id, name) \ + kj::StringPtr id; + KJ_HTTP_FOR_EACH_CONNECTION_HEADER(DECLARE_HEADER) +#undef DECLARE_HEADER + }; + + struct Request { + HttpMethod method; + kj::StringPtr url; + ConnectionHeaders connectionHeaders; + }; + struct Response { + uint statusCode; + kj::StringPtr statusText; + ConnectionHeaders connectionHeaders; + }; + + kj::Maybe tryParseRequest(kj::ArrayPtr content); + kj::Maybe tryParseResponse(kj::ArrayPtr content); + // Parse an HTTP header blob and add all the headers to this object. + // + // `content` should be all text from the start of the request to the first occurrance of two + // newlines in a row -- including the first of these two newlines, but excluding the second. + // + // The parse is performed with zero copies: The callee clobbers `content` with '\0' characters + // to split it into a bunch of shorter strings. The caller must keep `content` valid until the + // `HttpHeaders` is destroyed, or pass it to `takeOwnership()`. + + kj::String serializeRequest(HttpMethod method, kj::StringPtr url, + const ConnectionHeaders& connectionHeaders) const; + kj::String serializeResponse(uint statusCode, kj::StringPtr statusText, + const ConnectionHeaders& connectionHeaders) const; + // Serialize the headers as a complete request or response blob. The blob uses '\r\n' newlines + // and includes the double-newline to indicate the end of the headers. + + kj::String toString() const; + +private: + HttpHeaderTable* table; + + kj::Array indexedHeaders; + // Size is always table->idCount(). + + struct Header { + kj::StringPtr name; + kj::StringPtr value; + }; + kj::Vector

unindexedHeaders; + + kj::Vector> ownedStrings; + + kj::Maybe addNoCheck(kj::StringPtr name, kj::StringPtr value); + + kj::StringPtr cloneToOwn(kj::StringPtr str); + + kj::String serialize(kj::ArrayPtr word1, + kj::ArrayPtr word2, + kj::ArrayPtr word3, + const ConnectionHeaders& connectionHeaders) const; + + bool parseHeaders(char* ptr, char* end, ConnectionHeaders& connectionHeaders); + + // TODO(perf): Arguably we should store a map, but header sets are never very long + // TODO(perf): We could optimize for common headers by storing them directly as fields. We could + // also add direct accessors for those headers. +}; + +class WebSocket { +public: + WebSocket(kj::Own stream); + // Create a WebSocket wrapping the given I/O stream. + + kj::Promise send(kj::ArrayPtr message); + kj::Promise send(kj::ArrayPtr message); +}; + +class HttpClient { + // Interface to the client end of an HTTP connection. + // + // There are two kinds of clients: + // * Host clients are used when talking to a specific host. The `url` specified in a request + // is actually just a path. (A `Host` header is still required in all requests.) + // * Proxy clients are used when the target could be any arbitrary host on the internet. + // The `url` specified in a request is a full URL including protocol and hostname. + +public: + struct Response { + uint statusCode; + kj::StringPtr statusText; + const HttpHeaders* headers; + kj::Own body; + // `statusText` and `headers` remain valid until `body` is dropped. + }; + + struct Request { + kj::Own body; + // Write the request entity body to this stream, then drop it when done. + // + // May be null for GET and HEAD requests (which have no body) and requests that have + // Content-Length: 0. + + kj::Promise response; + // Promise for the eventual respnose. + }; + + virtual Request request(HttpMethod method, kj::StringPtr url, const HttpHeaders& headers, + kj::Maybe expectedBodySize = nullptr) = 0; + // Perform an HTTP request. + // + // `url` may be a full URL (with protocol and host) or it may be only the path part of the URL, + // depending on whether the client is a proxy client or a host client. + // + // `url` and `headers` need only remain valid until `request()` returns (they can be + // stack-allocated). + // + // `expectedBodySize`, if provided, must be exactly the number of bytes that will be written to + // the body. This will trigger use of the `Content-Length` connection header. Otherwise, + // `Transfer-Encoding: chunked` will be used. + + struct WebSocketResponse { + uint statusCode; + kj::StringPtr statusText; + const HttpHeaders* headers; + kj::OneOf, kj::Own> upstreamOrBody; + // `statusText` and `headers` remain valid until `upstreamOrBody` is dropped. + }; + virtual kj::Promise openWebSocket( + kj::StringPtr url, const HttpHeaders& headers, kj::Own downstream); + // Tries to open a WebSocket. Default implementation calls send() and never returns a WebSocket. + // + // `url` and `headers` are invalidated when the returned promise resolves. + + virtual kj::Promise> connect(kj::String host); + // Handles CONNECT requests. Only relevant for proxy clients. Default implementation throws + // UNIMPLEMENTED. +}; + +class HttpService { + // Interface which HTTP services should implement. + // + // This interface is functionally equivalent to HttpClient, but is intended for applications to + // implement rather than call. The ergonomics and performance of the method signatures are + // optimized for the serving end. + // + // As with clients, there are two kinds of services: + // * Host services are used when talking to a specific host. The `url` specified in a request + // is actually just a path. (A `Host` header is still required in all requests, and the service + // may in fact serve multiple origins via this header.) + // * Proxy services are used when the target could be any arbitrary host on the internet, i.e. to + // implement an HTTP proxy. The `url` specified in a request is a full URL including protocol + // and hostname. + +public: + class Response { + public: + virtual kj::Own send( + uint statusCode, kj::StringPtr statusText, const HttpHeaders& headers, + kj::Maybe expectedBodySize = nullptr) = 0; + // Begin the response. + // + // `statusText` and `headers` need only remain valid until send() returns (they can be + // stack-allocated). + }; + + virtual kj::Promise request( + HttpMethod method, kj::StringPtr url, const HttpHeaders& headers, + kj::AsyncInputStream& requestBody, Response& response) = 0; + // Perform an HTTP request. + // + // `url` may be a full URL (with protocol and host) or it may be only the path part of the URL, + // depending on whether the service is a proxy service or a host service. + // + // `url` and `headers` are invalidated on the first read from `requestBody` or when the returned + // promise resolves, whichever comes first. + + class WebSocketResponse: public Response { + public: + kj::Own startWebSocket( + uint statusCode, kj::StringPtr statusText, const HttpHeaders& headers, + WebSocket& upstream); + // Begin the response. + // + // `statusText` and `headers` need only remain valid until startWebSocket() returns (they can + // be stack-allocated). + }; + + virtual kj::Promise openWebSocket( + kj::StringPtr url, const HttpHeaders& headers, WebSocketResponse& response); + // Tries to open a WebSocket. Default implementation calls request() and never returns a + // WebSocket. + // + // `url` and `headers` are invalidated when the returned promise resolves. + + virtual kj::Promise> connect(kj::String host); + // Handles CONNECT requests. Only relevant for proxy services. Default implementation throws + // UNIMPLEMENTED. +}; + +kj::Own newHttpClient(HttpHeaderTable& responseHeaderTable, kj::Network& network, + kj::Maybe tlsNetwork = nullptr); +// Creates a proxy HttpClient that connects to hosts over the given network. +// +// `responseHeaderTable` is used when parsing HTTP responses. Requests can use any header table. +// +// `tlsNetwork` is required to support HTTPS destination URLs. Otherwise, only HTTP URLs can be +// fetched. + +kj::Own newHttpClient(HttpHeaderTable& responseHeaderTable, kj::AsyncIoStream& stream); +// Creates an HttpClient that speaks over the given pre-established connection. The client may +// be used as a proxy client or a host client depending on whether the peer is operating as +// a proxy. +// +// Note that since this client has only one stream to work with, it will try to pipeline all +// requests on this stream. If one request or response has an I/O failure, all subsequent requests +// fail as well. If the destination server chooses to close the connection after a response, +// subsequent requests will fail. If a response takes a long time, it blocks subsequent responses. +// If a WebSocket is opened successfully, all subsequent requests fail. + +kj::Own newHttpClient(HttpService& service); +kj::Own newHttpService(HttpClient& client); +// Adapts an HttpClient to an HttpService and vice versa. + +struct HttpServerSettings { + kj::Duration headerTimeout = 15 * kj::SECONDS; + // After initial connection open, or after receiving the first byte of a pipelined request, + // the client must send the complete request within this time. + + kj::Duration pipelineTimeout = 5 * kj::SECONDS; + // After one request/response completes, we'll wait up to this long for a pipelined request to + // arrive. +}; + +class HttpServer: private kj::TaskSet::ErrorHandler { + // Class which listens for requests on ports or connections and sends them to an HttpService. + +public: + typedef HttpServerSettings Settings; + + HttpServer(kj::Timer& timer, HttpHeaderTable& requestHeaderTable, HttpService& service, + Settings settings = Settings()); + // Set up an HttpServer that directs incoming connections to the given service. The service + // may be a host service or a proxy service depending on whether you are intending to implement + // an HTTP server or an HTTP proxy. + + kj::Promise drain(); + // Stop accepting new connections or new requests on existing connections. Finish any requests + // that are already executing, then close the connections. Returns once no more requests are + // in-flight. + + kj::Promise listenHttp(kj::ConnectionReceiver& port); + // Accepts HTTP connections on the given port and directs them to the handler. + // + // The returned promise never completes normally. It may throw if port.accept() throws. Dropping + // the returned promise will cause the server to stop listening on the port, but already-open + // connections will continue to be served. Destroy the whole HttpServer to cancel all I/O. + + kj::Promise listenHttp(kj::Own connection); + // Reads HTTP requests from the given connection and directs them to the handler. A successful + // completion of the promise indicates that all requests received on the connection resulted in + // a complete response, and the client closed the connection gracefully or drain() was called. + // The promise throws if an unparseable request is received or if some I/O error occurs. Dropping + // the returned promise will cancel all I/O on the connection and cancel any in-flight requests. + +private: + class Connection; + + kj::Timer& timer; + HttpHeaderTable& requestHeaderTable; + HttpService& service; + Settings settings; + + bool draining = false; + kj::ForkedPromise onDrain; + kj::Own> drainFulfiller; + + uint connectionCount = 0; + kj::Maybe>> zeroConnectionsFulfiller; + + kj::TaskSet tasks; + + HttpServer(kj::Timer& timer, HttpHeaderTable& requestHeaderTable, HttpService& service, + Settings settings, kj::PromiseFulfillerPair paf); + + kj::Promise listenLoop(kj::ConnectionReceiver& port); + + void taskFailed(kj::Exception&& exception) override; +}; + +// ======================================================================================= +// inline implementation + +inline void HttpHeaderId::requireFrom(HttpHeaderTable& table) const { + KJ_IREQUIRE(this->table == nullptr || this->table == &table, + "the provided HttpHeaderId is from the wrong HttpHeaderTable"); +} + +inline kj::Own HttpHeaderTable::Builder::build() { return kj::mv(table); } +inline HttpHeaderTable& HttpHeaderTable::Builder::getFutureTable() { return *table; } + +inline uint HttpHeaderTable::idCount() { return namesById.size(); } + +inline kj::StringPtr HttpHeaderTable::idToString(HttpHeaderId id) { + id.requireFrom(*this); + return namesById[id.id]; +} + +inline kj::Maybe HttpHeaders::get(HttpHeaderId id) const { + id.requireFrom(*table); + auto result = indexedHeaders[id.id]; + return result == nullptr ? kj::Maybe(nullptr) : result; +} + +inline void HttpHeaders::unset(HttpHeaderId id) { + id.requireFrom(*table); + indexedHeaders[id.id] = nullptr; +} + +template +inline void HttpHeaders::forEach(Func&& func) const { + for (auto i: kj::indices(indexedHeaders)) { + if (indexedHeaders[i] != nullptr) { + func(table->idToString(HttpHeaderId(table, i)), indexedHeaders[i]); + } + } + + for (auto& header: unindexedHeaders) { + func(header.name, header.value); + } +} + +} // namespace kj + +#endif // KJ_COMPAT_HTTP_H_ diff --git a/phonelibs/capnp-cpp/include/kj/debug.h b/phonelibs/capnp-cpp/include/kj/debug.h new file mode 100644 index 00000000000000..fff7f98bc02bb5 --- /dev/null +++ b/phonelibs/capnp-cpp/include/kj/debug.h @@ -0,0 +1,555 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +// This file declares convenient macros for debug logging and error handling. The macros make +// it excessively easy to extract useful context information from code. Example: +// +// KJ_ASSERT(a == b, a, b, "a and b must be the same."); +// +// On failure, this will throw an exception whose description looks like: +// +// myfile.c++:43: bug in code: expected a == b; a = 14; b = 72; a and b must be the same. +// +// As you can see, all arguments after the first provide additional context. +// +// The macros available are: +// +// * `KJ_LOG(severity, ...)`: Just writes a log message, to stderr by default (but you can +// intercept messages by implementing an ExceptionCallback). `severity` is `INFO`, `WARNING`, +// `ERROR`, or `FATAL`. By default, `INFO` logs are not written, but for command-line apps the +// user should be able to pass a flag like `--verbose` to enable them. Other log levels are +// enabled by default. Log messages -- like exceptions -- can be intercepted by registering an +// ExceptionCallback. +// +// * `KJ_DBG(...)`: Like `KJ_LOG`, but intended specifically for temporary log lines added while +// debugging a particular problem. Calls to `KJ_DBG` should always be deleted before committing +// code. It is suggested that you set up a pre-commit hook that checks for this. +// +// * `KJ_ASSERT(condition, ...)`: Throws an exception if `condition` is false, or aborts if +// exceptions are disabled. This macro should be used to check for bugs in the surrounding code +// and its dependencies, but NOT to check for invalid input. The macro may be followed by a +// brace-delimited code block; if so, the block will be executed in the case where the assertion +// fails, before throwing the exception. If control jumps out of the block (e.g. with "break", +// "return", or "goto"), then the error is considered "recoverable" -- in this case, if +// exceptions are disabled, execution will continue normally rather than aborting (but if +// exceptions are enabled, an exception will still be thrown on exiting the block). A "break" +// statement in particular will jump to the code immediately after the block (it does not break +// any surrounding loop or switch). Example: +// +// KJ_ASSERT(value >= 0, "Value cannot be negative.", value) { +// // Assertion failed. Set value to zero to "recover". +// value = 0; +// // Don't abort if exceptions are disabled. Continue normally. +// // (Still throw an exception if they are enabled, though.) +// break; +// } +// // When exceptions are disabled, we'll get here even if the assertion fails. +// // Otherwise, we get here only if the assertion passes. +// +// * `KJ_REQUIRE(condition, ...)`: Like `KJ_ASSERT` but used to check preconditions -- e.g. to +// validate parameters passed from a caller. A failure indicates that the caller is buggy. +// +// * `KJ_SYSCALL(code, ...)`: Executes `code` assuming it makes a system call. A negative result +// is considered an error, with error code reported via `errno`. EINTR is handled by retrying. +// Other errors are handled by throwing an exception. If you need to examine the return code, +// assign it to a variable like so: +// +// int fd; +// KJ_SYSCALL(fd = open(filename, O_RDONLY), filename); +// +// `KJ_SYSCALL` can be followed by a recovery block, just like `KJ_ASSERT`. +// +// * `KJ_NONBLOCKING_SYSCALL(code, ...)`: Like KJ_SYSCALL, but will not throw an exception on +// EAGAIN/EWOULDBLOCK. The calling code should check the syscall's return value to see if it +// indicates an error; in this case, it can assume the error was EAGAIN because any other error +// would have caused an exception to be thrown. +// +// * `KJ_CONTEXT(...)`: Notes additional contextual information relevant to any exceptions thrown +// from within the current scope. That is, until control exits the block in which KJ_CONTEXT() +// is used, if any exception is generated, it will contain the given information in its context +// chain. This is helpful because it can otherwise be very difficult to come up with error +// messages that make sense within low-level helper code. Note that the parameters to +// KJ_CONTEXT() are only evaluated if an exception is thrown. This implies that any variables +// used must remain valid until the end of the scope. +// +// Notes: +// * Do not write expressions with side-effects in the message content part of the macro, as the +// message will not necessarily be evaluated. +// * For every macro `FOO` above except `LOG`, there is also a `FAIL_FOO` macro used to report +// failures that already happened. For the macros that check a boolean condition, `FAIL_FOO` +// omits the first parameter and behaves like it was `false`. `FAIL_SYSCALL` and +// `FAIL_RECOVERABLE_SYSCALL` take a string and an OS error number as the first two parameters. +// The string should be the name of the failed system call. +// * For every macro `FOO` above, there is a `DFOO` version (or `RECOVERABLE_DFOO`) which is only +// executed in debug mode, i.e. when KJ_DEBUG is defined. KJ_DEBUG is defined automatically +// by common.h when compiling without optimization (unless NDEBUG is defined), but you can also +// define it explicitly (e.g. -DKJ_DEBUG). Generally, production builds should NOT use KJ_DEBUG +// as it may enable expensive checks that are unlikely to fail. + +#ifndef KJ_DEBUG_H_ +#define KJ_DEBUG_H_ + +#if defined(__GNUC__) && !KJ_HEADER_WARNINGS +#pragma GCC system_header +#endif + +#include "string.h" +#include "exception.h" + +#ifdef ERROR +// This is problematic because windows.h #defines ERROR, which we use in an enum here. +#error "Make sure to to undefine ERROR (or just #include ) before this file" +#endif + +namespace kj { + +#if _MSC_VER +// MSVC does __VA_ARGS__ differently from GCC: +// - A trailing comma before an empty __VA_ARGS__ is removed automatically, whereas GCC wants +// you to request this behavior with "##__VA_ARGS__". +// - If __VA_ARGS__ is passed directly as an argument to another macro, it will be treated as a +// *single* argument rather than an argument list. This can be worked around by wrapping the +// outer macro call in KJ_EXPAND(), which appraently forces __VA_ARGS__ to be expanded before +// the macro is evaluated. I don't understand the C preprocessor. +// - Using "#__VA_ARGS__" to stringify __VA_ARGS__ expands to zero tokens when __VA_ARGS__ is +// empty, rather than expanding to an empty string literal. We can work around by concatenating +// with an empty string literal. + +#define KJ_EXPAND(X) X + +#define KJ_LOG(severity, ...) \ + if (!::kj::_::Debug::shouldLog(::kj::LogSeverity::severity)) {} else \ + ::kj::_::Debug::log(__FILE__, __LINE__, ::kj::LogSeverity::severity, \ + "" #__VA_ARGS__, __VA_ARGS__) + +#define KJ_DBG(...) KJ_EXPAND(KJ_LOG(DBG, __VA_ARGS__)) + +#define KJ_REQUIRE(cond, ...) \ + if (KJ_LIKELY(cond)) {} else \ + for (::kj::_::Debug::Fault f(__FILE__, __LINE__, ::kj::Exception::Type::FAILED, \ + #cond, "" #__VA_ARGS__, __VA_ARGS__);; f.fatal()) + +#define KJ_FAIL_REQUIRE(...) \ + for (::kj::_::Debug::Fault f(__FILE__, __LINE__, ::kj::Exception::Type::FAILED, \ + nullptr, "" #__VA_ARGS__, __VA_ARGS__);; f.fatal()) + +#define KJ_SYSCALL(call, ...) \ + if (auto _kjSyscallResult = ::kj::_::Debug::syscall([&](){return (call);}, false)) {} else \ + for (::kj::_::Debug::Fault f(__FILE__, __LINE__, \ + _kjSyscallResult.getErrorNumber(), #call, "" #__VA_ARGS__, __VA_ARGS__);; f.fatal()) + +#define KJ_NONBLOCKING_SYSCALL(call, ...) \ + if (auto _kjSyscallResult = ::kj::_::Debug::syscall([&](){return (call);}, true)) {} else \ + for (::kj::_::Debug::Fault f(__FILE__, __LINE__, \ + _kjSyscallResult.getErrorNumber(), #call, "" #__VA_ARGS__, __VA_ARGS__);; f.fatal()) + +#define KJ_FAIL_SYSCALL(code, errorNumber, ...) \ + for (::kj::_::Debug::Fault f(__FILE__, __LINE__, \ + errorNumber, code, "" #__VA_ARGS__, __VA_ARGS__);; f.fatal()) + +#if _WIN32 + +#define KJ_WIN32(call, ...) \ + if (::kj::_::Debug::isWin32Success(call)) {} else \ + for (::kj::_::Debug::Fault f(__FILE__, __LINE__, \ + ::kj::_::Debug::getWin32Error(), #call, "" #__VA_ARGS__, __VA_ARGS__);; f.fatal()) + +#define KJ_WINSOCK(call, ...) \ + if ((call) != SOCKET_ERROR) {} else \ + for (::kj::_::Debug::Fault f(__FILE__, __LINE__, \ + ::kj::_::Debug::getWin32Error(), #call, "" #__VA_ARGS__, __VA_ARGS__);; f.fatal()) + +#define KJ_FAIL_WIN32(code, errorNumber, ...) \ + for (::kj::_::Debug::Fault f(__FILE__, __LINE__, \ + ::kj::_::Debug::Win32Error(errorNumber), code, "" #__VA_ARGS__, __VA_ARGS__);; f.fatal()) + +#endif + +#define KJ_UNIMPLEMENTED(...) \ + for (::kj::_::Debug::Fault f(__FILE__, __LINE__, ::kj::Exception::Type::UNIMPLEMENTED, \ + nullptr, "" #__VA_ARGS__, __VA_ARGS__);; f.fatal()) + +// TODO(msvc): MSVC mis-deduces `ContextImpl` as `ContextImpl` in some edge +// cases, such as inside nested lambdas inside member functions. Wrapping the type in +// `decltype(instance<...>())` helps it deduce the context function's type correctly. +#define KJ_CONTEXT(...) \ + auto KJ_UNIQUE_NAME(_kjContextFunc) = [&]() -> ::kj::_::Debug::Context::Value { \ + return ::kj::_::Debug::Context::Value(__FILE__, __LINE__, \ + ::kj::_::Debug::makeDescription("" #__VA_ARGS__, __VA_ARGS__)); \ + }; \ + decltype(::kj::instance<::kj::_::Debug::ContextImpl>()) \ + KJ_UNIQUE_NAME(_kjContext)(KJ_UNIQUE_NAME(_kjContextFunc)) + +#define KJ_REQUIRE_NONNULL(value, ...) \ + (*[&] { \ + auto _kj_result = ::kj::_::readMaybe(value); \ + if (KJ_UNLIKELY(!_kj_result)) { \ + ::kj::_::Debug::Fault(__FILE__, __LINE__, ::kj::Exception::Type::FAILED, \ + #value " != nullptr", "" #__VA_ARGS__, __VA_ARGS__).fatal(); \ + } \ + return _kj_result; \ + }()) + +#define KJ_EXCEPTION(type, ...) \ + ::kj::Exception(::kj::Exception::Type::type, __FILE__, __LINE__, \ + ::kj::_::Debug::makeDescription("" #__VA_ARGS__, __VA_ARGS__)) + +#else + +#define KJ_LOG(severity, ...) \ + if (!::kj::_::Debug::shouldLog(::kj::LogSeverity::severity)) {} else \ + ::kj::_::Debug::log(__FILE__, __LINE__, ::kj::LogSeverity::severity, \ + #__VA_ARGS__, ##__VA_ARGS__) + +#define KJ_DBG(...) KJ_LOG(DBG, ##__VA_ARGS__) + +#define KJ_REQUIRE(cond, ...) \ + if (KJ_LIKELY(cond)) {} else \ + for (::kj::_::Debug::Fault f(__FILE__, __LINE__, ::kj::Exception::Type::FAILED, \ + #cond, #__VA_ARGS__, ##__VA_ARGS__);; f.fatal()) + +#define KJ_FAIL_REQUIRE(...) \ + for (::kj::_::Debug::Fault f(__FILE__, __LINE__, ::kj::Exception::Type::FAILED, \ + nullptr, #__VA_ARGS__, ##__VA_ARGS__);; f.fatal()) + +#define KJ_SYSCALL(call, ...) \ + if (auto _kjSyscallResult = ::kj::_::Debug::syscall([&](){return (call);}, false)) {} else \ + for (::kj::_::Debug::Fault f(__FILE__, __LINE__, \ + _kjSyscallResult.getErrorNumber(), #call, #__VA_ARGS__, ##__VA_ARGS__);; f.fatal()) + +#define KJ_NONBLOCKING_SYSCALL(call, ...) \ + if (auto _kjSyscallResult = ::kj::_::Debug::syscall([&](){return (call);}, true)) {} else \ + for (::kj::_::Debug::Fault f(__FILE__, __LINE__, \ + _kjSyscallResult.getErrorNumber(), #call, #__VA_ARGS__, ##__VA_ARGS__);; f.fatal()) + +#define KJ_FAIL_SYSCALL(code, errorNumber, ...) \ + for (::kj::_::Debug::Fault f(__FILE__, __LINE__, \ + errorNumber, code, #__VA_ARGS__, ##__VA_ARGS__);; f.fatal()) + +#if _WIN32 + +#define KJ_WIN32(call, ...) \ + if (::kj::_::Debug::isWin32Success(call)) {} else \ + for (::kj::_::Debug::Fault f(__FILE__, __LINE__, \ + ::kj::_::Debug::getWin32Error(), #call, #__VA_ARGS__, ##__VA_ARGS__);; f.fatal()) + +#define KJ_WINSOCK(call, ...) \ + if ((call) != SOCKET_ERROR) {} else \ + for (::kj::_::Debug::Fault f(__FILE__, __LINE__, \ + ::kj::_::Debug::getWin32Error(), #call, #__VA_ARGS__, ##__VA_ARGS__);; f.fatal()) + +#define KJ_FAIL_WIN32(code, errorNumber, ...) \ + for (::kj::_::Debug::Fault f(__FILE__, __LINE__, \ + ::kj::_::Debug::Win32Error(errorNumber), code, #__VA_ARGS__, ##__VA_ARGS__);; f.fatal()) + +#endif + +#define KJ_UNIMPLEMENTED(...) \ + for (::kj::_::Debug::Fault f(__FILE__, __LINE__, ::kj::Exception::Type::UNIMPLEMENTED, \ + nullptr, #__VA_ARGS__, ##__VA_ARGS__);; f.fatal()) + +#define KJ_CONTEXT(...) \ + auto KJ_UNIQUE_NAME(_kjContextFunc) = [&]() -> ::kj::_::Debug::Context::Value { \ + return ::kj::_::Debug::Context::Value(__FILE__, __LINE__, \ + ::kj::_::Debug::makeDescription(#__VA_ARGS__, ##__VA_ARGS__)); \ + }; \ + ::kj::_::Debug::ContextImpl \ + KJ_UNIQUE_NAME(_kjContext)(KJ_UNIQUE_NAME(_kjContextFunc)) + +#define KJ_REQUIRE_NONNULL(value, ...) \ + (*({ \ + auto _kj_result = ::kj::_::readMaybe(value); \ + if (KJ_UNLIKELY(!_kj_result)) { \ + ::kj::_::Debug::Fault(__FILE__, __LINE__, ::kj::Exception::Type::FAILED, \ + #value " != nullptr", #__VA_ARGS__, ##__VA_ARGS__).fatal(); \ + } \ + kj::mv(_kj_result); \ + })) + +#define KJ_EXCEPTION(type, ...) \ + ::kj::Exception(::kj::Exception::Type::type, __FILE__, __LINE__, \ + ::kj::_::Debug::makeDescription(#__VA_ARGS__, ##__VA_ARGS__)) + +#endif + +#define KJ_SYSCALL_HANDLE_ERRORS(call) \ + if (int _kjSyscallError = ::kj::_::Debug::syscallError([&](){return (call);}, false)) \ + switch (int error = _kjSyscallError) +// Like KJ_SYSCALL, but doesn't throw. Instead, the block after the macro is a switch block on the +// error. Additionally, the int value `error` is defined within the block. So you can do: +// +// KJ_SYSCALL_HANDLE_ERRORS(foo()) { +// case ENOENT: +// handleNoSuchFile(); +// break; +// case EEXIST: +// handleExists(); +// break; +// default: +// KJ_FAIL_SYSCALL("foo()", error); +// } else { +// handleSuccessCase(); +// } + +#define KJ_ASSERT KJ_REQUIRE +#define KJ_FAIL_ASSERT KJ_FAIL_REQUIRE +#define KJ_ASSERT_NONNULL KJ_REQUIRE_NONNULL +// Use "ASSERT" in place of "REQUIRE" when the problem is local to the immediate surrounding code. +// That is, if the assert ever fails, it indicates that the immediate surrounding code is broken. + +#ifdef KJ_DEBUG +#define KJ_DLOG KJ_LOG +#define KJ_DASSERT KJ_ASSERT +#define KJ_DREQUIRE KJ_REQUIRE +#else +#define KJ_DLOG(...) do {} while (false) +#define KJ_DASSERT(...) do {} while (false) +#define KJ_DREQUIRE(...) do {} while (false) +#endif + +namespace _ { // private + +class Debug { +public: + Debug() = delete; + + typedef LogSeverity Severity; // backwards-compatibility + +#if _WIN32 + struct Win32Error { + // Hack for overloading purposes. + uint number; + inline explicit Win32Error(uint number): number(number) {} + }; +#endif + + static inline bool shouldLog(LogSeverity severity) { return severity >= minSeverity; } + // Returns whether messages of the given severity should be logged. + + static inline void setLogLevel(LogSeverity severity) { minSeverity = severity; } + // Set the minimum message severity which will be logged. + // + // TODO(someday): Expose publicly. + + template + static void log(const char* file, int line, LogSeverity severity, const char* macroArgs, + Params&&... params); + + class Fault { + public: + template + Fault(const char* file, int line, Code code, + const char* condition, const char* macroArgs, Params&&... params); + Fault(const char* file, int line, Exception::Type type, + const char* condition, const char* macroArgs); + Fault(const char* file, int line, int osErrorNumber, + const char* condition, const char* macroArgs); +#if _WIN32 + Fault(const char* file, int line, Win32Error osErrorNumber, + const char* condition, const char* macroArgs); +#endif + ~Fault() noexcept(false); + + KJ_NOINLINE KJ_NORETURN(void fatal()); + // Throw the exception. + + private: + void init(const char* file, int line, Exception::Type type, + const char* condition, const char* macroArgs, ArrayPtr argValues); + void init(const char* file, int line, int osErrorNumber, + const char* condition, const char* macroArgs, ArrayPtr argValues); +#if _WIN32 + void init(const char* file, int line, Win32Error osErrorNumber, + const char* condition, const char* macroArgs, ArrayPtr argValues); +#endif + + Exception* exception; + }; + + class SyscallResult { + public: + inline SyscallResult(int errorNumber): errorNumber(errorNumber) {} + inline operator void*() { return errorNumber == 0 ? this : nullptr; } + inline int getErrorNumber() { return errorNumber; } + + private: + int errorNumber; + }; + + template + static SyscallResult syscall(Call&& call, bool nonblocking); + template + static int syscallError(Call&& call, bool nonblocking); + +#if _WIN32 + static bool isWin32Success(int boolean); + static bool isWin32Success(void* handle); + static Win32Error getWin32Error(); +#endif + + class Context: public ExceptionCallback { + public: + Context(); + KJ_DISALLOW_COPY(Context); + virtual ~Context() noexcept(false); + + struct Value { + const char* file; + int line; + String description; + + inline Value(const char* file, int line, String&& description) + : file(file), line(line), description(mv(description)) {} + }; + + virtual Value evaluate() = 0; + + virtual void onRecoverableException(Exception&& exception) override; + virtual void onFatalException(Exception&& exception) override; + virtual void logMessage(LogSeverity severity, const char* file, int line, int contextDepth, + String&& text) override; + + private: + bool logged; + Maybe value; + + Value ensureInitialized(); + }; + + template + class ContextImpl: public Context { + public: + inline ContextImpl(Func& func): func(func) {} + KJ_DISALLOW_COPY(ContextImpl); + + Value evaluate() override { + return func(); + } + private: + Func& func; + }; + + template + static String makeDescription(const char* macroArgs, Params&&... params); + +private: + static LogSeverity minSeverity; + + static void logInternal(const char* file, int line, LogSeverity severity, const char* macroArgs, + ArrayPtr argValues); + static String makeDescriptionInternal(const char* macroArgs, ArrayPtr argValues); + + static int getOsErrorNumber(bool nonblocking); + // Get the error code of the last error (e.g. from errno). Returns -1 on EINTR. +}; + +template +void Debug::log(const char* file, int line, LogSeverity severity, const char* macroArgs, + Params&&... params) { + String argValues[sizeof...(Params)] = {str(params)...}; + logInternal(file, line, severity, macroArgs, arrayPtr(argValues, sizeof...(Params))); +} + +template <> +inline void Debug::log<>(const char* file, int line, LogSeverity severity, const char* macroArgs) { + logInternal(file, line, severity, macroArgs, nullptr); +} + +template +Debug::Fault::Fault(const char* file, int line, Code code, + const char* condition, const char* macroArgs, Params&&... params) + : exception(nullptr) { + String argValues[sizeof...(Params)] = {str(params)...}; + init(file, line, code, condition, macroArgs, + arrayPtr(argValues, sizeof...(Params))); +} + +inline Debug::Fault::Fault(const char* file, int line, int osErrorNumber, + const char* condition, const char* macroArgs) + : exception(nullptr) { + init(file, line, osErrorNumber, condition, macroArgs, nullptr); +} + +inline Debug::Fault::Fault(const char* file, int line, kj::Exception::Type type, + const char* condition, const char* macroArgs) + : exception(nullptr) { + init(file, line, type, condition, macroArgs, nullptr); +} + +#if _WIN32 +inline Debug::Fault::Fault(const char* file, int line, Win32Error osErrorNumber, + const char* condition, const char* macroArgs) + : exception(nullptr) { + init(file, line, osErrorNumber, condition, macroArgs, nullptr); +} + +inline bool Debug::isWin32Success(int boolean) { + return boolean; +} +inline bool Debug::isWin32Success(void* handle) { + // Assume null and INVALID_HANDLE_VALUE mean failure. + return handle != nullptr && handle != (void*)-1; +} +#endif + +template +Debug::SyscallResult Debug::syscall(Call&& call, bool nonblocking) { + while (call() < 0) { + int errorNum = getOsErrorNumber(nonblocking); + // getOsErrorNumber() returns -1 to indicate EINTR. + // Also, if nonblocking is true, then it returns 0 on EAGAIN, which will then be treated as a + // non-error. + if (errorNum != -1) { + return SyscallResult(errorNum); + } + } + return SyscallResult(0); +} + +template +int Debug::syscallError(Call&& call, bool nonblocking) { + while (call() < 0) { + int errorNum = getOsErrorNumber(nonblocking); + // getOsErrorNumber() returns -1 to indicate EINTR. + // Also, if nonblocking is true, then it returns 0 on EAGAIN, which will then be treated as a + // non-error. + if (errorNum != -1) { + return errorNum; + } + } + return 0; +} + +template +String Debug::makeDescription(const char* macroArgs, Params&&... params) { + String argValues[sizeof...(Params)] = {str(params)...}; + return makeDescriptionInternal(macroArgs, arrayPtr(argValues, sizeof...(Params))); +} + +template <> +inline String Debug::makeDescription<>(const char* macroArgs) { + return makeDescriptionInternal(macroArgs, nullptr); +} + +} // namespace _ (private) +} // namespace kj + +#endif // KJ_DEBUG_H_ diff --git a/phonelibs/capnp-cpp/include/kj/exception.h b/phonelibs/capnp-cpp/include/kj/exception.h new file mode 100644 index 00000000000000..f6c0b2daa61eeb --- /dev/null +++ b/phonelibs/capnp-cpp/include/kj/exception.h @@ -0,0 +1,363 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef KJ_EXCEPTION_H_ +#define KJ_EXCEPTION_H_ + +#if defined(__GNUC__) && !KJ_HEADER_WARNINGS +#pragma GCC system_header +#endif + +#include "memory.h" +#include "array.h" +#include "string.h" + +namespace kj { + +class ExceptionImpl; + +class Exception { + // Exception thrown in case of fatal errors. + // + // Actually, a subclass of this which also implements std::exception will be thrown, but we hide + // that fact from the interface to avoid #including . + +public: + enum class Type { + // What kind of failure? + + FAILED = 0, + // Something went wrong. This is the usual error type. KJ_ASSERT and KJ_REQUIRE throw this + // error type. + + OVERLOADED = 1, + // The call failed because of a temporary lack of resources. This could be space resources + // (out of memory, out of disk space) or time resources (request queue overflow, operation + // timed out). + // + // The operation might work if tried again, but it should NOT be repeated immediately as this + // may simply exacerbate the problem. + + DISCONNECTED = 2, + // The call required communication over a connection that has been lost. The callee will need + // to re-establish connections and try again. + + UNIMPLEMENTED = 3 + // The requested method is not implemented. The caller may wish to revert to a fallback + // approach based on other methods. + + // IF YOU ADD A NEW VALUE: + // - Update the stringifier. + // - Update Cap'n Proto's RPC protocol's Exception.Type enum. + }; + + Exception(Type type, const char* file, int line, String description = nullptr) noexcept; + Exception(Type type, String file, int line, String description = nullptr) noexcept; + Exception(const Exception& other) noexcept; + Exception(Exception&& other) = default; + ~Exception() noexcept; + + const char* getFile() const { return file; } + int getLine() const { return line; } + Type getType() const { return type; } + StringPtr getDescription() const { return description; } + ArrayPtr getStackTrace() const { return arrayPtr(trace, traceCount); } + + struct Context { + // Describes a bit about what was going on when the exception was thrown. + + const char* file; + int line; + String description; + Maybe> next; + + Context(const char* file, int line, String&& description, Maybe>&& next) + : file(file), line(line), description(mv(description)), next(mv(next)) {} + Context(const Context& other) noexcept; + }; + + inline Maybe getContext() const { + KJ_IF_MAYBE(c, context) { + return **c; + } else { + return nullptr; + } + } + + void wrapContext(const char* file, int line, String&& description); + // Wraps the context in a new node. This becomes the head node returned by getContext() -- it + // is expected that contexts will be added in reverse order as the exception passes up the + // callback stack. + + KJ_NOINLINE void extendTrace(uint ignoreCount); + // Append the current stack trace to the exception's trace, ignoring the first `ignoreCount` + // frames (see `getStackTrace()` for discussion of `ignoreCount`). + + KJ_NOINLINE void truncateCommonTrace(); + // Remove the part of the stack trace which the exception shares with the caller of this method. + // This is used by the async library to remove the async infrastructure from the stack trace + // before replacing it with the async trace. + + void addTrace(void* ptr); + // Append the given pointer to the backtrace, if it is not already full. This is used by the + // async library to trace through the promise chain that led to the exception. + +private: + String ownFile; + const char* file; + int line; + Type type; + String description; + Maybe> context; + void* trace[32]; + uint traceCount; + + friend class ExceptionImpl; +}; + +StringPtr KJ_STRINGIFY(Exception::Type type); +String KJ_STRINGIFY(const Exception& e); + +// ======================================================================================= + +enum class LogSeverity { + INFO, // Information describing what the code is up to, which users may request to see + // with a flag like `--verbose`. Does not indicate a problem. Not printed by + // default; you must call setLogLevel(INFO) to enable. + WARNING, // A problem was detected but execution can continue with correct output. + ERROR, // Something is wrong, but execution can continue with garbage output. + FATAL, // Something went wrong, and execution cannot continue. + DBG // Temporary debug logging. See KJ_DBG. + + // Make sure to update the stringifier if you add a new severity level. +}; + +StringPtr KJ_STRINGIFY(LogSeverity severity); + +class ExceptionCallback { + // If you don't like C++ exceptions, you may implement and register an ExceptionCallback in order + // to perform your own exception handling. For example, a reasonable thing to do is to have + // onRecoverableException() set a flag indicating that an error occurred, and then check for that + // flag just before writing to storage and/or returning results to the user. If the flag is set, + // discard whatever you have and return an error instead. + // + // ExceptionCallbacks must always be allocated on the stack. When an exception is thrown, the + // newest ExceptionCallback on the calling thread's stack is called. The default implementation + // of each method calls the next-oldest ExceptionCallback for that thread. Thus the callbacks + // behave a lot like try/catch blocks, except that they are called before any stack unwinding + // occurs. + +public: + ExceptionCallback(); + KJ_DISALLOW_COPY(ExceptionCallback); + virtual ~ExceptionCallback() noexcept(false); + + virtual void onRecoverableException(Exception&& exception); + // Called when an exception has been raised, but the calling code has the ability to continue by + // producing garbage output. This method _should_ throw the exception, but is allowed to simply + // return if garbage output is acceptable. + // + // The global default implementation throws an exception unless the library was compiled with + // -fno-exceptions, in which case it logs an error and returns. + + virtual void onFatalException(Exception&& exception); + // Called when an exception has been raised and the calling code cannot continue. If this method + // returns normally, abort() will be called. The method must throw the exception to avoid + // aborting. + // + // The global default implementation throws an exception unless the library was compiled with + // -fno-exceptions, in which case it logs an error and returns. + + virtual void logMessage(LogSeverity severity, const char* file, int line, int contextDepth, + String&& text); + // Called when something wants to log some debug text. `contextDepth` indicates how many levels + // of context the message passed through; it may make sense to indent the message accordingly. + // + // The global default implementation writes the text to stderr. + + enum class StackTraceMode { + FULL, + // Stringifying a stack trace will attempt to determine source file and line numbers. This may + // be expensive. For example, on Linux, this shells out to `addr2line`. + // + // This is the default in debug builds. + + ADDRESS_ONLY, + // Stringifying a stack trace will only generate a list of code addresses. + // + // This is the default in release builds. + + NONE + // Generating a stack trace will always return an empty array. + // + // This avoids ever unwinding the stack. On Windows in particular, the stack unwinding library + // has been observed to be pretty slow, so exception-heavy code might benefit significantly + // from this setting. (But exceptions should be rare...) + }; + + virtual StackTraceMode stackTraceMode(); + // Returns the current preferred stack trace mode. + +protected: + ExceptionCallback& next; + +private: + ExceptionCallback(ExceptionCallback& next); + + class RootExceptionCallback; + friend ExceptionCallback& getExceptionCallback(); +}; + +ExceptionCallback& getExceptionCallback(); +// Returns the current exception callback. + +KJ_NOINLINE KJ_NORETURN(void throwFatalException(kj::Exception&& exception, uint ignoreCount = 0)); +// Invoke the exception callback to throw the given fatal exception. If the exception callback +// returns, abort. + +KJ_NOINLINE void throwRecoverableException(kj::Exception&& exception, uint ignoreCount = 0); +// Invoke the exception callback to throw the given recoverable exception. If the exception +// callback returns, return normally. + +// ======================================================================================= + +namespace _ { class Runnable; } + +template +Maybe runCatchingExceptions(Func&& func) noexcept; +// Executes the given function (usually, a lambda returning nothing) catching any exceptions that +// are thrown. Returns the Exception if there was one, or null if the operation completed normally. +// Non-KJ exceptions will be wrapped. +// +// If exception are disabled (e.g. with -fno-exceptions), this will still detect whether any +// recoverable exceptions occurred while running the function and will return those. + +class UnwindDetector { + // Utility for detecting when a destructor is called due to unwind. Useful for: + // - Avoiding throwing exceptions in this case, which would terminate the program. + // - Detecting whether to commit or roll back a transaction. + // + // To use this class, either inherit privately from it or declare it as a member. The detector + // works by comparing the exception state against that when the constructor was called, so for + // an object that was actually constructed during exception unwind, it will behave as if no + // unwind is taking place. This is usually the desired behavior. + +public: + UnwindDetector(); + + bool isUnwinding() const; + // Returns true if the current thread is in a stack unwind that it wasn't in at the time the + // object was constructed. + + template + void catchExceptionsIfUnwinding(Func&& func) const; + // Runs the given function (e.g., a lambda). If isUnwinding() is true, any exceptions are + // caught and treated as secondary faults, meaning they are considered to be side-effects of the + // exception that is unwinding the stack. Otherwise, exceptions are passed through normally. + +private: + uint uncaughtCount; + + void catchExceptionsAsSecondaryFaults(_::Runnable& runnable) const; +}; + +namespace _ { // private + +class Runnable { +public: + virtual void run() = 0; +}; + +template +class RunnableImpl: public Runnable { +public: + RunnableImpl(Func&& func): func(kj::mv(func)) {} + void run() override { + func(); + } +private: + Func func; +}; + +Maybe runCatchingExceptions(Runnable& runnable) noexcept; + +} // namespace _ (private) + +template +Maybe runCatchingExceptions(Func&& func) noexcept { + _::RunnableImpl> runnable(kj::fwd(func)); + return _::runCatchingExceptions(runnable); +} + +template +void UnwindDetector::catchExceptionsIfUnwinding(Func&& func) const { + if (isUnwinding()) { + _::RunnableImpl> runnable(kj::fwd(func)); + catchExceptionsAsSecondaryFaults(runnable); + } else { + func(); + } +} + +#define KJ_ON_SCOPE_SUCCESS(code) \ + ::kj::UnwindDetector KJ_UNIQUE_NAME(_kjUnwindDetector); \ + KJ_DEFER(if (!KJ_UNIQUE_NAME(_kjUnwindDetector).isUnwinding()) { code; }) +// Runs `code` if the current scope is exited normally (not due to an exception). + +#define KJ_ON_SCOPE_FAILURE(code) \ + ::kj::UnwindDetector KJ_UNIQUE_NAME(_kjUnwindDetector); \ + KJ_DEFER(if (KJ_UNIQUE_NAME(_kjUnwindDetector).isUnwinding()) { code; }) +// Runs `code` if the current scope is exited due to an exception. + +// ======================================================================================= + +KJ_NOINLINE ArrayPtr getStackTrace(ArrayPtr space, uint ignoreCount); +// Attempt to get the current stack trace, returning a list of pointers to instructions. The +// returned array is a slice of `space`. Provide a larger `space` to get a deeper stack trace. +// If the platform doesn't support stack traces, returns an empty array. +// +// `ignoreCount` items will be truncated from the front of the trace. This is useful for chopping +// off a prefix of the trace that is uninteresting to the developer because it's just locations +// inside the debug infrastructure that is requesting the trace. Be careful to mark functions as +// KJ_NOINLINE if you intend to count them in `ignoreCount`. Note that, unfortunately, the +// ignored entries will still waste space in the `space` array (and the returned array's `begin()` +// is never exactly equal to `space.begin()` due to this effect, even if `ignoreCount` is zero +// since `getStackTrace()` needs to ignore its own internal frames). + +String stringifyStackTrace(ArrayPtr); +// Convert the stack trace to a string with file names and line numbers. This may involve executing +// suprocesses. + +String getStackTrace(); +// Get a stack trace right now and stringify it. Useful for debugging. + +void printStackTraceOnCrash(); +// Registers signal handlers on common "crash" signals like SIGSEGV that will (attempt to) print +// a stack trace. You should call this as early as possible on program startup. Programs using +// KJ_MAIN get this automatically. + +kj::StringPtr trimSourceFilename(kj::StringPtr filename); +// Given a source code file name, trim off noisy prefixes like "src/" or +// "/ekam-provider/canonical/". + +} // namespace kj + +#endif // KJ_EXCEPTION_H_ diff --git a/phonelibs/capnp-cpp/include/kj/function.h b/phonelibs/capnp-cpp/include/kj/function.h new file mode 100644 index 00000000000000..ba6601b560cd8e --- /dev/null +++ b/phonelibs/capnp-cpp/include/kj/function.h @@ -0,0 +1,277 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef KJ_FUNCTION_H_ +#define KJ_FUNCTION_H_ + +#if defined(__GNUC__) && !KJ_HEADER_WARNINGS +#pragma GCC system_header +#endif + +#include "memory.h" + +namespace kj { + +template +class Function; +// Function wrapper using virtual-based polymorphism. Use this when template polymorphism is +// not possible. You can, for example, accept a Function as a parameter: +// +// void setFilter(Function filter); +// +// The caller of `setFilter()` may then pass any callable object as the parameter. The callable +// object does not have to have the exact signature specified, just one that is "compatible" -- +// i.e. the return type is covariant and the parameters are contravariant. +// +// Unlike `std::function`, `kj::Function`s are movable but not copyable, just like `kj::Own`. This +// is to avoid unexpected heap allocation or slow atomic reference counting. +// +// When a `Function` is constructed from an lvalue, it captures only a reference to the value. +// When constructed from an rvalue, it invokes the value's move constructor. So, for example: +// +// struct AddN { +// int n; +// int operator(int i) { return i + n; } +// } +// +// Function f1 = AddN{2}; +// // f1 owns an instance of AddN. It may safely be moved out +// // of the local scope. +// +// AddN adder(2); +// Function f2 = adder; +// // f2 contains a reference to `adder`. Thus, it becomes invalid +// // when `adder` goes out-of-scope. +// +// AddN adder2(2); +// Function f3 = kj::mv(adder2); +// // f3 owns an insatnce of AddN moved from `adder2`. f3 may safely +// // be moved out of the local scope. +// +// Additionally, a Function may be bound to a class method using KJ_BIND_METHOD(object, methodName). +// For example: +// +// class Printer { +// public: +// void print(int i); +// void print(kj::StringPtr s); +// }; +// +// Printer p; +// +// Function intPrinter = KJ_BIND_METHOD(p, print); +// // Will call Printer::print(int). +// +// Function strPrinter = KJ_BIND_METHOD(p, print); +// // Will call Printer::print(kj::StringPtr). +// +// Notice how KJ_BIND_METHOD is able to figure out which overload to use depending on the kind of +// Function it is binding to. + +template +class ConstFunction; +// Like Function, but wraps a "const" (i.e. thread-safe) call. + +template +class Function { +public: + template + inline Function(F&& f): impl(heap>(kj::fwd(f))) {} + Function() = default; + + // Make sure people don't accidentally end up wrapping a reference when they meant to return + // a function. + KJ_DISALLOW_COPY(Function); + Function(Function&) = delete; + Function& operator=(Function&) = delete; + template Function(const Function&) = delete; + template Function& operator=(const Function&) = delete; + template Function(const ConstFunction&) = delete; + template Function& operator=(const ConstFunction&) = delete; + Function(Function&&) = default; + Function& operator=(Function&&) = default; + + inline Return operator()(Params... params) { + return (*impl)(kj::fwd(params)...); + } + + Function reference() { + // Forms a new Function of the same type that delegates to this Function by reference. + // Therefore, this Function must outlive the returned Function, but otherwise they behave + // exactly the same. + + return *impl; + } + +private: + class Iface { + public: + virtual Return operator()(Params... params) = 0; + }; + + template + class Impl final: public Iface { + public: + explicit Impl(F&& f): f(kj::fwd(f)) {} + + Return operator()(Params... params) override { + return f(kj::fwd(params)...); + } + + private: + F f; + }; + + Own impl; +}; + +template +class ConstFunction { +public: + template + inline ConstFunction(F&& f): impl(heap>(kj::fwd(f))) {} + ConstFunction() = default; + + // Make sure people don't accidentally end up wrapping a reference when they meant to return + // a function. + KJ_DISALLOW_COPY(ConstFunction); + ConstFunction(ConstFunction&) = delete; + ConstFunction& operator=(ConstFunction&) = delete; + template ConstFunction(const ConstFunction&) = delete; + template ConstFunction& operator=(const ConstFunction&) = delete; + template ConstFunction(const Function&) = delete; + template ConstFunction& operator=(const Function&) = delete; + ConstFunction(ConstFunction&&) = default; + ConstFunction& operator=(ConstFunction&&) = default; + + inline Return operator()(Params... params) const { + return (*impl)(kj::fwd(params)...); + } + + ConstFunction reference() const { + // Forms a new ConstFunction of the same type that delegates to this ConstFunction by reference. + // Therefore, this ConstFunction must outlive the returned ConstFunction, but otherwise they + // behave exactly the same. + + return *impl; + } + +private: + class Iface { + public: + virtual Return operator()(Params... params) const = 0; + }; + + template + class Impl final: public Iface { + public: + explicit Impl(F&& f): f(kj::fwd(f)) {} + + Return operator()(Params... params) const override { + return f(kj::fwd(params)...); + } + + private: + F f; + }; + + Own impl; +}; + +#if 1 + +namespace _ { // private + +template +class BoundMethod; + +template ::*method)(Params...)> +class BoundMethod::*)(Params...), method> { +public: + BoundMethod(T&& t): t(kj::fwd(t)) {} + + Return operator()(Params&&... params) { + return (t.*method)(kj::fwd(params)...); + } + +private: + T t; +}; + +template ::*method)(Params...) const> +class BoundMethod::*)(Params...) const, method> { +public: + BoundMethod(T&& t): t(kj::fwd(t)) {} + + Return operator()(Params&&... params) const { + return (t.*method)(kj::fwd(params)...); + } + +private: + T t; +}; + +} // namespace _ (private) + +#define KJ_BIND_METHOD(obj, method) \ + ::kj::_::BoundMethod::method), \ + &::kj::Decay::method>(obj) +// Macro that produces a functor object which forwards to the method `obj.name`. If `obj` is an +// lvalue, the functor will hold a reference to it. If `obj` is an rvalue, the functor will +// contain a copy (by move) of it. +// +// The current implementation requires that the method is not overloaded. +// +// TODO(someday): C++14's generic lambdas may be able to simplify this code considerably, and +// probably make it work with overloaded methods. + +#else +// Here's a better implementation of the above that doesn't work with GCC (but does with Clang) +// because it uses a local class with a template method. Sigh. This implementation supports +// overloaded methods. + +#define KJ_BIND_METHOD(obj, method) \ + ({ \ + typedef KJ_DECLTYPE_REF(obj) T; \ + class F { \ + public: \ + inline F(T&& t): t(::kj::fwd(t)) {} \ + template \ + auto operator()(Params&&... params) \ + -> decltype(::kj::instance().method(::kj::fwd(params)...)) { \ + return t.method(::kj::fwd(params)...); \ + } \ + private: \ + T t; \ + }; \ + (F(obj)); \ + }) +// Macro that produces a functor object which forwards to the method `obj.name`. If `obj` is an +// lvalue, the functor will hold a reference to it. If `obj` is an rvalue, the functor will +// contain a copy (by move) of it. + +#endif + +} // namespace kj + +#endif // KJ_FUNCTION_H_ diff --git a/phonelibs/capnp-cpp/include/kj/io.h b/phonelibs/capnp-cpp/include/kj/io.h new file mode 100644 index 00000000000000..f5c03bfe7b8a39 --- /dev/null +++ b/phonelibs/capnp-cpp/include/kj/io.h @@ -0,0 +1,419 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef KJ_IO_H_ +#define KJ_IO_H_ + +#if defined(__GNUC__) && !KJ_HEADER_WARNINGS +#pragma GCC system_header +#endif + +#include +#include "common.h" +#include "array.h" +#include "exception.h" + +namespace kj { + +// ======================================================================================= +// Abstract interfaces + +class InputStream { +public: + virtual ~InputStream() noexcept(false); + + size_t read(void* buffer, size_t minBytes, size_t maxBytes); + // Reads at least minBytes and at most maxBytes, copying them into the given buffer. Returns + // the size read. Throws an exception on errors. Implemented in terms of tryRead(). + // + // maxBytes is the number of bytes the caller really wants, but minBytes is the minimum amount + // needed by the caller before it can start doing useful processing. If the stream returns less + // than maxBytes, the caller will usually call read() again later to get the rest. Returning + // less than maxBytes is useful when it makes sense for the caller to parallelize processing + // with I/O. + // + // Never blocks if minBytes is zero. If minBytes is zero and maxBytes is non-zero, this may + // attempt a non-blocking read or may just return zero. To force a read, use a non-zero minBytes. + // To detect EOF without throwing an exception, use tryRead(). + // + // If the InputStream can't produce minBytes, it MUST throw an exception, as the caller is not + // expected to understand how to deal with partial reads. + + virtual size_t tryRead(void* buffer, size_t minBytes, size_t maxBytes) = 0; + // Like read(), but may return fewer than minBytes on EOF. + + inline void read(void* buffer, size_t bytes) { read(buffer, bytes, bytes); } + // Convenience method for reading an exact number of bytes. + + virtual void skip(size_t bytes); + // Skips past the given number of bytes, discarding them. The default implementation read()s + // into a scratch buffer. +}; + +class OutputStream { +public: + virtual ~OutputStream() noexcept(false); + + virtual void write(const void* buffer, size_t size) = 0; + // Always writes the full size. Throws exception on error. + + virtual void write(ArrayPtr> pieces); + // Equivalent to write()ing each byte array in sequence, which is what the default implementation + // does. Override if you can do something better, e.g. use writev() to do the write in a single + // syscall. +}; + +class BufferedInputStream: public InputStream { + // An input stream which buffers some bytes in memory to reduce system call overhead. + // - OR - + // An input stream that actually reads from some in-memory data structure and wants to give its + // caller a direct pointer to that memory to potentially avoid a copy. + +public: + virtual ~BufferedInputStream() noexcept(false); + + ArrayPtr getReadBuffer(); + // Get a direct pointer into the read buffer, which contains the next bytes in the input. If the + // caller consumes any bytes, it should then call skip() to indicate this. This always returns a + // non-empty buffer or throws an exception. Implemented in terms of tryGetReadBuffer(). + + virtual ArrayPtr tryGetReadBuffer() = 0; + // Like getReadBuffer() but may return an empty buffer on EOF. +}; + +class BufferedOutputStream: public OutputStream { + // An output stream which buffers some bytes in memory to reduce system call overhead. + // - OR - + // An output stream that actually writes into some in-memory data structure and wants to give its + // caller a direct pointer to that memory to potentially avoid a copy. + +public: + virtual ~BufferedOutputStream() noexcept(false); + + virtual ArrayPtr getWriteBuffer() = 0; + // Get a direct pointer into the write buffer. The caller may choose to fill in some prefix of + // this buffer and then pass it to write(), in which case write() may avoid a copy. It is + // incorrect to pass to write any slice of this buffer which is not a prefix. +}; + +// ======================================================================================= +// Buffered streams implemented as wrappers around regular streams + +class BufferedInputStreamWrapper: public BufferedInputStream { + // Implements BufferedInputStream in terms of an InputStream. + // + // Note that the underlying stream's position is unpredictable once the wrapper is destroyed, + // unless the entire stream was consumed. To read a predictable number of bytes in a buffered + // way without going over, you'd need this wrapper to wrap some other wrapper which itself + // implements an artificial EOF at the desired point. Such a stream should be trivial to write + // but is not provided by the library at this time. + +public: + explicit BufferedInputStreamWrapper(InputStream& inner, ArrayPtr buffer = nullptr); + // Creates a buffered stream wrapping the given non-buffered stream. No guarantee is made about + // the position of the inner stream after a buffered wrapper has been created unless the entire + // input is read. + // + // If the second parameter is non-null, the stream uses the given buffer instead of allocating + // its own. This may improve performance if the buffer can be reused. + + KJ_DISALLOW_COPY(BufferedInputStreamWrapper); + ~BufferedInputStreamWrapper() noexcept(false); + + // implements BufferedInputStream ---------------------------------- + ArrayPtr tryGetReadBuffer() override; + size_t tryRead(void* buffer, size_t minBytes, size_t maxBytes) override; + void skip(size_t bytes) override; + +private: + InputStream& inner; + Array ownedBuffer; + ArrayPtr buffer; + ArrayPtr bufferAvailable; +}; + +class BufferedOutputStreamWrapper: public BufferedOutputStream { + // Implements BufferedOutputStream in terms of an OutputStream. Note that writes to the + // underlying stream may be delayed until flush() is called or the wrapper is destroyed. + +public: + explicit BufferedOutputStreamWrapper(OutputStream& inner, ArrayPtr buffer = nullptr); + // Creates a buffered stream wrapping the given non-buffered stream. + // + // If the second parameter is non-null, the stream uses the given buffer instead of allocating + // its own. This may improve performance if the buffer can be reused. + + KJ_DISALLOW_COPY(BufferedOutputStreamWrapper); + ~BufferedOutputStreamWrapper() noexcept(false); + + void flush(); + // Force the wrapper to write any remaining bytes in its buffer to the inner stream. Note that + // this only flushes this object's buffer; this object has no idea how to flush any other buffers + // that may be present in the underlying stream. + + // implements BufferedOutputStream --------------------------------- + ArrayPtr getWriteBuffer() override; + void write(const void* buffer, size_t size) override; + +private: + OutputStream& inner; + Array ownedBuffer; + ArrayPtr buffer; + byte* bufferPos; + UnwindDetector unwindDetector; +}; + +// ======================================================================================= +// Array I/O + +class ArrayInputStream: public BufferedInputStream { +public: + explicit ArrayInputStream(ArrayPtr array); + KJ_DISALLOW_COPY(ArrayInputStream); + ~ArrayInputStream() noexcept(false); + + // implements BufferedInputStream ---------------------------------- + ArrayPtr tryGetReadBuffer() override; + size_t tryRead(void* buffer, size_t minBytes, size_t maxBytes) override; + void skip(size_t bytes) override; + +private: + ArrayPtr array; +}; + +class ArrayOutputStream: public BufferedOutputStream { +public: + explicit ArrayOutputStream(ArrayPtr array); + KJ_DISALLOW_COPY(ArrayOutputStream); + ~ArrayOutputStream() noexcept(false); + + ArrayPtr getArray() { + // Get the portion of the array which has been filled in. + return arrayPtr(array.begin(), fillPos); + } + + // implements BufferedInputStream ---------------------------------- + ArrayPtr getWriteBuffer() override; + void write(const void* buffer, size_t size) override; + +private: + ArrayPtr array; + byte* fillPos; +}; + +class VectorOutputStream: public BufferedOutputStream { +public: + explicit VectorOutputStream(size_t initialCapacity = 4096); + KJ_DISALLOW_COPY(VectorOutputStream); + ~VectorOutputStream() noexcept(false); + + ArrayPtr getArray() { + // Get the portion of the array which has been filled in. + return arrayPtr(vector.begin(), fillPos); + } + + // implements BufferedInputStream ---------------------------------- + ArrayPtr getWriteBuffer() override; + void write(const void* buffer, size_t size) override; + +private: + Array vector; + byte* fillPos; + + void grow(size_t minSize); +}; + +// ======================================================================================= +// File descriptor I/O + +class AutoCloseFd { + // A wrapper around a file descriptor which automatically closes the descriptor when destroyed. + // The wrapper supports move construction for transferring ownership of the descriptor. If + // close() returns an error, the destructor throws an exception, UNLESS the destructor is being + // called during unwind from another exception, in which case the close error is ignored. + // + // If your code is not exception-safe, you should not use AutoCloseFd. In this case you will + // have to call close() yourself and handle errors appropriately. + +public: + inline AutoCloseFd(): fd(-1) {} + inline AutoCloseFd(decltype(nullptr)): fd(-1) {} + inline explicit AutoCloseFd(int fd): fd(fd) {} + inline AutoCloseFd(AutoCloseFd&& other) noexcept: fd(other.fd) { other.fd = -1; } + KJ_DISALLOW_COPY(AutoCloseFd); + ~AutoCloseFd() noexcept(false); + + inline AutoCloseFd& operator=(AutoCloseFd&& other) { + AutoCloseFd old(kj::mv(*this)); + fd = other.fd; + other.fd = -1; + return *this; + } + + inline AutoCloseFd& operator=(decltype(nullptr)) { + AutoCloseFd old(kj::mv(*this)); + return *this; + } + + inline operator int() const { return fd; } + inline int get() const { return fd; } + + operator bool() const = delete; + // Deleting this operator prevents accidental use in boolean contexts, which + // the int conversion operator above would otherwise allow. + + inline bool operator==(decltype(nullptr)) { return fd < 0; } + inline bool operator!=(decltype(nullptr)) { return fd >= 0; } + +private: + int fd; + UnwindDetector unwindDetector; +}; + +inline auto KJ_STRINGIFY(const AutoCloseFd& fd) + -> decltype(kj::toCharSequence(implicitCast(fd))) { + return kj::toCharSequence(implicitCast(fd)); +} + +class FdInputStream: public InputStream { + // An InputStream wrapping a file descriptor. + +public: + explicit FdInputStream(int fd): fd(fd) {} + explicit FdInputStream(AutoCloseFd fd): fd(fd), autoclose(mv(fd)) {} + KJ_DISALLOW_COPY(FdInputStream); + ~FdInputStream() noexcept(false); + + size_t tryRead(void* buffer, size_t minBytes, size_t maxBytes) override; + + inline int getFd() const { return fd; } + +private: + int fd; + AutoCloseFd autoclose; +}; + +class FdOutputStream: public OutputStream { + // An OutputStream wrapping a file descriptor. + +public: + explicit FdOutputStream(int fd): fd(fd) {} + explicit FdOutputStream(AutoCloseFd fd): fd(fd), autoclose(mv(fd)) {} + KJ_DISALLOW_COPY(FdOutputStream); + ~FdOutputStream() noexcept(false); + + void write(const void* buffer, size_t size) override; + void write(ArrayPtr> pieces) override; + + inline int getFd() const { return fd; } + +private: + int fd; + AutoCloseFd autoclose; +}; + +// ======================================================================================= +// Win32 Handle I/O + +#ifdef _WIN32 + +class AutoCloseHandle { + // A wrapper around a Win32 HANDLE which automatically closes the handle when destroyed. + // The wrapper supports move construction for transferring ownership of the handle. If + // CloseHandle() returns an error, the destructor throws an exception, UNLESS the destructor is + // being called during unwind from another exception, in which case the close error is ignored. + // + // If your code is not exception-safe, you should not use AutoCloseHandle. In this case you will + // have to call close() yourself and handle errors appropriately. + +public: + inline AutoCloseHandle(): handle((void*)-1) {} + inline AutoCloseHandle(decltype(nullptr)): handle((void*)-1) {} + inline explicit AutoCloseHandle(void* handle): handle(handle) {} + inline AutoCloseHandle(AutoCloseHandle&& other) noexcept: handle(other.handle) { + other.handle = (void*)-1; + } + KJ_DISALLOW_COPY(AutoCloseHandle); + ~AutoCloseHandle() noexcept(false); + + inline AutoCloseHandle& operator=(AutoCloseHandle&& other) { + AutoCloseHandle old(kj::mv(*this)); + handle = other.handle; + other.handle = (void*)-1; + return *this; + } + + inline AutoCloseHandle& operator=(decltype(nullptr)) { + AutoCloseHandle old(kj::mv(*this)); + return *this; + } + + inline operator void*() const { return handle; } + inline void* get() const { return handle; } + + operator bool() const = delete; + // Deleting this operator prevents accidental use in boolean contexts, which + // the void* conversion operator above would otherwise allow. + + inline bool operator==(decltype(nullptr)) { return handle != (void*)-1; } + inline bool operator!=(decltype(nullptr)) { return handle == (void*)-1; } + +private: + void* handle; // -1 (aka INVALID_HANDLE_VALUE) if not valid. +}; + +class HandleInputStream: public InputStream { + // An InputStream wrapping a Win32 HANDLE. + +public: + explicit HandleInputStream(void* handle): handle(handle) {} + explicit HandleInputStream(AutoCloseHandle handle): handle(handle), autoclose(mv(handle)) {} + KJ_DISALLOW_COPY(HandleInputStream); + ~HandleInputStream() noexcept(false); + + size_t tryRead(void* buffer, size_t minBytes, size_t maxBytes) override; + +private: + void* handle; + AutoCloseHandle autoclose; +}; + +class HandleOutputStream: public OutputStream { + // An OutputStream wrapping a Win32 HANDLE. + +public: + explicit HandleOutputStream(void* handle): handle(handle) {} + explicit HandleOutputStream(AutoCloseHandle handle): handle(handle), autoclose(mv(handle)) {} + KJ_DISALLOW_COPY(HandleOutputStream); + ~HandleOutputStream() noexcept(false); + + void write(const void* buffer, size_t size) override; + +private: + void* handle; + AutoCloseHandle autoclose; +}; + +#endif // _WIN32 + +} // namespace kj + +#endif // KJ_IO_H_ diff --git a/phonelibs/capnp-cpp/include/kj/main.h b/phonelibs/capnp-cpp/include/kj/main.h new file mode 100644 index 00000000000000..4dcd804fd4d224 --- /dev/null +++ b/phonelibs/capnp-cpp/include/kj/main.h @@ -0,0 +1,407 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef KJ_MAIN_H_ +#define KJ_MAIN_H_ + +#if defined(__GNUC__) && !KJ_HEADER_WARNINGS +#pragma GCC system_header +#endif + +#include "array.h" +#include "string.h" +#include "vector.h" +#include "function.h" + +namespace kj { + +class ProcessContext { + // Context for command-line programs. + +public: + virtual StringPtr getProgramName() = 0; + // Get argv[0] as passed to main(). + + KJ_NORETURN(virtual void exit()) = 0; + // Indicates program completion. The program is considered successful unless `error()` was + // called. Typically this exits with _Exit(), meaning that the stack is not unwound, buffers + // are not flushed, etc. -- it is the responsibility of the caller to flush any buffers that + // matter. However, an alternate context implementation e.g. for unit testing purposes could + // choose to throw an exception instead. + // + // At first this approach may sound crazy. Isn't it much better to shut down cleanly? What if + // you lose data? However, it turns out that if you look at each common class of program, _Exit() + // is almost always preferable. Let's break it down: + // + // * Commands: A typical program you might run from the command line is single-threaded and + // exits quickly and deterministically. Commands often use buffered I/O and need to flush + // those buffers before exit. However, most of the work performed by destructors is not + // flushing buffers, but rather freeing up memory, placing objects into freelists, and closing + // file descriptors. All of this is irrelevant if the process is about to exit anyway, and + // for a command that runs quickly, time wasted freeing heap space may make a real difference + // in the overall runtime of a script. Meanwhile, it is usually easy to determine exactly what + // resources need to be flushed before exit, and easy to tell if they are not being flushed + // (because the command fails to produce the expected output). Therefore, it is reasonably + // easy for commands to explicitly ensure all output is flushed before exiting, and it is + // probably a good idea for them to do so anyway, because write failures should be detected + // and handled. For commands, a good strategy is to allocate any objects that require clean + // destruction on the stack, and allow them to go out of scope before the command exits. + // Meanwhile, any resources which do not need to be cleaned up should be allocated as members + // of the command's main class, whose destructor normally will not be called. + // + // * Interactive apps: Programs that interact with the user (whether they be graphical apps + // with windows or console-based apps like emacs) generally exit only when the user asks them + // to. Such applications may store large data structures in memory which need to be synced + // to disk, such as documents or user preferences. However, relying on stack unwind or global + // destructors as the mechanism for ensuring such syncing occurs is probably wrong. First of + // all, it's 2013, and applications ought to be actively syncing changes to non-volatile + // storage the moment those changes are made. Applications can crash at any time and a crash + // should never lose data that is more than half a second old. Meanwhile, if a user actually + // does try to close an application while unsaved changes exist, the application UI should + // prompt the user to decide what to do. Such a UI mechanism is obviously too high level to + // be implemented via destructors, so KJ's use of _Exit() shouldn't make a difference here. + // + // * Servers: A good server is fault-tolerant, prepared for the possibility that at any time + // it could crash, the OS could decide to kill it off, or the machine it is running on could + // just die. So, using _Exit() should be no problem. In fact, servers generally never even + // call exit anyway; they are killed externally. + // + // * Batch jobs: A long-running batch job is something between a command and a server. It + // probably knows exactly what needs to be flushed before exiting, and it probably should be + // fault-tolerant. + // + // Meanwhile, regardless of program type, if you are adhering to KJ style, then the use of + // _Exit() shouldn't be a problem anyway: + // + // * KJ style forbids global mutable state (singletons) in general and global constructors and + // destructors in particular. Therefore, everything that could possibly need cleanup either + // lives on the stack or is transitively owned by something living on the stack. + // + // * Calling exit() simply means "Don't clean up anything older than this stack frame.". If you + // have resources that require cleanup before exit, make sure they are owned by stack frames + // beyond the one that eventually calls exit(). To be as safe as possible, don't place any + // state in your program's main class, and don't call exit() yourself. Then, runMainAndExit() + // will do it, and the only thing on the stack at that time will be your main class, which + // has no state anyway. + // + // TODO(someday): Perhaps we should use the new std::quick_exit(), so that at_quick_exit() is + // available for those who really think they need it. Unfortunately, it is not yet available + // on many platforms. + + virtual void warning(StringPtr message) = 0; + // Print the given message to standard error. A newline is printed after the message if it + // doesn't already have one. + + virtual void error(StringPtr message) = 0; + // Like `warning()`, but also sets a flag indicating that the process has failed, and that when + // it eventually exits it should indicate an error status. + + KJ_NORETURN(virtual void exitError(StringPtr message)) = 0; + // Equivalent to `error(message)` followed by `exit()`. + + KJ_NORETURN(virtual void exitInfo(StringPtr message)) = 0; + // Displays the given non-error message to the user and then calls `exit()`. This is used to + // implement things like --help. + + virtual void increaseLoggingVerbosity() = 0; + // Increase the level of detail produced by the debug logging system. `MainBuilder` invokes + // this if the caller uses the -v flag. + + // TODO(someday): Add interfaces representing standard OS resources like the filesystem, so that + // these things can be mocked out. +}; + +class TopLevelProcessContext final: public ProcessContext { + // A ProcessContext implementation appropriate for use at the actual entry point of a process + // (as opposed to when you are trying to call a program's main function from within some other + // program). This implementation writes errors to stderr, and its `exit()` method actually + // calls the C `quick_exit()` function. + +public: + explicit TopLevelProcessContext(StringPtr programName); + + struct CleanShutdownException { int exitCode; }; + // If the environment variable KJ_CLEAN_SHUTDOWN is set, then exit() will actually throw this + // exception rather than exiting. `kj::runMain()` catches this exception and returns normally. + // This is useful primarily for testing purposes, to assist tools like memory leak checkers that + // are easily confused by quick_exit(). + + StringPtr getProgramName() override; + KJ_NORETURN(void exit() override); + void warning(StringPtr message) override; + void error(StringPtr message) override; + KJ_NORETURN(void exitError(StringPtr message) override); + KJ_NORETURN(void exitInfo(StringPtr message) override); + void increaseLoggingVerbosity() override; + +private: + StringPtr programName; + bool cleanShutdown; + bool hadErrors = false; +}; + +typedef Function params)> MainFunc; + +int runMainAndExit(ProcessContext& context, MainFunc&& func, int argc, char* argv[]); +// Runs the given main function and then exits using the given context. If an exception is thrown, +// this will catch it, report it via the context and exit with an error code. +// +// Normally this function does not return, because returning would probably lead to wasting time +// on cleanup when the process is just going to exit anyway. However, to facilitate memory leak +// checkers and other tools that require a clean shutdown to do their job, if the environment +// variable KJ_CLEAN_SHUTDOWN is set, the function will in fact return an exit code, which should +// then be returned from main(). +// +// Most users will use the KJ_MAIN() macro rather than call this function directly. + +#define KJ_MAIN(MainClass) \ + int main(int argc, char* argv[]) { \ + ::kj::TopLevelProcessContext context(argv[0]); \ + MainClass mainObject(context); \ + return ::kj::runMainAndExit(context, mainObject.getMain(), argc, argv); \ + } +// Convenience macro for declaring a main function based on the given class. The class must have +// a constructor that accepts a ProcessContext& and a method getMain() which returns +// kj::MainFunc (probably building it using a MainBuilder). + +class MainBuilder { + // Builds a main() function with nice argument parsing. As options and arguments are parsed, + // corresponding callbacks are called, so that you never have to write a massive switch() + // statement to interpret arguments. Additionally, this approach encourages you to write + // main classes that have a reasonable API that can be used as an alternative to their + // command-line interface. + // + // All StringPtrs passed to MainBuilder must remain valid until option parsing completes. The + // assumption is that these strings will all be literals, making this an easy requirement. If + // not, consider allocating them in an Arena. + // + // Some flags are automatically recognized by the main functions built by this class: + // --help: Prints help text and exits. The help text is constructed based on the + // information you provide to the builder as you define each flag. + // --verbose: Increase logging verbosity. + // --version: Print version information and exit. + // + // Example usage: + // + // class FooMain { + // public: + // FooMain(kj::ProcessContext& context): context(context) {} + // + // bool setAll() { all = true; return true; } + // // Enable the --all flag. + // + // kj::MainBuilder::Validity setOutput(kj::StringPtr name) { + // // Set the output file. + // + // if (name.endsWith(".foo")) { + // outputFile = name; + // return true; + // } else { + // return "Output file must have extension .foo."; + // } + // } + // + // kj::MainBuilder::Validity processInput(kj::StringPtr name) { + // // Process an input file. + // + // if (!exists(name)) { + // return kj::str(name, ": file not found"); + // } + // // ... process the input file ... + // return true; + // } + // + // kj::MainFunc getMain() { + // return MainBuilder(context, "Foo Builder v1.5", "Reads s and builds a Foo.") + // .addOption({'a', "all"}, KJ_BIND_METHOD(*this, setAll), + // "Frob all the widgets. Otherwise, only some widgets are frobbed.") + // .addOptionWithArg({'o', "output"}, KJ_BIND_METHOD(*this, setOutput), + // "", "Output to . Must be a .foo file.") + // .expectOneOrMoreArgs("", KJ_BIND_METHOD(*this, processInput)) + // .build(); + // } + // + // private: + // bool all = false; + // kj::StringPtr outputFile; + // kj::ProcessContext& context; + // }; + +public: + MainBuilder(ProcessContext& context, StringPtr version, + StringPtr briefDescription, StringPtr extendedDescription = nullptr); + ~MainBuilder() noexcept(false); + + class OptionName { + public: + OptionName() = default; + inline OptionName(char shortName): isLong(false), shortName(shortName) {} + inline OptionName(const char* longName): isLong(true), longName(longName) {} + + private: + bool isLong; + union { + char shortName; + const char* longName; + }; + friend class MainBuilder; + }; + + class Validity { + public: + inline Validity(bool valid) { + if (!valid) errorMessage = heapString("invalid argument"); + } + inline Validity(const char* errorMessage) + : errorMessage(heapString(errorMessage)) {} + inline Validity(String&& errorMessage) + : errorMessage(kj::mv(errorMessage)) {} + + inline const Maybe& getError() const { return errorMessage; } + inline Maybe releaseError() { return kj::mv(errorMessage); } + + private: + Maybe errorMessage; + friend class MainBuilder; + }; + + MainBuilder& addOption(std::initializer_list names, Function callback, + StringPtr helpText); + // Defines a new option (flag). `names` is a list of characters and strings that can be used to + // specify the option on the command line. Single-character names are used with "-" while string + // names are used with "--". `helpText` is a natural-language description of the flag. + // + // `callback` is called when the option is seen. Its return value indicates whether the option + // was accepted. If not, further option processing stops, and error is written, and the process + // exits. + // + // Example: + // + // builder.addOption({'a', "all"}, KJ_BIND_METHOD(*this, showAll), "Show all files."); + // + // This option could be specified in the following ways: + // + // -a + // --all + // + // Note that single-character option names can be combined into a single argument. For example, + // `-abcd` is equivalent to `-a -b -c -d`. + // + // The help text for this option would look like: + // + // -a, --all + // Show all files. + // + // Note that help text is automatically word-wrapped. + + MainBuilder& addOptionWithArg(std::initializer_list names, + Function callback, + StringPtr argumentTitle, StringPtr helpText); + // Like `addOption()`, but adds an option which accepts an argument. `argumentTitle` is used in + // the help text. The argument text is passed to the callback. + // + // Example: + // + // builder.addOptionWithArg({'o', "output"}, KJ_BIND_METHOD(*this, setOutput), + // "", "Output to ."); + // + // This option could be specified with an argument of "foo" in the following ways: + // + // -ofoo + // -o foo + // --output=foo + // --output foo + // + // Note that single-character option names can be combined, but only the last option can have an + // argument, since the characters after the option letter are interpreted as the argument. E.g. + // `-abofoo` would be equivalent to `-a -b -o foo`. + // + // The help text for this option would look like: + // + // -o FILENAME, --output=FILENAME + // Output to FILENAME. + + MainBuilder& addSubCommand(StringPtr name, Function getSubParser, + StringPtr briefHelpText); + // If exactly the given name is seen as an argument, invoke getSubParser() and then pass all + // remaining arguments to the parser it returns. This is useful for implementing commands which + // have lots of sub-commands, like "git" (which has sub-commands "checkout", "branch", "pull", + // etc.). + // + // `getSubParser` is only called if the command is seen. This avoids building main functions + // for commands that aren't used. + // + // `briefHelpText` should be brief enough to show immediately after the command name on a single + // line. It will not be wrapped. Users can use the built-in "help" command to get extended + // help on a particular command. + + MainBuilder& expectArg(StringPtr title, Function callback); + MainBuilder& expectOptionalArg(StringPtr title, Function callback); + MainBuilder& expectZeroOrMoreArgs(StringPtr title, Function callback); + MainBuilder& expectOneOrMoreArgs(StringPtr title, Function callback); + // Set callbacks to handle arguments. `expectArg()` and `expectOptionalArg()` specify positional + // arguments with special handling, while `expect{Zero,One}OrMoreArgs()` specifies a handler for + // an argument list (the handler is called once for each argument in the list). `title` + // specifies how the argument should be represented in the usage text. + // + // All options callbacks are called before argument callbacks, regardless of their ordering on + // the command line. This matches GNU getopt's behavior of permuting non-flag arguments to the + // end of the argument list. Also matching getopt, the special option "--" indicates that the + // rest of the command line is all arguments, not options, even if they start with '-'. + // + // The interpretation of positional arguments is fairly flexible. The non-optional arguments can + // be expected at the beginning, end, or in the middle. If more arguments are specified than + // the number of non-optional args, they are assigned to the optional argument handlers in the + // order of registration. + // + // For example, say you called: + // builder.expectArg("", ...); + // builder.expectOptionalArg("", ...); + // builder.expectArg("", ...); + // builder.expectZeroOrMoreArgs("", ...); + // builder.expectArg("", ...); + // + // This command requires at least three arguments: foo, baz, and corge. If four arguments are + // given, the second is assigned to bar. If five or more arguments are specified, then the + // arguments between the third and last are assigned to qux. Note that it never makes sense + // to call `expect*OrMoreArgs()` more than once since only the first call would ever be used. + // + // In practice, you probably shouldn't create such complicated commands as in the above example. + // But, this flexibility seems necessary to support commands where the first argument is special + // as well as commands (like `cp`) where the last argument is special. + + MainBuilder& callAfterParsing(Function callback); + // Call the given function after all arguments have been parsed. + + MainFunc build(); + // Build the "main" function, which simply parses the arguments. Once this returns, the + // `MainBuilder` is no longer valid. + +private: + struct Impl; + Own impl; + + class MainImpl; +}; + +} // namespace kj + +#endif // KJ_MAIN_H_ diff --git a/phonelibs/capnp-cpp/include/kj/memory.h b/phonelibs/capnp-cpp/include/kj/memory.h new file mode 100644 index 00000000000000..60912b0a344fce --- /dev/null +++ b/phonelibs/capnp-cpp/include/kj/memory.h @@ -0,0 +1,406 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef KJ_MEMORY_H_ +#define KJ_MEMORY_H_ + +#if defined(__GNUC__) && !KJ_HEADER_WARNINGS +#pragma GCC system_header +#endif + +#include "common.h" + +namespace kj { + +// ======================================================================================= +// Disposer -- Implementation details. + +class Disposer { + // Abstract interface for a thing that "disposes" of objects, where "disposing" usually means + // calling the destructor followed by freeing the underlying memory. `Own` encapsulates an + // object pointer with corresponding Disposer. + // + // Few developers will ever touch this interface. It is primarily useful for those implementing + // custom memory allocators. + +protected: + // Do not declare a destructor, as doing so will force a global initializer for each HeapDisposer + // instance. Eww! + + virtual void disposeImpl(void* pointer) const = 0; + // Disposes of the object, given a pointer to the beginning of the object. If the object is + // polymorphic, this pointer is determined by dynamic_cast(). For non-polymorphic types, + // Own does not allow any casting, so the pointer exactly matches the original one given to + // Own. + +public: + + template + void dispose(T* object) const; + // Helper wrapper around disposeImpl(). + // + // If T is polymorphic, calls `disposeImpl(dynamic_cast(object))`, otherwise calls + // `disposeImpl(implicitCast(object))`. + // + // Callers must not call dispose() on the same pointer twice, even if the first call throws + // an exception. + +private: + template + struct Dispose_; +}; + +template +class DestructorOnlyDisposer: public Disposer { + // A disposer that merely calls the type's destructor and nothing else. + +public: + static const DestructorOnlyDisposer instance; + + void disposeImpl(void* pointer) const override { + reinterpret_cast(pointer)->~T(); + } +}; + +template +const DestructorOnlyDisposer DestructorOnlyDisposer::instance = DestructorOnlyDisposer(); + +class NullDisposer: public Disposer { + // A disposer that does nothing. + +public: + static const NullDisposer instance; + + void disposeImpl(void* pointer) const override {} +}; + +// ======================================================================================= +// Own -- An owned pointer. + +template +class Own { + // A transferrable title to a T. When an Own goes out of scope, the object's Disposer is + // called to dispose of it. An Own can be efficiently passed by move, without relocating the + // underlying object; this transfers ownership. + // + // This is much like std::unique_ptr, except: + // - You cannot release(). An owned object is not necessarily allocated with new (see next + // point), so it would be hard to use release() correctly. + // - The deleter is made polymorphic by virtual call rather than by template. This is much + // more powerful -- it allows the use of custom allocators, freelists, etc. This could + // _almost_ be accomplished with unique_ptr by forcing everyone to use something like + // std::unique_ptr, except that things get hairy in the presence of multiple + // inheritance and upcasting, and anyway if you force everyone to use a custom deleter + // then you've lost any benefit to interoperating with the "standard" unique_ptr. + +public: + KJ_DISALLOW_COPY(Own); + inline Own(): disposer(nullptr), ptr(nullptr) {} + inline Own(Own&& other) noexcept + : disposer(other.disposer), ptr(other.ptr) { other.ptr = nullptr; } + inline Own(Own>&& other) noexcept + : disposer(other.disposer), ptr(other.ptr) { other.ptr = nullptr; } + template ()>> + inline Own(Own&& other) noexcept + : disposer(other.disposer), ptr(other.ptr) { + static_assert(__is_polymorphic(T), + "Casting owned pointers requires that the target type is polymorphic."); + other.ptr = nullptr; + } + inline Own(T* ptr, const Disposer& disposer) noexcept: disposer(&disposer), ptr(ptr) {} + + ~Own() noexcept(false) { dispose(); } + + inline Own& operator=(Own&& other) { + // Move-assingnment operator. + + // Careful, this might own `other`. Therefore we have to transfer the pointers first, then + // dispose. + const Disposer* disposerCopy = disposer; + T* ptrCopy = ptr; + disposer = other.disposer; + ptr = other.ptr; + other.ptr = nullptr; + if (ptrCopy != nullptr) { + disposerCopy->dispose(const_cast*>(ptrCopy)); + } + return *this; + } + + inline Own& operator=(decltype(nullptr)) { + dispose(); + return *this; + } + + template + Own downcast() { + // Downcast the pointer to Own, destroying the original pointer. If this pointer does not + // actually point at an instance of U, the results are undefined (throws an exception in debug + // mode if RTTI is enabled, otherwise you're on your own). + + Own result; + if (ptr != nullptr) { + result.ptr = &kj::downcast(*ptr); + result.disposer = disposer; + ptr = nullptr; + } + return result; + } + +#define NULLCHECK KJ_IREQUIRE(ptr != nullptr, "null Own<> dereference") + inline T* operator->() { NULLCHECK; return ptr; } + inline const T* operator->() const { NULLCHECK; return ptr; } + inline T& operator*() { NULLCHECK; return *ptr; } + inline const T& operator*() const { NULLCHECK; return *ptr; } +#undef NULLCHECK + inline T* get() { return ptr; } + inline const T* get() const { return ptr; } + inline operator T*() { return ptr; } + inline operator const T*() const { return ptr; } + +private: + const Disposer* disposer; // Only valid if ptr != nullptr. + T* ptr; + + inline explicit Own(decltype(nullptr)): disposer(nullptr), ptr(nullptr) {} + + inline bool operator==(decltype(nullptr)) { return ptr == nullptr; } + inline bool operator!=(decltype(nullptr)) { return ptr != nullptr; } + // Only called by Maybe>. + + inline void dispose() { + // Make sure that if an exception is thrown, we are left with a null ptr, so we won't possibly + // dispose again. + T* ptrCopy = ptr; + if (ptrCopy != nullptr) { + ptr = nullptr; + disposer->dispose(const_cast*>(ptrCopy)); + } + } + + template + friend class Own; + friend class Maybe>; +}; + +namespace _ { // private + +template +class OwnOwn { +public: + inline OwnOwn(Own&& value) noexcept: value(kj::mv(value)) {} + + inline Own& operator*() & { return value; } + inline const Own& operator*() const & { return value; } + inline Own&& operator*() && { return kj::mv(value); } + inline const Own&& operator*() const && { return kj::mv(value); } + inline Own* operator->() { return &value; } + inline const Own* operator->() const { return &value; } + inline operator Own*() { return value ? &value : nullptr; } + inline operator const Own*() const { return value ? &value : nullptr; } + +private: + Own value; +}; + +template +OwnOwn readMaybe(Maybe>&& maybe) { return OwnOwn(kj::mv(maybe.ptr)); } +template +Own* readMaybe(Maybe>& maybe) { return maybe.ptr ? &maybe.ptr : nullptr; } +template +const Own* readMaybe(const Maybe>& maybe) { return maybe.ptr ? &maybe.ptr : nullptr; } + +} // namespace _ (private) + +template +class Maybe> { +public: + inline Maybe(): ptr(nullptr) {} + inline Maybe(Own&& t) noexcept: ptr(kj::mv(t)) {} + inline Maybe(Maybe&& other) noexcept: ptr(kj::mv(other.ptr)) {} + + template + inline Maybe(Maybe>&& other): ptr(mv(other.ptr)) {} + template + inline Maybe(Own&& other): ptr(mv(other)) {} + + inline Maybe(decltype(nullptr)) noexcept: ptr(nullptr) {} + + inline operator Maybe() { return ptr.get(); } + inline operator Maybe() const { return ptr.get(); } + + inline Maybe& operator=(Maybe&& other) { ptr = kj::mv(other.ptr); return *this; } + + inline bool operator==(decltype(nullptr)) const { return ptr == nullptr; } + inline bool operator!=(decltype(nullptr)) const { return ptr != nullptr; } + + Own& orDefault(Own& defaultValue) { + if (ptr == nullptr) { + return defaultValue; + } else { + return ptr; + } + } + const Own& orDefault(const Own& defaultValue) const { + if (ptr == nullptr) { + return defaultValue; + } else { + return ptr; + } + } + + template + auto map(Func&& f) & -> Maybe&>()))> { + if (ptr == nullptr) { + return nullptr; + } else { + return f(ptr); + } + } + + template + auto map(Func&& f) const & -> Maybe&>()))> { + if (ptr == nullptr) { + return nullptr; + } else { + return f(ptr); + } + } + + template + auto map(Func&& f) && -> Maybe&&>()))> { + if (ptr == nullptr) { + return nullptr; + } else { + return f(kj::mv(ptr)); + } + } + + template + auto map(Func&& f) const && -> Maybe&&>()))> { + if (ptr == nullptr) { + return nullptr; + } else { + return f(kj::mv(ptr)); + } + } + +private: + Own ptr; + + template + friend class Maybe; + template + friend _::OwnOwn _::readMaybe(Maybe>&& maybe); + template + friend Own* _::readMaybe(Maybe>& maybe); + template + friend const Own* _::readMaybe(const Maybe>& maybe); +}; + +namespace _ { // private + +template +class HeapDisposer final: public Disposer { +public: + virtual void disposeImpl(void* pointer) const override { delete reinterpret_cast(pointer); } + + static const HeapDisposer instance; +}; + +template +const HeapDisposer HeapDisposer::instance = HeapDisposer(); + +} // namespace _ (private) + +template +Own heap(Params&&... params) { + // heap(...) allocates a T on the heap, forwarding the parameters to its constructor. The + // exact heap implementation is unspecified -- for now it is operator new, but you should not + // assume this. (Since we know the object size at delete time, we could actually implement an + // allocator that is more efficient than operator new.) + + return Own(new T(kj::fwd(params)...), _::HeapDisposer::instance); +} + +template +Own> heap(T&& orig) { + // Allocate a copy (or move) of the argument on the heap. + // + // The purpose of this overload is to allow you to omit the template parameter as there is only + // one argument and the purpose is to copy it. + + typedef Decay T2; + return Own(new T2(kj::fwd(orig)), _::HeapDisposer::instance); +} + +// ======================================================================================= +// SpaceFor -- assists in manual allocation + +template +class SpaceFor { + // A class which has the same size and alignment as T but does not call its constructor or + // destructor automatically. Instead, call construct() to construct a T in the space, which + // returns an Own which will take care of calling T's destructor later. + +public: + inline SpaceFor() {} + inline ~SpaceFor() {} + + template + Own construct(Params&&... params) { + ctor(value, kj::fwd(params)...); + return Own(&value, DestructorOnlyDisposer::instance); + } + +private: + union { + T value; + }; +}; + +// ======================================================================================= +// Inline implementation details + +template +struct Disposer::Dispose_ { + static void dispose(T* object, const Disposer& disposer) { + // Note that dynamic_cast does not require RTTI to be enabled, because the offset to + // the top of the object is in the vtable -- as it obviously needs to be to correctly implement + // operator delete. + disposer.disposeImpl(dynamic_cast(object)); + } +}; +template +struct Disposer::Dispose_ { + static void dispose(T* object, const Disposer& disposer) { + disposer.disposeImpl(static_cast(object)); + } +}; + +template +void Disposer::dispose(T* object) const { + Dispose_::dispose(object, *this); +} + +} // namespace kj + +#endif // KJ_MEMORY_H_ diff --git a/phonelibs/capnp-cpp/include/kj/mutex.h b/phonelibs/capnp-cpp/include/kj/mutex.h new file mode 100644 index 00000000000000..d211ebfeb1c603 --- /dev/null +++ b/phonelibs/capnp-cpp/include/kj/mutex.h @@ -0,0 +1,369 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef KJ_MUTEX_H_ +#define KJ_MUTEX_H_ + +#if defined(__GNUC__) && !KJ_HEADER_WARNINGS +#pragma GCC system_header +#endif + +#include "memory.h" +#include + +#if __linux__ && !defined(KJ_USE_FUTEX) +#define KJ_USE_FUTEX 1 +#endif + +#if !KJ_USE_FUTEX && !_WIN32 +// On Linux we use futex. On other platforms we wrap pthreads. +// TODO(someday): Write efficient low-level locking primitives for other platforms. +#include +#endif + +namespace kj { + +// ======================================================================================= +// Private details -- public interfaces follow below. + +namespace _ { // private + +class Mutex { + // Internal implementation details. See `MutexGuarded`. + +public: + Mutex(); + ~Mutex(); + KJ_DISALLOW_COPY(Mutex); + + enum Exclusivity { + EXCLUSIVE, + SHARED + }; + + void lock(Exclusivity exclusivity); + void unlock(Exclusivity exclusivity); + + void assertLockedByCaller(Exclusivity exclusivity); + // In debug mode, assert that the mutex is locked by the calling thread, or if that is + // non-trivial, assert that the mutex is locked (which should be good enough to catch problems + // in unit tests). In non-debug builds, do nothing. + +private: +#if KJ_USE_FUTEX + uint futex; + // bit 31 (msb) = set if exclusive lock held + // bit 30 (msb) = set if threads are waiting for exclusive lock + // bits 0-29 = count of readers; If an exclusive lock is held, this is the count of threads + // waiting for a read lock, otherwise it is the count of threads that currently hold a read + // lock. + + static constexpr uint EXCLUSIVE_HELD = 1u << 31; + static constexpr uint EXCLUSIVE_REQUESTED = 1u << 30; + static constexpr uint SHARED_COUNT_MASK = EXCLUSIVE_REQUESTED - 1; + +#elif _WIN32 + uintptr_t srwLock; // Actually an SRWLOCK, but don't want to #include in header. + +#else + mutable pthread_rwlock_t mutex; +#endif +}; + +class Once { + // Internal implementation details. See `Lazy`. + +public: +#if KJ_USE_FUTEX + inline Once(bool startInitialized = false) + : futex(startInitialized ? INITIALIZED : UNINITIALIZED) {} +#else + Once(bool startInitialized = false); + ~Once(); +#endif + KJ_DISALLOW_COPY(Once); + + class Initializer { + public: + virtual void run() = 0; + }; + + void runOnce(Initializer& init); + +#if _WIN32 // TODO(perf): Can we make this inline on win32 somehow? + bool isInitialized() noexcept; + +#else + inline bool isInitialized() noexcept { + // Fast path check to see if runOnce() would simply return immediately. +#if KJ_USE_FUTEX + return __atomic_load_n(&futex, __ATOMIC_ACQUIRE) == INITIALIZED; +#else + return __atomic_load_n(&state, __ATOMIC_ACQUIRE) == INITIALIZED; +#endif + } +#endif + + void reset(); + // Returns the state from initialized to uninitialized. It is an error to call this when + // not already initialized, or when runOnce() or isInitialized() might be called concurrently in + // another thread. + +private: +#if KJ_USE_FUTEX + uint futex; + + enum State { + UNINITIALIZED, + INITIALIZING, + INITIALIZING_WITH_WAITERS, + INITIALIZED + }; + +#elif _WIN32 + uintptr_t initOnce; // Actually an INIT_ONCE, but don't want to #include in header. + +#else + enum State { + UNINITIALIZED, + INITIALIZED + }; + State state; + pthread_mutex_t mutex; +#endif +}; + +} // namespace _ (private) + +// ======================================================================================= +// Public interface + +template +class Locked { + // Return type for `MutexGuarded::lock()`. `Locked` provides access to the bounded object + // and unlocks the mutex when it goes out of scope. + +public: + KJ_DISALLOW_COPY(Locked); + inline Locked(): mutex(nullptr), ptr(nullptr) {} + inline Locked(Locked&& other): mutex(other.mutex), ptr(other.ptr) { + other.mutex = nullptr; + other.ptr = nullptr; + } + inline ~Locked() { + if (mutex != nullptr) mutex->unlock(isConst() ? _::Mutex::SHARED : _::Mutex::EXCLUSIVE); + } + + inline Locked& operator=(Locked&& other) { + if (mutex != nullptr) mutex->unlock(isConst() ? _::Mutex::SHARED : _::Mutex::EXCLUSIVE); + mutex = other.mutex; + ptr = other.ptr; + other.mutex = nullptr; + other.ptr = nullptr; + return *this; + } + + inline void release() { + if (mutex != nullptr) mutex->unlock(isConst() ? _::Mutex::SHARED : _::Mutex::EXCLUSIVE); + mutex = nullptr; + ptr = nullptr; + } + + inline T* operator->() { return ptr; } + inline const T* operator->() const { return ptr; } + inline T& operator*() { return *ptr; } + inline const T& operator*() const { return *ptr; } + inline T* get() { return ptr; } + inline const T* get() const { return ptr; } + inline operator T*() { return ptr; } + inline operator const T*() const { return ptr; } + +private: + _::Mutex* mutex; + T* ptr; + + inline Locked(_::Mutex& mutex, T& value): mutex(&mutex), ptr(&value) {} + + template + friend class MutexGuarded; +}; + +template +class MutexGuarded { + // An object of type T, bounded by a mutex. In order to access the object, you must lock it. + // + // Write locks are not "recursive" -- trying to lock again in a thread that already holds a lock + // will deadlock. Recursive write locks are usually a sign of bad design. + // + // Unfortunately, **READ LOCKS ARE NOT RECURSIVE** either. Common sense says they should be. + // But on many operating systems (BSD, OSX), recursively read-locking a pthread_rwlock is + // actually unsafe. The problem is that writers are "prioritized" over readers, so a read lock + // request will block if any write lock requests are outstanding. So, if thread A takes a read + // lock, thread B requests a write lock (and starts waiting), and then thread A tries to take + // another read lock recursively, the result is deadlock. + +public: + template + explicit MutexGuarded(Params&&... params); + // Initialize the mutex-bounded object by passing the given parameters to its constructor. + + Locked lockExclusive() const; + // Exclusively locks the object and returns it. The returned `Locked` can be passed by + // move, similar to `Own`. + // + // This method is declared `const` in accordance with KJ style rules which say that constness + // should be used to indicate thread-safety. It is safe to share a const pointer between threads, + // but it is not safe to share a mutable pointer. Since the whole point of MutexGuarded is to + // be shared between threads, its methods should be const, even though locking it produces a + // non-const pointer to the contained object. + + Locked lockShared() const; + // Lock the value for shared access. Multiple shared locks can be taken concurrently, but cannot + // be held at the same time as a non-shared lock. + + inline const T& getWithoutLock() const { return value; } + inline T& getWithoutLock() { return value; } + // Escape hatch for cases where some external factor guarantees that it's safe to get the + // value. You should treat these like const_cast -- be highly suspicious of any use. + + inline const T& getAlreadyLockedShared() const; + inline T& getAlreadyLockedShared(); + inline T& getAlreadyLockedExclusive() const; + // Like `getWithoutLock()`, but asserts that the lock is already held by the calling thread. + +private: + mutable _::Mutex mutex; + mutable T value; +}; + +template +class MutexGuarded { + // MutexGuarded cannot guard a const type. This would be pointless anyway, and would complicate + // the implementation of Locked, which uses constness to decide what kind of lock it holds. + static_assert(sizeof(T) < 0, "MutexGuarded's type cannot be const."); +}; + +template +class Lazy { + // A lazily-initialized value. + +public: + template + T& get(Func&& init); + template + const T& get(Func&& init) const; + // The first thread to call get() will invoke the given init function to construct the value. + // Other threads will block until construction completes, then return the same value. + // + // `init` is a functor(typically a lambda) which takes `SpaceFor&` as its parameter and returns + // `Own`. If `init` throws an exception, the exception is propagated out of that thread's + // call to `get()`, and subsequent calls behave as if `get()` hadn't been called at all yet -- + // in other words, subsequent calls retry initialization until it succeeds. + +private: + mutable _::Once once; + mutable SpaceFor space; + mutable Own value; + + template + class InitImpl; +}; + +// ======================================================================================= +// Inline implementation details + +template +template +inline MutexGuarded::MutexGuarded(Params&&... params) + : value(kj::fwd(params)...) {} + +template +inline Locked MutexGuarded::lockExclusive() const { + mutex.lock(_::Mutex::EXCLUSIVE); + return Locked(mutex, value); +} + +template +inline Locked MutexGuarded::lockShared() const { + mutex.lock(_::Mutex::SHARED); + return Locked(mutex, value); +} + +template +inline const T& MutexGuarded::getAlreadyLockedShared() const { +#ifdef KJ_DEBUG + mutex.assertLockedByCaller(_::Mutex::SHARED); +#endif + return value; +} +template +inline T& MutexGuarded::getAlreadyLockedShared() { +#ifdef KJ_DEBUG + mutex.assertLockedByCaller(_::Mutex::SHARED); +#endif + return value; +} +template +inline T& MutexGuarded::getAlreadyLockedExclusive() const { +#ifdef KJ_DEBUG + mutex.assertLockedByCaller(_::Mutex::EXCLUSIVE); +#endif + return const_cast(value); +} + +template +template +class Lazy::InitImpl: public _::Once::Initializer { +public: + inline InitImpl(const Lazy& lazy, Func&& func): lazy(lazy), func(kj::fwd(func)) {} + + void run() override { + lazy.value = func(lazy.space); + } + +private: + const Lazy& lazy; + Func func; +}; + +template +template +inline T& Lazy::get(Func&& init) { + if (!once.isInitialized()) { + InitImpl initImpl(*this, kj::fwd(init)); + once.runOnce(initImpl); + } + return *value; +} + +template +template +inline const T& Lazy::get(Func&& init) const { + if (!once.isInitialized()) { + InitImpl initImpl(*this, kj::fwd(init)); + once.runOnce(initImpl); + } + return *value; +} + +} // namespace kj + +#endif // KJ_MUTEX_H_ diff --git a/phonelibs/capnp-cpp/include/kj/one-of.h b/phonelibs/capnp-cpp/include/kj/one-of.h new file mode 100644 index 00000000000000..6e143c44cf26dd --- /dev/null +++ b/phonelibs/capnp-cpp/include/kj/one-of.h @@ -0,0 +1,155 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef KJ_ONE_OF_H_ +#define KJ_ONE_OF_H_ + +#if defined(__GNUC__) && !KJ_HEADER_WARNINGS +#pragma GCC system_header +#endif + +#include "common.h" + +namespace kj { + +namespace _ { // private + +template +struct TypeIndex_ { static constexpr uint value = TypeIndex_::value; }; +template +struct TypeIndex_ { static constexpr uint value = i; }; + +} // namespace _ (private) + +template +class OneOf { + template + static inline constexpr uint typeIndex() { return _::TypeIndex_<1, Key, Variants...>::value; } + // Get the 1-based index of Key within the type list Types. + +public: + inline OneOf(): tag(0) {} + OneOf(const OneOf& other) { copyFrom(other); } + OneOf(OneOf&& other) { moveFrom(other); } + ~OneOf() { destroy(); } + + OneOf& operator=(const OneOf& other) { if (tag != 0) destroy(); copyFrom(other); return *this; } + OneOf& operator=(OneOf&& other) { if (tag != 0) destroy(); moveFrom(other); return *this; } + + inline bool operator==(decltype(nullptr)) const { return tag == 0; } + inline bool operator!=(decltype(nullptr)) const { return tag != 0; } + + template + bool is() const { + return tag == typeIndex(); + } + + template + T& get() { + KJ_IREQUIRE(is(), "Must check OneOf::is() before calling get()."); + return *reinterpret_cast(space); + } + template + const T& get() const { + KJ_IREQUIRE(is(), "Must check OneOf::is() before calling get()."); + return *reinterpret_cast(space); + } + + template + T& init(Params&&... params) { + if (tag != 0) destroy(); + ctor(*reinterpret_cast(space), kj::fwd(params)...); + tag = typeIndex(); + return *reinterpret_cast(space); + } + +private: + uint tag; + + static inline constexpr size_t maxSize(size_t a) { + return a; + } + template + static inline constexpr size_t maxSize(size_t a, size_t b, Rest... rest) { + return maxSize(kj::max(a, b), rest...); + } + // Returns the maximum of all the parameters. + // TODO(someday): Generalize the above template and make it common. I tried, but C++ decided to + // be difficult so I cut my losses. + + static constexpr auto spaceSize = maxSize(sizeof(Variants)...); + // TODO(msvc): This constant could just as well go directly inside space's bracket's, where it's + // used, but MSVC suffers a parse error on `...`. + + union { + byte space[spaceSize]; + + void* forceAligned; + // TODO(someday): Use C++11 alignas() once we require GCC 4.8 / Clang 3.3. + }; + + template + inline void doAll(T... t) {} + + template + inline bool destroyVariant() { + if (tag == typeIndex()) { + tag = 0; + dtor(*reinterpret_cast(space)); + } + return false; + } + void destroy() { + doAll(destroyVariant()...); + } + + template + inline bool copyVariantFrom(const OneOf& other) { + if (other.is()) { + ctor(*reinterpret_cast(space), other.get()); + } + return false; + } + void copyFrom(const OneOf& other) { + // Initialize as a copy of `other`. Expects that `this` starts out uninitialized, so the tag + // is invalid. + tag = other.tag; + doAll(copyVariantFrom(other)...); + } + + template + inline bool moveVariantFrom(OneOf& other) { + if (other.is()) { + ctor(*reinterpret_cast(space), kj::mv(other.get())); + } + return false; + } + void moveFrom(OneOf& other) { + // Initialize as a copy of `other`. Expects that `this` starts out uninitialized, so the tag + // is invalid. + tag = other.tag; + doAll(moveVariantFrom(other)...); + } +}; + +} // namespace kj + +#endif // KJ_ONE_OF_H_ diff --git a/phonelibs/capnp-cpp/include/kj/parse/char.h b/phonelibs/capnp-cpp/include/kj/parse/char.h new file mode 100644 index 00000000000000..2e6d51921d86ce --- /dev/null +++ b/phonelibs/capnp-cpp/include/kj/parse/char.h @@ -0,0 +1,361 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +// This file contains parsers useful for character stream inputs, including parsers to parse +// common kinds of tokens like identifiers, numbers, and quoted strings. + +#ifndef KJ_PARSE_CHAR_H_ +#define KJ_PARSE_CHAR_H_ + +#if defined(__GNUC__) && !KJ_HEADER_WARNINGS +#pragma GCC system_header +#endif + +#include "common.h" +#include "../string.h" +#include + +namespace kj { +namespace parse { + +// ======================================================================================= +// Exact char/string. + +class ExactString_ { +public: + constexpr inline ExactString_(const char* str): str(str) {} + + template + Maybe> operator()(Input& input) const { + const char* ptr = str; + + while (*ptr != '\0') { + if (input.atEnd() || input.current() != *ptr) return nullptr; + input.next(); + ++ptr; + } + + return Tuple<>(); + } + +private: + const char* str; +}; + +constexpr inline ExactString_ exactString(const char* str) { + return ExactString_(str); +} + +template +constexpr ExactlyConst_ exactChar() { + // Returns a parser that matches exactly the character given by the template argument (returning + // no result). + return ExactlyConst_(); +} + +// ======================================================================================= +// Char ranges / sets + +class CharGroup_ { +public: + constexpr inline CharGroup_(): bits{0, 0, 0, 0} {} + + constexpr inline CharGroup_ orRange(unsigned char first, unsigned char last) const { + return CharGroup_(bits[0] | (oneBits(last + 1) & ~oneBits(first )), + bits[1] | (oneBits(last - 63) & ~oneBits(first - 64)), + bits[2] | (oneBits(last - 127) & ~oneBits(first - 128)), + bits[3] | (oneBits(last - 191) & ~oneBits(first - 192))); + } + + constexpr inline CharGroup_ orAny(const char* chars) const { + return *chars == 0 ? *this : orChar(*chars).orAny(chars + 1); + } + + constexpr inline CharGroup_ orChar(unsigned char c) const { + return CharGroup_(bits[0] | bit(c), + bits[1] | bit(c - 64), + bits[2] | bit(c - 128), + bits[3] | bit(c - 256)); + } + + constexpr inline CharGroup_ orGroup(CharGroup_ other) const { + return CharGroup_(bits[0] | other.bits[0], + bits[1] | other.bits[1], + bits[2] | other.bits[2], + bits[3] | other.bits[3]); + } + + constexpr inline CharGroup_ invert() const { + return CharGroup_(~bits[0], ~bits[1], ~bits[2], ~bits[3]); + } + + constexpr inline bool contains(unsigned char c) const { + return (bits[c / 64] & (1ll << (c % 64))) != 0; + } + + template + Maybe operator()(Input& input) const { + if (input.atEnd()) return nullptr; + unsigned char c = input.current(); + if (contains(c)) { + input.next(); + return c; + } else { + return nullptr; + } + } + +private: + typedef unsigned long long Bits64; + + constexpr inline CharGroup_(Bits64 a, Bits64 b, Bits64 c, Bits64 d): bits{a, b, c, d} {} + Bits64 bits[4]; + + static constexpr inline Bits64 oneBits(int count) { + return count <= 0 ? 0ll : count >= 64 ? -1ll : ((1ll << count) - 1); + } + static constexpr inline Bits64 bit(int index) { + return index < 0 ? 0 : index >= 64 ? 0 : (1ll << index); + } +}; + +constexpr inline CharGroup_ charRange(char first, char last) { + // Create a parser which accepts any character in the range from `first` to `last`, inclusive. + // For example: `charRange('a', 'z')` matches all lower-case letters. The parser's result is the + // character matched. + // + // The returned object has methods which can be used to match more characters. The following + // produces a parser which accepts any letter as well as '_', '+', '-', and '.'. + // + // charRange('a', 'z').orRange('A', 'Z').orChar('_').orAny("+-.") + // + // You can also use `.invert()` to match the opposite set of characters. + + return CharGroup_().orRange(first, last); +} + +#if _MSC_VER +#define anyOfChars(chars) CharGroup_().orAny(chars) +// TODO(msvc): MSVC ICEs on the proper definition of `anyOfChars()`, which in turn prevents us from +// building the compiler or schema parser. We don't know why this happens, but Harris found that +// this horrible, horrible hack makes things work. This is awful, but it's better than nothing. +// Hopefully, MSVC will get fixed soon and we'll be able to remove this. +#else +constexpr inline CharGroup_ anyOfChars(const char* chars) { + // Returns a parser that accepts any of the characters in the given string (which should usually + // be a literal). The returned parser is of the same type as returned by `charRange()` -- see + // that function for more info. + + return CharGroup_().orAny(chars); +} +#endif + +// ======================================================================================= + +namespace _ { // private + +struct ArrayToString { + inline String operator()(const Array& arr) const { + return heapString(arr); + } +}; + +} // namespace _ (private) + +template +constexpr inline auto charsToString(SubParser&& subParser) + -> decltype(transform(kj::fwd(subParser), _::ArrayToString())) { + // Wraps a parser that returns Array such that it returns String instead. + return parse::transform(kj::fwd(subParser), _::ArrayToString()); +} + +// ======================================================================================= +// Basic character classes. + +constexpr auto alpha = charRange('a', 'z').orRange('A', 'Z'); +constexpr auto digit = charRange('0', '9'); +constexpr auto alphaNumeric = alpha.orGroup(digit); +constexpr auto nameStart = alpha.orChar('_'); +constexpr auto nameChar = alphaNumeric.orChar('_'); +constexpr auto hexDigit = charRange('0', '9').orRange('a', 'f').orRange('A', 'F'); +constexpr auto octDigit = charRange('0', '7'); +constexpr auto whitespaceChar = anyOfChars(" \f\n\r\t\v"); +constexpr auto controlChar = charRange(0, 0x1f).invert().orGroup(whitespaceChar).invert(); + +constexpr auto whitespace = many(anyOfChars(" \f\n\r\t\v")); + +constexpr auto discardWhitespace = discard(many(discard(anyOfChars(" \f\n\r\t\v")))); +// Like discard(whitespace) but avoids some memory allocation. + +// ======================================================================================= +// Identifiers + +namespace _ { // private + +struct IdentifierToString { + inline String operator()(char first, const Array& rest) const { + String result = heapString(rest.size() + 1); + result[0] = first; + memcpy(result.begin() + 1, rest.begin(), rest.size()); + return result; + } +}; + +} // namespace _ (private) + +constexpr auto identifier = transform(sequence(nameStart, many(nameChar)), _::IdentifierToString()); +// Parses an identifier (e.g. a C variable name). + +// ======================================================================================= +// Integers + +namespace _ { // private + +inline char parseDigit(char c) { + if (c < 'A') return c - '0'; + if (c < 'a') return c - 'A' + 10; + return c - 'a' + 10; +} + +template +struct ParseInteger { + inline uint64_t operator()(const Array& digits) const { + return operator()('0', digits); + } + uint64_t operator()(char first, const Array& digits) const { + uint64_t result = parseDigit(first); + for (char digit: digits) { + result = result * base + parseDigit(digit); + } + return result; + } +}; + + +} // namespace _ (private) + +constexpr auto integer = sequence( + oneOf( + transform(sequence(exactChar<'0'>(), exactChar<'x'>(), oneOrMore(hexDigit)), _::ParseInteger<16>()), + transform(sequence(exactChar<'0'>(), many(octDigit)), _::ParseInteger<8>()), + transform(sequence(charRange('1', '9'), many(digit)), _::ParseInteger<10>())), + notLookingAt(alpha.orAny("_."))); + +// ======================================================================================= +// Numbers (i.e. floats) + +namespace _ { // private + +struct ParseFloat { + double operator()(const Array& digits, + const Maybe>& fraction, + const Maybe, Array>>& exponent) const; +}; + +} // namespace _ (private) + +constexpr auto number = transform( + sequence( + oneOrMore(digit), + optional(sequence(exactChar<'.'>(), many(digit))), + optional(sequence(discard(anyOfChars("eE")), optional(anyOfChars("+-")), many(digit))), + notLookingAt(alpha.orAny("_."))), + _::ParseFloat()); + +// ======================================================================================= +// Quoted strings + +namespace _ { // private + +struct InterpretEscape { + char operator()(char c) const { + switch (c) { + case 'a': return '\a'; + case 'b': return '\b'; + case 'f': return '\f'; + case 'n': return '\n'; + case 'r': return '\r'; + case 't': return '\t'; + case 'v': return '\v'; + default: return c; + } + } +}; + +struct ParseHexEscape { + inline char operator()(char first, char second) const { + return (parseDigit(first) << 4) | parseDigit(second); + } +}; + +struct ParseHexByte { + inline byte operator()(char first, char second) const { + return (parseDigit(first) << 4) | parseDigit(second); + } +}; + +struct ParseOctEscape { + inline char operator()(char first, Maybe second, Maybe third) const { + char result = first - '0'; + KJ_IF_MAYBE(digit1, second) { + result = (result << 3) | (*digit1 - '0'); + KJ_IF_MAYBE(digit2, third) { + result = (result << 3) | (*digit2 - '0'); + } + } + return result; + } +}; + +} // namespace _ (private) + +constexpr auto escapeSequence = + sequence(exactChar<'\\'>(), oneOf( + transform(anyOfChars("abfnrtv'\"\\\?"), _::InterpretEscape()), + transform(sequence(exactChar<'x'>(), hexDigit, hexDigit), _::ParseHexEscape()), + transform(sequence(octDigit, optional(octDigit), optional(octDigit)), + _::ParseOctEscape()))); +// A parser that parses a C-string-style escape sequence (starting with a backslash). Returns +// a char. + +constexpr auto doubleQuotedString = charsToString(sequence( + exactChar<'\"'>(), + many(oneOf(anyOfChars("\\\n\"").invert(), escapeSequence)), + exactChar<'\"'>())); +// Parses a C-style double-quoted string. + +constexpr auto singleQuotedString = charsToString(sequence( + exactChar<'\''>(), + many(oneOf(anyOfChars("\\\n\'").invert(), escapeSequence)), + exactChar<'\''>())); +// Parses a C-style single-quoted string. + +constexpr auto doubleQuotedHexBinary = sequence( + exactChar<'0'>(), exactChar<'x'>(), exactChar<'\"'>(), + oneOrMore(transform(sequence(discardWhitespace, hexDigit, hexDigit), _::ParseHexByte())), + discardWhitespace, + exactChar<'\"'>()); +// Parses a double-quoted hex binary literal. Returns Array. + +} // namespace parse +} // namespace kj + +#endif // KJ_PARSE_CHAR_H_ diff --git a/phonelibs/capnp-cpp/include/kj/parse/common.h b/phonelibs/capnp-cpp/include/kj/parse/common.h new file mode 100644 index 00000000000000..3af3a8760d5e7e --- /dev/null +++ b/phonelibs/capnp-cpp/include/kj/parse/common.h @@ -0,0 +1,824 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +// Parser combinator framework! +// +// This file declares several functions which construct parsers, usually taking other parsers as +// input, thus making them parser combinators. +// +// A valid parser is any functor which takes a reference to an input cursor (defined below) as its +// input and returns a Maybe. The parser returns null on parse failure, or returns the parsed +// result on success. +// +// An "input cursor" is any type which implements the same interface as IteratorInput, below. Such +// a type acts as a pointer to the current input location. When a parser returns successfully, it +// will have updated the input cursor to point to the position just past the end of what was parsed. +// On failure, the cursor position is unspecified. + +#ifndef KJ_PARSE_COMMON_H_ +#define KJ_PARSE_COMMON_H_ + +#if defined(__GNUC__) && !KJ_HEADER_WARNINGS +#pragma GCC system_header +#endif + +#include "../common.h" +#include "../memory.h" +#include "../array.h" +#include "../tuple.h" +#include "../vector.h" +#if _MSC_VER +#include // result_of_t +#endif + +namespace kj { +namespace parse { + +template +class IteratorInput { + // A parser input implementation based on an iterator range. + +public: + IteratorInput(Iterator begin, Iterator end) + : parent(nullptr), pos(begin), end(end), best(begin) {} + explicit IteratorInput(IteratorInput& parent) + : parent(&parent), pos(parent.pos), end(parent.end), best(parent.pos) {} + ~IteratorInput() { + if (parent != nullptr) { + parent->best = kj::max(kj::max(pos, best), parent->best); + } + } + KJ_DISALLOW_COPY(IteratorInput); + + void advanceParent() { + parent->pos = pos; + } + void forgetParent() { + parent = nullptr; + } + + bool atEnd() { return pos == end; } + auto current() -> decltype(*instance()) { + KJ_IREQUIRE(!atEnd()); + return *pos; + } + auto consume() -> decltype(*instance()) { + KJ_IREQUIRE(!atEnd()); + return *pos++; + } + void next() { + KJ_IREQUIRE(!atEnd()); + ++pos; + } + + Iterator getBest() { return kj::max(pos, best); } + + Iterator getPosition() { return pos; } + +private: + IteratorInput* parent; + Iterator pos; + Iterator end; + Iterator best; // furthest we got with any sub-input +}; + +template struct OutputType_; +template struct OutputType_> { typedef T Type; }; +template +using OutputType = typename OutputType_< +#if _MSC_VER + std::result_of_t + // The instance() based version below results in: + // C2064: term does not evaluate to a function taking 1 arguments +#else + decltype(instance()(instance())) +#endif + >::Type; +// Synonym for the output type of a parser, given the parser type and the input type. + +// ======================================================================================= + +template +class ParserRef { + // Acts as a reference to some other parser, with simplified type. The referenced parser + // is polymorphic by virtual call rather than templates. For grammars of non-trivial size, + // it is important to inject refs into the grammar here and there to prevent the parser types + // from becoming ridiculous. Using too many of them can hurt performance, though. + +public: + ParserRef(): parser(nullptr), wrapper(nullptr) {} + ParserRef(const ParserRef&) = default; + ParserRef(ParserRef&&) = default; + ParserRef& operator=(const ParserRef& other) = default; + ParserRef& operator=(ParserRef&& other) = default; + + template + constexpr ParserRef(Other&& other) + : parser(&other), wrapper(&WrapperImplInstance>::instance) { + static_assert(kj::isReference(), "ParserRef should not be assigned to a temporary."); + } + + template + inline ParserRef& operator=(Other&& other) { + static_assert(kj::isReference(), "ParserRef should not be assigned to a temporary."); + parser = &other; + wrapper = &WrapperImplInstance>::instance; + return *this; + } + + KJ_ALWAYS_INLINE(Maybe operator()(Input& input) const) { + // Always inline in the hopes that this allows branch prediction to kick in so the virtual call + // doesn't hurt so much. + return wrapper->parse(parser, input); + } + +private: + struct Wrapper { + virtual Maybe parse(const void* parser, Input& input) const = 0; + }; + template + struct WrapperImpl: public Wrapper { + Maybe parse(const void* parser, Input& input) const override { + return (*reinterpret_cast(parser))(input); + } + }; + template + struct WrapperImplInstance { +#if _MSC_VER + // TODO(msvc): MSVC currently fails to initialize vtable pointers for constexpr values so + // we have to make this just const instead. + static const WrapperImpl instance; +#else + static constexpr WrapperImpl instance = WrapperImpl(); +#endif + }; + + const void* parser; + const Wrapper* wrapper; +}; + +template +template +#if _MSC_VER +const typename ParserRef::template WrapperImpl +ParserRef::WrapperImplInstance::instance = WrapperImpl(); +#else +constexpr typename ParserRef::template WrapperImpl +ParserRef::WrapperImplInstance::instance; +#endif + +template +constexpr ParserRef> ref(ParserImpl& impl) { + // Constructs a ParserRef. You must specify the input type explicitly, e.g. + // `ref(myParser)`. + + return ParserRef>(impl); +} + +// ------------------------------------------------------------------- +// any +// Output = one token + +class Any_ { +public: + template + Maybe().consume())>> operator()(Input& input) const { + if (input.atEnd()) { + return nullptr; + } else { + return input.consume(); + } + } +}; + +constexpr Any_ any = Any_(); +// A parser which matches any token and simply returns it. + +// ------------------------------------------------------------------- +// exactly() +// Output = Tuple<> + +template +class Exactly_ { +public: + explicit constexpr Exactly_(T&& expected): expected(expected) {} + + template + Maybe> operator()(Input& input) const { + if (input.atEnd() || input.current() != expected) { + return nullptr; + } else { + input.next(); + return Tuple<>(); + } + } + +private: + T expected; +}; + +template +constexpr Exactly_ exactly(T&& expected) { + // Constructs a parser which succeeds when the input is exactly the token specified. The + // result is always the empty tuple. + + return Exactly_(kj::fwd(expected)); +} + +// ------------------------------------------------------------------- +// exactlyConst() +// Output = Tuple<> + +template +class ExactlyConst_ { +public: + explicit constexpr ExactlyConst_() {} + + template + Maybe> operator()(Input& input) const { + if (input.atEnd() || input.current() != expected) { + return nullptr; + } else { + input.next(); + return Tuple<>(); + } + } +}; + +template +constexpr ExactlyConst_ exactlyConst() { + // Constructs a parser which succeeds when the input is exactly the token specified. The + // result is always the empty tuple. This parser is templated on the token value which may cause + // it to perform better -- or worse. Be sure to measure. + + return ExactlyConst_(); +} + +// ------------------------------------------------------------------- +// constResult() + +template +class ConstResult_ { +public: + explicit constexpr ConstResult_(SubParser&& subParser, Result&& result) + : subParser(kj::fwd(subParser)), result(kj::fwd(result)) {} + + template + Maybe operator()(Input& input) const { + if (subParser(input) == nullptr) { + return nullptr; + } else { + return result; + } + } + +private: + SubParser subParser; + Result result; +}; + +template +constexpr ConstResult_ constResult(SubParser&& subParser, Result&& result) { + // Constructs a parser which returns exactly `result` if `subParser` is successful. + return ConstResult_(kj::fwd(subParser), kj::fwd(result)); +} + +template +constexpr ConstResult_> discard(SubParser&& subParser) { + // Constructs a parser which wraps `subParser` but discards the result. + return constResult(kj::fwd(subParser), Tuple<>()); +} + +// ------------------------------------------------------------------- +// sequence() +// Output = Flattened Tuple of outputs of sub-parsers. + +template class Sequence_; + +template +class Sequence_ { +public: + template + explicit constexpr Sequence_(T&& firstSubParser, U&&... rest) + : first(kj::fwd(firstSubParser)), rest(kj::fwd(rest)...) {} + + // TODO(msvc): The trailing return types on `operator()` and `parseNext()` expose at least two + // bugs in MSVC: + // + // 1. An ICE. + // 2. 'error C2672: 'operator __surrogate_func': no matching overloaded function found)', + // which crops up in numerous places when trying to build the capnp command line tools. + // + // The only workaround I found for both bugs is to omit the trailing return types and instead + // rely on C++14's return type deduction. + + template + auto operator()(Input& input) const +#ifndef _MSC_VER + -> Maybe>(), + instance>()...))> +#endif + { + return parseNext(input); + } + + template + auto parseNext(Input& input, InitialParams&&... initialParams) const +#ifndef _MSC_VER + -> Maybe(initialParams)..., + instance>(), + instance>()...))> +#endif + { + KJ_IF_MAYBE(firstResult, first(input)) { + return rest.parseNext(input, kj::fwd(initialParams)..., + kj::mv(*firstResult)); + } else { + // TODO(msvc): MSVC depends on return type deduction to compile this function, so we need to + // help it deduce the right type on this code path. + return Maybe(initialParams)..., + instance>(), + instance>()...))>{nullptr}; + } + } + +private: + FirstSubParser first; + Sequence_ rest; +}; + +template <> +class Sequence_<> { +public: + template + Maybe> operator()(Input& input) const { + return parseNext(input); + } + + template + auto parseNext(Input& input, Params&&... params) const -> + Maybe(params)...))> { + return tuple(kj::fwd(params)...); + } +}; + +template +constexpr Sequence_ sequence(SubParsers&&... subParsers) { + // Constructs a parser that executes each of the parameter parsers in sequence and returns a + // tuple of their results. + + return Sequence_(kj::fwd(subParsers)...); +} + +// ------------------------------------------------------------------- +// many() +// Output = Array of output of sub-parser, or just a uint count if the sub-parser returns Tuple<>. + +template +class Many_ { + template > + struct Impl; +public: + explicit constexpr Many_(SubParser&& subParser) + : subParser(kj::fwd(subParser)) {} + + template + auto operator()(Input& input) const + -> decltype(Impl::apply(instance(), input)); + +private: + SubParser subParser; +}; + +template +template +struct Many_::Impl { + static Maybe> apply(const SubParser& subParser, Input& input) { + typedef Vector> Results; + Results results; + + while (!input.atEnd()) { + Input subInput(input); + + KJ_IF_MAYBE(subResult, subParser(subInput)) { + subInput.advanceParent(); + results.add(kj::mv(*subResult)); + } else { + break; + } + } + + if (atLeastOne && results.empty()) { + return nullptr; + } + + return results.releaseAsArray(); + } +}; + +template +template +struct Many_::Impl> { + // If the sub-parser output is Tuple<>, just return a count. + + static Maybe apply(const SubParser& subParser, Input& input) { + uint count = 0; + + while (!input.atEnd()) { + Input subInput(input); + + KJ_IF_MAYBE(subResult, subParser(subInput)) { + subInput.advanceParent(); + ++count; + } else { + break; + } + } + + if (atLeastOne && count == 0) { + return nullptr; + } + + return count; + } +}; + +template +template +auto Many_::operator()(Input& input) const + -> decltype(Impl::apply(instance(), input)) { + return Impl>::apply(subParser, input); +} + +template +constexpr Many_ many(SubParser&& subParser) { + // Constructs a parser that repeatedly executes the given parser until it fails, returning an + // Array of the results (or a uint count if `subParser` returns an empty tuple). + return Many_(kj::fwd(subParser)); +} + +template +constexpr Many_ oneOrMore(SubParser&& subParser) { + // Like `many()` but the parser must parse at least one item to be successful. + return Many_(kj::fwd(subParser)); +} + +// ------------------------------------------------------------------- +// times() +// Output = Array of output of sub-parser, or Tuple<> if sub-parser returns Tuple<>. + +template +class Times_ { + template > + struct Impl; +public: + explicit constexpr Times_(SubParser&& subParser, uint count) + : subParser(kj::fwd(subParser)), count(count) {} + + template + auto operator()(Input& input) const + -> decltype(Impl::apply(instance(), instance(), input)); + +private: + SubParser subParser; + uint count; +}; + +template +template +struct Times_::Impl { + static Maybe> apply(const SubParser& subParser, uint count, Input& input) { + auto results = heapArrayBuilder>(count); + + while (results.size() < count) { + if (input.atEnd()) { + return nullptr; + } else KJ_IF_MAYBE(subResult, subParser(input)) { + results.add(kj::mv(*subResult)); + } else { + return nullptr; + } + } + + return results.finish(); + } +}; + +template +template +struct Times_::Impl> { + // If the sub-parser output is Tuple<>, just return a count. + + static Maybe> apply(const SubParser& subParser, uint count, Input& input) { + uint actualCount = 0; + + while (actualCount < count) { + if (input.atEnd()) { + return nullptr; + } else KJ_IF_MAYBE(subResult, subParser(input)) { + ++actualCount; + } else { + return nullptr; + } + } + + return tuple(); + } +}; + +template +template +auto Times_::operator()(Input& input) const + -> decltype(Impl::apply(instance(), instance(), input)) { + return Impl>::apply(subParser, count, input); +} + +template +constexpr Times_ times(SubParser&& subParser, uint count) { + // Constructs a parser that repeats the subParser exactly `count` times. + return Times_(kj::fwd(subParser), count); +} + +// ------------------------------------------------------------------- +// optional() +// Output = Maybe + +template +class Optional_ { +public: + explicit constexpr Optional_(SubParser&& subParser) + : subParser(kj::fwd(subParser)) {} + + template + Maybe>> operator()(Input& input) const { + typedef Maybe> Result; + + Input subInput(input); + KJ_IF_MAYBE(subResult, subParser(subInput)) { + subInput.advanceParent(); + return Result(kj::mv(*subResult)); + } else { + return Result(nullptr); + } + } + +private: + SubParser subParser; +}; + +template +constexpr Optional_ optional(SubParser&& subParser) { + // Constructs a parser that accepts zero or one of the given sub-parser, returning a Maybe + // of the sub-parser's result. + return Optional_(kj::fwd(subParser)); +} + +// ------------------------------------------------------------------- +// oneOf() +// All SubParsers must have same output type, which becomes the output type of the +// OneOfParser. + +template +class OneOf_; + +template +class OneOf_ { +public: + explicit constexpr OneOf_(FirstSubParser&& firstSubParser, SubParsers&&... rest) + : first(kj::fwd(firstSubParser)), rest(kj::fwd(rest)...) {} + + template + Maybe> operator()(Input& input) const { + { + Input subInput(input); + Maybe> firstResult = first(subInput); + + if (firstResult != nullptr) { + subInput.advanceParent(); + return kj::mv(firstResult); + } + } + + // Hoping for some tail recursion here... + return rest(input); + } + +private: + FirstSubParser first; + OneOf_ rest; +}; + +template <> +class OneOf_<> { +public: + template + decltype(nullptr) operator()(Input& input) const { + return nullptr; + } +}; + +template +constexpr OneOf_ oneOf(SubParsers&&... parsers) { + // Constructs a parser that accepts one of a set of options. The parser behaves as the first + // sub-parser in the list which returns successfully. All of the sub-parsers must return the + // same type. + return OneOf_(kj::fwd(parsers)...); +} + +// ------------------------------------------------------------------- +// transform() +// Output = Result of applying transform functor to input value. If input is a tuple, it is +// unpacked to form the transformation parameters. + +template +struct Span { +public: + inline const Position& begin() const { return begin_; } + inline const Position& end() const { return end_; } + + Span() = default; + inline constexpr Span(Position&& begin, Position&& end): begin_(mv(begin)), end_(mv(end)) {} + +private: + Position begin_; + Position end_; +}; + +template +constexpr Span> span(Position&& start, Position&& end) { + return Span>(kj::fwd(start), kj::fwd(end)); +} + +template +class Transform_ { +public: + explicit constexpr Transform_(SubParser&& subParser, TransformFunc&& transform) + : subParser(kj::fwd(subParser)), transform(kj::fwd(transform)) {} + + template + Maybe(), + instance&&>()))> + operator()(Input& input) const { + KJ_IF_MAYBE(subResult, subParser(input)) { + return kj::apply(transform, kj::mv(*subResult)); + } else { + return nullptr; + } + } + +private: + SubParser subParser; + TransformFunc transform; +}; + +template +class TransformOrReject_ { +public: + explicit constexpr TransformOrReject_(SubParser&& subParser, TransformFunc&& transform) + : subParser(kj::fwd(subParser)), transform(kj::fwd(transform)) {} + + template + decltype(kj::apply(instance(), instance&&>())) + operator()(Input& input) const { + KJ_IF_MAYBE(subResult, subParser(input)) { + return kj::apply(transform, kj::mv(*subResult)); + } else { + return nullptr; + } + } + +private: + SubParser subParser; + TransformFunc transform; +}; + +template +class TransformWithLocation_ { +public: + explicit constexpr TransformWithLocation_(SubParser&& subParser, TransformFunc&& transform) + : subParser(kj::fwd(subParser)), transform(kj::fwd(transform)) {} + + template + Maybe(), + instance().getPosition())>>>(), + instance&&>()))> + operator()(Input& input) const { + auto start = input.getPosition(); + KJ_IF_MAYBE(subResult, subParser(input)) { + return kj::apply(transform, Span(kj::mv(start), input.getPosition()), + kj::mv(*subResult)); + } else { + return nullptr; + } + } + +private: + SubParser subParser; + TransformFunc transform; +}; + +template +constexpr Transform_ transform( + SubParser&& subParser, TransformFunc&& functor) { + // Constructs a parser which executes some other parser and then transforms the result by invoking + // `functor` on it. Typically `functor` is a lambda. It is invoked using `kj::apply`, + // meaning tuples will be unpacked as arguments. + return Transform_( + kj::fwd(subParser), kj::fwd(functor)); +} + +template +constexpr TransformOrReject_ transformOrReject( + SubParser&& subParser, TransformFunc&& functor) { + // Like `transform()` except that `functor` returns a `Maybe`. If it returns null, parsing fails, + // otherwise the parser's result is the content of the `Maybe`. + return TransformOrReject_( + kj::fwd(subParser), kj::fwd(functor)); +} + +template +constexpr TransformWithLocation_ transformWithLocation( + SubParser&& subParser, TransformFunc&& functor) { + // Like `transform` except that `functor` also takes a `Span` as its first parameter specifying + // the location of the parsed content. The span's position type is whatever the parser input's + // getPosition() returns. + return TransformWithLocation_( + kj::fwd(subParser), kj::fwd(functor)); +} + +// ------------------------------------------------------------------- +// notLookingAt() +// Fails if the given parser succeeds at the current location. + +template +class NotLookingAt_ { +public: + explicit constexpr NotLookingAt_(SubParser&& subParser) + : subParser(kj::fwd(subParser)) {} + + template + Maybe> operator()(Input& input) const { + Input subInput(input); + subInput.forgetParent(); + if (subParser(subInput) == nullptr) { + return Tuple<>(); + } else { + return nullptr; + } + } + +private: + SubParser subParser; +}; + +template +constexpr NotLookingAt_ notLookingAt(SubParser&& subParser) { + // Constructs a parser which fails at any position where the given parser succeeds. Otherwise, + // it succeeds without consuming any input and returns an empty tuple. + return NotLookingAt_(kj::fwd(subParser)); +} + +// ------------------------------------------------------------------- +// endOfInput() +// Output = Tuple<>, only succeeds if at end-of-input + +class EndOfInput_ { +public: + template + Maybe> operator()(Input& input) const { + if (input.atEnd()) { + return Tuple<>(); + } else { + return nullptr; + } + } +}; + +constexpr EndOfInput_ endOfInput = EndOfInput_(); +// A parser that succeeds only if it is called with no input. + +} // namespace parse +} // namespace kj + +#endif // KJ_PARSE_COMMON_H_ diff --git a/phonelibs/capnp-cpp/include/kj/refcount.h b/phonelibs/capnp-cpp/include/kj/refcount.h new file mode 100644 index 00000000000000..a24e4bf5b95e7d --- /dev/null +++ b/phonelibs/capnp-cpp/include/kj/refcount.h @@ -0,0 +1,107 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#include "memory.h" + +#ifndef KJ_REFCOUNT_H_ +#define KJ_REFCOUNT_H_ + +#if defined(__GNUC__) && !KJ_HEADER_WARNINGS +#pragma GCC system_header +#endif + +namespace kj { + +class Refcounted: private Disposer { + // Subclass this to create a class that contains a reference count. Then, use + // `kj::refcounted()` to allocate a new refcounted pointer. + // + // Do NOT use this lightly. Refcounting is a crutch. Good designs should strive to make object + // ownership clear, so that refcounting is not necessary. All that said, reference counting can + // sometimes simplify code that would otherwise become convoluted with explicit ownership, even + // when ownership relationships are clear at an abstract level. + // + // NOT THREADSAFE: This refcounting implementation assumes that an object's references are + // manipulated only in one thread, because atomic (thread-safe) refcounting is surprisingly slow. + // + // In general, abstract classes should _not_ subclass this. The concrete class at the bottom + // of the hierarchy should be the one to decide how it implements refcounting. Interfaces should + // expose only an `addRef()` method that returns `Own`. There are two reasons for + // this rule: + // 1. Interfaces would need to virtually inherit Refcounted, otherwise two refcounted interfaces + // could not be inherited by the same subclass. Virtual inheritance is awkward and + // inefficient. + // 2. An implementation may decide that it would rather return a copy than a refcount, or use + // some other strategy. + // + // TODO(cleanup): Rethink above. Virtual inheritance is not necessarily that bad. OTOH, a + // virtual function call for every refcount is sad in its own way. A Ref type to replace + // Own could also be nice. + +public: + virtual ~Refcounted() noexcept(false); + + inline bool isShared() const { return refcount > 1; } + // Check if there are multiple references to this object. This is sometimes useful for deciding + // whether it's safe to modify the object vs. make a copy. + +private: + mutable uint refcount = 0; + // "mutable" because disposeImpl() is const. Bleh. + + void disposeImpl(void* pointer) const override; + template + static Own addRefInternal(T* object); + + template + friend Own addRef(T& object); + template + friend Own refcounted(Params&&... params); +}; + +template +inline Own refcounted(Params&&... params) { + // Allocate a new refcounted instance of T, passing `params` to its constructor. Returns an + // initial reference to the object. More references can be created with `kj::addRef()`. + + return Refcounted::addRefInternal(new T(kj::fwd(params)...)); +} + +template +Own addRef(T& object) { + // Return a new reference to `object`, which must subclass Refcounted and have been allocated + // using `kj::refcounted<>()`. It is suggested that subclasses implement a non-static addRef() + // method which wraps this and returns the appropriate type. + + KJ_IREQUIRE(object.Refcounted::refcount > 0, "Object not allocated with kj::refcounted()."); + return Refcounted::addRefInternal(&object); +} + +template +Own Refcounted::addRefInternal(T* object) { + Refcounted* refcounted = object; + ++refcounted->refcount; + return Own(object, *refcounted); +} + +} // namespace kj + +#endif // KJ_REFCOUNT_H_ diff --git a/phonelibs/capnp-cpp/include/kj/std/iostream.h b/phonelibs/capnp-cpp/include/kj/std/iostream.h new file mode 100644 index 00000000000000..627e0fcf8622fe --- /dev/null +++ b/phonelibs/capnp-cpp/include/kj/std/iostream.h @@ -0,0 +1,88 @@ +// Copyright (c) 2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +/* + * Compatibility layer for stdlib iostream + */ + +#ifndef KJ_STD_IOSTREAM_H_ +#define KJ_STD_IOSTREAM_H_ + +#if defined(__GNUC__) && !KJ_HEADER_WARNINGS +#pragma GCC system_header +#endif + +#include "../io.h" +#include + +namespace kj { +namespace std { + +class StdOutputStream: public kj::OutputStream { + +public: + explicit StdOutputStream(::std::ostream& stream) : stream_(stream) {} + ~StdOutputStream() noexcept(false) {} + + virtual void write(const void* src, size_t size) override { + // Always writes the full size. + + stream_.write((char*)src, size); + } + + virtual void write(ArrayPtr> pieces) override { + // Equivalent to write()ing each byte array in sequence, which is what the + // default implementation does. Override if you can do something better, + // e.g. use writev() to do the write in a single syscall. + + for (auto piece : pieces) { + write(piece.begin(), piece.size()); + } + } + +private: + ::std::ostream& stream_; + +}; + +class StdInputStream: public kj::InputStream { + +public: + explicit StdInputStream(::std::istream& stream) : stream_(stream) {} + ~StdInputStream() noexcept(false) {} + + virtual size_t tryRead( + void* buffer, size_t minBytes, size_t maxBytes) override { + // Like read(), but may return fewer than minBytes on EOF. + + stream_.read((char*)buffer, maxBytes); + return stream_.gcount(); + } + +private: + ::std::istream& stream_; + +}; + +} // namespace std +} // namespace kj + +#endif // KJ_STD_IOSTREAM_H_ diff --git a/phonelibs/capnp-cpp/include/kj/string-tree.h b/phonelibs/capnp-cpp/include/kj/string-tree.h new file mode 100644 index 00000000000000..70a46319ef82a5 --- /dev/null +++ b/phonelibs/capnp-cpp/include/kj/string-tree.h @@ -0,0 +1,212 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef KJ_STRING_TREE_H_ +#define KJ_STRING_TREE_H_ + +#if defined(__GNUC__) && !KJ_HEADER_WARNINGS +#pragma GCC system_header +#endif + +#include "string.h" + +namespace kj { + +class StringTree { + // A long string, represented internally as a tree of strings. This data structure is like a + // String, but optimized for concatenation and iteration at the expense of seek time. The + // structure is intended to be used for building large text blobs from many small pieces, where + // repeatedly concatenating smaller strings into larger ones would waste copies. This structure + // is NOT intended for use cases requiring random access or computing substrings. For those, + // you should use a Rope, which is a much more complicated data structure. + // + // The proper way to construct a StringTree is via kj::strTree(...), which works just like + // kj::str(...) but returns a StringTree rather than a String. + // + // KJ_STRINGIFY() functions that construct large strings from many smaller strings are encouraged + // to return StringTree rather than a flat char container. + +public: + inline StringTree(): size_(0) {} + inline StringTree(String&& text): size_(text.size()), text(kj::mv(text)) {} + + StringTree(Array&& pieces, StringPtr delim); + // Build a StringTree by concatenating the given pieces, delimited by the given delimiter + // (e.g. ", "). + + inline size_t size() const { return size_; } + + template + void visit(Func&& func) const; + + String flatten() const; + // Return the contents as a string. + + // TODO(someday): flatten() when *this is an rvalue and when branches.size() == 0 could simply + // return `kj::mv(text)`. Requires reference qualifiers (Clang 3.3 / GCC 4.8). + + void flattenTo(char* __restrict__ target) const; + // Copy the contents to the given character array. Does not add a NUL terminator. + +private: + size_t size_; + String text; + + struct Branch; + Array branches; // In order. + + inline void fill(char* pos, size_t branchIndex); + template + void fill(char* pos, size_t branchIndex, First&& first, Rest&&... rest); + template + void fill(char* pos, size_t branchIndex, StringTree&& first, Rest&&... rest); + template + void fill(char* pos, size_t branchIndex, Array&& first, Rest&&... rest); + template + void fill(char* pos, size_t branchIndex, String&& first, Rest&&... rest); + + template + static StringTree concat(Params&&... params); + static StringTree&& concat(StringTree&& param) { return kj::mv(param); } + + template + static inline size_t flatSize(const T& t) { return t.size(); } + static inline size_t flatSize(String&& s) { return 0; } + static inline size_t flatSize(StringTree&& s) { return 0; } + + template + static inline size_t branchCount(const T& t) { return 0; } + static inline size_t branchCount(String&& s) { return 1; } + static inline size_t branchCount(StringTree&& s) { return 1; } + + template + friend StringTree strTree(Params&&... params); +}; + +inline StringTree&& KJ_STRINGIFY(StringTree&& tree) { return kj::mv(tree); } +inline const StringTree& KJ_STRINGIFY(const StringTree& tree) { return tree; } + +inline StringTree KJ_STRINGIFY(Array&& trees) { return StringTree(kj::mv(trees), ""); } + +template +StringTree strTree(Params&&... params); +// Build a StringTree by stringifying the given parameters and concatenating the results. +// If any of the parameters stringify to StringTree rvalues, they will be incorporated as +// branches to avoid a copy. + +// ======================================================================================= +// Inline implementation details + +namespace _ { // private + +template +char* fill(char* __restrict__ target, const StringTree& first, Rest&&... rest) { + // Make str() work with stringifiers that return StringTree by patching fill(). + + first.flattenTo(target); + return fill(target + first.size(), kj::fwd(rest)...); +} + +template constexpr bool isStringTree() { return false; } +template <> constexpr bool isStringTree() { return true; } + +inline StringTree&& toStringTreeOrCharSequence(StringTree&& tree) { return kj::mv(tree); } +inline StringTree toStringTreeOrCharSequence(String&& str) { return StringTree(kj::mv(str)); } + +template +inline auto toStringTreeOrCharSequence(T&& value) + -> decltype(toCharSequence(kj::fwd(value))) { + static_assert(!isStringTree>(), + "When passing a StringTree into kj::strTree(), either pass it by rvalue " + "(use kj::mv(value)) or explicitly call value.flatten() to make a copy."); + + return toCharSequence(kj::fwd(value)); +} + +} // namespace _ (private) + +struct StringTree::Branch { + size_t index; + // Index in `text` where this branch should be inserted. + + StringTree content; +}; + +template +void StringTree::visit(Func&& func) const { + size_t pos = 0; + for (auto& branch: branches) { + if (branch.index > pos) { + func(text.slice(pos, branch.index)); + pos = branch.index; + } + branch.content.visit(func); + } + if (text.size() > pos) { + func(text.slice(pos, text.size())); + } +} + +inline void StringTree::fill(char* pos, size_t branchIndex) { + KJ_IREQUIRE(pos == text.end() && branchIndex == branches.size(), + kj::str(text.end() - pos, ' ', branches.size() - branchIndex).cStr()); +} + +template +void StringTree::fill(char* pos, size_t branchIndex, First&& first, Rest&&... rest) { + pos = _::fill(pos, kj::fwd(first)); + fill(pos, branchIndex, kj::fwd(rest)...); +} + +template +void StringTree::fill(char* pos, size_t branchIndex, StringTree&& first, Rest&&... rest) { + branches[branchIndex].index = pos - text.begin(); + branches[branchIndex].content = kj::mv(first); + fill(pos, branchIndex + 1, kj::fwd(rest)...); +} + +template +void StringTree::fill(char* pos, size_t branchIndex, String&& first, Rest&&... rest) { + branches[branchIndex].index = pos - text.begin(); + branches[branchIndex].content = StringTree(kj::mv(first)); + fill(pos, branchIndex + 1, kj::fwd(rest)...); +} + +template +StringTree StringTree::concat(Params&&... params) { + StringTree result; + result.size_ = _::sum({params.size()...}); + result.text = heapString( + _::sum({StringTree::flatSize(kj::fwd(params))...})); + result.branches = heapArray( + _::sum({StringTree::branchCount(kj::fwd(params))...})); + result.fill(result.text.begin(), 0, kj::fwd(params)...); + return result; +} + +template +StringTree strTree(Params&&... params) { + return StringTree::concat(_::toStringTreeOrCharSequence(kj::fwd(params))...); +} + +} // namespace kj + +#endif // KJ_STRING_TREE_H_ diff --git a/phonelibs/capnp-cpp/include/kj/string.h b/phonelibs/capnp-cpp/include/kj/string.h new file mode 100644 index 00000000000000..9048be24170e5b --- /dev/null +++ b/phonelibs/capnp-cpp/include/kj/string.h @@ -0,0 +1,534 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef KJ_STRING_H_ +#define KJ_STRING_H_ + +#if defined(__GNUC__) && !KJ_HEADER_WARNINGS +#pragma GCC system_header +#endif + +#include +#include "array.h" +#include + +namespace kj { + +class StringPtr; +class String; + +class StringTree; // string-tree.h + +// Our STL string SFINAE trick does not work with GCC 4.7, but it works with Clang and GCC 4.8, so +// we'll just preprocess it out if not supported. +#if __clang__ || __GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) || _MSC_VER +#define KJ_COMPILER_SUPPORTS_STL_STRING_INTEROP 1 +#endif + +// ======================================================================================= +// StringPtr -- A NUL-terminated ArrayPtr containing UTF-8 text. +// +// NUL bytes are allowed to appear before the end of the string. The only requirement is that +// a NUL byte appear immediately after the last byte of the content. This terminator byte is not +// counted in the string's size. + +class StringPtr { +public: + inline StringPtr(): content("", 1) {} + inline StringPtr(decltype(nullptr)): content("", 1) {} + inline StringPtr(const char* value): content(value, strlen(value) + 1) {} + inline StringPtr(const char* value, size_t size): content(value, size + 1) { + KJ_IREQUIRE(value[size] == '\0', "StringPtr must be NUL-terminated."); + } + inline StringPtr(const char* begin, const char* end): StringPtr(begin, end - begin) {} + inline StringPtr(const String& value); + +#if KJ_COMPILER_SUPPORTS_STL_STRING_INTEROP + template ().c_str())> + inline StringPtr(const T& t): StringPtr(t.c_str()) {} + // Allow implicit conversion from any class that has a c_str() method (namely, std::string). + // We use a template trick to detect std::string in order to avoid including the header for + // those who don't want it. + + template ().c_str())> + inline operator T() const { return cStr(); } + // Allow implicit conversion to any class that has a c_str() method (namely, std::string). + // We use a template trick to detect std::string in order to avoid including the header for + // those who don't want it. +#endif + + inline operator ArrayPtr() const; + inline ArrayPtr asArray() const; + inline ArrayPtr asBytes() const { return asArray().asBytes(); } + // Result does not include NUL terminator. + + inline const char* cStr() const { return content.begin(); } + // Returns NUL-terminated string. + + inline size_t size() const { return content.size() - 1; } + // Result does not include NUL terminator. + + inline char operator[](size_t index) const { return content[index]; } + + inline const char* begin() const { return content.begin(); } + inline const char* end() const { return content.end() - 1; } + + inline bool operator==(decltype(nullptr)) const { return content.size() <= 1; } + inline bool operator!=(decltype(nullptr)) const { return content.size() > 1; } + + inline bool operator==(const StringPtr& other) const; + inline bool operator!=(const StringPtr& other) const { return !(*this == other); } + inline bool operator< (const StringPtr& other) const; + inline bool operator> (const StringPtr& other) const { return other < *this; } + inline bool operator<=(const StringPtr& other) const { return !(other < *this); } + inline bool operator>=(const StringPtr& other) const { return !(*this < other); } + + inline StringPtr slice(size_t start) const; + inline ArrayPtr slice(size_t start, size_t end) const; + // A string slice is only NUL-terminated if it is a suffix, so slice() has a one-parameter + // version that assumes end = size(). + + inline bool startsWith(const StringPtr& other) const; + inline bool endsWith(const StringPtr& other) const; + + inline Maybe findFirst(char c) const; + inline Maybe findLast(char c) const; + + template + T parseAs() const; + // Parse string as template number type. + // Integer numbers prefixed by "0x" and "0X" are parsed in base 16 (like strtoi with base 0). + // Integer numbers prefixed by "0" are parsed in base 10 (unlike strtoi with base 0). + // Overflowed integer numbers throw exception. + // Overflowed floating numbers return inf. + +private: + inline StringPtr(ArrayPtr content): content(content) {} + + ArrayPtr content; +}; + +inline bool operator==(const char* a, const StringPtr& b) { return b == a; } +inline bool operator!=(const char* a, const StringPtr& b) { return b != a; } + +template <> char StringPtr::parseAs() const; +template <> signed char StringPtr::parseAs() const; +template <> unsigned char StringPtr::parseAs() const; +template <> short StringPtr::parseAs() const; +template <> unsigned short StringPtr::parseAs() const; +template <> int StringPtr::parseAs() const; +template <> unsigned StringPtr::parseAs() const; +template <> long StringPtr::parseAs() const; +template <> unsigned long StringPtr::parseAs() const; +template <> long long StringPtr::parseAs() const; +template <> unsigned long long StringPtr::parseAs() const; +template <> float StringPtr::parseAs() const; +template <> double StringPtr::parseAs() const; + +// ======================================================================================= +// String -- A NUL-terminated Array containing UTF-8 text. +// +// NUL bytes are allowed to appear before the end of the string. The only requirement is that +// a NUL byte appear immediately after the last byte of the content. This terminator byte is not +// counted in the string's size. +// +// To allocate a String, you must call kj::heapString(). We do not implement implicit copying to +// the heap because this hides potential inefficiency from the developer. + +class String { +public: + String() = default; + inline String(decltype(nullptr)): content(nullptr) {} + inline String(char* value, size_t size, const ArrayDisposer& disposer); + // Does not copy. `size` does not include NUL terminator, but `value` must be NUL-terminated. + inline explicit String(Array buffer); + // Does not copy. Requires `buffer` ends with `\0`. + + inline operator ArrayPtr(); + inline operator ArrayPtr() const; + inline ArrayPtr asArray(); + inline ArrayPtr asArray() const; + inline ArrayPtr asBytes() { return asArray().asBytes(); } + inline ArrayPtr asBytes() const { return asArray().asBytes(); } + // Result does not include NUL terminator. + + inline Array releaseArray() { return kj::mv(content); } + // Disowns the backing array (which includes the NUL terminator) and returns it. The String value + // is clobbered (as if moved away). + + inline const char* cStr() const; + + inline size_t size() const; + // Result does not include NUL terminator. + + inline char operator[](size_t index) const; + inline char& operator[](size_t index); + + inline char* begin(); + inline char* end(); + inline const char* begin() const; + inline const char* end() const; + + inline bool operator==(decltype(nullptr)) const { return content.size() <= 1; } + inline bool operator!=(decltype(nullptr)) const { return content.size() > 1; } + + inline bool operator==(const StringPtr& other) const { return StringPtr(*this) == other; } + inline bool operator!=(const StringPtr& other) const { return StringPtr(*this) != other; } + inline bool operator< (const StringPtr& other) const { return StringPtr(*this) < other; } + inline bool operator> (const StringPtr& other) const { return StringPtr(*this) > other; } + inline bool operator<=(const StringPtr& other) const { return StringPtr(*this) <= other; } + inline bool operator>=(const StringPtr& other) const { return StringPtr(*this) >= other; } + + inline bool startsWith(const StringPtr& other) const { return StringPtr(*this).startsWith(other);} + inline bool endsWith(const StringPtr& other) const { return StringPtr(*this).endsWith(other); } + + inline StringPtr slice(size_t start) const { return StringPtr(*this).slice(start); } + inline ArrayPtr slice(size_t start, size_t end) const { + return StringPtr(*this).slice(start, end); + } + + inline Maybe findFirst(char c) const { return StringPtr(*this).findFirst(c); } + inline Maybe findLast(char c) const { return StringPtr(*this).findLast(c); } + + template + T parseAs() const { return StringPtr(*this).parseAs(); } + // Parse as number + +private: + Array content; +}; + +inline bool operator==(const char* a, const String& b) { return b == a; } +inline bool operator!=(const char* a, const String& b) { return b != a; } + +String heapString(size_t size); +// Allocate a String of the given size on the heap, not including NUL terminator. The NUL +// terminator will be initialized automatically but the rest of the content is not initialized. + +String heapString(const char* value); +String heapString(const char* value, size_t size); +String heapString(StringPtr value); +String heapString(const String& value); +String heapString(ArrayPtr value); +// Allocates a copy of the given value on the heap. + +// ======================================================================================= +// Magic str() function which transforms parameters to text and concatenates them into one big +// String. + +namespace _ { // private + +inline size_t sum(std::initializer_list nums) { + size_t result = 0; + for (auto num: nums) { + result += num; + } + return result; +} + +inline char* fill(char* ptr) { return ptr; } + +template +char* fill(char* __restrict__ target, const StringTree& first, Rest&&... rest); +// Make str() work with stringifiers that return StringTree by patching fill(). +// +// Defined in string-tree.h. + +template +char* fill(char* __restrict__ target, const First& first, Rest&&... rest) { + auto i = first.begin(); + auto end = first.end(); + while (i != end) { + *target++ = *i++; + } + return fill(target, kj::fwd(rest)...); +} + +template +String concat(Params&&... params) { + // Concatenate a bunch of containers into a single Array. The containers can be anything that + // is iterable and whose elements can be converted to `char`. + + String result = heapString(sum({params.size()...})); + fill(result.begin(), kj::fwd(params)...); + return result; +} + +inline String concat(String&& arr) { + return kj::mv(arr); +} + +struct Stringifier { + // This is a dummy type with only one instance: STR (below). To make an arbitrary type + // stringifiable, define `operator*(Stringifier, T)` to return an iterable container of `char`. + // The container type must have a `size()` method. Be sure to declare the operator in the same + // namespace as `T` **or** in the global scope. + // + // A more usual way to accomplish what we're doing here would be to require that you define + // a function like `toString(T)` and then rely on argument-dependent lookup. However, this has + // the problem that it pollutes other people's namespaces and even the global namespace. For + // example, some other project may already have functions called `toString` which do something + // different. Declaring `operator*` with `Stringifier` as the left operand cannot conflict with + // anything. + + inline ArrayPtr operator*(ArrayPtr s) const { return s; } + inline ArrayPtr operator*(ArrayPtr s) const { return s; } + inline ArrayPtr operator*(const Array& s) const { return s; } + inline ArrayPtr operator*(const Array& s) const { return s; } + template + inline ArrayPtr operator*(const CappedArray& s) const { return s; } + template + inline ArrayPtr operator*(const FixedArray& s) const { return s; } + inline ArrayPtr operator*(const char* s) const { return arrayPtr(s, strlen(s)); } + inline ArrayPtr operator*(const String& s) const { return s.asArray(); } + inline ArrayPtr operator*(const StringPtr& s) const { return s.asArray(); } + + inline Range operator*(const Range& r) const { return r; } + inline Repeat operator*(const Repeat& r) const { return r; } + + inline FixedArray operator*(char c) const { + FixedArray result; + result[0] = c; + return result; + } + + StringPtr operator*(decltype(nullptr)) const; + StringPtr operator*(bool b) const; + + CappedArray operator*(signed char i) const; + CappedArray operator*(unsigned char i) const; + CappedArray operator*(short i) const; + CappedArray operator*(unsigned short i) const; + CappedArray operator*(int i) const; + CappedArray operator*(unsigned int i) const; + CappedArray operator*(long i) const; + CappedArray operator*(unsigned long i) const; + CappedArray operator*(long long i) const; + CappedArray operator*(unsigned long long i) const; + CappedArray operator*(float f) const; + CappedArray operator*(double f) const; + CappedArray operator*(const void* s) const; + + template + String operator*(ArrayPtr arr) const; + template + String operator*(const Array& arr) const; + +#if KJ_COMPILER_SUPPORTS_STL_STRING_INTEROP // supports expression SFINAE? + template ().toString())> + inline Result operator*(T&& value) const { return kj::fwd(value).toString(); } +#endif +}; +static KJ_CONSTEXPR(const) Stringifier STR = Stringifier(); + +} // namespace _ (private) + +template +auto toCharSequence(T&& value) -> decltype(_::STR * kj::fwd(value)) { + // Returns an iterable of chars that represent a textual representation of the value, suitable + // for debugging. + // + // Most users should use str() instead, but toCharSequence() may occasionally be useful to avoid + // heap allocation overhead that str() implies. + // + // To specialize this function for your type, see KJ_STRINGIFY. + + return _::STR * kj::fwd(value); +} + +CappedArray hex(unsigned char i); +CappedArray hex(unsigned short i); +CappedArray hex(unsigned int i); +CappedArray hex(unsigned long i); +CappedArray hex(unsigned long long i); + +template +String str(Params&&... params) { + // Magic function which builds a string from a bunch of arbitrary values. Example: + // str(1, " / ", 2, " = ", 0.5) + // returns: + // "1 / 2 = 0.5" + // To teach `str` how to stringify a type, see `Stringifier`. + + return _::concat(toCharSequence(kj::fwd(params))...); +} + +inline String str(String&& s) { return mv(s); } +// Overload to prevent redundant allocation. + +template +String strArray(T&& arr, const char* delim) { + size_t delimLen = strlen(delim); + KJ_STACK_ARRAY(decltype(_::STR * arr[0]), pieces, kj::size(arr), 8, 32); + size_t size = 0; + for (size_t i = 0; i < kj::size(arr); i++) { + if (i > 0) size += delimLen; + pieces[i] = _::STR * arr[i]; + size += pieces[i].size(); + } + + String result = heapString(size); + char* pos = result.begin(); + for (size_t i = 0; i < kj::size(arr); i++) { + if (i > 0) { + memcpy(pos, delim, delimLen); + pos += delimLen; + } + pos = _::fill(pos, pieces[i]); + } + return result; +} + +namespace _ { // private + +template +inline String Stringifier::operator*(ArrayPtr arr) const { + return strArray(arr, ", "); +} + +template +inline String Stringifier::operator*(const Array& arr) const { + return strArray(arr, ", "); +} + +} // namespace _ (private) + +#define KJ_STRINGIFY(...) operator*(::kj::_::Stringifier, __VA_ARGS__) +// Defines a stringifier for a custom type. Example: +// +// class Foo {...}; +// inline StringPtr KJ_STRINGIFY(const Foo& foo) { return foo.name(); } +// +// This allows Foo to be passed to str(). +// +// The function should be declared either in the same namespace as the target type or in the global +// namespace. It can return any type which is an iterable container of chars. + +// ======================================================================================= +// Inline implementation details. + +inline StringPtr::StringPtr(const String& value): content(value.begin(), value.size() + 1) {} + +inline StringPtr::operator ArrayPtr() const { + return content.slice(0, content.size() - 1); +} + +inline ArrayPtr StringPtr::asArray() const { + return content.slice(0, content.size() - 1); +} + +inline bool StringPtr::operator==(const StringPtr& other) const { + return content.size() == other.content.size() && + memcmp(content.begin(), other.content.begin(), content.size() - 1) == 0; +} + +inline bool StringPtr::operator<(const StringPtr& other) const { + bool shorter = content.size() < other.content.size(); + int cmp = memcmp(content.begin(), other.content.begin(), + shorter ? content.size() : other.content.size()); + return cmp < 0 || (cmp == 0 && shorter); +} + +inline StringPtr StringPtr::slice(size_t start) const { + return StringPtr(content.slice(start, content.size())); +} +inline ArrayPtr StringPtr::slice(size_t start, size_t end) const { + return content.slice(start, end); +} + +inline bool StringPtr::startsWith(const StringPtr& other) const { + return other.content.size() <= content.size() && + memcmp(content.begin(), other.content.begin(), other.size()) == 0; +} +inline bool StringPtr::endsWith(const StringPtr& other) const { + return other.content.size() <= content.size() && + memcmp(end() - other.size(), other.content.begin(), other.size()) == 0; +} + +inline Maybe StringPtr::findFirst(char c) const { + const char* pos = reinterpret_cast(memchr(content.begin(), c, size())); + if (pos == nullptr) { + return nullptr; + } else { + return pos - content.begin(); + } +} + +inline Maybe StringPtr::findLast(char c) const { + for (size_t i = size(); i > 0; --i) { + if (content[i-1] == c) { + return i-1; + } + } + return nullptr; +} + +inline String::operator ArrayPtr() { + return content == nullptr ? ArrayPtr(nullptr) : content.slice(0, content.size() - 1); +} +inline String::operator ArrayPtr() const { + return content == nullptr ? ArrayPtr(nullptr) : content.slice(0, content.size() - 1); +} + +inline ArrayPtr String::asArray() { + return content == nullptr ? ArrayPtr(nullptr) : content.slice(0, content.size() - 1); +} +inline ArrayPtr String::asArray() const { + return content == nullptr ? ArrayPtr(nullptr) : content.slice(0, content.size() - 1); +} + +inline const char* String::cStr() const { return content == nullptr ? "" : content.begin(); } + +inline size_t String::size() const { return content == nullptr ? 0 : content.size() - 1; } + +inline char String::operator[](size_t index) const { return content[index]; } +inline char& String::operator[](size_t index) { return content[index]; } + +inline char* String::begin() { return content == nullptr ? nullptr : content.begin(); } +inline char* String::end() { return content == nullptr ? nullptr : content.end() - 1; } +inline const char* String::begin() const { return content == nullptr ? nullptr : content.begin(); } +inline const char* String::end() const { return content == nullptr ? nullptr : content.end() - 1; } + +inline String::String(char* value, size_t size, const ArrayDisposer& disposer) + : content(value, size + 1, disposer) { + KJ_IREQUIRE(value[size] == '\0', "String must be NUL-terminated."); +} + +inline String::String(Array buffer): content(kj::mv(buffer)) { + KJ_IREQUIRE(content.size() > 0 && content.back() == '\0', "String must be NUL-terminated."); +} + +inline String heapString(const char* value) { + return heapString(value, strlen(value)); +} +inline String heapString(StringPtr value) { + return heapString(value.begin(), value.size()); +} +inline String heapString(const String& value) { + return heapString(value.begin(), value.size()); +} +inline String heapString(ArrayPtr value) { + return heapString(value.begin(), value.size()); +} + +} // namespace kj + +#endif // KJ_STRING_H_ diff --git a/phonelibs/capnp-cpp/include/kj/test.h b/phonelibs/capnp-cpp/include/kj/test.h new file mode 100644 index 00000000000000..69e1c80840b85d --- /dev/null +++ b/phonelibs/capnp-cpp/include/kj/test.h @@ -0,0 +1,167 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef KJ_TEST_H_ +#define KJ_TEST_H_ + +#if defined(__GNUC__) && !KJ_HEADER_WARNINGS +#pragma GCC system_header +#endif + +#include "debug.h" +#include "vector.h" +#include "function.h" + +namespace kj { + +class TestRunner; + +class TestCase { +public: + TestCase(const char* file, uint line, const char* description); + ~TestCase(); + + virtual void run() = 0; + +private: + const char* file; + uint line; + const char* description; + TestCase* next; + TestCase** prev; + bool matchedFilter; + + friend class TestRunner; +}; + +#define KJ_TEST(description) \ + /* Make sure the linker fails if tests are not in anonymous namespaces. */ \ + extern int KJ_CONCAT(YouMustWrapTestsInAnonymousNamespace, __COUNTER__) KJ_UNUSED; \ + class KJ_UNIQUE_NAME(TestCase): public ::kj::TestCase { \ + public: \ + KJ_UNIQUE_NAME(TestCase)(): ::kj::TestCase(__FILE__, __LINE__, description) {} \ + void run() override; \ + } KJ_UNIQUE_NAME(testCase); \ + void KJ_UNIQUE_NAME(TestCase)::run() + +#if _MSC_VER +#define KJ_INDIRECT_EXPAND(m, vargs) m vargs +#define KJ_FAIL_EXPECT(...) \ + KJ_INDIRECT_EXPAND(KJ_LOG, (ERROR , __VA_ARGS__)); +#define KJ_EXPECT(cond, ...) \ + if (cond); else KJ_INDIRECT_EXPAND(KJ_FAIL_EXPECT, ("failed: expected " #cond , __VA_ARGS__)) +#else +#define KJ_FAIL_EXPECT(...) \ + KJ_LOG(ERROR, ##__VA_ARGS__); +#define KJ_EXPECT(cond, ...) \ + if (cond); else KJ_FAIL_EXPECT("failed: expected " #cond, ##__VA_ARGS__) +#endif + +#define KJ_EXPECT_THROW_RECOVERABLE(type, code) \ + do { \ + KJ_IF_MAYBE(e, ::kj::runCatchingExceptions([&]() { code; })) { \ + KJ_EXPECT(e->getType() == ::kj::Exception::Type::type, \ + "code threw wrong exception type: " #code, e->getType()); \ + } else { \ + KJ_FAIL_EXPECT("code did not throw: " #code); \ + } \ + } while (false) + +#define KJ_EXPECT_THROW_RECOVERABLE_MESSAGE(message, code) \ + do { \ + KJ_IF_MAYBE(e, ::kj::runCatchingExceptions([&]() { code; })) { \ + KJ_EXPECT(::kj::_::hasSubstring(e->getDescription(), message), \ + "exception description didn't contain expected substring", e->getDescription()); \ + } else { \ + KJ_FAIL_EXPECT("code did not throw: " #code); \ + } \ + } while (false) + +#if KJ_NO_EXCEPTIONS +#define KJ_EXPECT_THROW(type, code) \ + do { \ + KJ_EXPECT(::kj::_::expectFatalThrow(type, nullptr, [&]() { code; })); \ + } while (false) +#define KJ_EXPECT_THROW_MESSAGE(message, code) \ + do { \ + KJ_EXPECT(::kj::_::expectFatalThrow(nullptr, kj::StringPtr(message), [&]() { code; })); \ + } while (false) +#else +#define KJ_EXPECT_THROW KJ_EXPECT_THROW_RECOVERABLE +#define KJ_EXPECT_THROW_MESSAGE KJ_EXPECT_THROW_RECOVERABLE_MESSAGE +#endif + +#define KJ_EXPECT_LOG(level, substring) \ + ::kj::_::LogExpectation KJ_UNIQUE_NAME(_kjLogExpectation)(::kj::LogSeverity::level, substring) +// Expects that a log message with the given level and substring text will be printed within +// the current scope. This message will not cause the test to fail, even if it is an error. + +// ======================================================================================= + +namespace _ { // private + +bool hasSubstring(kj::StringPtr haystack, kj::StringPtr needle); + +#if KJ_NO_EXCEPTIONS +bool expectFatalThrow(Maybe type, Maybe message, + Function code); +// Expects that the given code will throw a fatal exception matching the given type and/or message. +// Since exceptions are disabled, the test will fork() and run in a subprocess. On Windows, where +// fork() is not available, this always returns true. +#endif + +class LogExpectation: public ExceptionCallback { +public: + LogExpectation(LogSeverity severity, StringPtr substring); + ~LogExpectation(); + + void logMessage(LogSeverity severity, const char* file, int line, int contextDepth, + String&& text) override; + +private: + LogSeverity severity; + StringPtr substring; + bool seen; + UnwindDetector unwindDetector; +}; + +class GlobFilter { + // Implements glob filters for the --filter flag. + // + // Exposed in header only for testing. + +public: + explicit GlobFilter(const char* pattern); + explicit GlobFilter(ArrayPtr pattern); + + bool matches(StringPtr name); + +private: + String pattern; + Vector states; + + void applyState(char c, int state); +}; + +} // namespace _ (private) +} // namespace kj + +#endif // KJ_TEST_H_ diff --git a/phonelibs/capnp-cpp/include/kj/thread.h b/phonelibs/capnp-cpp/include/kj/thread.h new file mode 100644 index 00000000000000..b17b88c520a2d8 --- /dev/null +++ b/phonelibs/capnp-cpp/include/kj/thread.h @@ -0,0 +1,82 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef KJ_THREAD_H_ +#define KJ_THREAD_H_ + +#if defined(__GNUC__) && !KJ_HEADER_WARNINGS +#pragma GCC system_header +#endif + +#include "common.h" +#include "function.h" +#include "exception.h" + +namespace kj { + +class Thread { + // A thread! Pass a lambda to the constructor, and it runs in the thread. The destructor joins + // the thread. If the function throws an exception, it is rethrown from the thread's destructor + // (if not unwinding from another exception). + +public: + explicit Thread(Function func); + KJ_DISALLOW_COPY(Thread); + + ~Thread() noexcept(false); + +#if !_WIN32 + void sendSignal(int signo); + // Send a Unix signal to the given thread, using pthread_kill or an equivalent. +#endif + + void detach(); + // Don't join the thread in ~Thread(). + +private: + struct ThreadState { + Function func; + kj::Maybe exception; + + unsigned int refcount; + // Owned by the parent thread and the child thread. + + void unref(); + }; + ThreadState* state; + +#if _WIN32 + void* threadHandle; +#else + unsigned long long threadId; // actually pthread_t +#endif + bool detached = false; + +#if _WIN32 + static unsigned long __stdcall runThread(void* ptr); +#else + static void* runThread(void* ptr); +#endif +}; + +} // namespace kj + +#endif // KJ_THREAD_H_ diff --git a/phonelibs/capnp-cpp/include/kj/threadlocal.h b/phonelibs/capnp-cpp/include/kj/threadlocal.h new file mode 100644 index 00000000000000..67d0db60ef7d6c --- /dev/null +++ b/phonelibs/capnp-cpp/include/kj/threadlocal.h @@ -0,0 +1,136 @@ +// Copyright (c) 2014, Jason Choy +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef KJ_THREADLOCAL_H_ +#define KJ_THREADLOCAL_H_ + +#if defined(__GNUC__) && !KJ_HEADER_WARNINGS +#pragma GCC system_header +#endif +// This file declares a macro `KJ_THREADLOCAL_PTR` for declaring thread-local pointer-typed +// variables. Use like: +// KJ_THREADLOCAL_PTR(MyType) foo = nullptr; +// This is equivalent to: +// thread_local MyType* foo = nullptr; +// This can only be used at the global scope. +// +// AVOID USING THIS. Use of thread-locals is discouraged because they often have many of the same +// properties as singletons: http://www.object-oriented-security.org/lets-argue/singletons +// +// Also, thread-locals tend to be hostile to event-driven code, which can be particularly +// surprising when using fibers (all fibers in the same thread will share the same threadlocals, +// even though they do not share a stack). +// +// That said, thread-locals are sometimes needed for runtime logistics in the KJ framework. For +// example, the current exception callback and current EventLoop are stored as thread-local +// pointers. Since KJ only ever needs to store pointers, not values, we avoid the question of +// whether these values' destructors need to be run, and we avoid the need for heap allocation. + +#include "common.h" + +#if !defined(KJ_USE_PTHREAD_THREADLOCAL) && defined(__APPLE__) +#include "TargetConditionals.h" +#if TARGET_OS_IPHONE +// iOS apparently does not support __thread (nor C++11 thread_local). +#define KJ_USE_PTHREAD_TLS 1 +#endif +#endif + +#if KJ_USE_PTHREAD_TLS +#include +#endif + +namespace kj { + +#if KJ_USE_PTHREAD_TLS +// If __thread is unavailable, we'll fall back to pthreads. + +#define KJ_THREADLOCAL_PTR(type) \ + namespace { struct KJ_UNIQUE_NAME(_kj_TlpTag); } \ + static ::kj::_::ThreadLocalPtr< type, KJ_UNIQUE_NAME(_kj_TlpTag)> +// Hack: In order to ensure each thread-local results in a unique template instance, we declare +// a one-off dummy type to use as the second type parameter. + +namespace _ { // private + +template +class ThreadLocalPtr { + // Hacky type to emulate __thread T*. We need a separate instance of the ThreadLocalPtr template + // for every thread-local variable, because we don't want to require a global constructor, and in + // order to initialize the TLS on first use we need to use a local static variable (in getKey()). + // Each template instance will get a separate such local static variable, fulfilling our need. + +public: + ThreadLocalPtr() = default; + constexpr ThreadLocalPtr(decltype(nullptr)) {} + // Allow initialization to nullptr without a global constructor. + + inline ThreadLocalPtr& operator=(T* val) { + pthread_setspecific(getKey(), val); + return *this; + } + + inline operator T*() const { + return get(); + } + + inline T& operator*() const { + return *get(); + } + + inline T* operator->() const { + return get(); + } + +private: + inline T* get() const { + return reinterpret_cast(pthread_getspecific(getKey())); + } + + inline static pthread_key_t getKey() { + static pthread_key_t key = createKey(); + return key; + } + + static pthread_key_t createKey() { + pthread_key_t key; + pthread_key_create(&key, 0); + return key; + } +}; + +} // namespace _ (private) + +#elif __GNUC__ + +#define KJ_THREADLOCAL_PTR(type) static __thread type* +// GCC's __thread is lighter-weight than thread_local and is good enough for our purposes. + +#else + +#define KJ_THREADLOCAL_PTR(type) static thread_local type* + +#endif // KJ_USE_PTHREAD_TLS + +} // namespace kj + +#endif // KJ_THREADLOCAL_H_ diff --git a/phonelibs/capnp-cpp/include/kj/time.h b/phonelibs/capnp-cpp/include/kj/time.h new file mode 100644 index 00000000000000..37d7b8a90eea91 --- /dev/null +++ b/phonelibs/capnp-cpp/include/kj/time.h @@ -0,0 +1,174 @@ +// Copyright (c) 2014 Google Inc. (contributed by Remy Blank ) +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef KJ_TIME_H_ +#define KJ_TIME_H_ + +#if defined(__GNUC__) && !KJ_HEADER_WARNINGS +#pragma GCC system_header +#endif + +#include "async.h" +#include "units.h" +#include + +namespace kj { +namespace _ { // private + +class NanosecondLabel; +class TimeLabel; +class DateLabel; + +} // namespace _ (private) + +using Duration = Quantity; +// A time value, in nanoseconds. + +constexpr Duration NANOSECONDS = unit(); +constexpr Duration MICROSECONDS = 1000 * NANOSECONDS; +constexpr Duration MILLISECONDS = 1000 * MICROSECONDS; +constexpr Duration SECONDS = 1000 * MILLISECONDS; +constexpr Duration MINUTES = 60 * SECONDS; +constexpr Duration HOURS = 60 * MINUTES; +constexpr Duration DAYS = 24 * HOURS; + +using TimePoint = Absolute; +// An absolute time measured by some particular instance of `Timer`. `Time`s from two different +// `Timer`s may be measured from different origins and so are not necessarily compatible. + +using Date = Absolute; +// A point in real-world time, measured relative to the Unix epoch (Jan 1, 1970 00:00:00 UTC). + +constexpr Date UNIX_EPOCH = origin(); +// The `Date` representing Jan 1, 1970 00:00:00 UTC. + +class Clock { + // Interface to read the current date and time. +public: + virtual Date now() = 0; +}; + +Clock& nullClock(); +// A clock which always returns UNIX_EPOCH as the current time. Useful when you don't care about +// time. + +class Timer { + // Interface to time and timer functionality. + // + // Each `Timer` may have a different origin, and some `Timer`s may in fact tick at a different + // rate than real time (e.g. a `Timer` could represent CPU time consumed by a thread). However, + // all `Timer`s are monotonic: time will never appear to move backwards, even if the calendar + // date as tracked by the system is manually modified. + +public: + virtual TimePoint now() = 0; + // Returns the current value of a clock that moves steadily forward, independent of any + // changes in the wall clock. The value is updated every time the event loop waits, + // and is constant in-between waits. + + virtual Promise atTime(TimePoint time) = 0; + // Returns a promise that returns as soon as now() >= time. + + virtual Promise afterDelay(Duration delay) = 0; + // Equivalent to atTime(now() + delay). + + template + Promise timeoutAt(TimePoint time, Promise&& promise) KJ_WARN_UNUSED_RESULT; + // Return a promise equivalent to `promise` but which throws an exception (and cancels the + // original promise) if it hasn't completed by `time`. The thrown exception is of type + // "OVERLOADED". + + template + Promise timeoutAfter(Duration delay, Promise&& promise) KJ_WARN_UNUSED_RESULT; + // Return a promise equivalent to `promise` but which throws an exception (and cancels the + // original promise) if it hasn't completed after `delay` from now. The thrown exception is of + // type "OVERLOADED". + +private: + static kj::Exception makeTimeoutException(); +}; + +class TimerImpl final: public Timer { + // Implementation of Timer that expects an external caller -- usually, the EventPort + // implementation -- to tell it when time has advanced. + +public: + TimerImpl(TimePoint startTime); + ~TimerImpl() noexcept(false); + + Maybe nextEvent(); + // Returns the time at which the next scheduled timer event will occur, or null if no timer + // events are scheduled. + + Maybe timeoutToNextEvent(TimePoint start, Duration unit, uint64_t max); + // Convenience method which computes a timeout value to pass to an event-waiting system call to + // cause it to time out when the next timer event occurs. + // + // `start` is the time at which the timeout starts counting. This is typically not the same as + // now() since some time may have passed since the last time advanceTo() was called. + // + // `unit` is the time unit in which the timeout is measured. This is often MILLISECONDS. Note + // that this method will fractional values *up*, to guarantee that the returned timeout waits + // until just *after* the time the event is scheduled. + // + // The timeout will be clamped to `max`. Use this to avoid an overflow if e.g. the OS wants a + // 32-bit value or a signed value. + // + // Returns nullptr if there are no future events. + + void advanceTo(TimePoint newTime); + // Set the time to `time` and fire any at() events that have been passed. + + // implements Timer ---------------------------------------------------------- + TimePoint now() override; + Promise atTime(TimePoint time) override; + Promise afterDelay(Duration delay) override; + +private: + struct Impl; + class TimerPromiseAdapter; + TimePoint time; + Own impl; +}; + +// ======================================================================================= +// inline implementation details + +template +Promise Timer::timeoutAt(TimePoint time, Promise&& promise) { + return promise.exclusiveJoin(atTime(time).then([]() -> kj::Promise { + return makeTimeoutException(); + })); +} + +template +Promise Timer::timeoutAfter(Duration delay, Promise&& promise) { + return promise.exclusiveJoin(afterDelay(delay).then([]() -> kj::Promise { + return makeTimeoutException(); + })); +} + +inline TimePoint TimerImpl::now() { return time; } + +} // namespace kj + +#endif // KJ_TIME_H_ diff --git a/phonelibs/capnp-cpp/include/kj/tuple.h b/phonelibs/capnp-cpp/include/kj/tuple.h new file mode 100644 index 00000000000000..2ea7276ec5af9a --- /dev/null +++ b/phonelibs/capnp-cpp/include/kj/tuple.h @@ -0,0 +1,364 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +// This file defines a notion of tuples that is simpler that `std::tuple`. It works as follows: +// - `kj::Tuple is the type of a tuple of an A, a B, and a C. +// - `kj::tuple(a, b, c)` returns a tuple containing a, b, and c. If any of these are themselves +// tuples, they are flattened, so `tuple(a, tuple(b, c), d)` is equivalent to `tuple(a, b, c, d)`. +// - `kj::get(myTuple)` returns the element of `myTuple` at index n. +// - `kj::apply(func, ...)` calls func on the following arguments after first expanding any tuples +// in the argument list. So `kj::apply(foo, a, tuple(b, c), d)` would call `foo(a, b, c, d)`. +// +// Note that: +// - The type `Tuple` is a synonym for T. This is why `get` and `apply` are not members of the +// type. +// - It is illegal for an element of `Tuple` to itself be a tuple, as tuples are meant to be +// flattened. +// - It is illegal for an element of `Tuple` to be a reference, due to problems this would cause +// with type inference and `tuple()`. + +#ifndef KJ_TUPLE_H_ +#define KJ_TUPLE_H_ + +#if defined(__GNUC__) && !KJ_HEADER_WARNINGS +#pragma GCC system_header +#endif + +#include "common.h" + +namespace kj { +namespace _ { // private + +template +struct TypeByIndex_; +template +struct TypeByIndex_<0, First, Rest...> { + typedef First Type; +}; +template +struct TypeByIndex_ + : public TypeByIndex_ {}; +template +struct TypeByIndex_ { + static_assert(index != index, "Index out-of-range."); +}; +template +using TypeByIndex = typename TypeByIndex_::Type; +// Chose a particular type out of a list of types, by index. + +template +struct Indexes {}; +// Dummy helper type that just encapsulates a sequential list of indexes, so that we can match +// templates against them and unpack them with '...'. + +template +struct MakeIndexes_: public MakeIndexes_ {}; +template +struct MakeIndexes_<0, prefix...> { + typedef Indexes Type; +}; +template +using MakeIndexes = typename MakeIndexes_::Type; +// Equivalent to Indexes<0, 1, 2, ..., end>. + +template +class Tuple; +template +inline TypeByIndex& getImpl(Tuple& tuple); +template +inline TypeByIndex&& getImpl(Tuple&& tuple); +template +inline const TypeByIndex& getImpl(const Tuple& tuple); + +template +struct TupleElement { + // Encapsulates one element of a tuple. The actual tuple implementation multiply-inherits + // from a TupleElement for each element, which is more efficient than a recursive definition. + + T value; + TupleElement() = default; + constexpr inline TupleElement(const T& value): value(value) {} + constexpr inline TupleElement(T&& value): value(kj::mv(value)) {} +}; + +template +struct TupleElement { + // If tuples contained references, one of the following would have to be true: + // - `auto x = tuple(y, z)` would cause x to be a tuple of references to y and z, which is + // probably not what you expected. + // - `Tuple x = tuple(a, b)` would not work, because `tuple()` returned + // Tuple. + static_assert(sizeof(T*) == 0, "Sorry, tuples cannot contain references."); +}; + +template +struct TupleElement> { + static_assert(sizeof(Tuple*) == 0, + "Tuples cannot contain other tuples -- they should be flattened."); +}; + +template +struct TupleImpl; + +template +struct TupleImpl, Types...> + : public TupleElement... { + // Implementation of Tuple. The only reason we need this rather than rolling this into class + // Tuple (below) is so that we can get "indexes" as an unpackable list. + + static_assert(sizeof...(indexes) == sizeof...(Types), "Incorrect use of TupleImpl."); + + template + inline TupleImpl(Params&&... params) + : TupleElement(kj::fwd(params))... { + // Work around Clang 3.2 bug 16303 where this is not detected. (Unfortunately, Clang sometimes + // segfaults instead.) + static_assert(sizeof...(params) == sizeof...(indexes), + "Wrong number of parameters to Tuple constructor."); + } + + template + constexpr inline TupleImpl(Tuple&& other) + : TupleElement(kj::mv(getImpl(other)))... {} + template + constexpr inline TupleImpl(Tuple& other) + : TupleElement(getImpl(other))... {} + template + constexpr inline TupleImpl(const Tuple& other) + : TupleElement(getImpl(other))... {} +}; + +struct MakeTupleFunc; + +template +class Tuple { + // The actual Tuple class (used for tuples of size other than 1). + +public: + template + constexpr inline Tuple(Tuple&& other): impl(kj::mv(other)) {} + template + constexpr inline Tuple(Tuple& other): impl(other) {} + template + constexpr inline Tuple(const Tuple& other): impl(other) {} + +private: + template + constexpr Tuple(Params&&... params): impl(kj::fwd(params)...) {} + + TupleImpl, T...> impl; + + template + friend inline TypeByIndex& getImpl(Tuple& tuple); + template + friend inline TypeByIndex&& getImpl(Tuple&& tuple); + template + friend inline const TypeByIndex& getImpl(const Tuple& tuple); + friend struct MakeTupleFunc; +}; + +template <> +class Tuple<> { + // Simplified zero-member version of Tuple. In particular this is important to make sure that + // Tuple<>() is constexpr. +}; + +template +class Tuple; +// Single-element tuple should never be used. The public API should ensure this. + +template +inline TypeByIndex& getImpl(Tuple& tuple) { + // Get member of a Tuple by index, e.g. `get<2>(myTuple)`. + static_assert(index < sizeof...(T), "Tuple element index out-of-bounds."); + return implicitCast>&>(tuple.impl).value; +} +template +inline TypeByIndex&& getImpl(Tuple&& tuple) { + // Get member of a Tuple by index, e.g. `get<2>(myTuple)`. + static_assert(index < sizeof...(T), "Tuple element index out-of-bounds."); + return kj::mv(implicitCast>&>(tuple.impl).value); +} +template +inline const TypeByIndex& getImpl(const Tuple& tuple) { + // Get member of a Tuple by index, e.g. `get<2>(myTuple)`. + static_assert(index < sizeof...(T), "Tuple element index out-of-bounds."); + return implicitCast>&>(tuple.impl).value; +} +template +inline T&& getImpl(T&& value) { + // Get member of a Tuple by index, e.g. `getImpl<2>(myTuple)`. + + // Non-tuples are equivalent to one-element tuples. + static_assert(index == 0, "Tuple element index out-of-bounds."); + return kj::fwd(value); +} + + +template +struct ExpandAndApplyResult_; +// Template which computes the return type of applying Func to T... after flattening tuples. +// SoFar starts as Tuple<> and accumulates the flattened parameter types -- so after this template +// is recursively expanded, T... is empty and SoFar is a Tuple containing all the parameters. + +template +struct ExpandAndApplyResult_, First, Rest...> + : public ExpandAndApplyResult_, Rest...> {}; +template +struct ExpandAndApplyResult_, Tuple, Rest...> + : public ExpandAndApplyResult_, FirstTypes&&..., Rest...> {}; +template +struct ExpandAndApplyResult_, Tuple&, Rest...> + : public ExpandAndApplyResult_, FirstTypes&..., Rest...> {}; +template +struct ExpandAndApplyResult_, const Tuple&, Rest...> + : public ExpandAndApplyResult_, const FirstTypes&..., Rest...> {}; +template +struct ExpandAndApplyResult_> { + typedef decltype(instance()(instance()...)) Type; +}; +template +using ExpandAndApplyResult = typename ExpandAndApplyResult_, T...>::Type; +// Computes the expected return type of `expandAndApply()`. + +template +inline auto expandAndApply(Func&& func) -> ExpandAndApplyResult { + return func(); +} + +template +struct ExpandAndApplyFunc { + Func&& func; + First&& first; + ExpandAndApplyFunc(Func&& func, First&& first) + : func(kj::fwd(func)), first(kj::fwd(first)) {} + template + auto operator()(T&&... params) + -> decltype(this->func(kj::fwd(first), kj::fwd(params)...)) { + return this->func(kj::fwd(first), kj::fwd(params)...); + } +}; + +template +inline auto expandAndApply(Func&& func, First&& first, Rest&&... rest) + -> ExpandAndApplyResult { + + return expandAndApply( + ExpandAndApplyFunc(kj::fwd(func), kj::fwd(first)), + kj::fwd(rest)...); +} + +template +inline auto expandAndApply(Func&& func, Tuple&& first, Rest&&... rest) + -> ExpandAndApplyResult { + return expandAndApplyWithIndexes(MakeIndexes(), + kj::fwd(func), kj::mv(first), kj::fwd(rest)...); +} + +template +inline auto expandAndApply(Func&& func, Tuple& first, Rest&&... rest) + -> ExpandAndApplyResult { + return expandAndApplyWithIndexes(MakeIndexes(), + kj::fwd(func), first, kj::fwd(rest)...); +} + +template +inline auto expandAndApply(Func&& func, const Tuple& first, Rest&&... rest) + -> ExpandAndApplyResult { + return expandAndApplyWithIndexes(MakeIndexes(), + kj::fwd(func), first, kj::fwd(rest)...); +} + +template +inline auto expandAndApplyWithIndexes( + Indexes, Func&& func, Tuple&& first, Rest&&... rest) + -> ExpandAndApplyResult { + return expandAndApply(kj::fwd(func), kj::mv(getImpl(first))..., + kj::fwd(rest)...); +} + +template +inline auto expandAndApplyWithIndexes( + Indexes, Func&& func, const Tuple& first, Rest&&... rest) + -> ExpandAndApplyResult { + return expandAndApply(kj::fwd(func), getImpl(first)..., + kj::fwd(rest)...); +} + +struct MakeTupleFunc { + template + Tuple...> operator()(Params&&... params) { + return Tuple...>(kj::fwd(params)...); + } + template + Decay operator()(Param&& param) { + return kj::fwd(param); + } +}; + +} // namespace _ (private) + +template struct Tuple_ { typedef _::Tuple Type; }; +template struct Tuple_ { typedef T Type; }; + +template using Tuple = typename Tuple_::Type; +// Tuple type. `Tuple` (i.e. a single-element tuple) is a synonym for `T`. Tuples of size +// other than 1 expand to an internal type. Either way, you can construct a Tuple using +// `kj::tuple(...)`, get an element by index `i` using `kj::get(myTuple)`, and expand the tuple +// as arguments to a function using `kj::apply(func, myTuple)`. +// +// Tuples are always flat -- that is, no element of a Tuple is ever itself a Tuple. If you +// construct a tuple from other tuples, the elements are flattened and concatenated. + +template +inline auto tuple(Params&&... params) + -> decltype(_::expandAndApply(_::MakeTupleFunc(), kj::fwd(params)...)) { + // Construct a new tuple from the given values. Any tuples in the argument list will be + // flattened into the result. + return _::expandAndApply(_::MakeTupleFunc(), kj::fwd(params)...); +} + +template +inline auto get(Tuple&& tuple) -> decltype(_::getImpl(kj::fwd(tuple))) { + // Unpack and return the tuple element at the given index. The index is specified as a template + // parameter, e.g. `kj::get<3>(myTuple)`. + return _::getImpl(kj::fwd(tuple)); +} + +template +inline auto apply(Func&& func, Params&&... params) + -> decltype(_::expandAndApply(kj::fwd(func), kj::fwd(params)...)) { + // Apply a function to some arguments, expanding tuples into separate arguments. + return _::expandAndApply(kj::fwd(func), kj::fwd(params)...); +} + +template struct TupleSize_ { static constexpr size_t size = 1; }; +template struct TupleSize_<_::Tuple> { + static constexpr size_t size = sizeof...(T); +}; + +template +constexpr size_t tupleSize() { return TupleSize_::size; } +// Returns size of the tuple T. + +} // namespace kj + +#endif // KJ_TUPLE_H_ diff --git a/phonelibs/capnp-cpp/include/kj/units.h b/phonelibs/capnp-cpp/include/kj/units.h new file mode 100644 index 00000000000000..8bba40338bcc05 --- /dev/null +++ b/phonelibs/capnp-cpp/include/kj/units.h @@ -0,0 +1,1172 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +// This file contains types which are intended to help detect incorrect usage at compile +// time, but should then be optimized down to basic primitives (usually, integers) by the +// compiler. + +#ifndef KJ_UNITS_H_ +#define KJ_UNITS_H_ + +#if defined(__GNUC__) && !KJ_HEADER_WARNINGS +#pragma GCC system_header +#endif + +#include "common.h" +#include + +namespace kj { + +// ======================================================================================= +// IDs + +template +struct Id { + // A type-safe numeric ID. `UnderlyingType` is the underlying integer representation. `Label` + // distinguishes this Id from other Id types. Sample usage: + // + // class Foo; + // typedef Id FooId; + // + // class Bar; + // typedef Id BarId; + // + // You can now use the FooId and BarId types without any possibility of accidentally using a + // FooId when you really wanted a BarId or vice-versa. + + UnderlyingType value; + + inline constexpr Id(): value(0) {} + inline constexpr explicit Id(int value): value(value) {} + + inline constexpr bool operator==(const Id& other) const { return value == other.value; } + inline constexpr bool operator!=(const Id& other) const { return value != other.value; } + inline constexpr bool operator<=(const Id& other) const { return value <= other.value; } + inline constexpr bool operator>=(const Id& other) const { return value >= other.value; } + inline constexpr bool operator< (const Id& other) const { return value < other.value; } + inline constexpr bool operator> (const Id& other) const { return value > other.value; } +}; + +// ======================================================================================= +// Quantity and UnitRatio -- implement unit analysis via the type system + +struct Unsafe_ {}; +constexpr Unsafe_ unsafe = Unsafe_(); +// Use as a parameter to constructors that are unsafe to indicate that you really do mean it. + +template +class Bounded; +template +class BoundedConst; + +template constexpr bool isIntegral() { return false; } +template <> constexpr bool isIntegral() { return true; } +template <> constexpr bool isIntegral() { return true; } +template <> constexpr bool isIntegral() { return true; } +template <> constexpr bool isIntegral() { return true; } +template <> constexpr bool isIntegral() { return true; } +template <> constexpr bool isIntegral() { return true; } +template <> constexpr bool isIntegral() { return true; } +template <> constexpr bool isIntegral() { return true; } +template <> constexpr bool isIntegral() { return true; } +template <> constexpr bool isIntegral() { return true; } +template <> constexpr bool isIntegral() { return true; } + +template +struct IsIntegralOrBounded_ { static constexpr bool value = isIntegral(); }; +template +struct IsIntegralOrBounded_> { static constexpr bool value = true; }; +template +struct IsIntegralOrBounded_> { static constexpr bool value = true; }; + +template +inline constexpr bool isIntegralOrBounded() { return IsIntegralOrBounded_::value; } + +template +class UnitRatio { + // A multiplier used to convert Quantities of one unit to Quantities of another unit. See + // Quantity, below. + // + // Construct this type by dividing one Quantity by another of a different unit. Use this type + // by multiplying it by a Quantity, or dividing a Quantity by it. + + static_assert(isIntegralOrBounded(), + "Underlying type for UnitRatio must be integer."); + +public: + inline UnitRatio() {} + + constexpr UnitRatio(Number unit1PerUnit2, decltype(unsafe)): unit1PerUnit2(unit1PerUnit2) {} + // This constructor was intended to be private, but GCC complains about it being private in a + // bunch of places that don't appear to even call it, so I made it public. Oh well. + + template + inline constexpr UnitRatio(const UnitRatio& other) + : unit1PerUnit2(other.unit1PerUnit2) {} + + template + inline constexpr UnitRatio + operator+(UnitRatio other) const { + return UnitRatio( + unit1PerUnit2 + other.unit1PerUnit2, unsafe); + } + template + inline constexpr UnitRatio + operator-(UnitRatio other) const { + return UnitRatio( + unit1PerUnit2 - other.unit1PerUnit2, unsafe); + } + + template + inline constexpr UnitRatio + operator*(UnitRatio other) const { + // U1 / U2 * U3 / U1 = U3 / U2 + return UnitRatio( + unit1PerUnit2 * other.unit1PerUnit2, unsafe); + } + template + inline constexpr UnitRatio + operator*(UnitRatio other) const { + // U1 / U2 * U2 / U3 = U1 / U3 + return UnitRatio( + unit1PerUnit2 * other.unit1PerUnit2, unsafe); + } + + template + inline constexpr UnitRatio + operator/(UnitRatio other) const { + // (U1 / U2) / (U1 / U3) = U3 / U2 + return UnitRatio( + unit1PerUnit2 / other.unit1PerUnit2, unsafe); + } + template + inline constexpr UnitRatio + operator/(UnitRatio other) const { + // (U1 / U2) / (U3 / U2) = U1 / U3 + return UnitRatio( + unit1PerUnit2 / other.unit1PerUnit2, unsafe); + } + + template + inline decltype(Number() / OtherNumber()) + operator/(UnitRatio other) const { + return unit1PerUnit2 / other.unit1PerUnit2; + } + + inline bool operator==(UnitRatio other) const { return unit1PerUnit2 == other.unit1PerUnit2; } + inline bool operator!=(UnitRatio other) const { return unit1PerUnit2 != other.unit1PerUnit2; } + +private: + Number unit1PerUnit2; + + template + friend class Quantity; + template + friend class UnitRatio; + + template + friend inline constexpr UnitRatio + operator*(N1, UnitRatio); +}; + +template () && isIntegralOrBounded()>> +inline constexpr UnitRatio + operator*(N1 n, UnitRatio r) { + return UnitRatio(n * r.unit1PerUnit2, unsafe); +} + +template +class Quantity { + // A type-safe numeric quantity, specified in terms of some unit. Two Quantities cannot be used + // in arithmetic unless they use the same unit. The `Unit` type parameter is only used to prevent + // accidental mixing of units; this type is never instantiated and can very well be incomplete. + // `Number` is the underlying primitive numeric type. + // + // Quantities support most basic arithmetic operators, intelligently handling units, and + // automatically casting the underlying type in the same way that the compiler would. + // + // To convert a primitive number to a Quantity, multiply it by unit>(). + // To convert a Quantity to a primitive number, divide it by unit>(). + // To convert a Quantity of one unit to another unit, multiply or divide by a UnitRatio. + // + // The Quantity class is not well-suited to hardcore physics as it does not allow multiplying + // one quantity by another. For example, multiplying meters by meters won't get you square + // meters; it will get you a compiler error. It would be interesting to see if template + // metaprogramming could properly deal with such things but this isn't needed for the present + // use case. + // + // Sample usage: + // + // class SecondsLabel; + // typedef Quantity Seconds; + // constexpr Seconds SECONDS = unit(); + // + // class MinutesLabel; + // typedef Quantity Minutes; + // constexpr Minutes MINUTES = unit(); + // + // constexpr UnitRatio SECONDS_PER_MINUTE = + // 60 * SECONDS / MINUTES; + // + // void waitFor(Seconds seconds) { + // sleep(seconds / SECONDS); + // } + // void waitFor(Minutes minutes) { + // waitFor(minutes * SECONDS_PER_MINUTE); + // } + // + // void waitThreeMinutes() { + // waitFor(3 * MINUTES); + // } + + static_assert(isIntegralOrBounded(), + "Underlying type for Quantity must be integer."); + +public: + inline constexpr Quantity() = default; + + inline constexpr Quantity(MaxValue_): value(maxValue) {} + inline constexpr Quantity(MinValue_): value(minValue) {} + // Allow initialization from maxValue and minValue. + // TODO(msvc): decltype(maxValue) and decltype(minValue) deduce unknown-type for these function + // parameters, causing the compiler to complain of a duplicate constructor definition, so we + // specify MaxValue_ and MinValue_ types explicitly. + + inline constexpr Quantity(Number value, decltype(unsafe)): value(value) {} + // This constructor was intended to be private, but GCC complains about it being private in a + // bunch of places that don't appear to even call it, so I made it public. Oh well. + + template + inline constexpr Quantity(const Quantity& other) + : value(other.value) {} + + template + inline Quantity& operator=(const Quantity& other) { + value = other.value; + return *this; + } + + template + inline constexpr Quantity + operator+(const Quantity& other) const { + return Quantity(value + other.value, unsafe); + } + template + inline constexpr Quantity + operator-(const Quantity& other) const { + return Quantity(value - other.value, unsafe); + } + template ()>> + inline constexpr Quantity + operator*(OtherNumber other) const { + return Quantity(value * other, unsafe); + } + template ()>> + inline constexpr Quantity + operator/(OtherNumber other) const { + return Quantity(value / other, unsafe); + } + template + inline constexpr decltype(Number() / OtherNumber()) + operator/(const Quantity& other) const { + return value / other.value; + } + template + inline constexpr Quantity + operator%(const Quantity& other) const { + return Quantity(value % other.value, unsafe); + } + + template + inline constexpr Quantity + operator*(UnitRatio ratio) const { + return Quantity( + value * ratio.unit1PerUnit2, unsafe); + } + template + inline constexpr Quantity + operator/(UnitRatio ratio) const { + return Quantity( + value / ratio.unit1PerUnit2, unsafe); + } + template + inline constexpr Quantity + operator%(UnitRatio ratio) const { + return Quantity( + value % ratio.unit1PerUnit2, unsafe); + } + template + inline constexpr UnitRatio + operator/(Quantity other) const { + return UnitRatio( + value / other.value, unsafe); + } + + template + inline constexpr bool operator==(const Quantity& other) const { + return value == other.value; + } + template + inline constexpr bool operator!=(const Quantity& other) const { + return value != other.value; + } + template + inline constexpr bool operator<=(const Quantity& other) const { + return value <= other.value; + } + template + inline constexpr bool operator>=(const Quantity& other) const { + return value >= other.value; + } + template + inline constexpr bool operator<(const Quantity& other) const { + return value < other.value; + } + template + inline constexpr bool operator>(const Quantity& other) const { + return value > other.value; + } + + template + inline Quantity& operator+=(const Quantity& other) { + value += other.value; + return *this; + } + template + inline Quantity& operator-=(const Quantity& other) { + value -= other.value; + return *this; + } + template + inline Quantity& operator*=(OtherNumber other) { + value *= other; + return *this; + } + template + inline Quantity& operator/=(OtherNumber other) { + value /= other.value; + return *this; + } + +private: + Number value; + + template + friend class Quantity; + + template + friend inline constexpr auto operator*(Number1 a, Quantity b) + -> Quantity; +}; + +template struct Unit_ { + static inline constexpr T get() { return T(1); } +}; +template +struct Unit_> { + static inline constexpr Quantity::get()), U> get() { + return Quantity::get()), U>(Unit_::get(), unsafe); + } +}; + +template +inline constexpr auto unit() -> decltype(Unit_::get()) { return Unit_::get(); } +// unit>() returns a Quantity of value 1. It also, intentionally, works on basic +// numeric types. + +template +inline constexpr auto operator*(Number1 a, Quantity b) + -> Quantity { + return Quantity(a * b.value, unsafe); +} + +template +inline constexpr auto operator*(UnitRatio ratio, + Quantity measure) + -> decltype(measure * ratio) { + return measure * ratio; +} + +// ======================================================================================= +// Absolute measures + +template +class Absolute { + // Wraps some other value -- typically a Quantity -- but represents a value measured based on + // some absolute origin. For example, if `Duration` is a type representing a time duration, + // Absolute might be a calendar date. + // + // Since Absolute represents measurements relative to some arbitrary origin, the only sensible + // arithmetic to perform on them is addition and subtraction. + + // TODO(someday): Do the same automatic expansion of integer width that Quantity does? Doesn't + // matter for our time use case, where we always use 64-bit anyway. Note that fixing this + // would implicitly allow things like multiplying an Absolute by a UnitRatio to change its + // units, which is actually totally logical and kind of neat. + +public: + inline constexpr Absolute operator+(const T& other) const { return Absolute(value + other); } + inline constexpr Absolute operator-(const T& other) const { return Absolute(value - other); } + inline constexpr T operator-(const Absolute& other) const { return value - other.value; } + + inline Absolute& operator+=(const T& other) { value += other; return *this; } + inline Absolute& operator-=(const T& other) { value -= other; return *this; } + + inline constexpr bool operator==(const Absolute& other) const { return value == other.value; } + inline constexpr bool operator!=(const Absolute& other) const { return value != other.value; } + inline constexpr bool operator<=(const Absolute& other) const { return value <= other.value; } + inline constexpr bool operator>=(const Absolute& other) const { return value >= other.value; } + inline constexpr bool operator< (const Absolute& other) const { return value < other.value; } + inline constexpr bool operator> (const Absolute& other) const { return value > other.value; } + +private: + T value; + + explicit constexpr Absolute(T value): value(value) {} + + template + friend inline constexpr U origin(); +}; + +template +inline constexpr Absolute operator+(const T& a, const Absolute& b) { + return b + a; +} + +template struct UnitOf_ { typedef T Type; }; +template struct UnitOf_> { typedef T Type; }; +template +using UnitOf = typename UnitOf_::Type; +// UnitOf> is T. UnitOf is AnythingElse. + +template +inline constexpr T origin() { return T(0 * unit>()); } +// origin>() returns an Absolute of value 0. It also, intentionally, works on basic +// numeric types. + +// ======================================================================================= +// Overflow avoidance + +template +struct BitCount_ { + static constexpr uint value = BitCount_<(n >> 1), accum + 1>::value; +}; +template +struct BitCount_<0, accum> { + static constexpr uint value = accum; +}; + +template +inline constexpr uint bitCount() { return BitCount_::value; } +// Number of bits required to represent the number `n`. + +template struct AtLeastUInt_ { + static_assert(bitCountBitCount < 7, "don't know how to represent integers over 64 bits"); +}; +template <> struct AtLeastUInt_<0> { typedef uint8_t Type; }; +template <> struct AtLeastUInt_<1> { typedef uint8_t Type; }; +template <> struct AtLeastUInt_<2> { typedef uint8_t Type; }; +template <> struct AtLeastUInt_<3> { typedef uint8_t Type; }; +template <> struct AtLeastUInt_<4> { typedef uint16_t Type; }; +template <> struct AtLeastUInt_<5> { typedef uint32_t Type; }; +template <> struct AtLeastUInt_<6> { typedef uint64_t Type; }; + +template +using AtLeastUInt = typename AtLeastUInt_()>::Type; +// AtLeastUInt is an unsigned integer of at least n bits. E.g. AtLeastUInt<12> is uint16_t. + +// ------------------------------------------------------------------- + +template +class BoundedConst { + // A constant integer value on which we can do bit size analysis. + +public: + BoundedConst() = default; + + inline constexpr uint unwrap() const { return value; } + +#define OP(op, check) \ + template \ + inline constexpr BoundedConst<(value op other)> \ + operator op(BoundedConst) const { \ + static_assert(check, "overflow in BoundedConst arithmetic"); \ + return BoundedConst<(value op other)>(); \ + } +#define COMPARE_OP(op) \ + template \ + inline constexpr bool operator op(BoundedConst) const { \ + return value op other; \ + } + + OP(+, value + other >= value) + OP(-, value - other <= value) + OP(*, value * other / other == value) + OP(/, true) // div by zero already errors out; no other division ever overflows + OP(%, true) // mod by zero already errors out; no other modulus ever overflows + OP(<<, value << other >= value) + OP(>>, true) // right shift can't overflow + OP(&, true) // bitwise ops can't overflow + OP(|, true) // bitwise ops can't overflow + + COMPARE_OP(==) + COMPARE_OP(!=) + COMPARE_OP(< ) + COMPARE_OP(> ) + COMPARE_OP(<=) + COMPARE_OP(>=) +#undef OP +#undef COMPARE_OP +}; + +template +struct Unit_> { + static inline constexpr BoundedConst<1> get() { return BoundedConst<1>(); } +}; + +template +struct Unit_> { + static inline constexpr BoundedConst<1> get() { return BoundedConst<1>(); } +}; + +template +inline constexpr BoundedConst bounded() { + return BoundedConst(); +} + +template +static constexpr uint64_t boundedAdd() { + static_assert(a + b >= a, "possible overflow detected"); + return a + b; +} +template +static constexpr uint64_t boundedSub() { + static_assert(a - b <= a, "possible underflow detected"); + return a - b; +} +template +static constexpr uint64_t boundedMul() { + static_assert(a * b / b == a, "possible overflow detected"); + return a * b; +} +template +static constexpr uint64_t boundedLShift() { + static_assert(a << b >= a, "possible overflow detected"); + return a << b; +} + +template +inline constexpr BoundedConst min(BoundedConst, BoundedConst) { + return bounded(); +} +template +inline constexpr BoundedConst max(BoundedConst, BoundedConst) { + return bounded(); +} +// We need to override min() and max() between constants because the ternary operator in the +// default implementation would complain. + +// ------------------------------------------------------------------- + +template +class Bounded { +public: + static_assert(maxN <= T(kj::maxValue), "possible overflow detected"); + + Bounded() = default; + + Bounded(const Bounded& other) = default; + template ()>> + inline constexpr Bounded(OtherInt value): value(value) { + static_assert(OtherInt(maxValue) <= maxN, "possible overflow detected"); + } + template + inline constexpr Bounded(const Bounded& other) + : value(other.value) { + static_assert(otherMax <= maxN, "possible overflow detected"); + } + template + inline constexpr Bounded(BoundedConst) + : value(otherValue) { + static_assert(otherValue <= maxN, "overflow detected"); + } + + Bounded& operator=(const Bounded& other) = default; + template ()>> + Bounded& operator=(OtherInt other) { + static_assert(OtherInt(maxValue) <= maxN, "possible overflow detected"); + value = other; + return *this; + } + template + inline Bounded& operator=(const Bounded& other) { + static_assert(otherMax <= maxN, "possible overflow detected"); + value = other.value; + return *this; + } + template + inline Bounded& operator=(BoundedConst) { + static_assert(otherValue <= maxN, "overflow detected"); + value = otherValue; + return *this; + } + + inline constexpr T unwrap() const { return value; } + +#define OP(op, newMax) \ + template \ + inline constexpr Bounded \ + operator op(const Bounded& other) const { \ + return Bounded(value op other.value, unsafe); \ + } +#define COMPARE_OP(op) \ + template \ + inline constexpr bool operator op(const Bounded& other) const { \ + return value op other.value; \ + } + + OP(+, (boundedAdd())) + OP(*, (boundedMul())) + OP(/, maxN) + OP(%, otherMax - 1) + + // operator- is intentionally omitted because we mostly use this with unsigned types, and + // subtraction requires proof that subtrahend is not greater than the minuend. + + COMPARE_OP(==) + COMPARE_OP(!=) + COMPARE_OP(< ) + COMPARE_OP(> ) + COMPARE_OP(<=) + COMPARE_OP(>=) + +#undef OP +#undef COMPARE_OP + + template + inline Bounded assertMax(ErrorFunc&& func) const { + // Assert that the number is no more than `newMax`. Otherwise, call `func`. + static_assert(newMax < maxN, "this bounded size assertion is redundant"); + if (KJ_UNLIKELY(value > newMax)) func(); + return Bounded(value, unsafe); + } + + template + inline Bounded subtractChecked( + const Bounded& other, ErrorFunc&& func) const { + // Subtract a number, calling func() if the result would underflow. + if (KJ_UNLIKELY(value < other.value)) func(); + return Bounded(value - other.value, unsafe); + } + + template + inline Bounded subtractChecked( + BoundedConst, ErrorFunc&& func) const { + // Subtract a number, calling func() if the result would underflow. + static_assert(otherValue <= maxN, "underflow detected"); + if (KJ_UNLIKELY(value < otherValue)) func(); + return Bounded(value - otherValue, unsafe); + } + + template + inline Maybe> trySubtract( + const Bounded& other) const { + // Subtract a number, calling func() if the result would underflow. + if (value < other.value) { + return nullptr; + } else { + return Bounded(value - other.value, unsafe); + } + } + + template + inline Maybe> trySubtract(BoundedConst) const { + // Subtract a number, calling func() if the result would underflow. + if (value < otherValue) { + return nullptr; + } else { + return Bounded(value - otherValue, unsafe); + } + } + + inline constexpr Bounded(T value, decltype(unsafe)): value(value) {} + template + inline constexpr Bounded(Bounded value, decltype(unsafe)) + : value(value.value) {} + // Mainly for internal use. + // + // Only use these as a last resort, with ample commentary on why you think it's safe. + +private: + T value; + + template + friend class Bounded; +}; + +template +inline constexpr Bounded bounded(Number value) { + return Bounded(value, unsafe); +} + +inline constexpr Bounded<1, uint8_t> bounded(bool value) { + return Bounded<1, uint8_t>(value, unsafe); +} + +template +inline constexpr Bounded(), Number> assumeBits(Number value) { + return Bounded(), Number>(value, unsafe); +} + +template +inline constexpr Bounded(), T> assumeBits(Bounded value) { + return Bounded(), T>(value, unsafe); +} + +template +inline constexpr auto assumeBits(Quantity value) + -> Quantity(value / unit>())), Unit> { + return Quantity(value / unit>())), Unit>( + assumeBits(value / unit>()), unsafe); +} + +template +inline constexpr Bounded assumeMax(Number value) { + return Bounded(value, unsafe); +} + +template +inline constexpr Bounded assumeMax(Bounded value) { + return Bounded(value, unsafe); +} + +template +inline constexpr auto assumeMax(Quantity value) + -> Quantity(value / unit>())), Unit> { + return Quantity(value / unit>())), Unit>( + assumeMax(value / unit>()), unsafe); +} + +template +inline constexpr Bounded assumeMax(BoundedConst, Number value) { + return assumeMax(value); +} + +template +inline constexpr Bounded assumeMax(BoundedConst, Bounded value) { + return assumeMax(value); +} + +template +inline constexpr auto assumeMax(Quantity, Unit>, Quantity value) + -> decltype(assumeMax(value)) { + return assumeMax(value); +} + +template +inline Bounded assertMax(Bounded value, ErrorFunc&& errorFunc) { + // Assert that the bounded value is less than or equal to the given maximum, calling errorFunc() + // if not. + static_assert(newMax < maxN, "this bounded size assertion is redundant"); + return value.template assertMax(kj::fwd(errorFunc)); +} + +template +inline Quantity, Unit> assertMax( + Quantity, Unit> value, ErrorFunc&& errorFunc) { + // Assert that the bounded value is less than or equal to the given maximum, calling errorFunc() + // if not. + static_assert(newMax < maxN, "this bounded size assertion is redundant"); + return (value / unit()).template assertMax( + kj::fwd(errorFunc)) * unit(); +} + +template +inline Bounded assertMax( + BoundedConst, Bounded value, ErrorFunc&& errorFunc) { + return assertMax(value, kj::mv(errorFunc)); +} + +template +inline Quantity, Unit> assertMax( + Quantity, Unit>, + Quantity, Unit> value, ErrorFunc&& errorFunc) { + return assertMax(value, kj::mv(errorFunc)); +} + +template +inline Bounded(), T> assertMaxBits( + Bounded value, ErrorFunc&& errorFunc = ErrorFunc()) { + // Assert that the bounded value requires no more than the given number of bits, calling + // errorFunc() if not. + return assertMax()>(value, kj::fwd(errorFunc)); +} + +template +inline Quantity(), T>, Unit> assertMaxBits( + Quantity, Unit> value, ErrorFunc&& errorFunc = ErrorFunc()) { + // Assert that the bounded value requires no more than the given number of bits, calling + // errorFunc() if not. + return assertMax()>(value, kj::fwd(errorFunc)); +} + +template +inline constexpr Bounded upgradeBound(Bounded value) { + return value; +} + +template +inline constexpr Quantity, Unit> upgradeBound( + Quantity, Unit> value) { + return value; +} + +template +inline auto subtractChecked(Bounded value, Other other, ErrorFunc&& errorFunc) + -> decltype(value.subtractChecked(other, kj::fwd(errorFunc))) { + return value.subtractChecked(other, kj::fwd(errorFunc)); +} + +template +inline auto subtractChecked(Quantity value, Quantity other, ErrorFunc&& errorFunc) + -> Quantity(errorFunc))), Unit> { + return subtractChecked(value / unit>(), + other / unit>(), + kj::fwd(errorFunc)) + * unit>(); +} + +template +inline auto trySubtract(Bounded value, Other other) + -> decltype(value.trySubtract(other)) { + return value.trySubtract(other); +} + +template +inline auto trySubtract(Quantity value, Quantity other) + -> Maybe> { + return trySubtract(value / unit>(), + other / unit>()) + .map([](decltype(subtractChecked(T(), U(), int())) x) { + return x * unit>(); + }); +} + +template +inline constexpr Bounded> +min(Bounded a, Bounded b) { + return Bounded>(kj::min(a.unwrap(), b.unwrap()), unsafe); +} +template +inline constexpr Bounded> +max(Bounded a, Bounded b) { + return Bounded>(kj::max(a.unwrap(), b.unwrap()), unsafe); +} +// We need to override min() and max() because: +// 1) WiderType<> might not choose the correct bounds. +// 2) One of the two sides of the ternary operator in the default implementation would fail to +// typecheck even though it is OK in practice. + +// ------------------------------------------------------------------- +// Operators between Bounded and BoundedConst + +#define OP(op, newMax) \ +template \ +inline constexpr Bounded<(newMax), decltype(T() op uint())> operator op( \ + Bounded value, BoundedConst) { \ + return Bounded<(newMax), decltype(T() op uint())>(value.unwrap() op cvalue, unsafe); \ +} + +#define REVERSE_OP(op, newMax) \ +template \ +inline constexpr Bounded<(newMax), decltype(uint() op T())> operator op( \ + BoundedConst, Bounded value) { \ + return Bounded<(newMax), decltype(uint() op T())>(cvalue op value.unwrap(), unsafe); \ +} + +#define COMPARE_OP(op) \ +template \ +inline constexpr bool operator op(Bounded value, BoundedConst) { \ + return value.unwrap() op cvalue; \ +} \ +template \ +inline constexpr bool operator op(BoundedConst, Bounded value) { \ + return cvalue op value.unwrap(); \ +} + +OP(+, (boundedAdd())) +REVERSE_OP(+, (boundedAdd())) + +OP(*, (boundedMul())) +REVERSE_OP(*, (boundedAdd())) + +OP(/, maxN / cvalue) +REVERSE_OP(/, cvalue) // denominator could be 1 + +OP(%, cvalue - 1) +REVERSE_OP(%, maxN - 1) + +OP(<<, (boundedLShift())) +REVERSE_OP(<<, (boundedLShift())) + +OP(>>, maxN >> cvalue) +REVERSE_OP(>>, cvalue >> maxN) + +OP(&, maxValueForBits()>() & cvalue) +REVERSE_OP(&, maxValueForBits()>() & cvalue) + +OP(|, maxN | cvalue) +REVERSE_OP(|, maxN | cvalue) + +COMPARE_OP(==) +COMPARE_OP(!=) +COMPARE_OP(< ) +COMPARE_OP(> ) +COMPARE_OP(<=) +COMPARE_OP(>=) + +#undef OP +#undef REVERSE_OP +#undef COMPARE_OP + +template +inline constexpr Bounded + operator-(BoundedConst, Bounded value) { + // We allow subtraction of a variable from a constant only if the constant is greater than or + // equal to the maximum possible value of the variable. Since the variable could be zero, the + // result can be as large as the constant. + // + // We do not allow subtraction of a constant from a variable because there's never a guarantee it + // won't underflow (unless the constant is zero, which is silly). + static_assert(cvalue >= maxN, "possible underflow detected"); + return Bounded(cvalue - value.unwrap(), unsafe); +} + +template +inline constexpr Bounded min(Bounded a, BoundedConst) { + return Bounded(kj::min(b, a.unwrap()), unsafe); +} +template +inline constexpr Bounded min(BoundedConst, Bounded a) { + return Bounded(kj::min(a.unwrap(), b), unsafe); +} +template +inline constexpr Bounded max(Bounded a, BoundedConst) { + return Bounded(kj::max(b, a.unwrap()), unsafe); +} +template +inline constexpr Bounded max(BoundedConst, Bounded a) { + return Bounded(kj::max(a.unwrap(), b), unsafe); +} +// We need to override min() between a Bounded and a constant since: +// 1) WiderType<> might choose BoundedConst over a 1-byte Bounded, which is wrong. +// 2) To clamp the bounds of the output type. +// 3) Same ternary operator typechecking issues. + +// ------------------------------------------------------------------- + +template +class SafeUnwrapper { +public: + inline explicit constexpr SafeUnwrapper(Bounded value): value(value.unwrap()) {} + + template ()>> + inline constexpr operator U() const { + static_assert(maxN <= U(maxValue), "possible truncation detected"); + return value; + } + + inline constexpr operator bool() const { + static_assert(maxN <= 1, "possible truncation detected"); + return value; + } + +private: + T value; +}; + +template +inline constexpr SafeUnwrapper unbound(Bounded bounded) { + // Unwraps the bounded value, returning a value that can be implicitly cast to any integer type. + // If this implicit cast could truncate, a compile-time error will be raised. + return SafeUnwrapper(bounded); +} + +template +class SafeConstUnwrapper { +public: + template ()>> + inline constexpr operator T() const { + static_assert(value <= T(maxValue), "this operation will truncate"); + return value; + } + + inline constexpr operator bool() const { + static_assert(value <= 1, "this operation will truncate"); + return value; + } +}; + +template +inline constexpr SafeConstUnwrapper unbound(BoundedConst) { + return SafeConstUnwrapper(); +} + +template +inline constexpr T unboundAs(U value) { + return unbound(value); +} + +template +inline constexpr T unboundMax(Bounded value) { + // Explicitly ungaurd expecting a value that is at most `maxN`. + static_assert(maxN <= requestedMax, "possible overflow detected"); + return value.unwrap(); +} + +template +inline constexpr uint unboundMax(BoundedConst) { + // Explicitly ungaurd expecting a value that is at most `maxN`. + static_assert(value <= requestedMax, "overflow detected"); + return value; +} + +template +inline constexpr auto unboundMaxBits(T value) -> + decltype(unboundMax()>(value)) { + // Explicitly ungaurd expecting a value that fits into `bits` bits. + return unboundMax()>(value); +} + +#define OP(op) \ +template \ +inline constexpr auto operator op(T a, SafeUnwrapper b) -> decltype(a op (T)b) { \ + return a op (AtLeastUInt)b; \ +} \ +template \ +inline constexpr auto operator op(SafeUnwrapper b, T a) -> decltype((T)b op a) { \ + return (AtLeastUInt)b op a; \ +} \ +template \ +inline constexpr auto operator op(T a, SafeConstUnwrapper b) -> decltype(a op (T)b) { \ + return a op (AtLeastUInt)b; \ +} \ +template \ +inline constexpr auto operator op(SafeConstUnwrapper b, T a) -> decltype((T)b op a) { \ + return (AtLeastUInt)b op a; \ +} + +OP(+) +OP(-) +OP(*) +OP(/) +OP(%) +OP(<<) +OP(>>) +OP(&) +OP(|) +OP(==) +OP(!=) +OP(<=) +OP(>=) +OP(<) +OP(>) + +#undef OP + +// ------------------------------------------------------------------- + +template +class Range> { +public: + inline constexpr Range(Bounded begin, Bounded end) + : inner(unbound(begin), unbound(end)) {} + inline explicit constexpr Range(Bounded end) + : inner(unbound(end)) {} + + class Iterator { + public: + Iterator() = default; + inline explicit Iterator(typename Range::Iterator inner): inner(inner) {} + + inline Bounded operator* () const { return Bounded(*inner, unsafe); } + inline Iterator& operator++() { ++inner; return *this; } + + inline bool operator==(const Iterator& other) const { return inner == other.inner; } + inline bool operator!=(const Iterator& other) const { return inner != other.inner; } + + private: + typename Range::Iterator inner; + }; + + inline Iterator begin() const { return Iterator(inner.begin()); } + inline Iterator end() const { return Iterator(inner.end()); } + +private: + Range inner; +}; + +template +class Range> { +public: + inline constexpr Range(Quantity begin, Quantity end) + : inner(begin / unit>(), end / unit>()) {} + inline explicit constexpr Range(Quantity end) + : inner(end / unit>()) {} + + class Iterator { + public: + Iterator() = default; + inline explicit Iterator(typename Range::Iterator inner): inner(inner) {} + + inline Quantity operator* () const { return *inner * unit>(); } + inline Iterator& operator++() { ++inner; return *this; } + + inline bool operator==(const Iterator& other) const { return inner == other.inner; } + inline bool operator!=(const Iterator& other) const { return inner != other.inner; } + + private: + typename Range::Iterator inner; + }; + + inline Iterator begin() const { return Iterator(inner.begin()); } + inline Iterator end() const { return Iterator(inner.end()); } + +private: + Range inner; +}; + +template +inline constexpr Range> zeroTo(BoundedConst end) { + return Range>(end); +} + +template +inline constexpr Range, Unit>> + zeroTo(Quantity, Unit> end) { + return Range, Unit>>(end); +} + +} // namespace kj + +#endif // KJ_UNITS_H_ diff --git a/phonelibs/capnp-cpp/include/kj/vector.h b/phonelibs/capnp-cpp/include/kj/vector.h new file mode 100644 index 00000000000000..44613f333173cd --- /dev/null +++ b/phonelibs/capnp-cpp/include/kj/vector.h @@ -0,0 +1,144 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef KJ_VECTOR_H_ +#define KJ_VECTOR_H_ + +#if defined(__GNUC__) && !KJ_HEADER_WARNINGS +#pragma GCC system_header +#endif + +#include "array.h" + +namespace kj { + +template +class Vector { + // Similar to std::vector, but based on KJ framework. + // + // This implementation always uses move constructors when growing the backing array. If the + // move constructor throws, the Vector is left in an inconsistent state. This is acceptable + // under KJ exception theory which assumes that exceptions leave things in inconsistent states. + + // TODO(someday): Allow specifying a custom allocator. + +public: + inline Vector() = default; + inline explicit Vector(size_t capacity): builder(heapArrayBuilder(capacity)) {} + + inline operator ArrayPtr() { return builder; } + inline operator ArrayPtr() const { return builder; } + inline ArrayPtr asPtr() { return builder.asPtr(); } + inline ArrayPtr asPtr() const { return builder.asPtr(); } + + inline size_t size() const { return builder.size(); } + inline bool empty() const { return size() == 0; } + inline size_t capacity() const { return builder.capacity(); } + inline T& operator[](size_t index) const { return builder[index]; } + + inline const T* begin() const { return builder.begin(); } + inline const T* end() const { return builder.end(); } + inline const T& front() const { return builder.front(); } + inline const T& back() const { return builder.back(); } + inline T* begin() { return builder.begin(); } + inline T* end() { return builder.end(); } + inline T& front() { return builder.front(); } + inline T& back() { return builder.back(); } + + inline Array releaseAsArray() { + // TODO(perf): Avoid a copy/move by allowing Array to point to incomplete space? + if (!builder.isFull()) { + setCapacity(size()); + } + return builder.finish(); + } + + template + inline T& add(Params&&... params) { + if (builder.isFull()) grow(); + return builder.add(kj::fwd(params)...); + } + + template + inline void addAll(Iterator begin, Iterator end) { + size_t needed = builder.size() + (end - begin); + if (needed > builder.capacity()) grow(needed); + builder.addAll(begin, end); + } + + template + inline void addAll(Container&& container) { + addAll(container.begin(), container.end()); + } + + inline void removeLast() { + builder.removeLast(); + } + + inline void resize(size_t size) { + if (size > builder.capacity()) grow(size); + builder.resize(size); + } + + inline void operator=(decltype(nullptr)) { + builder = nullptr; + } + + inline void clear() { + while (builder.size() > 0) { + builder.removeLast(); + } + } + + inline void truncate(size_t size) { + builder.truncate(size); + } + + inline void reserve(size_t size) { + if (size > builder.capacity()) { + setCapacity(size); + } + } + +private: + ArrayBuilder builder; + + void grow(size_t minCapacity = 0) { + setCapacity(kj::max(minCapacity, capacity() == 0 ? 4 : capacity() * 2)); + } + void setCapacity(size_t newSize) { + if (builder.size() > newSize) { + builder.truncate(newSize); + } + ArrayBuilder newBuilder = heapArrayBuilder(newSize); + newBuilder.addAll(kj::mv(builder)); + builder = kj::mv(newBuilder); + } +}; + +template +inline auto KJ_STRINGIFY(const Vector& v) -> decltype(toCharSequence(v.asPtr())) { + return toCharSequence(v.asPtr()); +} + +} // namespace kj + +#endif // KJ_VECTOR_H_ diff --git a/phonelibs/capnp-cpp/include/kj/windows-sanity.h b/phonelibs/capnp-cpp/include/kj/windows-sanity.h new file mode 100644 index 00000000000000..766ba2cbd67047 --- /dev/null +++ b/phonelibs/capnp-cpp/include/kj/windows-sanity.h @@ -0,0 +1,41 @@ +// Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +// Licensed under the MIT License: +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +// THE SOFTWARE. + +#ifndef KJ_WINDOWS_SANITY_H_ +#define KJ_WINDOWS_SANITY_H_ + +#if defined(__GNUC__) && !KJ_HEADER_WARNINGS +#pragma GCC system_header +#endif + +#ifndef _INC_WINDOWS +#error "windows.h needs to be included before kj/windows-sanity.h (or perhaps you don't need either?)" +#endif + +namespace win32 { + const auto ERROR_ = ERROR; +#undef ERROR + const auto ERROR = ERROR_; +} + +using win32::ERROR; + +#endif // KJ_WINDOWS_SANITY_H_ diff --git a/phonelibs/curl/build.txt b/phonelibs/curl/build.txt new file mode 100644 index 00000000000000..def0763b46f828 --- /dev/null +++ b/phonelibs/curl/build.txt @@ -0,0 +1,5 @@ +# with neos tree +cd ~/android/system +mka libcurl + +cp ~/android/system/out/target/product/oneplus3/obj/STATIC_LIBRARIES/libcurl_intermediates/libcurl.a lib/ diff --git a/phonelibs/curl/include/Makefile.am b/phonelibs/curl/include/Makefile.am new file mode 100644 index 00000000000000..3b24860299525e --- /dev/null +++ b/phonelibs/curl/include/Makefile.am @@ -0,0 +1,5 @@ +SUBDIRS = curl + +EXTRA_DIST = README + +AUTOMAKE_OPTIONS = foreign no-dependencies diff --git a/phonelibs/curl/include/README b/phonelibs/curl/include/README new file mode 100644 index 00000000000000..3e52a1d0a6cb13 --- /dev/null +++ b/phonelibs/curl/include/README @@ -0,0 +1,55 @@ + _ _ ____ _ + ___| | | | _ \| | + / __| | | | |_) | | + | (__| |_| | _ <| |___ + \___|\___/|_| \_\_____| + +Include files for libcurl, external users. + +They're all placed in the curl subdirectory here for better fit in any kind +of environment. You must include files from here using... + + #include + +... style and point the compiler's include path to the directory holding the +curl subdirectory. It makes it more likely to survive future modifications. + +NOTE FOR LIBCURL HACKERS + +The following notes apply to libcurl version 7.19.0 and later. + +* The distributed curl/curlbuild.h file is only intended to be used on systems + which can not run the also distributed configure script. + +* The distributed curlbuild.h file is generated as a copy of curlbuild.h.dist + when the libcurl source code distribution archive file is originally created. + +* If you check out from git on a non-configure platform, you must run the + appropriate buildconf* script to set up curlbuild.h and other local files + before being able of compiling the library. + +* On systems capable of running the configure script, the configure process + will overwrite the distributed include/curl/curlbuild.h file with one that + is suitable and specific to the library being configured and built, which + is generated from the include/curl/curlbuild.h.in template file. + +* If you intend to distribute an already compiled libcurl library you _MUST_ + also distribute along with it the generated curl/curlbuild.h which has been + used to compile it. Otherwise the library will be of no use for the users of + the library that you have built. It is _your_ responsibility to provide this + file. No one at the cURL project can know how you have built the library. + +* File curl/curlbuild.h includes platform and configuration dependent info, + and must not be modified by anyone. Configure script generates it for you. + +* We cannot assume anything else but very basic compiler features being + present. While libcurl requires an ANSI C compiler to build, some of the + earlier ANSI compilers clearly can't deal with some preprocessor operators. + +* Newlines must remain unix-style for older compilers' sake. + +* Comments must be written in the old-style /* unnested C-fashion */ + +To figure out how to do good and portable checks for features, operating +systems or specific hardwarare, a very good resource is Bjorn Reese's +collection at http://predef.sf.net/ diff --git a/phonelibs/curl/include/curl/.gitignore b/phonelibs/curl/include/curl/.gitignore new file mode 100644 index 00000000000000..5f3bc3ce01b9a6 --- /dev/null +++ b/phonelibs/curl/include/curl/.gitignore @@ -0,0 +1,3 @@ +stamp-h2 +stamp-h3 +curlver.h.dist diff --git a/phonelibs/curl/include/curl/Makefile.am b/phonelibs/curl/include/curl/Makefile.am new file mode 100644 index 00000000000000..86e8b78344de31 --- /dev/null +++ b/phonelibs/curl/include/curl/Makefile.am @@ -0,0 +1,53 @@ +#*************************************************************************** +# _ _ ____ _ +# Project ___| | | | _ \| | +# / __| | | | |_) | | +# | (__| |_| | _ <| |___ +# \___|\___/|_| \_\_____| +# +# Copyright (C) 1998 - 2011, Daniel Stenberg, , et al. +# +# This software is licensed as described in the file COPYING, which +# you should have received as part of this distribution. The terms +# are also available at http://curl.haxx.se/docs/copyright.html. +# +# You may opt to use, copy, modify, merge, publish, distribute and/or sell +# copies of the Software, and permit persons to whom the Software is +# furnished to do so, under the terms of the COPYING file. +# +# This software is distributed on an "AS IS" basis, WITHOUT WARRANTY OF ANY +# KIND, either express or implied. +# +########################################################################### +pkginclude_HEADERS = \ + curl.h curlver.h easy.h mprintf.h stdcheaders.h multi.h \ + typecheck-gcc.h curlbuild.h curlrules.h + +pkgincludedir= $(includedir)/curl + +# curlbuild.h does not exist in the git tree. When the original libcurl +# source code distribution archive file is created, curlbuild.h.dist is +# renamed to curlbuild.h and included in the tarball so that it can be +# used directly on non-configure systems. +# +# The distributed curlbuild.h will be overwritten on configure systems +# when the configure script runs, with one that is suitable and specific +# to the library being configured and built. +# +# curlbuild.h.in is the distributed template file from which the configure +# script creates curlbuild.h at library configuration time, overwiting the +# one included in the distribution archive. +# +# curlbuild.h.dist is not included in the source code distribution archive. + +EXTRA_DIST = curlbuild.h.in + +DISTCLEANFILES = curlbuild.h + +checksrc: + @@PERL@ $(top_srcdir)/lib/checksrc.pl -Wcurlbuild.h -D$(top_srcdir)/include/curl $(pkginclude_HEADERS) $(EXTRA_DIST) + +if CURLDEBUG +# for debug builds, we scan the sources on all regular make invokes +all-local: checksrc +endif diff --git a/phonelibs/curl/include/curl/curl.h b/phonelibs/curl/include/curl/curl.h new file mode 100644 index 00000000000000..eab2f6e99a541c --- /dev/null +++ b/phonelibs/curl/include/curl/curl.h @@ -0,0 +1,2376 @@ +#ifndef __CURL_CURL_H +#define __CURL_CURL_H +/*************************************************************************** + * _ _ ____ _ + * Project ___| | | | _ \| | + * / __| | | | |_) | | + * | (__| |_| | _ <| |___ + * \___|\___/|_| \_\_____| + * + * Copyright (C) 1998 - 2015, Daniel Stenberg, , et al. + * + * This software is licensed as described in the file COPYING, which + * you should have received as part of this distribution. The terms + * are also available at http://curl.haxx.se/docs/copyright.html. + * + * You may opt to use, copy, modify, merge, publish, distribute and/or sell + * copies of the Software, and permit persons to whom the Software is + * furnished to do so, under the terms of the COPYING file. + * + * This software is distributed on an "AS IS" basis, WITHOUT WARRANTY OF ANY + * KIND, either express or implied. + * + ***************************************************************************/ + +/* + * If you have libcurl problems, all docs and details are found here: + * http://curl.haxx.se/libcurl/ + * + * curl-library mailing list subscription and unsubscription web interface: + * http://cool.haxx.se/mailman/listinfo/curl-library/ + */ + +#include "curlver.h" /* libcurl version defines */ +#include "curlbuild.h" /* libcurl build definitions */ +#include "curlrules.h" /* libcurl rules enforcement */ + +/* + * Define WIN32 when build target is Win32 API + */ + +#if (defined(_WIN32) || defined(__WIN32__)) && \ + !defined(WIN32) && !defined(__SYMBIAN32__) +#define WIN32 +#endif + +#include +#include + +#if defined(__FreeBSD__) && (__FreeBSD__ >= 2) +/* Needed for __FreeBSD_version symbol definition */ +#include +#endif + +/* The include stuff here below is mainly for time_t! */ +#include +#include + +#if defined(WIN32) && !defined(_WIN32_WCE) && !defined(__CYGWIN__) +#if !(defined(_WINSOCKAPI_) || defined(_WINSOCK_H) || defined(__LWIP_OPT_H__)) +/* The check above prevents the winsock2 inclusion if winsock.h already was + included, since they can't co-exist without problems */ +#include +#include +#endif +#endif + +/* HP-UX systems version 9, 10 and 11 lack sys/select.h and so does oldish + libc5-based Linux systems. Only include it on systems that are known to + require it! */ +#if defined(_AIX) || defined(__NOVELL_LIBC__) || defined(__NetBSD__) || \ + defined(__minix) || defined(__SYMBIAN32__) || defined(__INTEGRITY) || \ + defined(ANDROID) || defined(__ANDROID__) || defined(__OpenBSD__) || \ + (defined(__FreeBSD_version) && (__FreeBSD_version < 800000)) +#include +#endif + +#if !defined(WIN32) && !defined(_WIN32_WCE) +#include +#endif + +#if !defined(WIN32) && !defined(__WATCOMC__) && !defined(__VXWORKS__) +#include +#endif + +#ifdef __BEOS__ +#include +#endif + +#ifdef __cplusplus +extern "C" { +#endif + +typedef void CURL; + +/* + * libcurl external API function linkage decorations. + */ + +#ifdef CURL_STATICLIB +# define CURL_EXTERN +#elif defined(WIN32) || defined(_WIN32) || defined(__SYMBIAN32__) +# if defined(BUILDING_LIBCURL) +# define CURL_EXTERN __declspec(dllexport) +# else +# define CURL_EXTERN __declspec(dllimport) +# endif +#elif defined(BUILDING_LIBCURL) && defined(CURL_HIDDEN_SYMBOLS) +# define CURL_EXTERN CURL_EXTERN_SYMBOL +#else +# define CURL_EXTERN +#endif + +#ifndef curl_socket_typedef +/* socket typedef */ +#if defined(WIN32) && !defined(__LWIP_OPT_H__) +typedef SOCKET curl_socket_t; +#define CURL_SOCKET_BAD INVALID_SOCKET +#else +typedef int curl_socket_t; +#define CURL_SOCKET_BAD -1 +#endif +#define curl_socket_typedef +#endif /* curl_socket_typedef */ + +struct curl_httppost { + struct curl_httppost *next; /* next entry in the list */ + char *name; /* pointer to allocated name */ + long namelength; /* length of name length */ + char *contents; /* pointer to allocated data contents */ + long contentslength; /* length of contents field */ + char *buffer; /* pointer to allocated buffer contents */ + long bufferlength; /* length of buffer field */ + char *contenttype; /* Content-Type */ + struct curl_slist* contentheader; /* list of extra headers for this form */ + struct curl_httppost *more; /* if one field name has more than one + file, this link should link to following + files */ + long flags; /* as defined below */ +#define HTTPPOST_FILENAME (1<<0) /* specified content is a file name */ +#define HTTPPOST_READFILE (1<<1) /* specified content is a file name */ +#define HTTPPOST_PTRNAME (1<<2) /* name is only stored pointer + do not free in formfree */ +#define HTTPPOST_PTRCONTENTS (1<<3) /* contents is only stored pointer + do not free in formfree */ +#define HTTPPOST_BUFFER (1<<4) /* upload file from buffer */ +#define HTTPPOST_PTRBUFFER (1<<5) /* upload file from pointer contents */ +#define HTTPPOST_CALLBACK (1<<6) /* upload file contents by using the + regular read callback to get the data + and pass the given pointer as custom + pointer */ + + char *showfilename; /* The file name to show. If not set, the + actual file name will be used (if this + is a file part) */ + void *userp; /* custom pointer used for + HTTPPOST_CALLBACK posts */ +}; + +/* This is the CURLOPT_PROGRESSFUNCTION callback proto. It is now considered + deprecated but was the only choice up until 7.31.0 */ +typedef int (*curl_progress_callback)(void *clientp, + double dltotal, + double dlnow, + double ultotal, + double ulnow); + +/* This is the CURLOPT_XFERINFOFUNCTION callback proto. It was introduced in + 7.32.0, it avoids floating point and provides more detailed information. */ +typedef int (*curl_xferinfo_callback)(void *clientp, + curl_off_t dltotal, + curl_off_t dlnow, + curl_off_t ultotal, + curl_off_t ulnow); + +#ifndef CURL_MAX_WRITE_SIZE + /* Tests have proven that 20K is a very bad buffer size for uploads on + Windows, while 16K for some odd reason performed a lot better. + We do the ifndef check to allow this value to easier be changed at build + time for those who feel adventurous. The practical minimum is about + 400 bytes since libcurl uses a buffer of this size as a scratch area + (unrelated to network send operations). */ +#define CURL_MAX_WRITE_SIZE 16384 +#endif + +#ifndef CURL_MAX_HTTP_HEADER +/* The only reason to have a max limit for this is to avoid the risk of a bad + server feeding libcurl with a never-ending header that will cause reallocs + infinitely */ +#define CURL_MAX_HTTP_HEADER (100*1024) +#endif + +/* This is a magic return code for the write callback that, when returned, + will signal libcurl to pause receiving on the current transfer. */ +#define CURL_WRITEFUNC_PAUSE 0x10000001 + +typedef size_t (*curl_write_callback)(char *buffer, + size_t size, + size_t nitems, + void *outstream); + + + +/* enumeration of file types */ +typedef enum { + CURLFILETYPE_FILE = 0, + CURLFILETYPE_DIRECTORY, + CURLFILETYPE_SYMLINK, + CURLFILETYPE_DEVICE_BLOCK, + CURLFILETYPE_DEVICE_CHAR, + CURLFILETYPE_NAMEDPIPE, + CURLFILETYPE_SOCKET, + CURLFILETYPE_DOOR, /* is possible only on Sun Solaris now */ + + CURLFILETYPE_UNKNOWN /* should never occur */ +} curlfiletype; + +#define CURLFINFOFLAG_KNOWN_FILENAME (1<<0) +#define CURLFINFOFLAG_KNOWN_FILETYPE (1<<1) +#define CURLFINFOFLAG_KNOWN_TIME (1<<2) +#define CURLFINFOFLAG_KNOWN_PERM (1<<3) +#define CURLFINFOFLAG_KNOWN_UID (1<<4) +#define CURLFINFOFLAG_KNOWN_GID (1<<5) +#define CURLFINFOFLAG_KNOWN_SIZE (1<<6) +#define CURLFINFOFLAG_KNOWN_HLINKCOUNT (1<<7) + +/* Content of this structure depends on information which is known and is + achievable (e.g. by FTP LIST parsing). Please see the url_easy_setopt(3) man + page for callbacks returning this structure -- some fields are mandatory, + some others are optional. The FLAG field has special meaning. */ +struct curl_fileinfo { + char *filename; + curlfiletype filetype; + time_t time; + unsigned int perm; + int uid; + int gid; + curl_off_t size; + long int hardlinks; + + struct { + /* If some of these fields is not NULL, it is a pointer to b_data. */ + char *time; + char *perm; + char *user; + char *group; + char *target; /* pointer to the target filename of a symlink */ + } strings; + + unsigned int flags; + + /* used internally */ + char * b_data; + size_t b_size; + size_t b_used; +}; + +/* return codes for CURLOPT_CHUNK_BGN_FUNCTION */ +#define CURL_CHUNK_BGN_FUNC_OK 0 +#define CURL_CHUNK_BGN_FUNC_FAIL 1 /* tell the lib to end the task */ +#define CURL_CHUNK_BGN_FUNC_SKIP 2 /* skip this chunk over */ + +/* if splitting of data transfer is enabled, this callback is called before + download of an individual chunk started. Note that parameter "remains" works + only for FTP wildcard downloading (for now), otherwise is not used */ +typedef long (*curl_chunk_bgn_callback)(const void *transfer_info, + void *ptr, + int remains); + +/* return codes for CURLOPT_CHUNK_END_FUNCTION */ +#define CURL_CHUNK_END_FUNC_OK 0 +#define CURL_CHUNK_END_FUNC_FAIL 1 /* tell the lib to end the task */ + +/* If splitting of data transfer is enabled this callback is called after + download of an individual chunk finished. + Note! After this callback was set then it have to be called FOR ALL chunks. + Even if downloading of this chunk was skipped in CHUNK_BGN_FUNC. + This is the reason why we don't need "transfer_info" parameter in this + callback and we are not interested in "remains" parameter too. */ +typedef long (*curl_chunk_end_callback)(void *ptr); + +/* return codes for FNMATCHFUNCTION */ +#define CURL_FNMATCHFUNC_MATCH 0 /* string corresponds to the pattern */ +#define CURL_FNMATCHFUNC_NOMATCH 1 /* pattern doesn't match the string */ +#define CURL_FNMATCHFUNC_FAIL 2 /* an error occurred */ + +/* callback type for wildcard downloading pattern matching. If the + string matches the pattern, return CURL_FNMATCHFUNC_MATCH value, etc. */ +typedef int (*curl_fnmatch_callback)(void *ptr, + const char *pattern, + const char *string); + +/* These are the return codes for the seek callbacks */ +#define CURL_SEEKFUNC_OK 0 +#define CURL_SEEKFUNC_FAIL 1 /* fail the entire transfer */ +#define CURL_SEEKFUNC_CANTSEEK 2 /* tell libcurl seeking can't be done, so + libcurl might try other means instead */ +typedef int (*curl_seek_callback)(void *instream, + curl_off_t offset, + int origin); /* 'whence' */ + +/* This is a return code for the read callback that, when returned, will + signal libcurl to immediately abort the current transfer. */ +#define CURL_READFUNC_ABORT 0x10000000 +/* This is a return code for the read callback that, when returned, will + signal libcurl to pause sending data on the current transfer. */ +#define CURL_READFUNC_PAUSE 0x10000001 + +typedef size_t (*curl_read_callback)(char *buffer, + size_t size, + size_t nitems, + void *instream); + +typedef enum { + CURLSOCKTYPE_IPCXN, /* socket created for a specific IP connection */ + CURLSOCKTYPE_ACCEPT, /* socket created by accept() call */ + CURLSOCKTYPE_LAST /* never use */ +} curlsocktype; + +/* The return code from the sockopt_callback can signal information back + to libcurl: */ +#define CURL_SOCKOPT_OK 0 +#define CURL_SOCKOPT_ERROR 1 /* causes libcurl to abort and return + CURLE_ABORTED_BY_CALLBACK */ +#define CURL_SOCKOPT_ALREADY_CONNECTED 2 + +typedef int (*curl_sockopt_callback)(void *clientp, + curl_socket_t curlfd, + curlsocktype purpose); + +struct curl_sockaddr { + int family; + int socktype; + int protocol; + unsigned int addrlen; /* addrlen was a socklen_t type before 7.18.0 but it + turned really ugly and painful on the systems that + lack this type */ + struct sockaddr addr; +}; + +typedef curl_socket_t +(*curl_opensocket_callback)(void *clientp, + curlsocktype purpose, + struct curl_sockaddr *address); + +typedef int +(*curl_closesocket_callback)(void *clientp, curl_socket_t item); + +typedef enum { + CURLIOE_OK, /* I/O operation successful */ + CURLIOE_UNKNOWNCMD, /* command was unknown to callback */ + CURLIOE_FAILRESTART, /* failed to restart the read */ + CURLIOE_LAST /* never use */ +} curlioerr; + +typedef enum { + CURLIOCMD_NOP, /* no operation */ + CURLIOCMD_RESTARTREAD, /* restart the read stream from start */ + CURLIOCMD_LAST /* never use */ +} curliocmd; + +typedef curlioerr (*curl_ioctl_callback)(CURL *handle, + int cmd, + void *clientp); + +/* + * The following typedef's are signatures of malloc, free, realloc, strdup and + * calloc respectively. Function pointers of these types can be passed to the + * curl_global_init_mem() function to set user defined memory management + * callback routines. + */ +typedef void *(*curl_malloc_callback)(size_t size); +typedef void (*curl_free_callback)(void *ptr); +typedef void *(*curl_realloc_callback)(void *ptr, size_t size); +typedef char *(*curl_strdup_callback)(const char *str); +typedef void *(*curl_calloc_callback)(size_t nmemb, size_t size); + +/* the kind of data that is passed to information_callback*/ +typedef enum { + CURLINFO_TEXT = 0, + CURLINFO_HEADER_IN, /* 1 */ + CURLINFO_HEADER_OUT, /* 2 */ + CURLINFO_DATA_IN, /* 3 */ + CURLINFO_DATA_OUT, /* 4 */ + CURLINFO_SSL_DATA_IN, /* 5 */ + CURLINFO_SSL_DATA_OUT, /* 6 */ + CURLINFO_END +} curl_infotype; + +typedef int (*curl_debug_callback) + (CURL *handle, /* the handle/transfer this concerns */ + curl_infotype type, /* what kind of data */ + char *data, /* points to the data */ + size_t size, /* size of the data pointed to */ + void *userptr); /* whatever the user please */ + +/* All possible error codes from all sorts of curl functions. Future versions + may return other values, stay prepared. + + Always add new return codes last. Never *EVER* remove any. The return + codes must remain the same! + */ + +typedef enum { + CURLE_OK = 0, + CURLE_UNSUPPORTED_PROTOCOL, /* 1 */ + CURLE_FAILED_INIT, /* 2 */ + CURLE_URL_MALFORMAT, /* 3 */ + CURLE_NOT_BUILT_IN, /* 4 - [was obsoleted in August 2007 for + 7.17.0, reused in April 2011 for 7.21.5] */ + CURLE_COULDNT_RESOLVE_PROXY, /* 5 */ + CURLE_COULDNT_RESOLVE_HOST, /* 6 */ + CURLE_COULDNT_CONNECT, /* 7 */ + CURLE_FTP_WEIRD_SERVER_REPLY, /* 8 */ + CURLE_REMOTE_ACCESS_DENIED, /* 9 a service was denied by the server + due to lack of access - when login fails + this is not returned. */ + CURLE_FTP_ACCEPT_FAILED, /* 10 - [was obsoleted in April 2006 for + 7.15.4, reused in Dec 2011 for 7.24.0]*/ + CURLE_FTP_WEIRD_PASS_REPLY, /* 11 */ + CURLE_FTP_ACCEPT_TIMEOUT, /* 12 - timeout occurred accepting server + [was obsoleted in August 2007 for 7.17.0, + reused in Dec 2011 for 7.24.0]*/ + CURLE_FTP_WEIRD_PASV_REPLY, /* 13 */ + CURLE_FTP_WEIRD_227_FORMAT, /* 14 */ + CURLE_FTP_CANT_GET_HOST, /* 15 */ + CURLE_HTTP2, /* 16 - A problem in the http2 framing layer. + [was obsoleted in August 2007 for 7.17.0, + reused in July 2014 for 7.38.0] */ + CURLE_FTP_COULDNT_SET_TYPE, /* 17 */ + CURLE_PARTIAL_FILE, /* 18 */ + CURLE_FTP_COULDNT_RETR_FILE, /* 19 */ + CURLE_OBSOLETE20, /* 20 - NOT USED */ + CURLE_QUOTE_ERROR, /* 21 - quote command failure */ + CURLE_HTTP_RETURNED_ERROR, /* 22 */ + CURLE_WRITE_ERROR, /* 23 */ + CURLE_OBSOLETE24, /* 24 - NOT USED */ + CURLE_UPLOAD_FAILED, /* 25 - failed upload "command" */ + CURLE_READ_ERROR, /* 26 - couldn't open/read from file */ + CURLE_OUT_OF_MEMORY, /* 27 */ + /* Note: CURLE_OUT_OF_MEMORY may sometimes indicate a conversion error + instead of a memory allocation error if CURL_DOES_CONVERSIONS + is defined + */ + CURLE_OPERATION_TIMEDOUT, /* 28 - the timeout time was reached */ + CURLE_OBSOLETE29, /* 29 - NOT USED */ + CURLE_FTP_PORT_FAILED, /* 30 - FTP PORT operation failed */ + CURLE_FTP_COULDNT_USE_REST, /* 31 - the REST command failed */ + CURLE_OBSOLETE32, /* 32 - NOT USED */ + CURLE_RANGE_ERROR, /* 33 - RANGE "command" didn't work */ + CURLE_HTTP_POST_ERROR, /* 34 */ + CURLE_SSL_CONNECT_ERROR, /* 35 - wrong when connecting with SSL */ + CURLE_BAD_DOWNLOAD_RESUME, /* 36 - couldn't resume download */ + CURLE_FILE_COULDNT_READ_FILE, /* 37 */ + CURLE_LDAP_CANNOT_BIND, /* 38 */ + CURLE_LDAP_SEARCH_FAILED, /* 39 */ + CURLE_OBSOLETE40, /* 40 - NOT USED */ + CURLE_FUNCTION_NOT_FOUND, /* 41 */ + CURLE_ABORTED_BY_CALLBACK, /* 42 */ + CURLE_BAD_FUNCTION_ARGUMENT, /* 43 */ + CURLE_OBSOLETE44, /* 44 - NOT USED */ + CURLE_INTERFACE_FAILED, /* 45 - CURLOPT_INTERFACE failed */ + CURLE_OBSOLETE46, /* 46 - NOT USED */ + CURLE_TOO_MANY_REDIRECTS , /* 47 - catch endless re-direct loops */ + CURLE_UNKNOWN_OPTION, /* 48 - User specified an unknown option */ + CURLE_TELNET_OPTION_SYNTAX , /* 49 - Malformed telnet option */ + CURLE_OBSOLETE50, /* 50 - NOT USED */ + CURLE_PEER_FAILED_VERIFICATION, /* 51 - peer's certificate or fingerprint + wasn't verified fine */ + CURLE_GOT_NOTHING, /* 52 - when this is a specific error */ + CURLE_SSL_ENGINE_NOTFOUND, /* 53 - SSL crypto engine not found */ + CURLE_SSL_ENGINE_SETFAILED, /* 54 - can not set SSL crypto engine as + default */ + CURLE_SEND_ERROR, /* 55 - failed sending network data */ + CURLE_RECV_ERROR, /* 56 - failure in receiving network data */ + CURLE_OBSOLETE57, /* 57 - NOT IN USE */ + CURLE_SSL_CERTPROBLEM, /* 58 - problem with the local certificate */ + CURLE_SSL_CIPHER, /* 59 - couldn't use specified cipher */ + CURLE_SSL_CACERT, /* 60 - problem with the CA cert (path?) */ + CURLE_BAD_CONTENT_ENCODING, /* 61 - Unrecognized/bad encoding */ + CURLE_LDAP_INVALID_URL, /* 62 - Invalid LDAP URL */ + CURLE_FILESIZE_EXCEEDED, /* 63 - Maximum file size exceeded */ + CURLE_USE_SSL_FAILED, /* 64 - Requested FTP SSL level failed */ + CURLE_SEND_FAIL_REWIND, /* 65 - Sending the data requires a rewind + that failed */ + CURLE_SSL_ENGINE_INITFAILED, /* 66 - failed to initialise ENGINE */ + CURLE_LOGIN_DENIED, /* 67 - user, password or similar was not + accepted and we failed to login */ + CURLE_TFTP_NOTFOUND, /* 68 - file not found on server */ + CURLE_TFTP_PERM, /* 69 - permission problem on server */ + CURLE_REMOTE_DISK_FULL, /* 70 - out of disk space on server */ + CURLE_TFTP_ILLEGAL, /* 71 - Illegal TFTP operation */ + CURLE_TFTP_UNKNOWNID, /* 72 - Unknown transfer ID */ + CURLE_REMOTE_FILE_EXISTS, /* 73 - File already exists */ + CURLE_TFTP_NOSUCHUSER, /* 74 - No such user */ + CURLE_CONV_FAILED, /* 75 - conversion failed */ + CURLE_CONV_REQD, /* 76 - caller must register conversion + callbacks using curl_easy_setopt options + CURLOPT_CONV_FROM_NETWORK_FUNCTION, + CURLOPT_CONV_TO_NETWORK_FUNCTION, and + CURLOPT_CONV_FROM_UTF8_FUNCTION */ + CURLE_SSL_CACERT_BADFILE, /* 77 - could not load CACERT file, missing + or wrong format */ + CURLE_REMOTE_FILE_NOT_FOUND, /* 78 - remote file not found */ + CURLE_SSH, /* 79 - error from the SSH layer, somewhat + generic so the error message will be of + interest when this has happened */ + + CURLE_SSL_SHUTDOWN_FAILED, /* 80 - Failed to shut down the SSL + connection */ + CURLE_AGAIN, /* 81 - socket is not ready for send/recv, + wait till it's ready and try again (Added + in 7.18.2) */ + CURLE_SSL_CRL_BADFILE, /* 82 - could not load CRL file, missing or + wrong format (Added in 7.19.0) */ + CURLE_SSL_ISSUER_ERROR, /* 83 - Issuer check failed. (Added in + 7.19.0) */ + CURLE_FTP_PRET_FAILED, /* 84 - a PRET command failed */ + CURLE_RTSP_CSEQ_ERROR, /* 85 - mismatch of RTSP CSeq numbers */ + CURLE_RTSP_SESSION_ERROR, /* 86 - mismatch of RTSP Session Ids */ + CURLE_FTP_BAD_FILE_LIST, /* 87 - unable to parse FTP file list */ + CURLE_CHUNK_FAILED, /* 88 - chunk callback reported error */ + CURLE_NO_CONNECTION_AVAILABLE, /* 89 - No connection available, the + session will be queued */ + CURLE_SSL_PINNEDPUBKEYNOTMATCH, /* 90 - specified pinned public key did not + match */ + CURLE_SSL_INVALIDCERTSTATUS, /* 91 - invalid certificate status */ + CURL_LAST /* never use! */ +} CURLcode; + +#ifndef CURL_NO_OLDIES /* define this to test if your app builds with all + the obsolete stuff removed! */ + +/* Previously obsolete error code re-used in 7.38.0 */ +#define CURLE_OBSOLETE16 CURLE_HTTP2 + +/* Previously obsolete error codes re-used in 7.24.0 */ +#define CURLE_OBSOLETE10 CURLE_FTP_ACCEPT_FAILED +#define CURLE_OBSOLETE12 CURLE_FTP_ACCEPT_TIMEOUT + +/* compatibility with older names */ +#define CURLOPT_ENCODING CURLOPT_ACCEPT_ENCODING + +/* The following were added in 7.21.5, April 2011 */ +#define CURLE_UNKNOWN_TELNET_OPTION CURLE_UNKNOWN_OPTION + +/* The following were added in 7.17.1 */ +/* These are scheduled to disappear by 2009 */ +#define CURLE_SSL_PEER_CERTIFICATE CURLE_PEER_FAILED_VERIFICATION + +/* The following were added in 7.17.0 */ +/* These are scheduled to disappear by 2009 */ +#define CURLE_OBSOLETE CURLE_OBSOLETE50 /* no one should be using this! */ +#define CURLE_BAD_PASSWORD_ENTERED CURLE_OBSOLETE46 +#define CURLE_BAD_CALLING_ORDER CURLE_OBSOLETE44 +#define CURLE_FTP_USER_PASSWORD_INCORRECT CURLE_OBSOLETE10 +#define CURLE_FTP_CANT_RECONNECT CURLE_OBSOLETE16 +#define CURLE_FTP_COULDNT_GET_SIZE CURLE_OBSOLETE32 +#define CURLE_FTP_COULDNT_SET_ASCII CURLE_OBSOLETE29 +#define CURLE_FTP_WEIRD_USER_REPLY CURLE_OBSOLETE12 +#define CURLE_FTP_WRITE_ERROR CURLE_OBSOLETE20 +#define CURLE_LIBRARY_NOT_FOUND CURLE_OBSOLETE40 +#define CURLE_MALFORMAT_USER CURLE_OBSOLETE24 +#define CURLE_SHARE_IN_USE CURLE_OBSOLETE57 +#define CURLE_URL_MALFORMAT_USER CURLE_NOT_BUILT_IN + +#define CURLE_FTP_ACCESS_DENIED CURLE_REMOTE_ACCESS_DENIED +#define CURLE_FTP_COULDNT_SET_BINARY CURLE_FTP_COULDNT_SET_TYPE +#define CURLE_FTP_QUOTE_ERROR CURLE_QUOTE_ERROR +#define CURLE_TFTP_DISKFULL CURLE_REMOTE_DISK_FULL +#define CURLE_TFTP_EXISTS CURLE_REMOTE_FILE_EXISTS +#define CURLE_HTTP_RANGE_ERROR CURLE_RANGE_ERROR +#define CURLE_FTP_SSL_FAILED CURLE_USE_SSL_FAILED + +/* The following were added earlier */ + +#define CURLE_OPERATION_TIMEOUTED CURLE_OPERATION_TIMEDOUT + +#define CURLE_HTTP_NOT_FOUND CURLE_HTTP_RETURNED_ERROR +#define CURLE_HTTP_PORT_FAILED CURLE_INTERFACE_FAILED +#define CURLE_FTP_COULDNT_STOR_FILE CURLE_UPLOAD_FAILED + +#define CURLE_FTP_PARTIAL_FILE CURLE_PARTIAL_FILE +#define CURLE_FTP_BAD_DOWNLOAD_RESUME CURLE_BAD_DOWNLOAD_RESUME + +/* This was the error code 50 in 7.7.3 and a few earlier versions, this + is no longer used by libcurl but is instead #defined here only to not + make programs break */ +#define CURLE_ALREADY_COMPLETE 99999 + +/* Provide defines for really old option names */ +#define CURLOPT_FILE CURLOPT_WRITEDATA /* name changed in 7.9.7 */ +#define CURLOPT_INFILE CURLOPT_READDATA /* name changed in 7.9.7 */ +#define CURLOPT_WRITEHEADER CURLOPT_HEADERDATA + +/* Since long deprecated options with no code in the lib that does anything + with them. */ +#define CURLOPT_WRITEINFO CURLOPT_OBSOLETE40 +#define CURLOPT_CLOSEPOLICY CURLOPT_OBSOLETE72 + +#endif /*!CURL_NO_OLDIES*/ + +/* This prototype applies to all conversion callbacks */ +typedef CURLcode (*curl_conv_callback)(char *buffer, size_t length); + +typedef CURLcode (*curl_ssl_ctx_callback)(CURL *curl, /* easy handle */ + void *ssl_ctx, /* actually an + OpenSSL SSL_CTX */ + void *userptr); + +typedef enum { + CURLPROXY_HTTP = 0, /* added in 7.10, new in 7.19.4 default is to use + CONNECT HTTP/1.1 */ + CURLPROXY_HTTP_1_0 = 1, /* added in 7.19.4, force to use CONNECT + HTTP/1.0 */ + CURLPROXY_SOCKS4 = 4, /* support added in 7.15.2, enum existed already + in 7.10 */ + CURLPROXY_SOCKS5 = 5, /* added in 7.10 */ + CURLPROXY_SOCKS4A = 6, /* added in 7.18.0 */ + CURLPROXY_SOCKS5_HOSTNAME = 7 /* Use the SOCKS5 protocol but pass along the + host name rather than the IP address. added + in 7.18.0 */ +} curl_proxytype; /* this enum was added in 7.10 */ + +/* + * Bitmasks for CURLOPT_HTTPAUTH and CURLOPT_PROXYAUTH options: + * + * CURLAUTH_NONE - No HTTP authentication + * CURLAUTH_BASIC - HTTP Basic authentication (default) + * CURLAUTH_DIGEST - HTTP Digest authentication + * CURLAUTH_NEGOTIATE - HTTP Negotiate (SPNEGO) authentication + * CURLAUTH_GSSNEGOTIATE - Alias for CURLAUTH_NEGOTIATE (deprecated) + * CURLAUTH_NTLM - HTTP NTLM authentication + * CURLAUTH_DIGEST_IE - HTTP Digest authentication with IE flavour + * CURLAUTH_NTLM_WB - HTTP NTLM authentication delegated to winbind helper + * CURLAUTH_ONLY - Use together with a single other type to force no + * authentication or just that single type + * CURLAUTH_ANY - All fine types set + * CURLAUTH_ANYSAFE - All fine types except Basic + */ + +#define CURLAUTH_NONE ((unsigned long)0) +#define CURLAUTH_BASIC (((unsigned long)1)<<0) +#define CURLAUTH_DIGEST (((unsigned long)1)<<1) +#define CURLAUTH_NEGOTIATE (((unsigned long)1)<<2) +/* Deprecated since the advent of CURLAUTH_NEGOTIATE */ +#define CURLAUTH_GSSNEGOTIATE CURLAUTH_NEGOTIATE +#define CURLAUTH_NTLM (((unsigned long)1)<<3) +#define CURLAUTH_DIGEST_IE (((unsigned long)1)<<4) +#define CURLAUTH_NTLM_WB (((unsigned long)1)<<5) +#define CURLAUTH_ONLY (((unsigned long)1)<<31) +#define CURLAUTH_ANY (~CURLAUTH_DIGEST_IE) +#define CURLAUTH_ANYSAFE (~(CURLAUTH_BASIC|CURLAUTH_DIGEST_IE)) + +#define CURLSSH_AUTH_ANY ~0 /* all types supported by the server */ +#define CURLSSH_AUTH_NONE 0 /* none allowed, silly but complete */ +#define CURLSSH_AUTH_PUBLICKEY (1<<0) /* public/private key files */ +#define CURLSSH_AUTH_PASSWORD (1<<1) /* password */ +#define CURLSSH_AUTH_HOST (1<<2) /* host key files */ +#define CURLSSH_AUTH_KEYBOARD (1<<3) /* keyboard interactive */ +#define CURLSSH_AUTH_AGENT (1<<4) /* agent (ssh-agent, pageant...) */ +#define CURLSSH_AUTH_DEFAULT CURLSSH_AUTH_ANY + +#define CURLGSSAPI_DELEGATION_NONE 0 /* no delegation (default) */ +#define CURLGSSAPI_DELEGATION_POLICY_FLAG (1<<0) /* if permitted by policy */ +#define CURLGSSAPI_DELEGATION_FLAG (1<<1) /* delegate always */ + +#define CURL_ERROR_SIZE 256 + +enum curl_khtype { + CURLKHTYPE_UNKNOWN, + CURLKHTYPE_RSA1, + CURLKHTYPE_RSA, + CURLKHTYPE_DSS +}; + +struct curl_khkey { + const char *key; /* points to a zero-terminated string encoded with base64 + if len is zero, otherwise to the "raw" data */ + size_t len; + enum curl_khtype keytype; +}; + +/* this is the set of return values expected from the curl_sshkeycallback + callback */ +enum curl_khstat { + CURLKHSTAT_FINE_ADD_TO_FILE, + CURLKHSTAT_FINE, + CURLKHSTAT_REJECT, /* reject the connection, return an error */ + CURLKHSTAT_DEFER, /* do not accept it, but we can't answer right now so + this causes a CURLE_DEFER error but otherwise the + connection will be left intact etc */ + CURLKHSTAT_LAST /* not for use, only a marker for last-in-list */ +}; + +/* this is the set of status codes pass in to the callback */ +enum curl_khmatch { + CURLKHMATCH_OK, /* match */ + CURLKHMATCH_MISMATCH, /* host found, key mismatch! */ + CURLKHMATCH_MISSING, /* no matching host/key found */ + CURLKHMATCH_LAST /* not for use, only a marker for last-in-list */ +}; + +typedef int + (*curl_sshkeycallback) (CURL *easy, /* easy handle */ + const struct curl_khkey *knownkey, /* known */ + const struct curl_khkey *foundkey, /* found */ + enum curl_khmatch, /* libcurl's view on the keys */ + void *clientp); /* custom pointer passed from app */ + +/* parameter for the CURLOPT_USE_SSL option */ +typedef enum { + CURLUSESSL_NONE, /* do not attempt to use SSL */ + CURLUSESSL_TRY, /* try using SSL, proceed anyway otherwise */ + CURLUSESSL_CONTROL, /* SSL for the control connection or fail */ + CURLUSESSL_ALL, /* SSL for all communication or fail */ + CURLUSESSL_LAST /* not an option, never use */ +} curl_usessl; + +/* Definition of bits for the CURLOPT_SSL_OPTIONS argument: */ + +/* - ALLOW_BEAST tells libcurl to allow the BEAST SSL vulnerability in the + name of improving interoperability with older servers. Some SSL libraries + have introduced work-arounds for this flaw but those work-arounds sometimes + make the SSL communication fail. To regain functionality with those broken + servers, a user can this way allow the vulnerability back. */ +#define CURLSSLOPT_ALLOW_BEAST (1<<0) + +#ifndef CURL_NO_OLDIES /* define this to test if your app builds with all + the obsolete stuff removed! */ + +/* Backwards compatibility with older names */ +/* These are scheduled to disappear by 2009 */ + +#define CURLFTPSSL_NONE CURLUSESSL_NONE +#define CURLFTPSSL_TRY CURLUSESSL_TRY +#define CURLFTPSSL_CONTROL CURLUSESSL_CONTROL +#define CURLFTPSSL_ALL CURLUSESSL_ALL +#define CURLFTPSSL_LAST CURLUSESSL_LAST +#define curl_ftpssl curl_usessl +#endif /*!CURL_NO_OLDIES*/ + +/* parameter for the CURLOPT_FTP_SSL_CCC option */ +typedef enum { + CURLFTPSSL_CCC_NONE, /* do not send CCC */ + CURLFTPSSL_CCC_PASSIVE, /* Let the server initiate the shutdown */ + CURLFTPSSL_CCC_ACTIVE, /* Initiate the shutdown */ + CURLFTPSSL_CCC_LAST /* not an option, never use */ +} curl_ftpccc; + +/* parameter for the CURLOPT_FTPSSLAUTH option */ +typedef enum { + CURLFTPAUTH_DEFAULT, /* let libcurl decide */ + CURLFTPAUTH_SSL, /* use "AUTH SSL" */ + CURLFTPAUTH_TLS, /* use "AUTH TLS" */ + CURLFTPAUTH_LAST /* not an option, never use */ +} curl_ftpauth; + +/* parameter for the CURLOPT_FTP_CREATE_MISSING_DIRS option */ +typedef enum { + CURLFTP_CREATE_DIR_NONE, /* do NOT create missing dirs! */ + CURLFTP_CREATE_DIR, /* (FTP/SFTP) if CWD fails, try MKD and then CWD + again if MKD succeeded, for SFTP this does + similar magic */ + CURLFTP_CREATE_DIR_RETRY, /* (FTP only) if CWD fails, try MKD and then CWD + again even if MKD failed! */ + CURLFTP_CREATE_DIR_LAST /* not an option, never use */ +} curl_ftpcreatedir; + +/* parameter for the CURLOPT_FTP_FILEMETHOD option */ +typedef enum { + CURLFTPMETHOD_DEFAULT, /* let libcurl pick */ + CURLFTPMETHOD_MULTICWD, /* single CWD operation for each path part */ + CURLFTPMETHOD_NOCWD, /* no CWD at all */ + CURLFTPMETHOD_SINGLECWD, /* one CWD to full dir, then work on file */ + CURLFTPMETHOD_LAST /* not an option, never use */ +} curl_ftpmethod; + +/* bitmask defines for CURLOPT_HEADEROPT */ +#define CURLHEADER_UNIFIED 0 +#define CURLHEADER_SEPARATE (1<<0) + +/* CURLPROTO_ defines are for the CURLOPT_*PROTOCOLS options */ +#define CURLPROTO_HTTP (1<<0) +#define CURLPROTO_HTTPS (1<<1) +#define CURLPROTO_FTP (1<<2) +#define CURLPROTO_FTPS (1<<3) +#define CURLPROTO_SCP (1<<4) +#define CURLPROTO_SFTP (1<<5) +#define CURLPROTO_TELNET (1<<6) +#define CURLPROTO_LDAP (1<<7) +#define CURLPROTO_LDAPS (1<<8) +#define CURLPROTO_DICT (1<<9) +#define CURLPROTO_FILE (1<<10) +#define CURLPROTO_TFTP (1<<11) +#define CURLPROTO_IMAP (1<<12) +#define CURLPROTO_IMAPS (1<<13) +#define CURLPROTO_POP3 (1<<14) +#define CURLPROTO_POP3S (1<<15) +#define CURLPROTO_SMTP (1<<16) +#define CURLPROTO_SMTPS (1<<17) +#define CURLPROTO_RTSP (1<<18) +#define CURLPROTO_RTMP (1<<19) +#define CURLPROTO_RTMPT (1<<20) +#define CURLPROTO_RTMPE (1<<21) +#define CURLPROTO_RTMPTE (1<<22) +#define CURLPROTO_RTMPS (1<<23) +#define CURLPROTO_RTMPTS (1<<24) +#define CURLPROTO_GOPHER (1<<25) +#define CURLPROTO_SMB (1<<26) +#define CURLPROTO_SMBS (1<<27) +#define CURLPROTO_ALL (~0) /* enable everything */ + +/* long may be 32 or 64 bits, but we should never depend on anything else + but 32 */ +#define CURLOPTTYPE_LONG 0 +#define CURLOPTTYPE_OBJECTPOINT 10000 +#define CURLOPTTYPE_FUNCTIONPOINT 20000 +#define CURLOPTTYPE_OFF_T 30000 + +/* name is uppercase CURLOPT_, + type is one of the defined CURLOPTTYPE_ + number is unique identifier */ +#ifdef CINIT +#undef CINIT +#endif + +#ifdef CURL_ISOCPP +#define CINIT(na,t,nu) CURLOPT_ ## na = CURLOPTTYPE_ ## t + nu +#else +/* The macro "##" is ISO C, we assume pre-ISO C doesn't support it. */ +#define LONG CURLOPTTYPE_LONG +#define OBJECTPOINT CURLOPTTYPE_OBJECTPOINT +#define FUNCTIONPOINT CURLOPTTYPE_FUNCTIONPOINT +#define OFF_T CURLOPTTYPE_OFF_T +#define CINIT(name,type,number) CURLOPT_/**/name = type + number +#endif + +/* + * This macro-mania below setups the CURLOPT_[what] enum, to be used with + * curl_easy_setopt(). The first argument in the CINIT() macro is the [what] + * word. + */ + +typedef enum { + /* This is the FILE * or void * the regular output should be written to. */ + CINIT(WRITEDATA, OBJECTPOINT, 1), + + /* The full URL to get/put */ + CINIT(URL, OBJECTPOINT, 2), + + /* Port number to connect to, if other than default. */ + CINIT(PORT, LONG, 3), + + /* Name of proxy to use. */ + CINIT(PROXY, OBJECTPOINT, 4), + + /* "user:password;options" to use when fetching. */ + CINIT(USERPWD, OBJECTPOINT, 5), + + /* "user:password" to use with proxy. */ + CINIT(PROXYUSERPWD, OBJECTPOINT, 6), + + /* Range to get, specified as an ASCII string. */ + CINIT(RANGE, OBJECTPOINT, 7), + + /* not used */ + + /* Specified file stream to upload from (use as input): */ + CINIT(READDATA, OBJECTPOINT, 9), + + /* Buffer to receive error messages in, must be at least CURL_ERROR_SIZE + * bytes big. If this is not used, error messages go to stderr instead: */ + CINIT(ERRORBUFFER, OBJECTPOINT, 10), + + /* Function that will be called to store the output (instead of fwrite). The + * parameters will use fwrite() syntax, make sure to follow them. */ + CINIT(WRITEFUNCTION, FUNCTIONPOINT, 11), + + /* Function that will be called to read the input (instead of fread). The + * parameters will use fread() syntax, make sure to follow them. */ + CINIT(READFUNCTION, FUNCTIONPOINT, 12), + + /* Time-out the read operation after this amount of seconds */ + CINIT(TIMEOUT, LONG, 13), + + /* If the CURLOPT_INFILE is used, this can be used to inform libcurl about + * how large the file being sent really is. That allows better error + * checking and better verifies that the upload was successful. -1 means + * unknown size. + * + * For large file support, there is also a _LARGE version of the key + * which takes an off_t type, allowing platforms with larger off_t + * sizes to handle larger files. See below for INFILESIZE_LARGE. + */ + CINIT(INFILESIZE, LONG, 14), + + /* POST static input fields. */ + CINIT(POSTFIELDS, OBJECTPOINT, 15), + + /* Set the referrer page (needed by some CGIs) */ + CINIT(REFERER, OBJECTPOINT, 16), + + /* Set the FTP PORT string (interface name, named or numerical IP address) + Use i.e '-' to use default address. */ + CINIT(FTPPORT, OBJECTPOINT, 17), + + /* Set the User-Agent string (examined by some CGIs) */ + CINIT(USERAGENT, OBJECTPOINT, 18), + + /* If the download receives less than "low speed limit" bytes/second + * during "low speed time" seconds, the operations is aborted. + * You could i.e if you have a pretty high speed connection, abort if + * it is less than 2000 bytes/sec during 20 seconds. + */ + + /* Set the "low speed limit" */ + CINIT(LOW_SPEED_LIMIT, LONG, 19), + + /* Set the "low speed time" */ + CINIT(LOW_SPEED_TIME, LONG, 20), + + /* Set the continuation offset. + * + * Note there is also a _LARGE version of this key which uses + * off_t types, allowing for large file offsets on platforms which + * use larger-than-32-bit off_t's. Look below for RESUME_FROM_LARGE. + */ + CINIT(RESUME_FROM, LONG, 21), + + /* Set cookie in request: */ + CINIT(COOKIE, OBJECTPOINT, 22), + + /* This points to a linked list of headers, struct curl_slist kind. This + list is also used for RTSP (in spite of its name) */ + CINIT(HTTPHEADER, OBJECTPOINT, 23), + + /* This points to a linked list of post entries, struct curl_httppost */ + CINIT(HTTPPOST, OBJECTPOINT, 24), + + /* name of the file keeping your private SSL-certificate */ + CINIT(SSLCERT, OBJECTPOINT, 25), + + /* password for the SSL or SSH private key */ + CINIT(KEYPASSWD, OBJECTPOINT, 26), + + /* send TYPE parameter? */ + CINIT(CRLF, LONG, 27), + + /* send linked-list of QUOTE commands */ + CINIT(QUOTE, OBJECTPOINT, 28), + + /* send FILE * or void * to store headers to, if you use a callback it + is simply passed to the callback unmodified */ + CINIT(HEADERDATA, OBJECTPOINT, 29), + + /* point to a file to read the initial cookies from, also enables + "cookie awareness" */ + CINIT(COOKIEFILE, OBJECTPOINT, 31), + + /* What version to specifically try to use. + See CURL_SSLVERSION defines below. */ + CINIT(SSLVERSION, LONG, 32), + + /* What kind of HTTP time condition to use, see defines */ + CINIT(TIMECONDITION, LONG, 33), + + /* Time to use with the above condition. Specified in number of seconds + since 1 Jan 1970 */ + CINIT(TIMEVALUE, LONG, 34), + + /* 35 = OBSOLETE */ + + /* Custom request, for customizing the get command like + HTTP: DELETE, TRACE and others + FTP: to use a different list command + */ + CINIT(CUSTOMREQUEST, OBJECTPOINT, 36), + + /* HTTP request, for odd commands like DELETE, TRACE and others */ + CINIT(STDERR, OBJECTPOINT, 37), + + /* 38 is not used */ + + /* send linked-list of post-transfer QUOTE commands */ + CINIT(POSTQUOTE, OBJECTPOINT, 39), + + CINIT(OBSOLETE40, OBJECTPOINT, 40), /* OBSOLETE, do not use! */ + + CINIT(VERBOSE, LONG, 41), /* talk a lot */ + CINIT(HEADER, LONG, 42), /* throw the header out too */ + CINIT(NOPROGRESS, LONG, 43), /* shut off the progress meter */ + CINIT(NOBODY, LONG, 44), /* use HEAD to get http document */ + CINIT(FAILONERROR, LONG, 45), /* no output on http error codes >= 400 */ + CINIT(UPLOAD, LONG, 46), /* this is an upload */ + CINIT(POST, LONG, 47), /* HTTP POST method */ + CINIT(DIRLISTONLY, LONG, 48), /* bare names when listing directories */ + + CINIT(APPEND, LONG, 50), /* Append instead of overwrite on upload! */ + + /* Specify whether to read the user+password from the .netrc or the URL. + * This must be one of the CURL_NETRC_* enums below. */ + CINIT(NETRC, LONG, 51), + + CINIT(FOLLOWLOCATION, LONG, 52), /* use Location: Luke! */ + + CINIT(TRANSFERTEXT, LONG, 53), /* transfer data in text/ASCII format */ + CINIT(PUT, LONG, 54), /* HTTP PUT */ + + /* 55 = OBSOLETE */ + + /* DEPRECATED + * Function that will be called instead of the internal progress display + * function. This function should be defined as the curl_progress_callback + * prototype defines. */ + CINIT(PROGRESSFUNCTION, FUNCTIONPOINT, 56), + + /* Data passed to the CURLOPT_PROGRESSFUNCTION and CURLOPT_XFERINFOFUNCTION + callbacks */ + CINIT(PROGRESSDATA, OBJECTPOINT, 57), +#define CURLOPT_XFERINFODATA CURLOPT_PROGRESSDATA + + /* We want the referrer field set automatically when following locations */ + CINIT(AUTOREFERER, LONG, 58), + + /* Port of the proxy, can be set in the proxy string as well with: + "[host]:[port]" */ + CINIT(PROXYPORT, LONG, 59), + + /* size of the POST input data, if strlen() is not good to use */ + CINIT(POSTFIELDSIZE, LONG, 60), + + /* tunnel non-http operations through a HTTP proxy */ + CINIT(HTTPPROXYTUNNEL, LONG, 61), + + /* Set the interface string to use as outgoing network interface */ + CINIT(INTERFACE, OBJECTPOINT, 62), + + /* Set the krb4/5 security level, this also enables krb4/5 awareness. This + * is a string, 'clear', 'safe', 'confidential' or 'private'. If the string + * is set but doesn't match one of these, 'private' will be used. */ + CINIT(KRBLEVEL, OBJECTPOINT, 63), + + /* Set if we should verify the peer in ssl handshake, set 1 to verify. */ + CINIT(SSL_VERIFYPEER, LONG, 64), + + /* The CApath or CAfile used to validate the peer certificate + this option is used only if SSL_VERIFYPEER is true */ + CINIT(CAINFO, OBJECTPOINT, 65), + + /* 66 = OBSOLETE */ + /* 67 = OBSOLETE */ + + /* Maximum number of http redirects to follow */ + CINIT(MAXREDIRS, LONG, 68), + + /* Pass a long set to 1 to get the date of the requested document (if + possible)! Pass a zero to shut it off. */ + CINIT(FILETIME, LONG, 69), + + /* This points to a linked list of telnet options */ + CINIT(TELNETOPTIONS, OBJECTPOINT, 70), + + /* Max amount of cached alive connections */ + CINIT(MAXCONNECTS, LONG, 71), + + CINIT(OBSOLETE72, LONG, 72), /* OBSOLETE, do not use! */ + + /* 73 = OBSOLETE */ + + /* Set to explicitly use a new connection for the upcoming transfer. + Do not use this unless you're absolutely sure of this, as it makes the + operation slower and is less friendly for the network. */ + CINIT(FRESH_CONNECT, LONG, 74), + + /* Set to explicitly forbid the upcoming transfer's connection to be re-used + when done. Do not use this unless you're absolutely sure of this, as it + makes the operation slower and is less friendly for the network. */ + CINIT(FORBID_REUSE, LONG, 75), + + /* Set to a file name that contains random data for libcurl to use to + seed the random engine when doing SSL connects. */ + CINIT(RANDOM_FILE, OBJECTPOINT, 76), + + /* Set to the Entropy Gathering Daemon socket pathname */ + CINIT(EGDSOCKET, OBJECTPOINT, 77), + + /* Time-out connect operations after this amount of seconds, if connects are + OK within this time, then fine... This only aborts the connect phase. */ + CINIT(CONNECTTIMEOUT, LONG, 78), + + /* Function that will be called to store headers (instead of fwrite). The + * parameters will use fwrite() syntax, make sure to follow them. */ + CINIT(HEADERFUNCTION, FUNCTIONPOINT, 79), + + /* Set this to force the HTTP request to get back to GET. Only really usable + if POST, PUT or a custom request have been used first. + */ + CINIT(HTTPGET, LONG, 80), + + /* Set if we should verify the Common name from the peer certificate in ssl + * handshake, set 1 to check existence, 2 to ensure that it matches the + * provided hostname. */ + CINIT(SSL_VERIFYHOST, LONG, 81), + + /* Specify which file name to write all known cookies in after completed + operation. Set file name to "-" (dash) to make it go to stdout. */ + CINIT(COOKIEJAR, OBJECTPOINT, 82), + + /* Specify which SSL ciphers to use */ + CINIT(SSL_CIPHER_LIST, OBJECTPOINT, 83), + + /* Specify which HTTP version to use! This must be set to one of the + CURL_HTTP_VERSION* enums set below. */ + CINIT(HTTP_VERSION, LONG, 84), + + /* Specifically switch on or off the FTP engine's use of the EPSV command. By + default, that one will always be attempted before the more traditional + PASV command. */ + CINIT(FTP_USE_EPSV, LONG, 85), + + /* type of the file keeping your SSL-certificate ("DER", "PEM", "ENG") */ + CINIT(SSLCERTTYPE, OBJECTPOINT, 86), + + /* name of the file keeping your private SSL-key */ + CINIT(SSLKEY, OBJECTPOINT, 87), + + /* type of the file keeping your private SSL-key ("DER", "PEM", "ENG") */ + CINIT(SSLKEYTYPE, OBJECTPOINT, 88), + + /* crypto engine for the SSL-sub system */ + CINIT(SSLENGINE, OBJECTPOINT, 89), + + /* set the crypto engine for the SSL-sub system as default + the param has no meaning... + */ + CINIT(SSLENGINE_DEFAULT, LONG, 90), + + /* Non-zero value means to use the global dns cache */ + CINIT(DNS_USE_GLOBAL_CACHE, LONG, 91), /* DEPRECATED, do not use! */ + + /* DNS cache timeout */ + CINIT(DNS_CACHE_TIMEOUT, LONG, 92), + + /* send linked-list of pre-transfer QUOTE commands */ + CINIT(PREQUOTE, OBJECTPOINT, 93), + + /* set the debug function */ + CINIT(DEBUGFUNCTION, FUNCTIONPOINT, 94), + + /* set the data for the debug function */ + CINIT(DEBUGDATA, OBJECTPOINT, 95), + + /* mark this as start of a cookie session */ + CINIT(COOKIESESSION, LONG, 96), + + /* The CApath directory used to validate the peer certificate + this option is used only if SSL_VERIFYPEER is true */ + CINIT(CAPATH, OBJECTPOINT, 97), + + /* Instruct libcurl to use a smaller receive buffer */ + CINIT(BUFFERSIZE, LONG, 98), + + /* Instruct libcurl to not use any signal/alarm handlers, even when using + timeouts. This option is useful for multi-threaded applications. + See libcurl-the-guide for more background information. */ + CINIT(NOSIGNAL, LONG, 99), + + /* Provide a CURLShare for mutexing non-ts data */ + CINIT(SHARE, OBJECTPOINT, 100), + + /* indicates type of proxy. accepted values are CURLPROXY_HTTP (default), + CURLPROXY_SOCKS4, CURLPROXY_SOCKS4A and CURLPROXY_SOCKS5. */ + CINIT(PROXYTYPE, LONG, 101), + + /* Set the Accept-Encoding string. Use this to tell a server you would like + the response to be compressed. Before 7.21.6, this was known as + CURLOPT_ENCODING */ + CINIT(ACCEPT_ENCODING, OBJECTPOINT, 102), + + /* Set pointer to private data */ + CINIT(PRIVATE, OBJECTPOINT, 103), + + /* Set aliases for HTTP 200 in the HTTP Response header */ + CINIT(HTTP200ALIASES, OBJECTPOINT, 104), + + /* Continue to send authentication (user+password) when following locations, + even when hostname changed. This can potentially send off the name + and password to whatever host the server decides. */ + CINIT(UNRESTRICTED_AUTH, LONG, 105), + + /* Specifically switch on or off the FTP engine's use of the EPRT command ( + it also disables the LPRT attempt). By default, those ones will always be + attempted before the good old traditional PORT command. */ + CINIT(FTP_USE_EPRT, LONG, 106), + + /* Set this to a bitmask value to enable the particular authentications + methods you like. Use this in combination with CURLOPT_USERPWD. + Note that setting multiple bits may cause extra network round-trips. */ + CINIT(HTTPAUTH, LONG, 107), + + /* Set the ssl context callback function, currently only for OpenSSL ssl_ctx + in second argument. The function must be matching the + curl_ssl_ctx_callback proto. */ + CINIT(SSL_CTX_FUNCTION, FUNCTIONPOINT, 108), + + /* Set the userdata for the ssl context callback function's third + argument */ + CINIT(SSL_CTX_DATA, OBJECTPOINT, 109), + + /* FTP Option that causes missing dirs to be created on the remote server. + In 7.19.4 we introduced the convenience enums for this option using the + CURLFTP_CREATE_DIR prefix. + */ + CINIT(FTP_CREATE_MISSING_DIRS, LONG, 110), + + /* Set this to a bitmask value to enable the particular authentications + methods you like. Use this in combination with CURLOPT_PROXYUSERPWD. + Note that setting multiple bits may cause extra network round-trips. */ + CINIT(PROXYAUTH, LONG, 111), + + /* FTP option that changes the timeout, in seconds, associated with + getting a response. This is different from transfer timeout time and + essentially places a demand on the FTP server to acknowledge commands + in a timely manner. */ + CINIT(FTP_RESPONSE_TIMEOUT, LONG, 112), +#define CURLOPT_SERVER_RESPONSE_TIMEOUT CURLOPT_FTP_RESPONSE_TIMEOUT + + /* Set this option to one of the CURL_IPRESOLVE_* defines (see below) to + tell libcurl to resolve names to those IP versions only. This only has + affect on systems with support for more than one, i.e IPv4 _and_ IPv6. */ + CINIT(IPRESOLVE, LONG, 113), + + /* Set this option to limit the size of a file that will be downloaded from + an HTTP or FTP server. + + Note there is also _LARGE version which adds large file support for + platforms which have larger off_t sizes. See MAXFILESIZE_LARGE below. */ + CINIT(MAXFILESIZE, LONG, 114), + + /* See the comment for INFILESIZE above, but in short, specifies + * the size of the file being uploaded. -1 means unknown. + */ + CINIT(INFILESIZE_LARGE, OFF_T, 115), + + /* Sets the continuation offset. There is also a LONG version of this; + * look above for RESUME_FROM. + */ + CINIT(RESUME_FROM_LARGE, OFF_T, 116), + + /* Sets the maximum size of data that will be downloaded from + * an HTTP or FTP server. See MAXFILESIZE above for the LONG version. + */ + CINIT(MAXFILESIZE_LARGE, OFF_T, 117), + + /* Set this option to the file name of your .netrc file you want libcurl + to parse (using the CURLOPT_NETRC option). If not set, libcurl will do + a poor attempt to find the user's home directory and check for a .netrc + file in there. */ + CINIT(NETRC_FILE, OBJECTPOINT, 118), + + /* Enable SSL/TLS for FTP, pick one of: + CURLUSESSL_TRY - try using SSL, proceed anyway otherwise + CURLUSESSL_CONTROL - SSL for the control connection or fail + CURLUSESSL_ALL - SSL for all communication or fail + */ + CINIT(USE_SSL, LONG, 119), + + /* The _LARGE version of the standard POSTFIELDSIZE option */ + CINIT(POSTFIELDSIZE_LARGE, OFF_T, 120), + + /* Enable/disable the TCP Nagle algorithm */ + CINIT(TCP_NODELAY, LONG, 121), + + /* 122 OBSOLETE, used in 7.12.3. Gone in 7.13.0 */ + /* 123 OBSOLETE. Gone in 7.16.0 */ + /* 124 OBSOLETE, used in 7.12.3. Gone in 7.13.0 */ + /* 125 OBSOLETE, used in 7.12.3. Gone in 7.13.0 */ + /* 126 OBSOLETE, used in 7.12.3. Gone in 7.13.0 */ + /* 127 OBSOLETE. Gone in 7.16.0 */ + /* 128 OBSOLETE. Gone in 7.16.0 */ + + /* When FTP over SSL/TLS is selected (with CURLOPT_USE_SSL), this option + can be used to change libcurl's default action which is to first try + "AUTH SSL" and then "AUTH TLS" in this order, and proceed when a OK + response has been received. + + Available parameters are: + CURLFTPAUTH_DEFAULT - let libcurl decide + CURLFTPAUTH_SSL - try "AUTH SSL" first, then TLS + CURLFTPAUTH_TLS - try "AUTH TLS" first, then SSL + */ + CINIT(FTPSSLAUTH, LONG, 129), + + CINIT(IOCTLFUNCTION, FUNCTIONPOINT, 130), + CINIT(IOCTLDATA, OBJECTPOINT, 131), + + /* 132 OBSOLETE. Gone in 7.16.0 */ + /* 133 OBSOLETE. Gone in 7.16.0 */ + + /* zero terminated string for pass on to the FTP server when asked for + "account" info */ + CINIT(FTP_ACCOUNT, OBJECTPOINT, 134), + + /* feed cookies into cookie engine */ + CINIT(COOKIELIST, OBJECTPOINT, 135), + + /* ignore Content-Length */ + CINIT(IGNORE_CONTENT_LENGTH, LONG, 136), + + /* Set to non-zero to skip the IP address received in a 227 PASV FTP server + response. Typically used for FTP-SSL purposes but is not restricted to + that. libcurl will then instead use the same IP address it used for the + control connection. */ + CINIT(FTP_SKIP_PASV_IP, LONG, 137), + + /* Select "file method" to use when doing FTP, see the curl_ftpmethod + above. */ + CINIT(FTP_FILEMETHOD, LONG, 138), + + /* Local port number to bind the socket to */ + CINIT(LOCALPORT, LONG, 139), + + /* Number of ports to try, including the first one set with LOCALPORT. + Thus, setting it to 1 will make no additional attempts but the first. + */ + CINIT(LOCALPORTRANGE, LONG, 140), + + /* no transfer, set up connection and let application use the socket by + extracting it with CURLINFO_LASTSOCKET */ + CINIT(CONNECT_ONLY, LONG, 141), + + /* Function that will be called to convert from the + network encoding (instead of using the iconv calls in libcurl) */ + CINIT(CONV_FROM_NETWORK_FUNCTION, FUNCTIONPOINT, 142), + + /* Function that will be called to convert to the + network encoding (instead of using the iconv calls in libcurl) */ + CINIT(CONV_TO_NETWORK_FUNCTION, FUNCTIONPOINT, 143), + + /* Function that will be called to convert from UTF8 + (instead of using the iconv calls in libcurl) + Note that this is used only for SSL certificate processing */ + CINIT(CONV_FROM_UTF8_FUNCTION, FUNCTIONPOINT, 144), + + /* if the connection proceeds too quickly then need to slow it down */ + /* limit-rate: maximum number of bytes per second to send or receive */ + CINIT(MAX_SEND_SPEED_LARGE, OFF_T, 145), + CINIT(MAX_RECV_SPEED_LARGE, OFF_T, 146), + + /* Pointer to command string to send if USER/PASS fails. */ + CINIT(FTP_ALTERNATIVE_TO_USER, OBJECTPOINT, 147), + + /* callback function for setting socket options */ + CINIT(SOCKOPTFUNCTION, FUNCTIONPOINT, 148), + CINIT(SOCKOPTDATA, OBJECTPOINT, 149), + + /* set to 0 to disable session ID re-use for this transfer, default is + enabled (== 1) */ + CINIT(SSL_SESSIONID_CACHE, LONG, 150), + + /* allowed SSH authentication methods */ + CINIT(SSH_AUTH_TYPES, LONG, 151), + + /* Used by scp/sftp to do public/private key authentication */ + CINIT(SSH_PUBLIC_KEYFILE, OBJECTPOINT, 152), + CINIT(SSH_PRIVATE_KEYFILE, OBJECTPOINT, 153), + + /* Send CCC (Clear Command Channel) after authentication */ + CINIT(FTP_SSL_CCC, LONG, 154), + + /* Same as TIMEOUT and CONNECTTIMEOUT, but with ms resolution */ + CINIT(TIMEOUT_MS, LONG, 155), + CINIT(CONNECTTIMEOUT_MS, LONG, 156), + + /* set to zero to disable the libcurl's decoding and thus pass the raw body + data to the application even when it is encoded/compressed */ + CINIT(HTTP_TRANSFER_DECODING, LONG, 157), + CINIT(HTTP_CONTENT_DECODING, LONG, 158), + + /* Permission used when creating new files and directories on the remote + server for protocols that support it, SFTP/SCP/FILE */ + CINIT(NEW_FILE_PERMS, LONG, 159), + CINIT(NEW_DIRECTORY_PERMS, LONG, 160), + + /* Set the behaviour of POST when redirecting. Values must be set to one + of CURL_REDIR* defines below. This used to be called CURLOPT_POST301 */ + CINIT(POSTREDIR, LONG, 161), + + /* used by scp/sftp to verify the host's public key */ + CINIT(SSH_HOST_PUBLIC_KEY_MD5, OBJECTPOINT, 162), + + /* Callback function for opening socket (instead of socket(2)). Optionally, + callback is able change the address or refuse to connect returning + CURL_SOCKET_BAD. The callback should have type + curl_opensocket_callback */ + CINIT(OPENSOCKETFUNCTION, FUNCTIONPOINT, 163), + CINIT(OPENSOCKETDATA, OBJECTPOINT, 164), + + /* POST volatile input fields. */ + CINIT(COPYPOSTFIELDS, OBJECTPOINT, 165), + + /* set transfer mode (;type=) when doing FTP via an HTTP proxy */ + CINIT(PROXY_TRANSFER_MODE, LONG, 166), + + /* Callback function for seeking in the input stream */ + CINIT(SEEKFUNCTION, FUNCTIONPOINT, 167), + CINIT(SEEKDATA, OBJECTPOINT, 168), + + /* CRL file */ + CINIT(CRLFILE, OBJECTPOINT, 169), + + /* Issuer certificate */ + CINIT(ISSUERCERT, OBJECTPOINT, 170), + + /* (IPv6) Address scope */ + CINIT(ADDRESS_SCOPE, LONG, 171), + + /* Collect certificate chain info and allow it to get retrievable with + CURLINFO_CERTINFO after the transfer is complete. */ + CINIT(CERTINFO, LONG, 172), + + /* "name" and "pwd" to use when fetching. */ + CINIT(USERNAME, OBJECTPOINT, 173), + CINIT(PASSWORD, OBJECTPOINT, 174), + + /* "name" and "pwd" to use with Proxy when fetching. */ + CINIT(PROXYUSERNAME, OBJECTPOINT, 175), + CINIT(PROXYPASSWORD, OBJECTPOINT, 176), + + /* Comma separated list of hostnames defining no-proxy zones. These should + match both hostnames directly, and hostnames within a domain. For + example, local.com will match local.com and www.local.com, but NOT + notlocal.com or www.notlocal.com. For compatibility with other + implementations of this, .local.com will be considered to be the same as + local.com. A single * is the only valid wildcard, and effectively + disables the use of proxy. */ + CINIT(NOPROXY, OBJECTPOINT, 177), + + /* block size for TFTP transfers */ + CINIT(TFTP_BLKSIZE, LONG, 178), + + /* Socks Service */ + CINIT(SOCKS5_GSSAPI_SERVICE, OBJECTPOINT, 179), + + /* Socks Service */ + CINIT(SOCKS5_GSSAPI_NEC, LONG, 180), + + /* set the bitmask for the protocols that are allowed to be used for the + transfer, which thus helps the app which takes URLs from users or other + external inputs and want to restrict what protocol(s) to deal + with. Defaults to CURLPROTO_ALL. */ + CINIT(PROTOCOLS, LONG, 181), + + /* set the bitmask for the protocols that libcurl is allowed to follow to, + as a subset of the CURLOPT_PROTOCOLS ones. That means the protocol needs + to be set in both bitmasks to be allowed to get redirected to. Defaults + to all protocols except FILE and SCP. */ + CINIT(REDIR_PROTOCOLS, LONG, 182), + + /* set the SSH knownhost file name to use */ + CINIT(SSH_KNOWNHOSTS, OBJECTPOINT, 183), + + /* set the SSH host key callback, must point to a curl_sshkeycallback + function */ + CINIT(SSH_KEYFUNCTION, FUNCTIONPOINT, 184), + + /* set the SSH host key callback custom pointer */ + CINIT(SSH_KEYDATA, OBJECTPOINT, 185), + + /* set the SMTP mail originator */ + CINIT(MAIL_FROM, OBJECTPOINT, 186), + + /* set the SMTP mail receiver(s) */ + CINIT(MAIL_RCPT, OBJECTPOINT, 187), + + /* FTP: send PRET before PASV */ + CINIT(FTP_USE_PRET, LONG, 188), + + /* RTSP request method (OPTIONS, SETUP, PLAY, etc...) */ + CINIT(RTSP_REQUEST, LONG, 189), + + /* The RTSP session identifier */ + CINIT(RTSP_SESSION_ID, OBJECTPOINT, 190), + + /* The RTSP stream URI */ + CINIT(RTSP_STREAM_URI, OBJECTPOINT, 191), + + /* The Transport: header to use in RTSP requests */ + CINIT(RTSP_TRANSPORT, OBJECTPOINT, 192), + + /* Manually initialize the client RTSP CSeq for this handle */ + CINIT(RTSP_CLIENT_CSEQ, LONG, 193), + + /* Manually initialize the server RTSP CSeq for this handle */ + CINIT(RTSP_SERVER_CSEQ, LONG, 194), + + /* The stream to pass to INTERLEAVEFUNCTION. */ + CINIT(INTERLEAVEDATA, OBJECTPOINT, 195), + + /* Let the application define a custom write method for RTP data */ + CINIT(INTERLEAVEFUNCTION, FUNCTIONPOINT, 196), + + /* Turn on wildcard matching */ + CINIT(WILDCARDMATCH, LONG, 197), + + /* Directory matching callback called before downloading of an + individual file (chunk) started */ + CINIT(CHUNK_BGN_FUNCTION, FUNCTIONPOINT, 198), + + /* Directory matching callback called after the file (chunk) + was downloaded, or skipped */ + CINIT(CHUNK_END_FUNCTION, FUNCTIONPOINT, 199), + + /* Change match (fnmatch-like) callback for wildcard matching */ + CINIT(FNMATCH_FUNCTION, FUNCTIONPOINT, 200), + + /* Let the application define custom chunk data pointer */ + CINIT(CHUNK_DATA, OBJECTPOINT, 201), + + /* FNMATCH_FUNCTION user pointer */ + CINIT(FNMATCH_DATA, OBJECTPOINT, 202), + + /* send linked-list of name:port:address sets */ + CINIT(RESOLVE, OBJECTPOINT, 203), + + /* Set a username for authenticated TLS */ + CINIT(TLSAUTH_USERNAME, OBJECTPOINT, 204), + + /* Set a password for authenticated TLS */ + CINIT(TLSAUTH_PASSWORD, OBJECTPOINT, 205), + + /* Set authentication type for authenticated TLS */ + CINIT(TLSAUTH_TYPE, OBJECTPOINT, 206), + + /* Set to 1 to enable the "TE:" header in HTTP requests to ask for + compressed transfer-encoded responses. Set to 0 to disable the use of TE: + in outgoing requests. The current default is 0, but it might change in a + future libcurl release. + + libcurl will ask for the compressed methods it knows of, and if that + isn't any, it will not ask for transfer-encoding at all even if this + option is set to 1. + + */ + CINIT(TRANSFER_ENCODING, LONG, 207), + + /* Callback function for closing socket (instead of close(2)). The callback + should have type curl_closesocket_callback */ + CINIT(CLOSESOCKETFUNCTION, FUNCTIONPOINT, 208), + CINIT(CLOSESOCKETDATA, OBJECTPOINT, 209), + + /* allow GSSAPI credential delegation */ + CINIT(GSSAPI_DELEGATION, LONG, 210), + + /* Set the name servers to use for DNS resolution */ + CINIT(DNS_SERVERS, OBJECTPOINT, 211), + + /* Time-out accept operations (currently for FTP only) after this amount + of miliseconds. */ + CINIT(ACCEPTTIMEOUT_MS, LONG, 212), + + /* Set TCP keepalive */ + CINIT(TCP_KEEPALIVE, LONG, 213), + + /* non-universal keepalive knobs (Linux, AIX, HP-UX, more) */ + CINIT(TCP_KEEPIDLE, LONG, 214), + CINIT(TCP_KEEPINTVL, LONG, 215), + + /* Enable/disable specific SSL features with a bitmask, see CURLSSLOPT_* */ + CINIT(SSL_OPTIONS, LONG, 216), + + /* Set the SMTP auth originator */ + CINIT(MAIL_AUTH, OBJECTPOINT, 217), + + /* Enable/disable SASL initial response */ + CINIT(SASL_IR, LONG, 218), + + /* Function that will be called instead of the internal progress display + * function. This function should be defined as the curl_xferinfo_callback + * prototype defines. (Deprecates CURLOPT_PROGRESSFUNCTION) */ + CINIT(XFERINFOFUNCTION, FUNCTIONPOINT, 219), + + /* The XOAUTH2 bearer token */ + CINIT(XOAUTH2_BEARER, OBJECTPOINT, 220), + + /* Set the interface string to use as outgoing network + * interface for DNS requests. + * Only supported by the c-ares DNS backend */ + CINIT(DNS_INTERFACE, OBJECTPOINT, 221), + + /* Set the local IPv4 address to use for outgoing DNS requests. + * Only supported by the c-ares DNS backend */ + CINIT(DNS_LOCAL_IP4, OBJECTPOINT, 222), + + /* Set the local IPv4 address to use for outgoing DNS requests. + * Only supported by the c-ares DNS backend */ + CINIT(DNS_LOCAL_IP6, OBJECTPOINT, 223), + + /* Set authentication options directly */ + CINIT(LOGIN_OPTIONS, OBJECTPOINT, 224), + + /* Enable/disable TLS NPN extension (http2 over ssl might fail without) */ + CINIT(SSL_ENABLE_NPN, LONG, 225), + + /* Enable/disable TLS ALPN extension (http2 over ssl might fail without) */ + CINIT(SSL_ENABLE_ALPN, LONG, 226), + + /* Time to wait for a response to a HTTP request containing an + * Expect: 100-continue header before sending the data anyway. */ + CINIT(EXPECT_100_TIMEOUT_MS, LONG, 227), + + /* This points to a linked list of headers used for proxy requests only, + struct curl_slist kind */ + CINIT(PROXYHEADER, OBJECTPOINT, 228), + + /* Pass in a bitmask of "header options" */ + CINIT(HEADEROPT, LONG, 229), + + /* The public key in DER form used to validate the peer public key + this option is used only if SSL_VERIFYPEER is true */ + CINIT(PINNEDPUBLICKEY, OBJECTPOINT, 230), + + /* Path to Unix domain socket */ + CINIT(UNIX_SOCKET_PATH, OBJECTPOINT, 231), + + /* Set if we should verify the certificate status. */ + CINIT(SSL_VERIFYSTATUS, LONG, 232), + + /* Set if we should enable TLS false start. */ + CINIT(SSL_FALSESTART, LONG, 233), + + /* Do not squash dot-dot sequences */ + CINIT(PATH_AS_IS, LONG, 234), + + /* Proxy Service Name */ + CINIT(PROXY_SERVICE_NAME, OBJECTPOINT, 235), + + /* Service Name */ + CINIT(SERVICE_NAME, OBJECTPOINT, 236), + + /* Wait/don't wait for pipe/mutex to clarify */ + CINIT(PIPEWAIT, LONG, 237), + + CURLOPT_LASTENTRY /* the last unused */ +} CURLoption; + +#ifndef CURL_NO_OLDIES /* define this to test if your app builds with all + the obsolete stuff removed! */ + +/* Backwards compatibility with older names */ +/* These are scheduled to disappear by 2011 */ + +/* This was added in version 7.19.1 */ +#define CURLOPT_POST301 CURLOPT_POSTREDIR + +/* These are scheduled to disappear by 2009 */ + +/* The following were added in 7.17.0 */ +#define CURLOPT_SSLKEYPASSWD CURLOPT_KEYPASSWD +#define CURLOPT_FTPAPPEND CURLOPT_APPEND +#define CURLOPT_FTPLISTONLY CURLOPT_DIRLISTONLY +#define CURLOPT_FTP_SSL CURLOPT_USE_SSL + +/* The following were added earlier */ + +#define CURLOPT_SSLCERTPASSWD CURLOPT_KEYPASSWD +#define CURLOPT_KRB4LEVEL CURLOPT_KRBLEVEL + +#else +/* This is set if CURL_NO_OLDIES is defined at compile-time */ +#undef CURLOPT_DNS_USE_GLOBAL_CACHE /* soon obsolete */ +#endif + + + /* Below here follows defines for the CURLOPT_IPRESOLVE option. If a host + name resolves addresses using more than one IP protocol version, this + option might be handy to force libcurl to use a specific IP version. */ +#define CURL_IPRESOLVE_WHATEVER 0 /* default, resolves addresses to all IP + versions that your system allows */ +#define CURL_IPRESOLVE_V4 1 /* resolve to IPv4 addresses */ +#define CURL_IPRESOLVE_V6 2 /* resolve to IPv6 addresses */ + + /* three convenient "aliases" that follow the name scheme better */ +#define CURLOPT_RTSPHEADER CURLOPT_HTTPHEADER + + /* These enums are for use with the CURLOPT_HTTP_VERSION option. */ +enum { + CURL_HTTP_VERSION_NONE, /* setting this means we don't care, and that we'd + like the library to choose the best possible + for us! */ + CURL_HTTP_VERSION_1_0, /* please use HTTP 1.0 in the request */ + CURL_HTTP_VERSION_1_1, /* please use HTTP 1.1 in the request */ + CURL_HTTP_VERSION_2_0, /* please use HTTP 2.0 in the request */ + + CURL_HTTP_VERSION_LAST /* *ILLEGAL* http version */ +}; + +/* Convenience definition simple because the name of the version is HTTP/2 and + not 2.0. The 2_0 version of the enum name was set while the version was + still planned to be 2.0 and we stick to it for compatibility. */ +#define CURL_HTTP_VERSION_2 CURL_HTTP_VERSION_2_0 + +/* + * Public API enums for RTSP requests + */ +enum { + CURL_RTSPREQ_NONE, /* first in list */ + CURL_RTSPREQ_OPTIONS, + CURL_RTSPREQ_DESCRIBE, + CURL_RTSPREQ_ANNOUNCE, + CURL_RTSPREQ_SETUP, + CURL_RTSPREQ_PLAY, + CURL_RTSPREQ_PAUSE, + CURL_RTSPREQ_TEARDOWN, + CURL_RTSPREQ_GET_PARAMETER, + CURL_RTSPREQ_SET_PARAMETER, + CURL_RTSPREQ_RECORD, + CURL_RTSPREQ_RECEIVE, + CURL_RTSPREQ_LAST /* last in list */ +}; + + /* These enums are for use with the CURLOPT_NETRC option. */ +enum CURL_NETRC_OPTION { + CURL_NETRC_IGNORED, /* The .netrc will never be read. + * This is the default. */ + CURL_NETRC_OPTIONAL, /* A user:password in the URL will be preferred + * to one in the .netrc. */ + CURL_NETRC_REQUIRED, /* A user:password in the URL will be ignored. + * Unless one is set programmatically, the .netrc + * will be queried. */ + CURL_NETRC_LAST +}; + +enum { + CURL_SSLVERSION_DEFAULT, + CURL_SSLVERSION_TLSv1, /* TLS 1.x */ + CURL_SSLVERSION_SSLv2, + CURL_SSLVERSION_SSLv3, + CURL_SSLVERSION_TLSv1_0, + CURL_SSLVERSION_TLSv1_1, + CURL_SSLVERSION_TLSv1_2, + + CURL_SSLVERSION_LAST /* never use, keep last */ +}; + +enum CURL_TLSAUTH { + CURL_TLSAUTH_NONE, + CURL_TLSAUTH_SRP, + CURL_TLSAUTH_LAST /* never use, keep last */ +}; + +/* symbols to use with CURLOPT_POSTREDIR. + CURL_REDIR_POST_301, CURL_REDIR_POST_302 and CURL_REDIR_POST_303 + can be bitwise ORed so that CURL_REDIR_POST_301 | CURL_REDIR_POST_302 + | CURL_REDIR_POST_303 == CURL_REDIR_POST_ALL */ + +#define CURL_REDIR_GET_ALL 0 +#define CURL_REDIR_POST_301 1 +#define CURL_REDIR_POST_302 2 +#define CURL_REDIR_POST_303 4 +#define CURL_REDIR_POST_ALL \ + (CURL_REDIR_POST_301|CURL_REDIR_POST_302|CURL_REDIR_POST_303) + +typedef enum { + CURL_TIMECOND_NONE, + + CURL_TIMECOND_IFMODSINCE, + CURL_TIMECOND_IFUNMODSINCE, + CURL_TIMECOND_LASTMOD, + + CURL_TIMECOND_LAST +} curl_TimeCond; + + +/* curl_strequal() and curl_strnequal() are subject for removal in a future + libcurl, see lib/README.curlx for details */ +CURL_EXTERN int (curl_strequal)(const char *s1, const char *s2); +CURL_EXTERN int (curl_strnequal)(const char *s1, const char *s2, size_t n); + +/* name is uppercase CURLFORM_ */ +#ifdef CFINIT +#undef CFINIT +#endif + +#ifdef CURL_ISOCPP +#define CFINIT(name) CURLFORM_ ## name +#else +/* The macro "##" is ISO C, we assume pre-ISO C doesn't support it. */ +#define CFINIT(name) CURLFORM_/**/name +#endif + +typedef enum { + CFINIT(NOTHING), /********* the first one is unused ************/ + + /* */ + CFINIT(COPYNAME), + CFINIT(PTRNAME), + CFINIT(NAMELENGTH), + CFINIT(COPYCONTENTS), + CFINIT(PTRCONTENTS), + CFINIT(CONTENTSLENGTH), + CFINIT(FILECONTENT), + CFINIT(ARRAY), + CFINIT(OBSOLETE), + CFINIT(FILE), + + CFINIT(BUFFER), + CFINIT(BUFFERPTR), + CFINIT(BUFFERLENGTH), + + CFINIT(CONTENTTYPE), + CFINIT(CONTENTHEADER), + CFINIT(FILENAME), + CFINIT(END), + CFINIT(OBSOLETE2), + + CFINIT(STREAM), + + CURLFORM_LASTENTRY /* the last unused */ +} CURLformoption; + +#undef CFINIT /* done */ + +/* structure to be used as parameter for CURLFORM_ARRAY */ +struct curl_forms { + CURLformoption option; + const char *value; +}; + +/* use this for multipart formpost building */ +/* Returns code for curl_formadd() + * + * Returns: + * CURL_FORMADD_OK on success + * CURL_FORMADD_MEMORY if the FormInfo allocation fails + * CURL_FORMADD_OPTION_TWICE if one option is given twice for one Form + * CURL_FORMADD_NULL if a null pointer was given for a char + * CURL_FORMADD_MEMORY if the allocation of a FormInfo struct failed + * CURL_FORMADD_UNKNOWN_OPTION if an unknown option was used + * CURL_FORMADD_INCOMPLETE if the some FormInfo is not complete (or error) + * CURL_FORMADD_MEMORY if a curl_httppost struct cannot be allocated + * CURL_FORMADD_MEMORY if some allocation for string copying failed. + * CURL_FORMADD_ILLEGAL_ARRAY if an illegal option is used in an array + * + ***************************************************************************/ +typedef enum { + CURL_FORMADD_OK, /* first, no error */ + + CURL_FORMADD_MEMORY, + CURL_FORMADD_OPTION_TWICE, + CURL_FORMADD_NULL, + CURL_FORMADD_UNKNOWN_OPTION, + CURL_FORMADD_INCOMPLETE, + CURL_FORMADD_ILLEGAL_ARRAY, + CURL_FORMADD_DISABLED, /* libcurl was built with this disabled */ + + CURL_FORMADD_LAST /* last */ +} CURLFORMcode; + +/* + * NAME curl_formadd() + * + * DESCRIPTION + * + * Pretty advanced function for building multi-part formposts. Each invoke + * adds one part that together construct a full post. Then use + * CURLOPT_HTTPPOST to send it off to libcurl. + */ +CURL_EXTERN CURLFORMcode curl_formadd(struct curl_httppost **httppost, + struct curl_httppost **last_post, + ...); + +/* + * callback function for curl_formget() + * The void *arg pointer will be the one passed as second argument to + * curl_formget(). + * The character buffer passed to it must not be freed. + * Should return the buffer length passed to it as the argument "len" on + * success. + */ +typedef size_t (*curl_formget_callback)(void *arg, const char *buf, + size_t len); + +/* + * NAME curl_formget() + * + * DESCRIPTION + * + * Serialize a curl_httppost struct built with curl_formadd(). + * Accepts a void pointer as second argument which will be passed to + * the curl_formget_callback function. + * Returns 0 on success. + */ +CURL_EXTERN int curl_formget(struct curl_httppost *form, void *arg, + curl_formget_callback append); +/* + * NAME curl_formfree() + * + * DESCRIPTION + * + * Free a multipart formpost previously built with curl_formadd(). + */ +CURL_EXTERN void curl_formfree(struct curl_httppost *form); + +/* + * NAME curl_getenv() + * + * DESCRIPTION + * + * Returns a malloc()'ed string that MUST be curl_free()ed after usage is + * complete. DEPRECATED - see lib/README.curlx + */ +CURL_EXTERN char *curl_getenv(const char *variable); + +/* + * NAME curl_version() + * + * DESCRIPTION + * + * Returns a static ascii string of the libcurl version. + */ +CURL_EXTERN char *curl_version(void); + +/* + * NAME curl_easy_escape() + * + * DESCRIPTION + * + * Escapes URL strings (converts all letters consider illegal in URLs to their + * %XX versions). This function returns a new allocated string or NULL if an + * error occurred. + */ +CURL_EXTERN char *curl_easy_escape(CURL *handle, + const char *string, + int length); + +/* the previous version: */ +CURL_EXTERN char *curl_escape(const char *string, + int length); + + +/* + * NAME curl_easy_unescape() + * + * DESCRIPTION + * + * Unescapes URL encoding in strings (converts all %XX codes to their 8bit + * versions). This function returns a new allocated string or NULL if an error + * occurred. + * Conversion Note: On non-ASCII platforms the ASCII %XX codes are + * converted into the host encoding. + */ +CURL_EXTERN char *curl_easy_unescape(CURL *handle, + const char *string, + int length, + int *outlength); + +/* the previous version */ +CURL_EXTERN char *curl_unescape(const char *string, + int length); + +/* + * NAME curl_free() + * + * DESCRIPTION + * + * Provided for de-allocation in the same translation unit that did the + * allocation. Added in libcurl 7.10 + */ +CURL_EXTERN void curl_free(void *p); + +/* + * NAME curl_global_init() + * + * DESCRIPTION + * + * curl_global_init() should be invoked exactly once for each application that + * uses libcurl and before any call of other libcurl functions. + * + * This function is not thread-safe! + */ +CURL_EXTERN CURLcode curl_global_init(long flags); + +/* + * NAME curl_global_init_mem() + * + * DESCRIPTION + * + * curl_global_init() or curl_global_init_mem() should be invoked exactly once + * for each application that uses libcurl. This function can be used to + * initialize libcurl and set user defined memory management callback + * functions. Users can implement memory management routines to check for + * memory leaks, check for mis-use of the curl library etc. User registered + * callback routines with be invoked by this library instead of the system + * memory management routines like malloc, free etc. + */ +CURL_EXTERN CURLcode curl_global_init_mem(long flags, + curl_malloc_callback m, + curl_free_callback f, + curl_realloc_callback r, + curl_strdup_callback s, + curl_calloc_callback c); + +/* + * NAME curl_global_cleanup() + * + * DESCRIPTION + * + * curl_global_cleanup() should be invoked exactly once for each application + * that uses libcurl + */ +CURL_EXTERN void curl_global_cleanup(void); + +/* linked-list structure for the CURLOPT_QUOTE option (and other) */ +struct curl_slist { + char *data; + struct curl_slist *next; +}; + +/* + * NAME curl_slist_append() + * + * DESCRIPTION + * + * Appends a string to a linked list. If no list exists, it will be created + * first. Returns the new list, after appending. + */ +CURL_EXTERN struct curl_slist *curl_slist_append(struct curl_slist *, + const char *); + +/* + * NAME curl_slist_free_all() + * + * DESCRIPTION + * + * free a previously built curl_slist. + */ +CURL_EXTERN void curl_slist_free_all(struct curl_slist *); + +/* + * NAME curl_getdate() + * + * DESCRIPTION + * + * Returns the time, in seconds since 1 Jan 1970 of the time string given in + * the first argument. The time argument in the second parameter is unused + * and should be set to NULL. + */ +CURL_EXTERN time_t curl_getdate(const char *p, const time_t *unused); + +/* info about the certificate chain, only for OpenSSL builds. Asked + for with CURLOPT_CERTINFO / CURLINFO_CERTINFO */ +struct curl_certinfo { + int num_of_certs; /* number of certificates with information */ + struct curl_slist **certinfo; /* for each index in this array, there's a + linked list with textual information in the + format "name: value" */ +}; + +/* enum for the different supported SSL backends */ +typedef enum { + CURLSSLBACKEND_NONE = 0, + CURLSSLBACKEND_OPENSSL = 1, + CURLSSLBACKEND_GNUTLS = 2, + CURLSSLBACKEND_NSS = 3, + CURLSSLBACKEND_OBSOLETE4 = 4, /* Was QSOSSL. */ + CURLSSLBACKEND_GSKIT = 5, + CURLSSLBACKEND_POLARSSL = 6, + CURLSSLBACKEND_CYASSL = 7, + CURLSSLBACKEND_SCHANNEL = 8, + CURLSSLBACKEND_DARWINSSL = 9, + CURLSSLBACKEND_AXTLS = 10 +} curl_sslbackend; + +/* Information about the SSL library used and the respective internal SSL + handle, which can be used to obtain further information regarding the + connection. Asked for with CURLINFO_TLS_SESSION. */ +struct curl_tlssessioninfo { + curl_sslbackend backend; + void *internals; +}; + +#define CURLINFO_STRING 0x100000 +#define CURLINFO_LONG 0x200000 +#define CURLINFO_DOUBLE 0x300000 +#define CURLINFO_SLIST 0x400000 +#define CURLINFO_MASK 0x0fffff +#define CURLINFO_TYPEMASK 0xf00000 + +typedef enum { + CURLINFO_NONE, /* first, never use this */ + CURLINFO_EFFECTIVE_URL = CURLINFO_STRING + 1, + CURLINFO_RESPONSE_CODE = CURLINFO_LONG + 2, + CURLINFO_TOTAL_TIME = CURLINFO_DOUBLE + 3, + CURLINFO_NAMELOOKUP_TIME = CURLINFO_DOUBLE + 4, + CURLINFO_CONNECT_TIME = CURLINFO_DOUBLE + 5, + CURLINFO_PRETRANSFER_TIME = CURLINFO_DOUBLE + 6, + CURLINFO_SIZE_UPLOAD = CURLINFO_DOUBLE + 7, + CURLINFO_SIZE_DOWNLOAD = CURLINFO_DOUBLE + 8, + CURLINFO_SPEED_DOWNLOAD = CURLINFO_DOUBLE + 9, + CURLINFO_SPEED_UPLOAD = CURLINFO_DOUBLE + 10, + CURLINFO_HEADER_SIZE = CURLINFO_LONG + 11, + CURLINFO_REQUEST_SIZE = CURLINFO_LONG + 12, + CURLINFO_SSL_VERIFYRESULT = CURLINFO_LONG + 13, + CURLINFO_FILETIME = CURLINFO_LONG + 14, + CURLINFO_CONTENT_LENGTH_DOWNLOAD = CURLINFO_DOUBLE + 15, + CURLINFO_CONTENT_LENGTH_UPLOAD = CURLINFO_DOUBLE + 16, + CURLINFO_STARTTRANSFER_TIME = CURLINFO_DOUBLE + 17, + CURLINFO_CONTENT_TYPE = CURLINFO_STRING + 18, + CURLINFO_REDIRECT_TIME = CURLINFO_DOUBLE + 19, + CURLINFO_REDIRECT_COUNT = CURLINFO_LONG + 20, + CURLINFO_PRIVATE = CURLINFO_STRING + 21, + CURLINFO_HTTP_CONNECTCODE = CURLINFO_LONG + 22, + CURLINFO_HTTPAUTH_AVAIL = CURLINFO_LONG + 23, + CURLINFO_PROXYAUTH_AVAIL = CURLINFO_LONG + 24, + CURLINFO_OS_ERRNO = CURLINFO_LONG + 25, + CURLINFO_NUM_CONNECTS = CURLINFO_LONG + 26, + CURLINFO_SSL_ENGINES = CURLINFO_SLIST + 27, + CURLINFO_COOKIELIST = CURLINFO_SLIST + 28, + CURLINFO_LASTSOCKET = CURLINFO_LONG + 29, + CURLINFO_FTP_ENTRY_PATH = CURLINFO_STRING + 30, + CURLINFO_REDIRECT_URL = CURLINFO_STRING + 31, + CURLINFO_PRIMARY_IP = CURLINFO_STRING + 32, + CURLINFO_APPCONNECT_TIME = CURLINFO_DOUBLE + 33, + CURLINFO_CERTINFO = CURLINFO_SLIST + 34, + CURLINFO_CONDITION_UNMET = CURLINFO_LONG + 35, + CURLINFO_RTSP_SESSION_ID = CURLINFO_STRING + 36, + CURLINFO_RTSP_CLIENT_CSEQ = CURLINFO_LONG + 37, + CURLINFO_RTSP_SERVER_CSEQ = CURLINFO_LONG + 38, + CURLINFO_RTSP_CSEQ_RECV = CURLINFO_LONG + 39, + CURLINFO_PRIMARY_PORT = CURLINFO_LONG + 40, + CURLINFO_LOCAL_IP = CURLINFO_STRING + 41, + CURLINFO_LOCAL_PORT = CURLINFO_LONG + 42, + CURLINFO_TLS_SESSION = CURLINFO_SLIST + 43, + /* Fill in new entries below here! */ + + CURLINFO_LASTONE = 43 +} CURLINFO; + +/* CURLINFO_RESPONSE_CODE is the new name for the option previously known as + CURLINFO_HTTP_CODE */ +#define CURLINFO_HTTP_CODE CURLINFO_RESPONSE_CODE + +typedef enum { + CURLCLOSEPOLICY_NONE, /* first, never use this */ + + CURLCLOSEPOLICY_OLDEST, + CURLCLOSEPOLICY_LEAST_RECENTLY_USED, + CURLCLOSEPOLICY_LEAST_TRAFFIC, + CURLCLOSEPOLICY_SLOWEST, + CURLCLOSEPOLICY_CALLBACK, + + CURLCLOSEPOLICY_LAST /* last, never use this */ +} curl_closepolicy; + +#define CURL_GLOBAL_SSL (1<<0) +#define CURL_GLOBAL_WIN32 (1<<1) +#define CURL_GLOBAL_ALL (CURL_GLOBAL_SSL|CURL_GLOBAL_WIN32) +#define CURL_GLOBAL_NOTHING 0 +#define CURL_GLOBAL_DEFAULT CURL_GLOBAL_ALL +#define CURL_GLOBAL_ACK_EINTR (1<<2) + + +/***************************************************************************** + * Setup defines, protos etc for the sharing stuff. + */ + +/* Different data locks for a single share */ +typedef enum { + CURL_LOCK_DATA_NONE = 0, + /* CURL_LOCK_DATA_SHARE is used internally to say that + * the locking is just made to change the internal state of the share + * itself. + */ + CURL_LOCK_DATA_SHARE, + CURL_LOCK_DATA_COOKIE, + CURL_LOCK_DATA_DNS, + CURL_LOCK_DATA_SSL_SESSION, + CURL_LOCK_DATA_CONNECT, + CURL_LOCK_DATA_LAST +} curl_lock_data; + +/* Different lock access types */ +typedef enum { + CURL_LOCK_ACCESS_NONE = 0, /* unspecified action */ + CURL_LOCK_ACCESS_SHARED = 1, /* for read perhaps */ + CURL_LOCK_ACCESS_SINGLE = 2, /* for write perhaps */ + CURL_LOCK_ACCESS_LAST /* never use */ +} curl_lock_access; + +typedef void (*curl_lock_function)(CURL *handle, + curl_lock_data data, + curl_lock_access locktype, + void *userptr); +typedef void (*curl_unlock_function)(CURL *handle, + curl_lock_data data, + void *userptr); + +typedef void CURLSH; + +typedef enum { + CURLSHE_OK, /* all is fine */ + CURLSHE_BAD_OPTION, /* 1 */ + CURLSHE_IN_USE, /* 2 */ + CURLSHE_INVALID, /* 3 */ + CURLSHE_NOMEM, /* 4 out of memory */ + CURLSHE_NOT_BUILT_IN, /* 5 feature not present in lib */ + CURLSHE_LAST /* never use */ +} CURLSHcode; + +typedef enum { + CURLSHOPT_NONE, /* don't use */ + CURLSHOPT_SHARE, /* specify a data type to share */ + CURLSHOPT_UNSHARE, /* specify which data type to stop sharing */ + CURLSHOPT_LOCKFUNC, /* pass in a 'curl_lock_function' pointer */ + CURLSHOPT_UNLOCKFUNC, /* pass in a 'curl_unlock_function' pointer */ + CURLSHOPT_USERDATA, /* pass in a user data pointer used in the lock/unlock + callback functions */ + CURLSHOPT_LAST /* never use */ +} CURLSHoption; + +CURL_EXTERN CURLSH *curl_share_init(void); +CURL_EXTERN CURLSHcode curl_share_setopt(CURLSH *, CURLSHoption option, ...); +CURL_EXTERN CURLSHcode curl_share_cleanup(CURLSH *); + +/**************************************************************************** + * Structures for querying information about the curl library at runtime. + */ + +typedef enum { + CURLVERSION_FIRST, + CURLVERSION_SECOND, + CURLVERSION_THIRD, + CURLVERSION_FOURTH, + CURLVERSION_LAST /* never actually use this */ +} CURLversion; + +/* The 'CURLVERSION_NOW' is the symbolic name meant to be used by + basically all programs ever that want to get version information. It is + meant to be a built-in version number for what kind of struct the caller + expects. If the struct ever changes, we redefine the NOW to another enum + from above. */ +#define CURLVERSION_NOW CURLVERSION_FOURTH + +typedef struct { + CURLversion age; /* age of the returned struct */ + const char *version; /* LIBCURL_VERSION */ + unsigned int version_num; /* LIBCURL_VERSION_NUM */ + const char *host; /* OS/host/cpu/machine when configured */ + int features; /* bitmask, see defines below */ + const char *ssl_version; /* human readable string */ + long ssl_version_num; /* not used anymore, always 0 */ + const char *libz_version; /* human readable string */ + /* protocols is terminated by an entry with a NULL protoname */ + const char * const *protocols; + + /* The fields below this were added in CURLVERSION_SECOND */ + const char *ares; + int ares_num; + + /* This field was added in CURLVERSION_THIRD */ + const char *libidn; + + /* These field were added in CURLVERSION_FOURTH */ + + /* Same as '_libiconv_version' if built with HAVE_ICONV */ + int iconv_ver_num; + + const char *libssh_version; /* human readable string */ + +} curl_version_info_data; + +#define CURL_VERSION_IPV6 (1<<0) /* IPv6-enabled */ +#define CURL_VERSION_KERBEROS4 (1<<1) /* Kerberos V4 auth is supported + (deprecated) */ +#define CURL_VERSION_SSL (1<<2) /* SSL options are present */ +#define CURL_VERSION_LIBZ (1<<3) /* libz features are present */ +#define CURL_VERSION_NTLM (1<<4) /* NTLM auth is supported */ +#define CURL_VERSION_GSSNEGOTIATE (1<<5) /* Negotiate auth is supported + (deprecated) */ +#define CURL_VERSION_DEBUG (1<<6) /* Built with debug capabilities */ +#define CURL_VERSION_ASYNCHDNS (1<<7) /* Asynchronous DNS resolves */ +#define CURL_VERSION_SPNEGO (1<<8) /* SPNEGO auth is supported */ +#define CURL_VERSION_LARGEFILE (1<<9) /* Supports files larger than 2GB */ +#define CURL_VERSION_IDN (1<<10) /* Internationized Domain Names are + supported */ +#define CURL_VERSION_SSPI (1<<11) /* Built against Windows SSPI */ +#define CURL_VERSION_CONV (1<<12) /* Character conversions supported */ +#define CURL_VERSION_CURLDEBUG (1<<13) /* Debug memory tracking supported */ +#define CURL_VERSION_TLSAUTH_SRP (1<<14) /* TLS-SRP auth is supported */ +#define CURL_VERSION_NTLM_WB (1<<15) /* NTLM delegation to winbind helper + is suported */ +#define CURL_VERSION_HTTP2 (1<<16) /* HTTP2 support built-in */ +#define CURL_VERSION_GSSAPI (1<<17) /* Built against a GSS-API library */ +#define CURL_VERSION_KERBEROS5 (1<<18) /* Kerberos V5 auth is supported */ +#define CURL_VERSION_UNIX_SOCKETS (1<<19) /* Unix domain sockets support */ + + /* + * NAME curl_version_info() + * + * DESCRIPTION + * + * This function returns a pointer to a static copy of the version info + * struct. See above. + */ +CURL_EXTERN curl_version_info_data *curl_version_info(CURLversion); + +/* + * NAME curl_easy_strerror() + * + * DESCRIPTION + * + * The curl_easy_strerror function may be used to turn a CURLcode value + * into the equivalent human readable error string. This is useful + * for printing meaningful error messages. + */ +CURL_EXTERN const char *curl_easy_strerror(CURLcode); + +/* + * NAME curl_share_strerror() + * + * DESCRIPTION + * + * The curl_share_strerror function may be used to turn a CURLSHcode value + * into the equivalent human readable error string. This is useful + * for printing meaningful error messages. + */ +CURL_EXTERN const char *curl_share_strerror(CURLSHcode); + +/* + * NAME curl_easy_pause() + * + * DESCRIPTION + * + * The curl_easy_pause function pauses or unpauses transfers. Select the new + * state by setting the bitmask, use the convenience defines below. + * + */ +CURL_EXTERN CURLcode curl_easy_pause(CURL *handle, int bitmask); + +#define CURLPAUSE_RECV (1<<0) +#define CURLPAUSE_RECV_CONT (0) + +#define CURLPAUSE_SEND (1<<2) +#define CURLPAUSE_SEND_CONT (0) + +#define CURLPAUSE_ALL (CURLPAUSE_RECV|CURLPAUSE_SEND) +#define CURLPAUSE_CONT (CURLPAUSE_RECV_CONT|CURLPAUSE_SEND_CONT) + +#ifdef __cplusplus +} +#endif + +/* unfortunately, the easy.h and multi.h include files need options and info + stuff before they can be included! */ +#include "easy.h" /* nothing in curl is fun without the easy stuff */ +#include "multi.h" + +/* the typechecker doesn't work in C++ (yet) */ +#if defined(__GNUC__) && defined(__GNUC_MINOR__) && \ + ((__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 3)) && \ + !defined(__cplusplus) && !defined(CURL_DISABLE_TYPECHECK) +#include "typecheck-gcc.h" +#else +#if defined(__STDC__) && (__STDC__ >= 1) +/* This preprocessor magic that replaces a call with the exact same call is + only done to make sure application authors pass exactly three arguments + to these functions. */ +#define curl_easy_setopt(handle,opt,param) curl_easy_setopt(handle,opt,param) +#define curl_easy_getinfo(handle,info,arg) curl_easy_getinfo(handle,info,arg) +#define curl_share_setopt(share,opt,param) curl_share_setopt(share,opt,param) +#define curl_multi_setopt(handle,opt,param) curl_multi_setopt(handle,opt,param) +#endif /* __STDC__ >= 1 */ +#endif /* gcc >= 4.3 && !__cplusplus */ + +#endif /* __CURL_CURL_H */ diff --git a/phonelibs/curl/include/curl/curlbuild.h b/phonelibs/curl/include/curl/curlbuild.h new file mode 100644 index 00000000000000..2bf01cf37c520d --- /dev/null +++ b/phonelibs/curl/include/curl/curlbuild.h @@ -0,0 +1,195 @@ +/* include/curl/curlbuild.h. Generated from curlbuild.h.in by configure. */ +#ifndef __CURL_CURLBUILD_H +#define __CURL_CURLBUILD_H +/*************************************************************************** + * _ _ ____ _ + * Project ___| | | | _ \| | + * / __| | | | |_) | | + * | (__| |_| | _ <| |___ + * \___|\___/|_| \_\_____| + * + * Copyright (C) 1998 - 2012, Daniel Stenberg, , et al. + * + * This software is licensed as described in the file COPYING, which + * you should have received as part of this distribution. The terms + * are also available at http://curl.haxx.se/docs/copyright.html. + * + * You may opt to use, copy, modify, merge, publish, distribute and/or sell + * copies of the Software, and permit persons to whom the Software is + * furnished to do so, under the terms of the COPYING file. + * + * This software is distributed on an "AS IS" basis, WITHOUT WARRANTY OF ANY + * KIND, either express or implied. + * + ***************************************************************************/ + +/* ================================================================ */ +/* NOTES FOR CONFIGURE CAPABLE SYSTEMS */ +/* ================================================================ */ + +/* + * NOTE 1: + * ------- + * + * Nothing in this file is intended to be modified or adjusted by the + * curl library user nor by the curl library builder. + * + * If you think that something actually needs to be changed, adjusted + * or fixed in this file, then, report it on the libcurl development + * mailing list: http://cool.haxx.se/mailman/listinfo/curl-library/ + * + * This header file shall only export symbols which are 'curl' or 'CURL' + * prefixed, otherwise public name space would be polluted. + * + * NOTE 2: + * ------- + * + * Right now you might be staring at file include/curl/curlbuild.h.in or + * at file include/curl/curlbuild.h, this is due to the following reason: + * + * On systems capable of running the configure script, the configure process + * will overwrite the distributed include/curl/curlbuild.h file with one that + * is suitable and specific to the library being configured and built, which + * is generated from the include/curl/curlbuild.h.in template file. + * + */ + +/* ================================================================ */ +/* DEFINITION OF THESE SYMBOLS SHALL NOT TAKE PLACE ANYWHERE ELSE */ +/* ================================================================ */ + +#ifdef CURL_SIZEOF_LONG +#error "CURL_SIZEOF_LONG shall not be defined except in curlbuild.h" + Error Compilation_aborted_CURL_SIZEOF_LONG_already_defined +#endif + +#ifdef CURL_TYPEOF_CURL_SOCKLEN_T +#error "CURL_TYPEOF_CURL_SOCKLEN_T shall not be defined except in curlbuild.h" + Error Compilation_aborted_CURL_TYPEOF_CURL_SOCKLEN_T_already_defined +#endif + +#ifdef CURL_SIZEOF_CURL_SOCKLEN_T +#error "CURL_SIZEOF_CURL_SOCKLEN_T shall not be defined except in curlbuild.h" + Error Compilation_aborted_CURL_SIZEOF_CURL_SOCKLEN_T_already_defined +#endif + +#ifdef CURL_TYPEOF_CURL_OFF_T +#error "CURL_TYPEOF_CURL_OFF_T shall not be defined except in curlbuild.h" + Error Compilation_aborted_CURL_TYPEOF_CURL_OFF_T_already_defined +#endif + +#ifdef CURL_FORMAT_CURL_OFF_T +#error "CURL_FORMAT_CURL_OFF_T shall not be defined except in curlbuild.h" + Error Compilation_aborted_CURL_FORMAT_CURL_OFF_T_already_defined +#endif + +#ifdef CURL_FORMAT_CURL_OFF_TU +#error "CURL_FORMAT_CURL_OFF_TU shall not be defined except in curlbuild.h" + Error Compilation_aborted_CURL_FORMAT_CURL_OFF_TU_already_defined +#endif + +#ifdef CURL_FORMAT_OFF_T +#error "CURL_FORMAT_OFF_T shall not be defined except in curlbuild.h" + Error Compilation_aborted_CURL_FORMAT_OFF_T_already_defined +#endif + +#ifdef CURL_SIZEOF_CURL_OFF_T +#error "CURL_SIZEOF_CURL_OFF_T shall not be defined except in curlbuild.h" + Error Compilation_aborted_CURL_SIZEOF_CURL_OFF_T_already_defined +#endif + +#ifdef CURL_SUFFIX_CURL_OFF_T +#error "CURL_SUFFIX_CURL_OFF_T shall not be defined except in curlbuild.h" + Error Compilation_aborted_CURL_SUFFIX_CURL_OFF_T_already_defined +#endif + +#ifdef CURL_SUFFIX_CURL_OFF_TU +#error "CURL_SUFFIX_CURL_OFF_TU shall not be defined except in curlbuild.h" + Error Compilation_aborted_CURL_SUFFIX_CURL_OFF_TU_already_defined +#endif + +/* ================================================================ */ +/* EXTERNAL INTERFACE SETTINGS FOR CONFIGURE CAPABLE SYSTEMS ONLY */ +/* ================================================================ */ + +/* Configure process defines this to 1 when it finds out that system */ +/* header file ws2tcpip.h must be included by the external interface. */ +/* #undef CURL_PULL_WS2TCPIP_H */ +#ifdef CURL_PULL_WS2TCPIP_H +# ifndef WIN32_LEAN_AND_MEAN +# define WIN32_LEAN_AND_MEAN +# endif +# include +# include +# include +#endif + +/* Configure process defines this to 1 when it finds out that system */ +/* header file sys/types.h must be included by the external interface. */ +#define CURL_PULL_SYS_TYPES_H 1 +#ifdef CURL_PULL_SYS_TYPES_H +# include +#endif + +/* Configure process defines this to 1 when it finds out that system */ +/* header file stdint.h must be included by the external interface. */ +#define CURL_PULL_STDINT_H 1 +#ifdef CURL_PULL_STDINT_H +# include +#endif + +/* Configure process defines this to 1 when it finds out that system */ +/* header file inttypes.h must be included by the external interface. */ +#define CURL_PULL_INTTYPES_H 1 +#ifdef CURL_PULL_INTTYPES_H +# include +#endif + +/* Configure process defines this to 1 when it finds out that system */ +/* header file sys/socket.h must be included by the external interface. */ +#define CURL_PULL_SYS_SOCKET_H 1 +#ifdef CURL_PULL_SYS_SOCKET_H +# include +#endif + +/* Configure process defines this to 1 when it finds out that system */ +/* header file sys/poll.h must be included by the external interface. */ +/* #undef CURL_PULL_SYS_POLL_H */ +#ifdef CURL_PULL_SYS_POLL_H +# include +#endif + +/* Integral data type used for curl_socklen_t. */ +#define CURL_TYPEOF_CURL_SOCKLEN_T socklen_t + +/* The size of `curl_socklen_t', as computed by sizeof. */ +#define CURL_SIZEOF_CURL_SOCKLEN_T 4 + +/* Data type definition of curl_socklen_t. */ +typedef CURL_TYPEOF_CURL_SOCKLEN_T curl_socklen_t; + +/* Signed integral data type used for curl_off_t. */ +#define CURL_TYPEOF_CURL_OFF_T int64_t + +/* Data type definition of curl_off_t. */ +typedef CURL_TYPEOF_CURL_OFF_T curl_off_t; + +/* curl_off_t formatting string directive without "%" conversion specifier. */ +#define CURL_FORMAT_CURL_OFF_T "lld" + +/* unsigned curl_off_t formatting string without "%" conversion specifier. */ +#define CURL_FORMAT_CURL_OFF_TU "llu" + +/* curl_off_t formatting string directive with "%" conversion specifier. */ +#define CURL_FORMAT_OFF_T "%lld" + +/* The size of `curl_off_t', as computed by sizeof. */ +#define CURL_SIZEOF_CURL_OFF_T 8 + +/* curl_off_t constant suffix. */ +#define CURL_SUFFIX_CURL_OFF_T LL + +/* unsigned curl_off_t constant suffix. */ +#define CURL_SUFFIX_CURL_OFF_TU ULL + +#endif /* __CURL_CURLBUILD_H */ diff --git a/phonelibs/curl/include/curl/curlbuild.h.cmake b/phonelibs/curl/include/curl/curlbuild.h.cmake new file mode 100644 index 00000000000000..60bc7a70ec547e --- /dev/null +++ b/phonelibs/curl/include/curl/curlbuild.h.cmake @@ -0,0 +1,197 @@ +#ifndef __CURL_CURLBUILD_H +#define __CURL_CURLBUILD_H +/*************************************************************************** + * _ _ ____ _ + * Project ___| | | | _ \| | + * / __| | | | |_) | | + * | (__| |_| | _ <| |___ + * \___|\___/|_| \_\_____| + * + * Copyright (C) 1998 - 2008, Daniel Stenberg, , et al. + * + * This software is licensed as described in the file COPYING, which + * you should have received as part of this distribution. The terms + * are also available at http://curl.haxx.se/docs/copyright.html. + * + * You may opt to use, copy, modify, merge, publish, distribute and/or sell + * copies of the Software, and permit persons to whom the Software is + * furnished to do so, under the terms of the COPYING file. + * + * This software is distributed on an "AS IS" basis, WITHOUT WARRANTY OF ANY + * KIND, either express or implied. + * + ***************************************************************************/ + +/* ================================================================ */ +/* NOTES FOR CONFIGURE CAPABLE SYSTEMS */ +/* ================================================================ */ + +/* + * NOTE 1: + * ------- + * + * Nothing in this file is intended to be modified or adjusted by the + * curl library user nor by the curl library builder. + * + * If you think that something actually needs to be changed, adjusted + * or fixed in this file, then, report it on the libcurl development + * mailing list: http://cool.haxx.se/mailman/listinfo/curl-library/ + * + * This header file shall only export symbols which are 'curl' or 'CURL' + * prefixed, otherwise public name space would be polluted. + * + * NOTE 2: + * ------- + * + * Right now you might be staring at file include/curl/curlbuild.h.in or + * at file include/curl/curlbuild.h, this is due to the following reason: + * + * On systems capable of running the configure script, the configure process + * will overwrite the distributed include/curl/curlbuild.h file with one that + * is suitable and specific to the library being configured and built, which + * is generated from the include/curl/curlbuild.h.in template file. + * + */ + +/* ================================================================ */ +/* DEFINITION OF THESE SYMBOLS SHALL NOT TAKE PLACE ANYWHERE ELSE */ +/* ================================================================ */ + +#ifdef CURL_SIZEOF_LONG +#error "CURL_SIZEOF_LONG shall not be defined except in curlbuild.h" + Error Compilation_aborted_CURL_SIZEOF_LONG_already_defined +#endif + +#ifdef CURL_TYPEOF_CURL_SOCKLEN_T +#error "CURL_TYPEOF_CURL_SOCKLEN_T shall not be defined except in curlbuild.h" + Error Compilation_aborted_CURL_TYPEOF_CURL_SOCKLEN_T_already_defined +#endif + +#ifdef CURL_SIZEOF_CURL_SOCKLEN_T +#error "CURL_SIZEOF_CURL_SOCKLEN_T shall not be defined except in curlbuild.h" + Error Compilation_aborted_CURL_SIZEOF_CURL_SOCKLEN_T_already_defined +#endif + +#ifdef CURL_TYPEOF_CURL_OFF_T +#error "CURL_TYPEOF_CURL_OFF_T shall not be defined except in curlbuild.h" + Error Compilation_aborted_CURL_TYPEOF_CURL_OFF_T_already_defined +#endif + +#ifdef CURL_FORMAT_CURL_OFF_T +#error "CURL_FORMAT_CURL_OFF_T shall not be defined except in curlbuild.h" + Error Compilation_aborted_CURL_FORMAT_CURL_OFF_T_already_defined +#endif + +#ifdef CURL_FORMAT_CURL_OFF_TU +#error "CURL_FORMAT_CURL_OFF_TU shall not be defined except in curlbuild.h" + Error Compilation_aborted_CURL_FORMAT_CURL_OFF_TU_already_defined +#endif + +#ifdef CURL_FORMAT_OFF_T +#error "CURL_FORMAT_OFF_T shall not be defined except in curlbuild.h" + Error Compilation_aborted_CURL_FORMAT_OFF_T_already_defined +#endif + +#ifdef CURL_SIZEOF_CURL_OFF_T +#error "CURL_SIZEOF_CURL_OFF_T shall not be defined except in curlbuild.h" + Error Compilation_aborted_CURL_SIZEOF_CURL_OFF_T_already_defined +#endif + +#ifdef CURL_SUFFIX_CURL_OFF_T +#error "CURL_SUFFIX_CURL_OFF_T shall not be defined except in curlbuild.h" + Error Compilation_aborted_CURL_SUFFIX_CURL_OFF_T_already_defined +#endif + +#ifdef CURL_SUFFIX_CURL_OFF_TU +#error "CURL_SUFFIX_CURL_OFF_TU shall not be defined except in curlbuild.h" + Error Compilation_aborted_CURL_SUFFIX_CURL_OFF_TU_already_defined +#endif + +/* ================================================================ */ +/* EXTERNAL INTERFACE SETTINGS FOR CONFIGURE CAPABLE SYSTEMS ONLY */ +/* ================================================================ */ + +/* Configure process defines this to 1 when it finds out that system */ +/* header file ws2tcpip.h must be included by the external interface. */ +#cmakedefine CURL_PULL_WS2TCPIP_H +#ifdef CURL_PULL_WS2TCPIP_H +# ifndef WIN32_LEAN_AND_MEAN +# define WIN32_LEAN_AND_MEAN +# endif +# include +# include +# include +#endif + +/* Configure process defines this to 1 when it finds out that system */ +/* header file sys/types.h must be included by the external interface. */ +#cmakedefine CURL_PULL_SYS_TYPES_H +#ifdef CURL_PULL_SYS_TYPES_H +# include +#endif + +/* Configure process defines this to 1 when it finds out that system */ +/* header file stdint.h must be included by the external interface. */ +#cmakedefine CURL_PULL_STDINT_H +#ifdef CURL_PULL_STDINT_H +# include +#endif + +/* Configure process defines this to 1 when it finds out that system */ +/* header file inttypes.h must be included by the external interface. */ +#cmakedefine CURL_PULL_INTTYPES_H +#ifdef CURL_PULL_INTTYPES_H +# include +#endif + +/* Configure process defines this to 1 when it finds out that system */ +/* header file sys/socket.h must be included by the external interface. */ +#cmakedefine CURL_PULL_SYS_SOCKET_H +#ifdef CURL_PULL_SYS_SOCKET_H +# include +#endif + +/* Configure process defines this to 1 when it finds out that system */ +/* header file sys/poll.h must be included by the external interface. */ +#cmakedefine CURL_PULL_SYS_POLL_H +#ifdef CURL_PULL_SYS_POLL_H +# include +#endif + +/* The size of `long', as computed by sizeof. */ +#define CURL_SIZEOF_LONG ${CURL_SIZEOF_LONG} + +/* Integral data type used for curl_socklen_t. */ +#define CURL_TYPEOF_CURL_SOCKLEN_T ${CURL_TYPEOF_CURL_SOCKLEN_T} + +/* The size of `curl_socklen_t', as computed by sizeof. */ +#define CURL_SIZEOF_CURL_SOCKLEN_T ${CURL_SIZEOF_CURL_SOCKLEN_T} + +/* Data type definition of curl_socklen_t. */ +typedef CURL_TYPEOF_CURL_SOCKLEN_T curl_socklen_t; + +/* Signed integral data type used for curl_off_t. */ +#define CURL_TYPEOF_CURL_OFF_T ${CURL_TYPEOF_CURL_OFF_T} + +/* Data type definition of curl_off_t. */ +typedef CURL_TYPEOF_CURL_OFF_T curl_off_t; + +/* curl_off_t formatting string directive without "%" conversion specifier. */ +#define CURL_FORMAT_CURL_OFF_T "${CURL_FORMAT_CURL_OFF_T}" + +/* unsigned curl_off_t formatting string without "%" conversion specifier. */ +#define CURL_FORMAT_CURL_OFF_TU "${CURL_FORMAT_CURL_OFF_TU}" + +/* curl_off_t formatting string directive with "%" conversion specifier. */ +#define CURL_FORMAT_OFF_T "${CURL_FORMAT_OFF_T}" + +/* The size of `curl_off_t', as computed by sizeof. */ +#define CURL_SIZEOF_CURL_OFF_T ${CURL_SIZEOF_CURL_OFF_T} + +/* curl_off_t constant suffix. */ +#define CURL_SUFFIX_CURL_OFF_T ${CURL_SUFFIX_CURL_OFF_T} + +/* unsigned curl_off_t constant suffix. */ +#define CURL_SUFFIX_CURL_OFF_TU ${CURL_SUFFIX_CURL_OFF_TU} + +#endif /* __CURL_CURLBUILD_H */ diff --git a/phonelibs/curl/include/curl/curlbuild.h.dist b/phonelibs/curl/include/curl/curlbuild.h.dist new file mode 100644 index 00000000000000..f09419a8439151 --- /dev/null +++ b/phonelibs/curl/include/curl/curlbuild.h.dist @@ -0,0 +1,585 @@ +#ifndef __CURL_CURLBUILD_H +#define __CURL_CURLBUILD_H +/*************************************************************************** + * _ _ ____ _ + * Project ___| | | | _ \| | + * / __| | | | |_) | | + * | (__| |_| | _ <| |___ + * \___|\___/|_| \_\_____| + * + * Copyright (C) 1998 - 2013, Daniel Stenberg, , et al. + * + * This software is licensed as described in the file COPYING, which + * you should have received as part of this distribution. The terms + * are also available at http://curl.haxx.se/docs/copyright.html. + * + * You may opt to use, copy, modify, merge, publish, distribute and/or sell + * copies of the Software, and permit persons to whom the Software is + * furnished to do so, under the terms of the COPYING file. + * + * This software is distributed on an "AS IS" basis, WITHOUT WARRANTY OF ANY + * KIND, either express or implied. + * + ***************************************************************************/ + +/* ================================================================ */ +/* NOTES FOR CONFIGURE CAPABLE SYSTEMS */ +/* ================================================================ */ + +/* + * NOTE 1: + * ------- + * + * See file include/curl/curlbuild.h.in, run configure, and forget + * that this file exists it is only used for non-configure systems. + * But you can keep reading if you want ;-) + * + */ + +/* ================================================================ */ +/* NOTES FOR NON-CONFIGURE SYSTEMS */ +/* ================================================================ */ + +/* + * NOTE 1: + * ------- + * + * Nothing in this file is intended to be modified or adjusted by the + * curl library user nor by the curl library builder. + * + * If you think that something actually needs to be changed, adjusted + * or fixed in this file, then, report it on the libcurl development + * mailing list: http://cool.haxx.se/mailman/listinfo/curl-library/ + * + * Try to keep one section per platform, compiler and architecture, + * otherwise, if an existing section is reused for a different one and + * later on the original is adjusted, probably the piggybacking one can + * be adversely changed. + * + * In order to differentiate between platforms/compilers/architectures + * use only compiler built in predefined preprocessor symbols. + * + * This header file shall only export symbols which are 'curl' or 'CURL' + * prefixed, otherwise public name space would be polluted. + * + * NOTE 2: + * ------- + * + * For any given platform/compiler curl_off_t must be typedef'ed to a + * 64-bit wide signed integral data type. The width of this data type + * must remain constant and independent of any possible large file + * support settings. + * + * As an exception to the above, curl_off_t shall be typedef'ed to a + * 32-bit wide signed integral data type if there is no 64-bit type. + * + * As a general rule, curl_off_t shall not be mapped to off_t. This + * rule shall only be violated if off_t is the only 64-bit data type + * available and the size of off_t is independent of large file support + * settings. Keep your build on the safe side avoiding an off_t gating. + * If you have a 64-bit off_t then take for sure that another 64-bit + * data type exists, dig deeper and you will find it. + * + * NOTE 3: + * ------- + * + * Right now you might be staring at file include/curl/curlbuild.h.dist or + * at file include/curl/curlbuild.h, this is due to the following reason: + * file include/curl/curlbuild.h.dist is renamed to include/curl/curlbuild.h + * when the libcurl source code distribution archive file is created. + * + * File include/curl/curlbuild.h.dist is not included in the distribution + * archive. File include/curl/curlbuild.h is not present in the git tree. + * + * The distributed include/curl/curlbuild.h file is only intended to be used + * on systems which can not run the also distributed configure script. + * + * On systems capable of running the configure script, the configure process + * will overwrite the distributed include/curl/curlbuild.h file with one that + * is suitable and specific to the library being configured and built, which + * is generated from the include/curl/curlbuild.h.in template file. + * + * If you check out from git on a non-configure platform, you must run the + * appropriate buildconf* script to set up curlbuild.h and other local files. + * + */ + +/* ================================================================ */ +/* DEFINITION OF THESE SYMBOLS SHALL NOT TAKE PLACE ANYWHERE ELSE */ +/* ================================================================ */ + +#ifdef CURL_SIZEOF_LONG +# error "CURL_SIZEOF_LONG shall not be defined except in curlbuild.h" + Error Compilation_aborted_CURL_SIZEOF_LONG_already_defined +#endif + +#ifdef CURL_TYPEOF_CURL_SOCKLEN_T +# error "CURL_TYPEOF_CURL_SOCKLEN_T shall not be defined except in curlbuild.h" + Error Compilation_aborted_CURL_TYPEOF_CURL_SOCKLEN_T_already_defined +#endif + +#ifdef CURL_SIZEOF_CURL_SOCKLEN_T +# error "CURL_SIZEOF_CURL_SOCKLEN_T shall not be defined except in curlbuild.h" + Error Compilation_aborted_CURL_SIZEOF_CURL_SOCKLEN_T_already_defined +#endif + +#ifdef CURL_TYPEOF_CURL_OFF_T +# error "CURL_TYPEOF_CURL_OFF_T shall not be defined except in curlbuild.h" + Error Compilation_aborted_CURL_TYPEOF_CURL_OFF_T_already_defined +#endif + +#ifdef CURL_FORMAT_CURL_OFF_T +# error "CURL_FORMAT_CURL_OFF_T shall not be defined except in curlbuild.h" + Error Compilation_aborted_CURL_FORMAT_CURL_OFF_T_already_defined +#endif + +#ifdef CURL_FORMAT_CURL_OFF_TU +# error "CURL_FORMAT_CURL_OFF_TU shall not be defined except in curlbuild.h" + Error Compilation_aborted_CURL_FORMAT_CURL_OFF_TU_already_defined +#endif + +#ifdef CURL_FORMAT_OFF_T +# error "CURL_FORMAT_OFF_T shall not be defined except in curlbuild.h" + Error Compilation_aborted_CURL_FORMAT_OFF_T_already_defined +#endif + +#ifdef CURL_SIZEOF_CURL_OFF_T +# error "CURL_SIZEOF_CURL_OFF_T shall not be defined except in curlbuild.h" + Error Compilation_aborted_CURL_SIZEOF_CURL_OFF_T_already_defined +#endif + +#ifdef CURL_SUFFIX_CURL_OFF_T +# error "CURL_SUFFIX_CURL_OFF_T shall not be defined except in curlbuild.h" + Error Compilation_aborted_CURL_SUFFIX_CURL_OFF_T_already_defined +#endif + +#ifdef CURL_SUFFIX_CURL_OFF_TU +# error "CURL_SUFFIX_CURL_OFF_TU shall not be defined except in curlbuild.h" + Error Compilation_aborted_CURL_SUFFIX_CURL_OFF_TU_already_defined +#endif + +/* ================================================================ */ +/* EXTERNAL INTERFACE SETTINGS FOR NON-CONFIGURE SYSTEMS ONLY */ +/* ================================================================ */ + +#if defined(__DJGPP__) || defined(__GO32__) +# if defined(__DJGPP__) && (__DJGPP__ > 1) +# define CURL_SIZEOF_LONG 4 +# define CURL_TYPEOF_CURL_OFF_T long long +# define CURL_FORMAT_CURL_OFF_T "lld" +# define CURL_FORMAT_CURL_OFF_TU "llu" +# define CURL_FORMAT_OFF_T "%lld" +# define CURL_SIZEOF_CURL_OFF_T 8 +# define CURL_SUFFIX_CURL_OFF_T LL +# define CURL_SUFFIX_CURL_OFF_TU ULL +# else +# define CURL_SIZEOF_LONG 4 +# define CURL_TYPEOF_CURL_OFF_T long +# define CURL_FORMAT_CURL_OFF_T "ld" +# define CURL_FORMAT_CURL_OFF_TU "lu" +# define CURL_FORMAT_OFF_T "%ld" +# define CURL_SIZEOF_CURL_OFF_T 4 +# define CURL_SUFFIX_CURL_OFF_T L +# define CURL_SUFFIX_CURL_OFF_TU UL +# endif +# define CURL_TYPEOF_CURL_SOCKLEN_T int +# define CURL_SIZEOF_CURL_SOCKLEN_T 4 + +#elif defined(__SALFORDC__) +# define CURL_SIZEOF_LONG 4 +# define CURL_TYPEOF_CURL_OFF_T long +# define CURL_FORMAT_CURL_OFF_T "ld" +# define CURL_FORMAT_CURL_OFF_TU "lu" +# define CURL_FORMAT_OFF_T "%ld" +# define CURL_SIZEOF_CURL_OFF_T 4 +# define CURL_SUFFIX_CURL_OFF_T L +# define CURL_SUFFIX_CURL_OFF_TU UL +# define CURL_TYPEOF_CURL_SOCKLEN_T int +# define CURL_SIZEOF_CURL_SOCKLEN_T 4 + +#elif defined(__BORLANDC__) +# if (__BORLANDC__ < 0x520) +# define CURL_SIZEOF_LONG 4 +# define CURL_TYPEOF_CURL_OFF_T long +# define CURL_FORMAT_CURL_OFF_T "ld" +# define CURL_FORMAT_CURL_OFF_TU "lu" +# define CURL_FORMAT_OFF_T "%ld" +# define CURL_SIZEOF_CURL_OFF_T 4 +# define CURL_SUFFIX_CURL_OFF_T L +# define CURL_SUFFIX_CURL_OFF_TU UL +# else +# define CURL_SIZEOF_LONG 4 +# define CURL_TYPEOF_CURL_OFF_T __int64 +# define CURL_FORMAT_CURL_OFF_T "I64d" +# define CURL_FORMAT_CURL_OFF_TU "I64u" +# define CURL_FORMAT_OFF_T "%I64d" +# define CURL_SIZEOF_CURL_OFF_T 8 +# define CURL_SUFFIX_CURL_OFF_T i64 +# define CURL_SUFFIX_CURL_OFF_TU ui64 +# endif +# define CURL_TYPEOF_CURL_SOCKLEN_T int +# define CURL_SIZEOF_CURL_SOCKLEN_T 4 + +#elif defined(__TURBOC__) +# define CURL_SIZEOF_LONG 4 +# define CURL_TYPEOF_CURL_OFF_T long +# define CURL_FORMAT_CURL_OFF_T "ld" +# define CURL_FORMAT_CURL_OFF_TU "lu" +# define CURL_FORMAT_OFF_T "%ld" +# define CURL_SIZEOF_CURL_OFF_T 4 +# define CURL_SUFFIX_CURL_OFF_T L +# define CURL_SUFFIX_CURL_OFF_TU UL +# define CURL_TYPEOF_CURL_SOCKLEN_T int +# define CURL_SIZEOF_CURL_SOCKLEN_T 4 + +#elif defined(__WATCOMC__) +# if defined(__386__) +# define CURL_SIZEOF_LONG 4 +# define CURL_TYPEOF_CURL_OFF_T __int64 +# define CURL_FORMAT_CURL_OFF_T "I64d" +# define CURL_FORMAT_CURL_OFF_TU "I64u" +# define CURL_FORMAT_OFF_T "%I64d" +# define CURL_SIZEOF_CURL_OFF_T 8 +# define CURL_SUFFIX_CURL_OFF_T i64 +# define CURL_SUFFIX_CURL_OFF_TU ui64 +# else +# define CURL_SIZEOF_LONG 4 +# define CURL_TYPEOF_CURL_OFF_T long +# define CURL_FORMAT_CURL_OFF_T "ld" +# define CURL_FORMAT_CURL_OFF_TU "lu" +# define CURL_FORMAT_OFF_T "%ld" +# define CURL_SIZEOF_CURL_OFF_T 4 +# define CURL_SUFFIX_CURL_OFF_T L +# define CURL_SUFFIX_CURL_OFF_TU UL +# endif +# define CURL_TYPEOF_CURL_SOCKLEN_T int +# define CURL_SIZEOF_CURL_SOCKLEN_T 4 + +#elif defined(__POCC__) +# if (__POCC__ < 280) +# define CURL_SIZEOF_LONG 4 +# define CURL_TYPEOF_CURL_OFF_T long +# define CURL_FORMAT_CURL_OFF_T "ld" +# define CURL_FORMAT_CURL_OFF_TU "lu" +# define CURL_FORMAT_OFF_T "%ld" +# define CURL_SIZEOF_CURL_OFF_T 4 +# define CURL_SUFFIX_CURL_OFF_T L +# define CURL_SUFFIX_CURL_OFF_TU UL +# elif defined(_MSC_VER) +# define CURL_SIZEOF_LONG 4 +# define CURL_TYPEOF_CURL_OFF_T __int64 +# define CURL_FORMAT_CURL_OFF_T "I64d" +# define CURL_FORMAT_CURL_OFF_TU "I64u" +# define CURL_FORMAT_OFF_T "%I64d" +# define CURL_SIZEOF_CURL_OFF_T 8 +# define CURL_SUFFIX_CURL_OFF_T i64 +# define CURL_SUFFIX_CURL_OFF_TU ui64 +# else +# define CURL_SIZEOF_LONG 4 +# define CURL_TYPEOF_CURL_OFF_T long long +# define CURL_FORMAT_CURL_OFF_T "lld" +# define CURL_FORMAT_CURL_OFF_TU "llu" +# define CURL_FORMAT_OFF_T "%lld" +# define CURL_SIZEOF_CURL_OFF_T 8 +# define CURL_SUFFIX_CURL_OFF_T LL +# define CURL_SUFFIX_CURL_OFF_TU ULL +# endif +# define CURL_TYPEOF_CURL_SOCKLEN_T int +# define CURL_SIZEOF_CURL_SOCKLEN_T 4 + +#elif defined(__LCC__) +# define CURL_SIZEOF_LONG 4 +# define CURL_TYPEOF_CURL_OFF_T long +# define CURL_FORMAT_CURL_OFF_T "ld" +# define CURL_FORMAT_CURL_OFF_TU "lu" +# define CURL_FORMAT_OFF_T "%ld" +# define CURL_SIZEOF_CURL_OFF_T 4 +# define CURL_SUFFIX_CURL_OFF_T L +# define CURL_SUFFIX_CURL_OFF_TU UL +# define CURL_TYPEOF_CURL_SOCKLEN_T int +# define CURL_SIZEOF_CURL_SOCKLEN_T 4 + +#elif defined(__SYMBIAN32__) +# if defined(__EABI__) /* Treat all ARM compilers equally */ +# define CURL_SIZEOF_LONG 4 +# define CURL_TYPEOF_CURL_OFF_T long long +# define CURL_FORMAT_CURL_OFF_T "lld" +# define CURL_FORMAT_CURL_OFF_TU "llu" +# define CURL_FORMAT_OFF_T "%lld" +# define CURL_SIZEOF_CURL_OFF_T 8 +# define CURL_SUFFIX_CURL_OFF_T LL +# define CURL_SUFFIX_CURL_OFF_TU ULL +# elif defined(__CW32__) +# pragma longlong on +# define CURL_SIZEOF_LONG 4 +# define CURL_TYPEOF_CURL_OFF_T long long +# define CURL_FORMAT_CURL_OFF_T "lld" +# define CURL_FORMAT_CURL_OFF_TU "llu" +# define CURL_FORMAT_OFF_T "%lld" +# define CURL_SIZEOF_CURL_OFF_T 8 +# define CURL_SUFFIX_CURL_OFF_T LL +# define CURL_SUFFIX_CURL_OFF_TU ULL +# elif defined(__VC32__) +# define CURL_SIZEOF_LONG 4 +# define CURL_TYPEOF_CURL_OFF_T __int64 +# define CURL_FORMAT_CURL_OFF_T "lld" +# define CURL_FORMAT_CURL_OFF_TU "llu" +# define CURL_FORMAT_OFF_T "%lld" +# define CURL_SIZEOF_CURL_OFF_T 8 +# define CURL_SUFFIX_CURL_OFF_T LL +# define CURL_SUFFIX_CURL_OFF_TU ULL +# endif +# define CURL_TYPEOF_CURL_SOCKLEN_T unsigned int +# define CURL_SIZEOF_CURL_SOCKLEN_T 4 + +#elif defined(__MWERKS__) +# define CURL_SIZEOF_LONG 4 +# define CURL_TYPEOF_CURL_OFF_T long long +# define CURL_FORMAT_CURL_OFF_T "lld" +# define CURL_FORMAT_CURL_OFF_TU "llu" +# define CURL_FORMAT_OFF_T "%lld" +# define CURL_SIZEOF_CURL_OFF_T 8 +# define CURL_SUFFIX_CURL_OFF_T LL +# define CURL_SUFFIX_CURL_OFF_TU ULL +# define CURL_TYPEOF_CURL_SOCKLEN_T int +# define CURL_SIZEOF_CURL_SOCKLEN_T 4 + +#elif defined(_WIN32_WCE) +# define CURL_SIZEOF_LONG 4 +# define CURL_TYPEOF_CURL_OFF_T __int64 +# define CURL_FORMAT_CURL_OFF_T "I64d" +# define CURL_FORMAT_CURL_OFF_TU "I64u" +# define CURL_FORMAT_OFF_T "%I64d" +# define CURL_SIZEOF_CURL_OFF_T 8 +# define CURL_SUFFIX_CURL_OFF_T i64 +# define CURL_SUFFIX_CURL_OFF_TU ui64 +# define CURL_TYPEOF_CURL_SOCKLEN_T int +# define CURL_SIZEOF_CURL_SOCKLEN_T 4 + +#elif defined(__MINGW32__) +# define CURL_SIZEOF_LONG 4 +# define CURL_TYPEOF_CURL_OFF_T long long +# define CURL_FORMAT_CURL_OFF_T "I64d" +# define CURL_FORMAT_CURL_OFF_TU "I64u" +# define CURL_FORMAT_OFF_T "%I64d" +# define CURL_SIZEOF_CURL_OFF_T 8 +# define CURL_SUFFIX_CURL_OFF_T LL +# define CURL_SUFFIX_CURL_OFF_TU ULL +# define CURL_TYPEOF_CURL_SOCKLEN_T int +# define CURL_SIZEOF_CURL_SOCKLEN_T 4 + +#elif defined(__VMS) +# if defined(__VAX) +# define CURL_SIZEOF_LONG 4 +# define CURL_TYPEOF_CURL_OFF_T long +# define CURL_FORMAT_CURL_OFF_T "ld" +# define CURL_FORMAT_CURL_OFF_TU "lu" +# define CURL_FORMAT_OFF_T "%ld" +# define CURL_SIZEOF_CURL_OFF_T 4 +# define CURL_SUFFIX_CURL_OFF_T L +# define CURL_SUFFIX_CURL_OFF_TU UL +# else +# define CURL_SIZEOF_LONG 4 +# define CURL_TYPEOF_CURL_OFF_T long long +# define CURL_FORMAT_CURL_OFF_T "lld" +# define CURL_FORMAT_CURL_OFF_TU "llu" +# define CURL_FORMAT_OFF_T "%lld" +# define CURL_SIZEOF_CURL_OFF_T 8 +# define CURL_SUFFIX_CURL_OFF_T LL +# define CURL_SUFFIX_CURL_OFF_TU ULL +# endif +# define CURL_TYPEOF_CURL_SOCKLEN_T unsigned int +# define CURL_SIZEOF_CURL_SOCKLEN_T 4 + +#elif defined(__OS400__) +# if defined(__ILEC400__) +# define CURL_SIZEOF_LONG 4 +# define CURL_TYPEOF_CURL_OFF_T long long +# define CURL_FORMAT_CURL_OFF_T "lld" +# define CURL_FORMAT_CURL_OFF_TU "llu" +# define CURL_FORMAT_OFF_T "%lld" +# define CURL_SIZEOF_CURL_OFF_T 8 +# define CURL_SUFFIX_CURL_OFF_T LL +# define CURL_SUFFIX_CURL_OFF_TU ULL +# define CURL_TYPEOF_CURL_SOCKLEN_T socklen_t +# define CURL_SIZEOF_CURL_SOCKLEN_T 4 +# define CURL_PULL_SYS_TYPES_H 1 +# define CURL_PULL_SYS_SOCKET_H 1 +# endif + +#elif defined(__MVS__) +# if defined(__IBMC__) || defined(__IBMCPP__) +# if defined(_ILP32) +# define CURL_SIZEOF_LONG 4 +# elif defined(_LP64) +# define CURL_SIZEOF_LONG 8 +# endif +# if defined(_LONG_LONG) +# define CURL_TYPEOF_CURL_OFF_T long long +# define CURL_FORMAT_CURL_OFF_T "lld" +# define CURL_FORMAT_CURL_OFF_TU "llu" +# define CURL_FORMAT_OFF_T "%lld" +# define CURL_SIZEOF_CURL_OFF_T 8 +# define CURL_SUFFIX_CURL_OFF_T LL +# define CURL_SUFFIX_CURL_OFF_TU ULL +# elif defined(_LP64) +# define CURL_TYPEOF_CURL_OFF_T long +# define CURL_FORMAT_CURL_OFF_T "ld" +# define CURL_FORMAT_CURL_OFF_TU "lu" +# define CURL_FORMAT_OFF_T "%ld" +# define CURL_SIZEOF_CURL_OFF_T 8 +# define CURL_SUFFIX_CURL_OFF_T L +# define CURL_SUFFIX_CURL_OFF_TU UL +# else +# define CURL_TYPEOF_CURL_OFF_T long +# define CURL_FORMAT_CURL_OFF_T "ld" +# define CURL_FORMAT_CURL_OFF_TU "lu" +# define CURL_FORMAT_OFF_T "%ld" +# define CURL_SIZEOF_CURL_OFF_T 4 +# define CURL_SUFFIX_CURL_OFF_T L +# define CURL_SUFFIX_CURL_OFF_TU UL +# endif +# define CURL_TYPEOF_CURL_SOCKLEN_T socklen_t +# define CURL_SIZEOF_CURL_SOCKLEN_T 4 +# define CURL_PULL_SYS_TYPES_H 1 +# define CURL_PULL_SYS_SOCKET_H 1 +# endif + +#elif defined(__370__) +# if defined(__IBMC__) || defined(__IBMCPP__) +# if defined(_ILP32) +# define CURL_SIZEOF_LONG 4 +# elif defined(_LP64) +# define CURL_SIZEOF_LONG 8 +# endif +# if defined(_LONG_LONG) +# define CURL_TYPEOF_CURL_OFF_T long long +# define CURL_FORMAT_CURL_OFF_T "lld" +# define CURL_FORMAT_CURL_OFF_TU "llu" +# define CURL_FORMAT_OFF_T "%lld" +# define CURL_SIZEOF_CURL_OFF_T 8 +# define CURL_SUFFIX_CURL_OFF_T LL +# define CURL_SUFFIX_CURL_OFF_TU ULL +# elif defined(_LP64) +# define CURL_TYPEOF_CURL_OFF_T long +# define CURL_FORMAT_CURL_OFF_T "ld" +# define CURL_FORMAT_CURL_OFF_TU "lu" +# define CURL_FORMAT_OFF_T "%ld" +# define CURL_SIZEOF_CURL_OFF_T 8 +# define CURL_SUFFIX_CURL_OFF_T L +# define CURL_SUFFIX_CURL_OFF_TU UL +# else +# define CURL_TYPEOF_CURL_OFF_T long +# define CURL_FORMAT_CURL_OFF_T "ld" +# define CURL_FORMAT_CURL_OFF_TU "lu" +# define CURL_FORMAT_OFF_T "%ld" +# define CURL_SIZEOF_CURL_OFF_T 4 +# define CURL_SUFFIX_CURL_OFF_T L +# define CURL_SUFFIX_CURL_OFF_TU UL +# endif +# define CURL_TYPEOF_CURL_SOCKLEN_T socklen_t +# define CURL_SIZEOF_CURL_SOCKLEN_T 4 +# define CURL_PULL_SYS_TYPES_H 1 +# define CURL_PULL_SYS_SOCKET_H 1 +# endif + +#elif defined(TPF) +# define CURL_SIZEOF_LONG 8 +# define CURL_TYPEOF_CURL_OFF_T long +# define CURL_FORMAT_CURL_OFF_T "ld" +# define CURL_FORMAT_CURL_OFF_TU "lu" +# define CURL_FORMAT_OFF_T "%ld" +# define CURL_SIZEOF_CURL_OFF_T 8 +# define CURL_SUFFIX_CURL_OFF_T L +# define CURL_SUFFIX_CURL_OFF_TU UL +# define CURL_TYPEOF_CURL_SOCKLEN_T int +# define CURL_SIZEOF_CURL_SOCKLEN_T 4 + +/* ===================================== */ +/* KEEP MSVC THE PENULTIMATE ENTRY */ +/* ===================================== */ + +#elif defined(_MSC_VER) +# if (_MSC_VER >= 900) && (_INTEGRAL_MAX_BITS >= 64) +# define CURL_SIZEOF_LONG 4 +# define CURL_TYPEOF_CURL_OFF_T __int64 +# define CURL_FORMAT_CURL_OFF_T "I64d" +# define CURL_FORMAT_CURL_OFF_TU "I64u" +# define CURL_FORMAT_OFF_T "%I64d" +# define CURL_SIZEOF_CURL_OFF_T 8 +# define CURL_SUFFIX_CURL_OFF_T i64 +# define CURL_SUFFIX_CURL_OFF_TU ui64 +# else +# define CURL_SIZEOF_LONG 4 +# define CURL_TYPEOF_CURL_OFF_T long +# define CURL_FORMAT_CURL_OFF_T "ld" +# define CURL_FORMAT_CURL_OFF_TU "lu" +# define CURL_FORMAT_OFF_T "%ld" +# define CURL_SIZEOF_CURL_OFF_T 4 +# define CURL_SUFFIX_CURL_OFF_T L +# define CURL_SUFFIX_CURL_OFF_TU UL +# endif +# define CURL_TYPEOF_CURL_SOCKLEN_T int +# define CURL_SIZEOF_CURL_SOCKLEN_T 4 + +/* ===================================== */ +/* KEEP GENERIC GCC THE LAST ENTRY */ +/* ===================================== */ + +#elif defined(__GNUC__) +# if defined(__ILP32__) || \ + defined(__i386__) || defined(__ppc__) || defined(__arm__) || defined(__sparc__) +# define CURL_SIZEOF_LONG 4 +# define CURL_TYPEOF_CURL_OFF_T long long +# define CURL_FORMAT_CURL_OFF_T "lld" +# define CURL_FORMAT_CURL_OFF_TU "llu" +# define CURL_FORMAT_OFF_T "%lld" +# define CURL_SIZEOF_CURL_OFF_T 8 +# define CURL_SUFFIX_CURL_OFF_T LL +# define CURL_SUFFIX_CURL_OFF_TU ULL +# elif defined(__LP64__) || \ + defined(__x86_64__) || defined(__ppc64__) || defined(__sparc64__) +# define CURL_SIZEOF_LONG 8 +# define CURL_TYPEOF_CURL_OFF_T long +# define CURL_FORMAT_CURL_OFF_T "ld" +# define CURL_FORMAT_CURL_OFF_TU "lu" +# define CURL_FORMAT_OFF_T "%ld" +# define CURL_SIZEOF_CURL_OFF_T 8 +# define CURL_SUFFIX_CURL_OFF_T L +# define CURL_SUFFIX_CURL_OFF_TU UL +# endif +# define CURL_TYPEOF_CURL_SOCKLEN_T socklen_t +# define CURL_SIZEOF_CURL_SOCKLEN_T 4 +# define CURL_PULL_SYS_TYPES_H 1 +# define CURL_PULL_SYS_SOCKET_H 1 + +#else +# error "Unknown non-configure build target!" + Error Compilation_aborted_Unknown_non_configure_build_target +#endif + +/* CURL_PULL_SYS_TYPES_H is defined above when inclusion of header file */ +/* sys/types.h is required here to properly make type definitions below. */ +#ifdef CURL_PULL_SYS_TYPES_H +# include +#endif + +/* CURL_PULL_SYS_SOCKET_H is defined above when inclusion of header file */ +/* sys/socket.h is required here to properly make type definitions below. */ +#ifdef CURL_PULL_SYS_SOCKET_H +# include +#endif + +/* Data type definition of curl_socklen_t. */ + +#ifdef CURL_TYPEOF_CURL_SOCKLEN_T + typedef CURL_TYPEOF_CURL_SOCKLEN_T curl_socklen_t; +#endif + +/* Data type definition of curl_off_t. */ + +#ifdef CURL_TYPEOF_CURL_OFF_T + typedef CURL_TYPEOF_CURL_OFF_T curl_off_t; +#endif + +#endif /* __CURL_CURLBUILD_H */ diff --git a/phonelibs/curl/include/curl/curlbuild.h.in b/phonelibs/curl/include/curl/curlbuild.h.in new file mode 100644 index 00000000000000..7cb2b6ef7eb1c7 --- /dev/null +++ b/phonelibs/curl/include/curl/curlbuild.h.in @@ -0,0 +1,194 @@ +#ifndef __CURL_CURLBUILD_H +#define __CURL_CURLBUILD_H +/*************************************************************************** + * _ _ ____ _ + * Project ___| | | | _ \| | + * / __| | | | |_) | | + * | (__| |_| | _ <| |___ + * \___|\___/|_| \_\_____| + * + * Copyright (C) 1998 - 2012, Daniel Stenberg, , et al. + * + * This software is licensed as described in the file COPYING, which + * you should have received as part of this distribution. The terms + * are also available at http://curl.haxx.se/docs/copyright.html. + * + * You may opt to use, copy, modify, merge, publish, distribute and/or sell + * copies of the Software, and permit persons to whom the Software is + * furnished to do so, under the terms of the COPYING file. + * + * This software is distributed on an "AS IS" basis, WITHOUT WARRANTY OF ANY + * KIND, either express or implied. + * + ***************************************************************************/ + +/* ================================================================ */ +/* NOTES FOR CONFIGURE CAPABLE SYSTEMS */ +/* ================================================================ */ + +/* + * NOTE 1: + * ------- + * + * Nothing in this file is intended to be modified or adjusted by the + * curl library user nor by the curl library builder. + * + * If you think that something actually needs to be changed, adjusted + * or fixed in this file, then, report it on the libcurl development + * mailing list: http://cool.haxx.se/mailman/listinfo/curl-library/ + * + * This header file shall only export symbols which are 'curl' or 'CURL' + * prefixed, otherwise public name space would be polluted. + * + * NOTE 2: + * ------- + * + * Right now you might be staring at file include/curl/curlbuild.h.in or + * at file include/curl/curlbuild.h, this is due to the following reason: + * + * On systems capable of running the configure script, the configure process + * will overwrite the distributed include/curl/curlbuild.h file with one that + * is suitable and specific to the library being configured and built, which + * is generated from the include/curl/curlbuild.h.in template file. + * + */ + +/* ================================================================ */ +/* DEFINITION OF THESE SYMBOLS SHALL NOT TAKE PLACE ANYWHERE ELSE */ +/* ================================================================ */ + +#ifdef CURL_SIZEOF_LONG +#error "CURL_SIZEOF_LONG shall not be defined except in curlbuild.h" + Error Compilation_aborted_CURL_SIZEOF_LONG_already_defined +#endif + +#ifdef CURL_TYPEOF_CURL_SOCKLEN_T +#error "CURL_TYPEOF_CURL_SOCKLEN_T shall not be defined except in curlbuild.h" + Error Compilation_aborted_CURL_TYPEOF_CURL_SOCKLEN_T_already_defined +#endif + +#ifdef CURL_SIZEOF_CURL_SOCKLEN_T +#error "CURL_SIZEOF_CURL_SOCKLEN_T shall not be defined except in curlbuild.h" + Error Compilation_aborted_CURL_SIZEOF_CURL_SOCKLEN_T_already_defined +#endif + +#ifdef CURL_TYPEOF_CURL_OFF_T +#error "CURL_TYPEOF_CURL_OFF_T shall not be defined except in curlbuild.h" + Error Compilation_aborted_CURL_TYPEOF_CURL_OFF_T_already_defined +#endif + +#ifdef CURL_FORMAT_CURL_OFF_T +#error "CURL_FORMAT_CURL_OFF_T shall not be defined except in curlbuild.h" + Error Compilation_aborted_CURL_FORMAT_CURL_OFF_T_already_defined +#endif + +#ifdef CURL_FORMAT_CURL_OFF_TU +#error "CURL_FORMAT_CURL_OFF_TU shall not be defined except in curlbuild.h" + Error Compilation_aborted_CURL_FORMAT_CURL_OFF_TU_already_defined +#endif + +#ifdef CURL_FORMAT_OFF_T +#error "CURL_FORMAT_OFF_T shall not be defined except in curlbuild.h" + Error Compilation_aborted_CURL_FORMAT_OFF_T_already_defined +#endif + +#ifdef CURL_SIZEOF_CURL_OFF_T +#error "CURL_SIZEOF_CURL_OFF_T shall not be defined except in curlbuild.h" + Error Compilation_aborted_CURL_SIZEOF_CURL_OFF_T_already_defined +#endif + +#ifdef CURL_SUFFIX_CURL_OFF_T +#error "CURL_SUFFIX_CURL_OFF_T shall not be defined except in curlbuild.h" + Error Compilation_aborted_CURL_SUFFIX_CURL_OFF_T_already_defined +#endif + +#ifdef CURL_SUFFIX_CURL_OFF_TU +#error "CURL_SUFFIX_CURL_OFF_TU shall not be defined except in curlbuild.h" + Error Compilation_aborted_CURL_SUFFIX_CURL_OFF_TU_already_defined +#endif + +/* ================================================================ */ +/* EXTERNAL INTERFACE SETTINGS FOR CONFIGURE CAPABLE SYSTEMS ONLY */ +/* ================================================================ */ + +/* Configure process defines this to 1 when it finds out that system */ +/* header file ws2tcpip.h must be included by the external interface. */ +#undef CURL_PULL_WS2TCPIP_H +#ifdef CURL_PULL_WS2TCPIP_H +# ifndef WIN32_LEAN_AND_MEAN +# define WIN32_LEAN_AND_MEAN +# endif +# include +# include +# include +#endif + +/* Configure process defines this to 1 when it finds out that system */ +/* header file sys/types.h must be included by the external interface. */ +#undef CURL_PULL_SYS_TYPES_H +#ifdef CURL_PULL_SYS_TYPES_H +# include +#endif + +/* Configure process defines this to 1 when it finds out that system */ +/* header file stdint.h must be included by the external interface. */ +#undef CURL_PULL_STDINT_H +#ifdef CURL_PULL_STDINT_H +# include +#endif + +/* Configure process defines this to 1 when it finds out that system */ +/* header file inttypes.h must be included by the external interface. */ +#undef CURL_PULL_INTTYPES_H +#ifdef CURL_PULL_INTTYPES_H +# include +#endif + +/* Configure process defines this to 1 when it finds out that system */ +/* header file sys/socket.h must be included by the external interface. */ +#undef CURL_PULL_SYS_SOCKET_H +#ifdef CURL_PULL_SYS_SOCKET_H +# include +#endif + +/* Configure process defines this to 1 when it finds out that system */ +/* header file sys/poll.h must be included by the external interface. */ +#undef CURL_PULL_SYS_POLL_H +#ifdef CURL_PULL_SYS_POLL_H +# include +#endif + +/* Integral data type used for curl_socklen_t. */ +#undef CURL_TYPEOF_CURL_SOCKLEN_T + +/* The size of `curl_socklen_t', as computed by sizeof. */ +#undef CURL_SIZEOF_CURL_SOCKLEN_T + +/* Data type definition of curl_socklen_t. */ +typedef CURL_TYPEOF_CURL_SOCKLEN_T curl_socklen_t; + +/* Signed integral data type used for curl_off_t. */ +#undef CURL_TYPEOF_CURL_OFF_T + +/* Data type definition of curl_off_t. */ +typedef CURL_TYPEOF_CURL_OFF_T curl_off_t; + +/* curl_off_t formatting string directive without "%" conversion specifier. */ +#undef CURL_FORMAT_CURL_OFF_T + +/* unsigned curl_off_t formatting string without "%" conversion specifier. */ +#undef CURL_FORMAT_CURL_OFF_TU + +/* curl_off_t formatting string directive with "%" conversion specifier. */ +#undef CURL_FORMAT_OFF_T + +/* The size of `curl_off_t', as computed by sizeof. */ +#undef CURL_SIZEOF_CURL_OFF_T + +/* curl_off_t constant suffix. */ +#undef CURL_SUFFIX_CURL_OFF_T + +/* unsigned curl_off_t constant suffix. */ +#undef CURL_SUFFIX_CURL_OFF_TU + +#endif /* __CURL_CURLBUILD_H */ diff --git a/phonelibs/curl/include/curl/curlrules.h b/phonelibs/curl/include/curl/curlrules.h new file mode 100644 index 00000000000000..1163e95f48ac87 --- /dev/null +++ b/phonelibs/curl/include/curl/curlrules.h @@ -0,0 +1,248 @@ +#ifndef __CURL_CURLRULES_H +#define __CURL_CURLRULES_H +/*************************************************************************** + * _ _ ____ _ + * Project ___| | | | _ \| | + * / __| | | | |_) | | + * | (__| |_| | _ <| |___ + * \___|\___/|_| \_\_____| + * + * Copyright (C) 1998 - 2012, Daniel Stenberg, , et al. + * + * This software is licensed as described in the file COPYING, which + * you should have received as part of this distribution. The terms + * are also available at http://curl.haxx.se/docs/copyright.html. + * + * You may opt to use, copy, modify, merge, publish, distribute and/or sell + * copies of the Software, and permit persons to whom the Software is + * furnished to do so, under the terms of the COPYING file. + * + * This software is distributed on an "AS IS" basis, WITHOUT WARRANTY OF ANY + * KIND, either express or implied. + * + ***************************************************************************/ + +/* ================================================================ */ +/* COMPILE TIME SANITY CHECKS */ +/* ================================================================ */ + +/* + * NOTE 1: + * ------- + * + * All checks done in this file are intentionally placed in a public + * header file which is pulled by curl/curl.h when an application is + * being built using an already built libcurl library. Additionally + * this file is also included and used when building the library. + * + * If compilation fails on this file it is certainly sure that the + * problem is elsewhere. It could be a problem in the curlbuild.h + * header file, or simply that you are using different compilation + * settings than those used to build the library. + * + * Nothing in this file is intended to be modified or adjusted by the + * curl library user nor by the curl library builder. + * + * Do not deactivate any check, these are done to make sure that the + * library is properly built and used. + * + * You can find further help on the libcurl development mailing list: + * http://cool.haxx.se/mailman/listinfo/curl-library/ + * + * NOTE 2 + * ------ + * + * Some of the following compile time checks are based on the fact + * that the dimension of a constant array can not be a negative one. + * In this way if the compile time verification fails, the compilation + * will fail issuing an error. The error description wording is compiler + * dependent but it will be quite similar to one of the following: + * + * "negative subscript or subscript is too large" + * "array must have at least one element" + * "-1 is an illegal array size" + * "size of array is negative" + * + * If you are building an application which tries to use an already + * built libcurl library and you are getting this kind of errors on + * this file, it is a clear indication that there is a mismatch between + * how the library was built and how you are trying to use it for your + * application. Your already compiled or binary library provider is the + * only one who can give you the details you need to properly use it. + */ + +/* + * Verify that some macros are actually defined. + */ + +#ifndef CURL_TYPEOF_CURL_SOCKLEN_T +# error "CURL_TYPEOF_CURL_SOCKLEN_T definition is missing!" + Error Compilation_aborted_CURL_TYPEOF_CURL_SOCKLEN_T_is_missing +#endif + +#ifndef CURL_SIZEOF_CURL_SOCKLEN_T +# error "CURL_SIZEOF_CURL_SOCKLEN_T definition is missing!" + Error Compilation_aborted_CURL_SIZEOF_CURL_SOCKLEN_T_is_missing +#endif + +#ifndef CURL_TYPEOF_CURL_OFF_T +# error "CURL_TYPEOF_CURL_OFF_T definition is missing!" + Error Compilation_aborted_CURL_TYPEOF_CURL_OFF_T_is_missing +#endif + +#ifndef CURL_FORMAT_CURL_OFF_T +# error "CURL_FORMAT_CURL_OFF_T definition is missing!" + Error Compilation_aborted_CURL_FORMAT_CURL_OFF_T_is_missing +#endif + +#ifndef CURL_FORMAT_CURL_OFF_TU +# error "CURL_FORMAT_CURL_OFF_TU definition is missing!" + Error Compilation_aborted_CURL_FORMAT_CURL_OFF_TU_is_missing +#endif + +#ifndef CURL_FORMAT_OFF_T +# error "CURL_FORMAT_OFF_T definition is missing!" + Error Compilation_aborted_CURL_FORMAT_OFF_T_is_missing +#endif + +#ifndef CURL_SIZEOF_CURL_OFF_T +# error "CURL_SIZEOF_CURL_OFF_T definition is missing!" + Error Compilation_aborted_CURL_SIZEOF_CURL_OFF_T_is_missing +#endif + +#ifndef CURL_SUFFIX_CURL_OFF_T +# error "CURL_SUFFIX_CURL_OFF_T definition is missing!" + Error Compilation_aborted_CURL_SUFFIX_CURL_OFF_T_is_missing +#endif + +#ifndef CURL_SUFFIX_CURL_OFF_TU +# error "CURL_SUFFIX_CURL_OFF_TU definition is missing!" + Error Compilation_aborted_CURL_SUFFIX_CURL_OFF_TU_is_missing +#endif + +/* + * Macros private to this header file. + */ + +#define CurlchkszEQ(t, s) sizeof(t) == s ? 1 : -1 + +#define CurlchkszGE(t1, t2) sizeof(t1) >= sizeof(t2) ? 1 : -1 + +/* + * Verify that the size previously defined and expected for + * curl_off_t is actually the the same as the one reported + * by sizeof() at compile time. + */ + +typedef char + __curl_rule_02__ + [CurlchkszEQ(curl_off_t, CURL_SIZEOF_CURL_OFF_T)]; + +/* + * Verify at compile time that the size of curl_off_t as reported + * by sizeof() is greater or equal than the one reported for long + * for the current compilation. + */ + +typedef char + __curl_rule_03__ + [CurlchkszGE(curl_off_t, long)]; + +/* + * Verify that the size previously defined and expected for + * curl_socklen_t is actually the the same as the one reported + * by sizeof() at compile time. + */ + +typedef char + __curl_rule_04__ + [CurlchkszEQ(curl_socklen_t, CURL_SIZEOF_CURL_SOCKLEN_T)]; + +/* + * Verify at compile time that the size of curl_socklen_t as reported + * by sizeof() is greater or equal than the one reported for int for + * the current compilation. + */ + +typedef char + __curl_rule_05__ + [CurlchkszGE(curl_socklen_t, int)]; + +/* ================================================================ */ +/* EXTERNALLY AND INTERNALLY VISIBLE DEFINITIONS */ +/* ================================================================ */ + +/* + * CURL_ISOCPP and CURL_OFF_T_C definitions are done here in order to allow + * these to be visible and exported by the external libcurl interface API, + * while also making them visible to the library internals, simply including + * curl_setup.h, without actually needing to include curl.h internally. + * If some day this section would grow big enough, all this should be moved + * to its own header file. + */ + +/* + * Figure out if we can use the ## preprocessor operator, which is supported + * by ISO/ANSI C and C++. Some compilers support it without setting __STDC__ + * or __cplusplus so we need to carefully check for them too. + */ + +#if defined(__STDC__) || defined(_MSC_VER) || defined(__cplusplus) || \ + defined(__HP_aCC) || defined(__BORLANDC__) || defined(__LCC__) || \ + defined(__POCC__) || defined(__SALFORDC__) || defined(__HIGHC__) || \ + defined(__ILEC400__) + /* This compiler is believed to have an ISO compatible preprocessor */ +#define CURL_ISOCPP +#else + /* This compiler is believed NOT to have an ISO compatible preprocessor */ +#undef CURL_ISOCPP +#endif + +/* + * Macros for minimum-width signed and unsigned curl_off_t integer constants. + */ + +#if defined(__BORLANDC__) && (__BORLANDC__ == 0x0551) +# define __CURL_OFF_T_C_HLPR2(x) x +# define __CURL_OFF_T_C_HLPR1(x) __CURL_OFF_T_C_HLPR2(x) +# define CURL_OFF_T_C(Val) __CURL_OFF_T_C_HLPR1(Val) ## \ + __CURL_OFF_T_C_HLPR1(CURL_SUFFIX_CURL_OFF_T) +# define CURL_OFF_TU_C(Val) __CURL_OFF_T_C_HLPR1(Val) ## \ + __CURL_OFF_T_C_HLPR1(CURL_SUFFIX_CURL_OFF_TU) +#else +# ifdef CURL_ISOCPP +# define __CURL_OFF_T_C_HLPR2(Val,Suffix) Val ## Suffix +# else +# define __CURL_OFF_T_C_HLPR2(Val,Suffix) Val/**/Suffix +# endif +# define __CURL_OFF_T_C_HLPR1(Val,Suffix) __CURL_OFF_T_C_HLPR2(Val,Suffix) +# define CURL_OFF_T_C(Val) __CURL_OFF_T_C_HLPR1(Val,CURL_SUFFIX_CURL_OFF_T) +# define CURL_OFF_TU_C(Val) __CURL_OFF_T_C_HLPR1(Val,CURL_SUFFIX_CURL_OFF_TU) +#endif + +/* + * Get rid of macros private to this header file. + */ + +#undef CurlchkszEQ +#undef CurlchkszGE + +/* + * Get rid of macros not intended to exist beyond this point. + */ + +#undef CURL_PULL_WS2TCPIP_H +#undef CURL_PULL_SYS_TYPES_H +#undef CURL_PULL_SYS_SOCKET_H +#undef CURL_PULL_SYS_POLL_H +#undef CURL_PULL_STDINT_H +#undef CURL_PULL_INTTYPES_H + +#undef CURL_TYPEOF_CURL_SOCKLEN_T +#undef CURL_TYPEOF_CURL_OFF_T + +#ifdef CURL_NO_OLDIES +#undef CURL_FORMAT_OFF_T /* not required since 7.19.0 - obsoleted in 7.20.0 */ +#endif + +#endif /* __CURL_CURLRULES_H */ diff --git a/phonelibs/curl/include/curl/curlver.h b/phonelibs/curl/include/curl/curlver.h new file mode 100644 index 00000000000000..be442eff8f6441 --- /dev/null +++ b/phonelibs/curl/include/curl/curlver.h @@ -0,0 +1,77 @@ +#ifndef __CURL_CURLVER_H +#define __CURL_CURLVER_H +/*************************************************************************** + * _ _ ____ _ + * Project ___| | | | _ \| | + * / __| | | | |_) | | + * | (__| |_| | _ <| |___ + * \___|\___/|_| \_\_____| + * + * Copyright (C) 1998 - 2015, Daniel Stenberg, , et al. + * + * This software is licensed as described in the file COPYING, which + * you should have received as part of this distribution. The terms + * are also available at http://curl.haxx.se/docs/copyright.html. + * + * You may opt to use, copy, modify, merge, publish, distribute and/or sell + * copies of the Software, and permit persons to whom the Software is + * furnished to do so, under the terms of the COPYING file. + * + * This software is distributed on an "AS IS" basis, WITHOUT WARRANTY OF ANY + * KIND, either express or implied. + * + ***************************************************************************/ + +/* This header file contains nothing but libcurl version info, generated by + a script at release-time. This was made its own header file in 7.11.2 */ + +/* This is the global package copyright */ +#define LIBCURL_COPYRIGHT "1996 - 2015 Daniel Stenberg, ." + +/* This is the version number of the libcurl package from which this header + file origins: */ +#define LIBCURL_VERSION "7.43.0-DEV" + +/* The numeric version number is also available "in parts" by using these + defines: */ +#define LIBCURL_VERSION_MAJOR 7 +#define LIBCURL_VERSION_MINOR 43 +#define LIBCURL_VERSION_PATCH 0 + +/* This is the numeric version of the libcurl version number, meant for easier + parsing and comparions by programs. The LIBCURL_VERSION_NUM define will + always follow this syntax: + + 0xXXYYZZ + + Where XX, YY and ZZ are the main version, release and patch numbers in + hexadecimal (using 8 bits each). All three numbers are always represented + using two digits. 1.2 would appear as "0x010200" while version 9.11.7 + appears as "0x090b07". + + This 6-digit (24 bits) hexadecimal number does not show pre-release number, + and it is always a greater number in a more recent release. It makes + comparisons with greater than and less than work. + + Note: This define is the full hex number and _does not_ use the + CURL_VERSION_BITS() macro since curl's own configure script greps for it + and needs it to contain the full number. +*/ +#define LIBCURL_VERSION_NUM 0x072B00 + +/* + * This is the date and time when the full source package was created. The + * timestamp is not stored in git, as the timestamp is properly set in the + * tarballs by the maketgz script. + * + * The format of the date should follow this template: + * + * "Mon Feb 12 11:35:33 UTC 2007" + */ +#define LIBCURL_TIMESTAMP "DEV" + +#define CURL_VERSION_BITS(x,y,z) ((x)<<16|(y)<<8|z) +#define CURL_AT_LEAST_VERSION(x,y,z) \ + (LIBCURL_VERSION_NUM >= CURL_VERSION_BITS(x, y, z)) + +#endif /* __CURL_CURLVER_H */ diff --git a/phonelibs/curl/include/curl/easy.h b/phonelibs/curl/include/curl/easy.h new file mode 100644 index 00000000000000..c1e3e76096e392 --- /dev/null +++ b/phonelibs/curl/include/curl/easy.h @@ -0,0 +1,102 @@ +#ifndef __CURL_EASY_H +#define __CURL_EASY_H +/*************************************************************************** + * _ _ ____ _ + * Project ___| | | | _ \| | + * / __| | | | |_) | | + * | (__| |_| | _ <| |___ + * \___|\___/|_| \_\_____| + * + * Copyright (C) 1998 - 2008, Daniel Stenberg, , et al. + * + * This software is licensed as described in the file COPYING, which + * you should have received as part of this distribution. The terms + * are also available at http://curl.haxx.se/docs/copyright.html. + * + * You may opt to use, copy, modify, merge, publish, distribute and/or sell + * copies of the Software, and permit persons to whom the Software is + * furnished to do so, under the terms of the COPYING file. + * + * This software is distributed on an "AS IS" basis, WITHOUT WARRANTY OF ANY + * KIND, either express or implied. + * + ***************************************************************************/ +#ifdef __cplusplus +extern "C" { +#endif + +CURL_EXTERN CURL *curl_easy_init(void); +CURL_EXTERN CURLcode curl_easy_setopt(CURL *curl, CURLoption option, ...); +CURL_EXTERN CURLcode curl_easy_perform(CURL *curl); +CURL_EXTERN void curl_easy_cleanup(CURL *curl); + +/* + * NAME curl_easy_getinfo() + * + * DESCRIPTION + * + * Request internal information from the curl session with this function. The + * third argument MUST be a pointer to a long, a pointer to a char * or a + * pointer to a double (as the documentation describes elsewhere). The data + * pointed to will be filled in accordingly and can be relied upon only if the + * function returns CURLE_OK. This function is intended to get used *AFTER* a + * performed transfer, all results from this function are undefined until the + * transfer is completed. + */ +CURL_EXTERN CURLcode curl_easy_getinfo(CURL *curl, CURLINFO info, ...); + + +/* + * NAME curl_easy_duphandle() + * + * DESCRIPTION + * + * Creates a new curl session handle with the same options set for the handle + * passed in. Duplicating a handle could only be a matter of cloning data and + * options, internal state info and things like persistent connections cannot + * be transferred. It is useful in multithreaded applications when you can run + * curl_easy_duphandle() for each new thread to avoid a series of identical + * curl_easy_setopt() invokes in every thread. + */ +CURL_EXTERN CURL* curl_easy_duphandle(CURL *curl); + +/* + * NAME curl_easy_reset() + * + * DESCRIPTION + * + * Re-initializes a CURL handle to the default values. This puts back the + * handle to the same state as it was in when it was just created. + * + * It does keep: live connections, the Session ID cache, the DNS cache and the + * cookies. + */ +CURL_EXTERN void curl_easy_reset(CURL *curl); + +/* + * NAME curl_easy_recv() + * + * DESCRIPTION + * + * Receives data from the connected socket. Use after successful + * curl_easy_perform() with CURLOPT_CONNECT_ONLY option. + */ +CURL_EXTERN CURLcode curl_easy_recv(CURL *curl, void *buffer, size_t buflen, + size_t *n); + +/* + * NAME curl_easy_send() + * + * DESCRIPTION + * + * Sends data over the connected socket. Use after successful + * curl_easy_perform() with CURLOPT_CONNECT_ONLY option. + */ +CURL_EXTERN CURLcode curl_easy_send(CURL *curl, const void *buffer, + size_t buflen, size_t *n); + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/curl/include/curl/mprintf.h b/phonelibs/curl/include/curl/mprintf.h new file mode 100644 index 00000000000000..c6b0d7679a6cf9 --- /dev/null +++ b/phonelibs/curl/include/curl/mprintf.h @@ -0,0 +1,74 @@ +#ifndef __CURL_MPRINTF_H +#define __CURL_MPRINTF_H +/*************************************************************************** + * _ _ ____ _ + * Project ___| | | | _ \| | + * / __| | | | |_) | | + * | (__| |_| | _ <| |___ + * \___|\___/|_| \_\_____| + * + * Copyright (C) 1998 - 2015, Daniel Stenberg, , et al. + * + * This software is licensed as described in the file COPYING, which + * you should have received as part of this distribution. The terms + * are also available at http://curl.haxx.se/docs/copyright.html. + * + * You may opt to use, copy, modify, merge, publish, distribute and/or sell + * copies of the Software, and permit persons to whom the Software is + * furnished to do so, under the terms of the COPYING file. + * + * This software is distributed on an "AS IS" basis, WITHOUT WARRANTY OF ANY + * KIND, either express or implied. + * + ***************************************************************************/ + +#include +#include /* needed for FILE */ + +#include "curl.h" + +#ifdef __cplusplus +extern "C" { +#endif + +CURL_EXTERN int curl_mprintf(const char *format, ...); +CURL_EXTERN int curl_mfprintf(FILE *fd, const char *format, ...); +CURL_EXTERN int curl_msprintf(char *buffer, const char *format, ...); +CURL_EXTERN int curl_msnprintf(char *buffer, size_t maxlength, + const char *format, ...); +CURL_EXTERN int curl_mvprintf(const char *format, va_list args); +CURL_EXTERN int curl_mvfprintf(FILE *fd, const char *format, va_list args); +CURL_EXTERN int curl_mvsprintf(char *buffer, const char *format, va_list args); +CURL_EXTERN int curl_mvsnprintf(char *buffer, size_t maxlength, + const char *format, va_list args); +CURL_EXTERN char *curl_maprintf(const char *format, ...); +CURL_EXTERN char *curl_mvaprintf(const char *format, va_list args); + +#ifdef _MPRINTF_REPLACE +# undef printf +# undef fprintf +# undef sprintf +# undef vsprintf +# undef snprintf +# undef vprintf +# undef vfprintf +# undef vsnprintf +# undef aprintf +# undef vaprintf +# define printf curl_mprintf +# define fprintf curl_mfprintf +# define sprintf curl_msprintf +# define vsprintf curl_mvsprintf +# define snprintf curl_msnprintf +# define vprintf curl_mvprintf +# define vfprintf curl_mvfprintf +# define vsnprintf curl_mvsnprintf +# define aprintf curl_maprintf +# define vaprintf curl_mvaprintf +#endif + +#ifdef __cplusplus +} +#endif + +#endif /* __CURL_MPRINTF_H */ diff --git a/phonelibs/curl/include/curl/multi.h b/phonelibs/curl/include/curl/multi.h new file mode 100644 index 00000000000000..0d859f8fd98c50 --- /dev/null +++ b/phonelibs/curl/include/curl/multi.h @@ -0,0 +1,404 @@ +#ifndef __CURL_MULTI_H +#define __CURL_MULTI_H +/*************************************************************************** + * _ _ ____ _ + * Project ___| | | | _ \| | + * / __| | | | |_) | | + * | (__| |_| | _ <| |___ + * \___|\___/|_| \_\_____| + * + * Copyright (C) 1998 - 2015, Daniel Stenberg, , et al. + * + * This software is licensed as described in the file COPYING, which + * you should have received as part of this distribution. The terms + * are also available at http://curl.haxx.se/docs/copyright.html. + * + * You may opt to use, copy, modify, merge, publish, distribute and/or sell + * copies of the Software, and permit persons to whom the Software is + * furnished to do so, under the terms of the COPYING file. + * + * This software is distributed on an "AS IS" basis, WITHOUT WARRANTY OF ANY + * KIND, either express or implied. + * + ***************************************************************************/ +/* + This is an "external" header file. Don't give away any internals here! + + GOALS + + o Enable a "pull" interface. The application that uses libcurl decides where + and when to ask libcurl to get/send data. + + o Enable multiple simultaneous transfers in the same thread without making it + complicated for the application. + + o Enable the application to select() on its own file descriptors and curl's + file descriptors simultaneous easily. + +*/ + +/* + * This header file should not really need to include "curl.h" since curl.h + * itself includes this file and we expect user applications to do #include + * without the need for especially including multi.h. + * + * For some reason we added this include here at one point, and rather than to + * break existing (wrongly written) libcurl applications, we leave it as-is + * but with this warning attached. + */ +#include "curl.h" + +#ifdef __cplusplus +extern "C" { +#endif + +typedef void CURLM; + +typedef enum { + CURLM_CALL_MULTI_PERFORM = -1, /* please call curl_multi_perform() or + curl_multi_socket*() soon */ + CURLM_OK, + CURLM_BAD_HANDLE, /* the passed-in handle is not a valid CURLM handle */ + CURLM_BAD_EASY_HANDLE, /* an easy handle was not good/valid */ + CURLM_OUT_OF_MEMORY, /* if you ever get this, you're in deep sh*t */ + CURLM_INTERNAL_ERROR, /* this is a libcurl bug */ + CURLM_BAD_SOCKET, /* the passed in socket argument did not match */ + CURLM_UNKNOWN_OPTION, /* curl_multi_setopt() with unsupported option */ + CURLM_ADDED_ALREADY, /* an easy handle already added to a multi handle was + attempted to get added - again */ + CURLM_LAST +} CURLMcode; + +/* just to make code nicer when using curl_multi_socket() you can now check + for CURLM_CALL_MULTI_SOCKET too in the same style it works for + curl_multi_perform() and CURLM_CALL_MULTI_PERFORM */ +#define CURLM_CALL_MULTI_SOCKET CURLM_CALL_MULTI_PERFORM + +/* bitmask bits for CURLMOPT_PIPELINING */ +#define CURLPIPE_NOTHING 0L +#define CURLPIPE_HTTP1 1L +#define CURLPIPE_MULTIPLEX 2L + +typedef enum { + CURLMSG_NONE, /* first, not used */ + CURLMSG_DONE, /* This easy handle has completed. 'result' contains + the CURLcode of the transfer */ + CURLMSG_LAST /* last, not used */ +} CURLMSG; + +struct CURLMsg { + CURLMSG msg; /* what this message means */ + CURL *easy_handle; /* the handle it concerns */ + union { + void *whatever; /* message-specific data */ + CURLcode result; /* return code for transfer */ + } data; +}; +typedef struct CURLMsg CURLMsg; + +/* Based on poll(2) structure and values. + * We don't use pollfd and POLL* constants explicitly + * to cover platforms without poll(). */ +#define CURL_WAIT_POLLIN 0x0001 +#define CURL_WAIT_POLLPRI 0x0002 +#define CURL_WAIT_POLLOUT 0x0004 + +struct curl_waitfd { + curl_socket_t fd; + short events; + short revents; /* not supported yet */ +}; + +/* + * Name: curl_multi_init() + * + * Desc: inititalize multi-style curl usage + * + * Returns: a new CURLM handle to use in all 'curl_multi' functions. + */ +CURL_EXTERN CURLM *curl_multi_init(void); + +/* + * Name: curl_multi_add_handle() + * + * Desc: add a standard curl handle to the multi stack + * + * Returns: CURLMcode type, general multi error code. + */ +CURL_EXTERN CURLMcode curl_multi_add_handle(CURLM *multi_handle, + CURL *curl_handle); + + /* + * Name: curl_multi_remove_handle() + * + * Desc: removes a curl handle from the multi stack again + * + * Returns: CURLMcode type, general multi error code. + */ +CURL_EXTERN CURLMcode curl_multi_remove_handle(CURLM *multi_handle, + CURL *curl_handle); + + /* + * Name: curl_multi_fdset() + * + * Desc: Ask curl for its fd_set sets. The app can use these to select() or + * poll() on. We want curl_multi_perform() called as soon as one of + * them are ready. + * + * Returns: CURLMcode type, general multi error code. + */ +CURL_EXTERN CURLMcode curl_multi_fdset(CURLM *multi_handle, + fd_set *read_fd_set, + fd_set *write_fd_set, + fd_set *exc_fd_set, + int *max_fd); + +/* + * Name: curl_multi_wait() + * + * Desc: Poll on all fds within a CURLM set as well as any + * additional fds passed to the function. + * + * Returns: CURLMcode type, general multi error code. + */ +CURL_EXTERN CURLMcode curl_multi_wait(CURLM *multi_handle, + struct curl_waitfd extra_fds[], + unsigned int extra_nfds, + int timeout_ms, + int *ret); + + /* + * Name: curl_multi_perform() + * + * Desc: When the app thinks there's data available for curl it calls this + * function to read/write whatever there is right now. This returns + * as soon as the reads and writes are done. This function does not + * require that there actually is data available for reading or that + * data can be written, it can be called just in case. It returns + * the number of handles that still transfer data in the second + * argument's integer-pointer. + * + * Returns: CURLMcode type, general multi error code. *NOTE* that this only + * returns errors etc regarding the whole multi stack. There might + * still have occurred problems on invidual transfers even when this + * returns OK. + */ +CURL_EXTERN CURLMcode curl_multi_perform(CURLM *multi_handle, + int *running_handles); + + /* + * Name: curl_multi_cleanup() + * + * Desc: Cleans up and removes a whole multi stack. It does not free or + * touch any individual easy handles in any way. We need to define + * in what state those handles will be if this function is called + * in the middle of a transfer. + * + * Returns: CURLMcode type, general multi error code. + */ +CURL_EXTERN CURLMcode curl_multi_cleanup(CURLM *multi_handle); + +/* + * Name: curl_multi_info_read() + * + * Desc: Ask the multi handle if there's any messages/informationals from + * the individual transfers. Messages include informationals such as + * error code from the transfer or just the fact that a transfer is + * completed. More details on these should be written down as well. + * + * Repeated calls to this function will return a new struct each + * time, until a special "end of msgs" struct is returned as a signal + * that there is no more to get at this point. + * + * The data the returned pointer points to will not survive calling + * curl_multi_cleanup(). + * + * The 'CURLMsg' struct is meant to be very simple and only contain + * very basic informations. If more involved information is wanted, + * we will provide the particular "transfer handle" in that struct + * and that should/could/would be used in subsequent + * curl_easy_getinfo() calls (or similar). The point being that we + * must never expose complex structs to applications, as then we'll + * undoubtably get backwards compatibility problems in the future. + * + * Returns: A pointer to a filled-in struct, or NULL if it failed or ran out + * of structs. It also writes the number of messages left in the + * queue (after this read) in the integer the second argument points + * to. + */ +CURL_EXTERN CURLMsg *curl_multi_info_read(CURLM *multi_handle, + int *msgs_in_queue); + +/* + * Name: curl_multi_strerror() + * + * Desc: The curl_multi_strerror function may be used to turn a CURLMcode + * value into the equivalent human readable error string. This is + * useful for printing meaningful error messages. + * + * Returns: A pointer to a zero-terminated error message. + */ +CURL_EXTERN const char *curl_multi_strerror(CURLMcode); + +/* + * Name: curl_multi_socket() and + * curl_multi_socket_all() + * + * Desc: An alternative version of curl_multi_perform() that allows the + * application to pass in one of the file descriptors that have been + * detected to have "action" on them and let libcurl perform. + * See man page for details. + */ +#define CURL_POLL_NONE 0 +#define CURL_POLL_IN 1 +#define CURL_POLL_OUT 2 +#define CURL_POLL_INOUT 3 +#define CURL_POLL_REMOVE 4 + +#define CURL_SOCKET_TIMEOUT CURL_SOCKET_BAD + +#define CURL_CSELECT_IN 0x01 +#define CURL_CSELECT_OUT 0x02 +#define CURL_CSELECT_ERR 0x04 + +typedef int (*curl_socket_callback)(CURL *easy, /* easy handle */ + curl_socket_t s, /* socket */ + int what, /* see above */ + void *userp, /* private callback + pointer */ + void *socketp); /* private socket + pointer */ +/* + * Name: curl_multi_timer_callback + * + * Desc: Called by libcurl whenever the library detects a change in the + * maximum number of milliseconds the app is allowed to wait before + * curl_multi_socket() or curl_multi_perform() must be called + * (to allow libcurl's timed events to take place). + * + * Returns: The callback should return zero. + */ +typedef int (*curl_multi_timer_callback)(CURLM *multi, /* multi handle */ + long timeout_ms, /* see above */ + void *userp); /* private callback + pointer */ + +CURL_EXTERN CURLMcode curl_multi_socket(CURLM *multi_handle, curl_socket_t s, + int *running_handles); + +CURL_EXTERN CURLMcode curl_multi_socket_action(CURLM *multi_handle, + curl_socket_t s, + int ev_bitmask, + int *running_handles); + +CURL_EXTERN CURLMcode curl_multi_socket_all(CURLM *multi_handle, + int *running_handles); + +#ifndef CURL_ALLOW_OLD_MULTI_SOCKET +/* This macro below was added in 7.16.3 to push users who recompile to use + the new curl_multi_socket_action() instead of the old curl_multi_socket() +*/ +#define curl_multi_socket(x,y,z) curl_multi_socket_action(x,y,0,z) +#endif + +/* + * Name: curl_multi_timeout() + * + * Desc: Returns the maximum number of milliseconds the app is allowed to + * wait before curl_multi_socket() or curl_multi_perform() must be + * called (to allow libcurl's timed events to take place). + * + * Returns: CURLM error code. + */ +CURL_EXTERN CURLMcode curl_multi_timeout(CURLM *multi_handle, + long *milliseconds); + +#undef CINIT /* re-using the same name as in curl.h */ + +#ifdef CURL_ISOCPP +#define CINIT(name,type,num) CURLMOPT_ ## name = CURLOPTTYPE_ ## type + num +#else +/* The macro "##" is ISO C, we assume pre-ISO C doesn't support it. */ +#define LONG CURLOPTTYPE_LONG +#define OBJECTPOINT CURLOPTTYPE_OBJECTPOINT +#define FUNCTIONPOINT CURLOPTTYPE_FUNCTIONPOINT +#define OFF_T CURLOPTTYPE_OFF_T +#define CINIT(name,type,number) CURLMOPT_/**/name = type + number +#endif + +typedef enum { + /* This is the socket callback function pointer */ + CINIT(SOCKETFUNCTION, FUNCTIONPOINT, 1), + + /* This is the argument passed to the socket callback */ + CINIT(SOCKETDATA, OBJECTPOINT, 2), + + /* set to 1 to enable pipelining for this multi handle */ + CINIT(PIPELINING, LONG, 3), + + /* This is the timer callback function pointer */ + CINIT(TIMERFUNCTION, FUNCTIONPOINT, 4), + + /* This is the argument passed to the timer callback */ + CINIT(TIMERDATA, OBJECTPOINT, 5), + + /* maximum number of entries in the connection cache */ + CINIT(MAXCONNECTS, LONG, 6), + + /* maximum number of (pipelining) connections to one host */ + CINIT(MAX_HOST_CONNECTIONS, LONG, 7), + + /* maximum number of requests in a pipeline */ + CINIT(MAX_PIPELINE_LENGTH, LONG, 8), + + /* a connection with a content-length longer than this + will not be considered for pipelining */ + CINIT(CONTENT_LENGTH_PENALTY_SIZE, OFF_T, 9), + + /* a connection with a chunk length longer than this + will not be considered for pipelining */ + CINIT(CHUNK_LENGTH_PENALTY_SIZE, OFF_T, 10), + + /* a list of site names(+port) that are blacklisted from + pipelining */ + CINIT(PIPELINING_SITE_BL, OBJECTPOINT, 11), + + /* a list of server types that are blacklisted from + pipelining */ + CINIT(PIPELINING_SERVER_BL, OBJECTPOINT, 12), + + /* maximum number of open connections in total */ + CINIT(MAX_TOTAL_CONNECTIONS, LONG, 13), + + CURLMOPT_LASTENTRY /* the last unused */ +} CURLMoption; + + +/* + * Name: curl_multi_setopt() + * + * Desc: Sets options for the multi handle. + * + * Returns: CURLM error code. + */ +CURL_EXTERN CURLMcode curl_multi_setopt(CURLM *multi_handle, + CURLMoption option, ...); + + +/* + * Name: curl_multi_assign() + * + * Desc: This function sets an association in the multi handle between the + * given socket and a private pointer of the application. This is + * (only) useful for curl_multi_socket uses. + * + * Returns: CURLM error code. + */ +CURL_EXTERN CURLMcode curl_multi_assign(CURLM *multi_handle, + curl_socket_t sockfd, void *sockp); + +#ifdef __cplusplus +} /* end of extern "C" */ +#endif + +#endif diff --git a/phonelibs/curl/include/curl/stdcheaders.h b/phonelibs/curl/include/curl/stdcheaders.h new file mode 100644 index 00000000000000..ad82ef6335d616 --- /dev/null +++ b/phonelibs/curl/include/curl/stdcheaders.h @@ -0,0 +1,33 @@ +#ifndef __STDC_HEADERS_H +#define __STDC_HEADERS_H +/*************************************************************************** + * _ _ ____ _ + * Project ___| | | | _ \| | + * / __| | | | |_) | | + * | (__| |_| | _ <| |___ + * \___|\___/|_| \_\_____| + * + * Copyright (C) 1998 - 2010, Daniel Stenberg, , et al. + * + * This software is licensed as described in the file COPYING, which + * you should have received as part of this distribution. The terms + * are also available at http://curl.haxx.se/docs/copyright.html. + * + * You may opt to use, copy, modify, merge, publish, distribute and/or sell + * copies of the Software, and permit persons to whom the Software is + * furnished to do so, under the terms of the COPYING file. + * + * This software is distributed on an "AS IS" basis, WITHOUT WARRANTY OF ANY + * KIND, either express or implied. + * + ***************************************************************************/ + +#include + +size_t fread (void *, size_t, size_t, FILE *); +size_t fwrite (const void *, size_t, size_t, FILE *); + +int strcasecmp(const char *, const char *); +int strncasecmp(const char *, const char *, size_t); + +#endif /* __STDC_HEADERS_H */ diff --git a/phonelibs/curl/include/curl/typecheck-gcc.h b/phonelibs/curl/include/curl/typecheck-gcc.h new file mode 100644 index 00000000000000..13fb0fa9ee3d21 --- /dev/null +++ b/phonelibs/curl/include/curl/typecheck-gcc.h @@ -0,0 +1,612 @@ +#ifndef __CURL_TYPECHECK_GCC_H +#define __CURL_TYPECHECK_GCC_H +/*************************************************************************** + * _ _ ____ _ + * Project ___| | | | _ \| | + * / __| | | | |_) | | + * | (__| |_| | _ <| |___ + * \___|\___/|_| \_\_____| + * + * Copyright (C) 1998 - 2014, Daniel Stenberg, , et al. + * + * This software is licensed as described in the file COPYING, which + * you should have received as part of this distribution. The terms + * are also available at http://curl.haxx.se/docs/copyright.html. + * + * You may opt to use, copy, modify, merge, publish, distribute and/or sell + * copies of the Software, and permit persons to whom the Software is + * furnished to do so, under the terms of the COPYING file. + * + * This software is distributed on an "AS IS" basis, WITHOUT WARRANTY OF ANY + * KIND, either express or implied. + * + ***************************************************************************/ + +/* wraps curl_easy_setopt() with typechecking */ + +/* To add a new kind of warning, add an + * if(_curl_is_sometype_option(_curl_opt)) + * if(!_curl_is_sometype(value)) + * _curl_easy_setopt_err_sometype(); + * block and define _curl_is_sometype_option, _curl_is_sometype and + * _curl_easy_setopt_err_sometype below + * + * NOTE: We use two nested 'if' statements here instead of the && operator, in + * order to work around gcc bug #32061. It affects only gcc 4.3.x/4.4.x + * when compiling with -Wlogical-op. + * + * To add an option that uses the same type as an existing option, you'll just + * need to extend the appropriate _curl_*_option macro + */ +#define curl_easy_setopt(handle, option, value) \ +__extension__ ({ \ + __typeof__ (option) _curl_opt = option; \ + if(__builtin_constant_p(_curl_opt)) { \ + if(_curl_is_long_option(_curl_opt)) \ + if(!_curl_is_long(value)) \ + _curl_easy_setopt_err_long(); \ + if(_curl_is_off_t_option(_curl_opt)) \ + if(!_curl_is_off_t(value)) \ + _curl_easy_setopt_err_curl_off_t(); \ + if(_curl_is_string_option(_curl_opt)) \ + if(!_curl_is_string(value)) \ + _curl_easy_setopt_err_string(); \ + if(_curl_is_write_cb_option(_curl_opt)) \ + if(!_curl_is_write_cb(value)) \ + _curl_easy_setopt_err_write_callback(); \ + if((_curl_opt) == CURLOPT_READFUNCTION) \ + if(!_curl_is_read_cb(value)) \ + _curl_easy_setopt_err_read_cb(); \ + if((_curl_opt) == CURLOPT_IOCTLFUNCTION) \ + if(!_curl_is_ioctl_cb(value)) \ + _curl_easy_setopt_err_ioctl_cb(); \ + if((_curl_opt) == CURLOPT_SOCKOPTFUNCTION) \ + if(!_curl_is_sockopt_cb(value)) \ + _curl_easy_setopt_err_sockopt_cb(); \ + if((_curl_opt) == CURLOPT_OPENSOCKETFUNCTION) \ + if(!_curl_is_opensocket_cb(value)) \ + _curl_easy_setopt_err_opensocket_cb(); \ + if((_curl_opt) == CURLOPT_PROGRESSFUNCTION) \ + if(!_curl_is_progress_cb(value)) \ + _curl_easy_setopt_err_progress_cb(); \ + if((_curl_opt) == CURLOPT_DEBUGFUNCTION) \ + if(!_curl_is_debug_cb(value)) \ + _curl_easy_setopt_err_debug_cb(); \ + if((_curl_opt) == CURLOPT_SSL_CTX_FUNCTION) \ + if(!_curl_is_ssl_ctx_cb(value)) \ + _curl_easy_setopt_err_ssl_ctx_cb(); \ + if(_curl_is_conv_cb_option(_curl_opt)) \ + if(!_curl_is_conv_cb(value)) \ + _curl_easy_setopt_err_conv_cb(); \ + if((_curl_opt) == CURLOPT_SEEKFUNCTION) \ + if(!_curl_is_seek_cb(value)) \ + _curl_easy_setopt_err_seek_cb(); \ + if(_curl_is_cb_data_option(_curl_opt)) \ + if(!_curl_is_cb_data(value)) \ + _curl_easy_setopt_err_cb_data(); \ + if((_curl_opt) == CURLOPT_ERRORBUFFER) \ + if(!_curl_is_error_buffer(value)) \ + _curl_easy_setopt_err_error_buffer(); \ + if((_curl_opt) == CURLOPT_STDERR) \ + if(!_curl_is_FILE(value)) \ + _curl_easy_setopt_err_FILE(); \ + if(_curl_is_postfields_option(_curl_opt)) \ + if(!_curl_is_postfields(value)) \ + _curl_easy_setopt_err_postfields(); \ + if((_curl_opt) == CURLOPT_HTTPPOST) \ + if(!_curl_is_arr((value), struct curl_httppost)) \ + _curl_easy_setopt_err_curl_httpost(); \ + if(_curl_is_slist_option(_curl_opt)) \ + if(!_curl_is_arr((value), struct curl_slist)) \ + _curl_easy_setopt_err_curl_slist(); \ + if((_curl_opt) == CURLOPT_SHARE) \ + if(!_curl_is_ptr((value), CURLSH)) \ + _curl_easy_setopt_err_CURLSH(); \ + } \ + curl_easy_setopt(handle, _curl_opt, value); \ +}) + +/* wraps curl_easy_getinfo() with typechecking */ +/* FIXME: don't allow const pointers */ +#define curl_easy_getinfo(handle, info, arg) \ +__extension__ ({ \ + __typeof__ (info) _curl_info = info; \ + if(__builtin_constant_p(_curl_info)) { \ + if(_curl_is_string_info(_curl_info)) \ + if(!_curl_is_arr((arg), char *)) \ + _curl_easy_getinfo_err_string(); \ + if(_curl_is_long_info(_curl_info)) \ + if(!_curl_is_arr((arg), long)) \ + _curl_easy_getinfo_err_long(); \ + if(_curl_is_double_info(_curl_info)) \ + if(!_curl_is_arr((arg), double)) \ + _curl_easy_getinfo_err_double(); \ + if(_curl_is_slist_info(_curl_info)) \ + if(!_curl_is_arr((arg), struct curl_slist *)) \ + _curl_easy_getinfo_err_curl_slist(); \ + } \ + curl_easy_getinfo(handle, _curl_info, arg); \ +}) + +/* TODO: typechecking for curl_share_setopt() and curl_multi_setopt(), + * for now just make sure that the functions are called with three + * arguments + */ +#define curl_share_setopt(share,opt,param) curl_share_setopt(share,opt,param) +#define curl_multi_setopt(handle,opt,param) curl_multi_setopt(handle,opt,param) + + +/* the actual warnings, triggered by calling the _curl_easy_setopt_err* + * functions */ + +/* To define a new warning, use _CURL_WARNING(identifier, "message") */ +#define _CURL_WARNING(id, message) \ + static void __attribute__((__warning__(message))) \ + __attribute__((__unused__)) __attribute__((__noinline__)) \ + id(void) { __asm__(""); } + +_CURL_WARNING(_curl_easy_setopt_err_long, + "curl_easy_setopt expects a long argument for this option") +_CURL_WARNING(_curl_easy_setopt_err_curl_off_t, + "curl_easy_setopt expects a curl_off_t argument for this option") +_CURL_WARNING(_curl_easy_setopt_err_string, + "curl_easy_setopt expects a " + "string (char* or char[]) argument for this option" + ) +_CURL_WARNING(_curl_easy_setopt_err_write_callback, + "curl_easy_setopt expects a curl_write_callback argument for this option") +_CURL_WARNING(_curl_easy_setopt_err_read_cb, + "curl_easy_setopt expects a curl_read_callback argument for this option") +_CURL_WARNING(_curl_easy_setopt_err_ioctl_cb, + "curl_easy_setopt expects a curl_ioctl_callback argument for this option") +_CURL_WARNING(_curl_easy_setopt_err_sockopt_cb, + "curl_easy_setopt expects a curl_sockopt_callback argument for this option") +_CURL_WARNING(_curl_easy_setopt_err_opensocket_cb, + "curl_easy_setopt expects a " + "curl_opensocket_callback argument for this option" + ) +_CURL_WARNING(_curl_easy_setopt_err_progress_cb, + "curl_easy_setopt expects a curl_progress_callback argument for this option") +_CURL_WARNING(_curl_easy_setopt_err_debug_cb, + "curl_easy_setopt expects a curl_debug_callback argument for this option") +_CURL_WARNING(_curl_easy_setopt_err_ssl_ctx_cb, + "curl_easy_setopt expects a curl_ssl_ctx_callback argument for this option") +_CURL_WARNING(_curl_easy_setopt_err_conv_cb, + "curl_easy_setopt expects a curl_conv_callback argument for this option") +_CURL_WARNING(_curl_easy_setopt_err_seek_cb, + "curl_easy_setopt expects a curl_seek_callback argument for this option") +_CURL_WARNING(_curl_easy_setopt_err_cb_data, + "curl_easy_setopt expects a " + "private data pointer as argument for this option") +_CURL_WARNING(_curl_easy_setopt_err_error_buffer, + "curl_easy_setopt expects a " + "char buffer of CURL_ERROR_SIZE as argument for this option") +_CURL_WARNING(_curl_easy_setopt_err_FILE, + "curl_easy_setopt expects a FILE* argument for this option") +_CURL_WARNING(_curl_easy_setopt_err_postfields, + "curl_easy_setopt expects a void* or char* argument for this option") +_CURL_WARNING(_curl_easy_setopt_err_curl_httpost, + "curl_easy_setopt expects a struct curl_httppost* argument for this option") +_CURL_WARNING(_curl_easy_setopt_err_curl_slist, + "curl_easy_setopt expects a struct curl_slist* argument for this option") +_CURL_WARNING(_curl_easy_setopt_err_CURLSH, + "curl_easy_setopt expects a CURLSH* argument for this option") + +_CURL_WARNING(_curl_easy_getinfo_err_string, + "curl_easy_getinfo expects a pointer to char * for this info") +_CURL_WARNING(_curl_easy_getinfo_err_long, + "curl_easy_getinfo expects a pointer to long for this info") +_CURL_WARNING(_curl_easy_getinfo_err_double, + "curl_easy_getinfo expects a pointer to double for this info") +_CURL_WARNING(_curl_easy_getinfo_err_curl_slist, + "curl_easy_getinfo expects a pointer to struct curl_slist * for this info") + +/* groups of curl_easy_setops options that take the same type of argument */ + +/* To add a new option to one of the groups, just add + * (option) == CURLOPT_SOMETHING + * to the or-expression. If the option takes a long or curl_off_t, you don't + * have to do anything + */ + +/* evaluates to true if option takes a long argument */ +#define _curl_is_long_option(option) \ + (0 < (option) && (option) < CURLOPTTYPE_OBJECTPOINT) + +#define _curl_is_off_t_option(option) \ + ((option) > CURLOPTTYPE_OFF_T) + +/* evaluates to true if option takes a char* argument */ +#define _curl_is_string_option(option) \ + ((option) == CURLOPT_URL || \ + (option) == CURLOPT_PROXY || \ + (option) == CURLOPT_INTERFACE || \ + (option) == CURLOPT_NETRC_FILE || \ + (option) == CURLOPT_USERPWD || \ + (option) == CURLOPT_USERNAME || \ + (option) == CURLOPT_PASSWORD || \ + (option) == CURLOPT_PROXYUSERPWD || \ + (option) == CURLOPT_PROXYUSERNAME || \ + (option) == CURLOPT_PROXYPASSWORD || \ + (option) == CURLOPT_NOPROXY || \ + (option) == CURLOPT_ACCEPT_ENCODING || \ + (option) == CURLOPT_REFERER || \ + (option) == CURLOPT_USERAGENT || \ + (option) == CURLOPT_COOKIE || \ + (option) == CURLOPT_COOKIEFILE || \ + (option) == CURLOPT_COOKIEJAR || \ + (option) == CURLOPT_COOKIELIST || \ + (option) == CURLOPT_FTPPORT || \ + (option) == CURLOPT_FTP_ALTERNATIVE_TO_USER || \ + (option) == CURLOPT_FTP_ACCOUNT || \ + (option) == CURLOPT_RANGE || \ + (option) == CURLOPT_CUSTOMREQUEST || \ + (option) == CURLOPT_SSLCERT || \ + (option) == CURLOPT_SSLCERTTYPE || \ + (option) == CURLOPT_SSLKEY || \ + (option) == CURLOPT_SSLKEYTYPE || \ + (option) == CURLOPT_KEYPASSWD || \ + (option) == CURLOPT_SSLENGINE || \ + (option) == CURLOPT_CAINFO || \ + (option) == CURLOPT_CAPATH || \ + (option) == CURLOPT_RANDOM_FILE || \ + (option) == CURLOPT_EGDSOCKET || \ + (option) == CURLOPT_SSL_CIPHER_LIST || \ + (option) == CURLOPT_KRBLEVEL || \ + (option) == CURLOPT_SSH_HOST_PUBLIC_KEY_MD5 || \ + (option) == CURLOPT_SSH_PUBLIC_KEYFILE || \ + (option) == CURLOPT_SSH_PRIVATE_KEYFILE || \ + (option) == CURLOPT_CRLFILE || \ + (option) == CURLOPT_ISSUERCERT || \ + (option) == CURLOPT_SOCKS5_GSSAPI_SERVICE || \ + (option) == CURLOPT_SSH_KNOWNHOSTS || \ + (option) == CURLOPT_MAIL_FROM || \ + (option) == CURLOPT_RTSP_SESSION_ID || \ + (option) == CURLOPT_RTSP_STREAM_URI || \ + (option) == CURLOPT_RTSP_TRANSPORT || \ + (option) == CURLOPT_XOAUTH2_BEARER || \ + (option) == CURLOPT_DNS_SERVERS || \ + (option) == CURLOPT_DNS_INTERFACE || \ + (option) == CURLOPT_DNS_LOCAL_IP4 || \ + (option) == CURLOPT_DNS_LOCAL_IP6 || \ + (option) == CURLOPT_LOGIN_OPTIONS || \ + (option) == CURLOPT_PROXY_SERVICE_NAME || \ + (option) == CURLOPT_SERVICE_NAME || \ + 0) + +/* evaluates to true if option takes a curl_write_callback argument */ +#define _curl_is_write_cb_option(option) \ + ((option) == CURLOPT_HEADERFUNCTION || \ + (option) == CURLOPT_WRITEFUNCTION) + +/* evaluates to true if option takes a curl_conv_callback argument */ +#define _curl_is_conv_cb_option(option) \ + ((option) == CURLOPT_CONV_TO_NETWORK_FUNCTION || \ + (option) == CURLOPT_CONV_FROM_NETWORK_FUNCTION || \ + (option) == CURLOPT_CONV_FROM_UTF8_FUNCTION) + +/* evaluates to true if option takes a data argument to pass to a callback */ +#define _curl_is_cb_data_option(option) \ + ((option) == CURLOPT_WRITEDATA || \ + (option) == CURLOPT_READDATA || \ + (option) == CURLOPT_IOCTLDATA || \ + (option) == CURLOPT_SOCKOPTDATA || \ + (option) == CURLOPT_OPENSOCKETDATA || \ + (option) == CURLOPT_PROGRESSDATA || \ + (option) == CURLOPT_HEADERDATA || \ + (option) == CURLOPT_DEBUGDATA || \ + (option) == CURLOPT_SSL_CTX_DATA || \ + (option) == CURLOPT_SEEKDATA || \ + (option) == CURLOPT_PRIVATE || \ + (option) == CURLOPT_SSH_KEYDATA || \ + (option) == CURLOPT_INTERLEAVEDATA || \ + (option) == CURLOPT_CHUNK_DATA || \ + (option) == CURLOPT_FNMATCH_DATA || \ + 0) + +/* evaluates to true if option takes a POST data argument (void* or char*) */ +#define _curl_is_postfields_option(option) \ + ((option) == CURLOPT_POSTFIELDS || \ + (option) == CURLOPT_COPYPOSTFIELDS || \ + 0) + +/* evaluates to true if option takes a struct curl_slist * argument */ +#define _curl_is_slist_option(option) \ + ((option) == CURLOPT_HTTPHEADER || \ + (option) == CURLOPT_HTTP200ALIASES || \ + (option) == CURLOPT_QUOTE || \ + (option) == CURLOPT_POSTQUOTE || \ + (option) == CURLOPT_PREQUOTE || \ + (option) == CURLOPT_TELNETOPTIONS || \ + (option) == CURLOPT_MAIL_RCPT || \ + 0) + +/* groups of curl_easy_getinfo infos that take the same type of argument */ + +/* evaluates to true if info expects a pointer to char * argument */ +#define _curl_is_string_info(info) \ + (CURLINFO_STRING < (info) && (info) < CURLINFO_LONG) + +/* evaluates to true if info expects a pointer to long argument */ +#define _curl_is_long_info(info) \ + (CURLINFO_LONG < (info) && (info) < CURLINFO_DOUBLE) + +/* evaluates to true if info expects a pointer to double argument */ +#define _curl_is_double_info(info) \ + (CURLINFO_DOUBLE < (info) && (info) < CURLINFO_SLIST) + +/* true if info expects a pointer to struct curl_slist * argument */ +#define _curl_is_slist_info(info) \ + (CURLINFO_SLIST < (info)) + + +/* typecheck helpers -- check whether given expression has requested type*/ + +/* For pointers, you can use the _curl_is_ptr/_curl_is_arr macros, + * otherwise define a new macro. Search for __builtin_types_compatible_p + * in the GCC manual. + * NOTE: these macros MUST NOT EVALUATE their arguments! The argument is + * the actual expression passed to the curl_easy_setopt macro. This + * means that you can only apply the sizeof and __typeof__ operators, no + * == or whatsoever. + */ + +/* XXX: should evaluate to true iff expr is a pointer */ +#define _curl_is_any_ptr(expr) \ + (sizeof(expr) == sizeof(void*)) + +/* evaluates to true if expr is NULL */ +/* XXX: must not evaluate expr, so this check is not accurate */ +#define _curl_is_NULL(expr) \ + (__builtin_types_compatible_p(__typeof__(expr), __typeof__(NULL))) + +/* evaluates to true if expr is type*, const type* or NULL */ +#define _curl_is_ptr(expr, type) \ + (_curl_is_NULL(expr) || \ + __builtin_types_compatible_p(__typeof__(expr), type *) || \ + __builtin_types_compatible_p(__typeof__(expr), const type *)) + +/* evaluates to true if expr is one of type[], type*, NULL or const type* */ +#define _curl_is_arr(expr, type) \ + (_curl_is_ptr((expr), type) || \ + __builtin_types_compatible_p(__typeof__(expr), type [])) + +/* evaluates to true if expr is a string */ +#define _curl_is_string(expr) \ + (_curl_is_arr((expr), char) || \ + _curl_is_arr((expr), signed char) || \ + _curl_is_arr((expr), unsigned char)) + +/* evaluates to true if expr is a long (no matter the signedness) + * XXX: for now, int is also accepted (and therefore short and char, which + * are promoted to int when passed to a variadic function) */ +#define _curl_is_long(expr) \ + (__builtin_types_compatible_p(__typeof__(expr), long) || \ + __builtin_types_compatible_p(__typeof__(expr), signed long) || \ + __builtin_types_compatible_p(__typeof__(expr), unsigned long) || \ + __builtin_types_compatible_p(__typeof__(expr), int) || \ + __builtin_types_compatible_p(__typeof__(expr), signed int) || \ + __builtin_types_compatible_p(__typeof__(expr), unsigned int) || \ + __builtin_types_compatible_p(__typeof__(expr), short) || \ + __builtin_types_compatible_p(__typeof__(expr), signed short) || \ + __builtin_types_compatible_p(__typeof__(expr), unsigned short) || \ + __builtin_types_compatible_p(__typeof__(expr), char) || \ + __builtin_types_compatible_p(__typeof__(expr), signed char) || \ + __builtin_types_compatible_p(__typeof__(expr), unsigned char)) + +/* evaluates to true if expr is of type curl_off_t */ +#define _curl_is_off_t(expr) \ + (__builtin_types_compatible_p(__typeof__(expr), curl_off_t)) + +/* evaluates to true if expr is abuffer suitable for CURLOPT_ERRORBUFFER */ +/* XXX: also check size of an char[] array? */ +#define _curl_is_error_buffer(expr) \ + (_curl_is_NULL(expr) || \ + __builtin_types_compatible_p(__typeof__(expr), char *) || \ + __builtin_types_compatible_p(__typeof__(expr), char[])) + +/* evaluates to true if expr is of type (const) void* or (const) FILE* */ +#if 0 +#define _curl_is_cb_data(expr) \ + (_curl_is_ptr((expr), void) || \ + _curl_is_ptr((expr), FILE)) +#else /* be less strict */ +#define _curl_is_cb_data(expr) \ + _curl_is_any_ptr(expr) +#endif + +/* evaluates to true if expr is of type FILE* */ +#define _curl_is_FILE(expr) \ + (__builtin_types_compatible_p(__typeof__(expr), FILE *)) + +/* evaluates to true if expr can be passed as POST data (void* or char*) */ +#define _curl_is_postfields(expr) \ + (_curl_is_ptr((expr), void) || \ + _curl_is_arr((expr), char)) + +/* FIXME: the whole callback checking is messy... + * The idea is to tolerate char vs. void and const vs. not const + * pointers in arguments at least + */ +/* helper: __builtin_types_compatible_p distinguishes between functions and + * function pointers, hide it */ +#define _curl_callback_compatible(func, type) \ + (__builtin_types_compatible_p(__typeof__(func), type) || \ + __builtin_types_compatible_p(__typeof__(func), type*)) + +/* evaluates to true if expr is of type curl_read_callback or "similar" */ +#define _curl_is_read_cb(expr) \ + (_curl_is_NULL(expr) || \ + __builtin_types_compatible_p(__typeof__(expr), __typeof__(fread)) || \ + __builtin_types_compatible_p(__typeof__(expr), curl_read_callback) || \ + _curl_callback_compatible((expr), _curl_read_callback1) || \ + _curl_callback_compatible((expr), _curl_read_callback2) || \ + _curl_callback_compatible((expr), _curl_read_callback3) || \ + _curl_callback_compatible((expr), _curl_read_callback4) || \ + _curl_callback_compatible((expr), _curl_read_callback5) || \ + _curl_callback_compatible((expr), _curl_read_callback6)) +typedef size_t (_curl_read_callback1)(char *, size_t, size_t, void*); +typedef size_t (_curl_read_callback2)(char *, size_t, size_t, const void*); +typedef size_t (_curl_read_callback3)(char *, size_t, size_t, FILE*); +typedef size_t (_curl_read_callback4)(void *, size_t, size_t, void*); +typedef size_t (_curl_read_callback5)(void *, size_t, size_t, const void*); +typedef size_t (_curl_read_callback6)(void *, size_t, size_t, FILE*); + +/* evaluates to true if expr is of type curl_write_callback or "similar" */ +#define _curl_is_write_cb(expr) \ + (_curl_is_read_cb(expr) || \ + __builtin_types_compatible_p(__typeof__(expr), __typeof__(fwrite)) || \ + __builtin_types_compatible_p(__typeof__(expr), curl_write_callback) || \ + _curl_callback_compatible((expr), _curl_write_callback1) || \ + _curl_callback_compatible((expr), _curl_write_callback2) || \ + _curl_callback_compatible((expr), _curl_write_callback3) || \ + _curl_callback_compatible((expr), _curl_write_callback4) || \ + _curl_callback_compatible((expr), _curl_write_callback5) || \ + _curl_callback_compatible((expr), _curl_write_callback6)) +typedef size_t (_curl_write_callback1)(const char *, size_t, size_t, void*); +typedef size_t (_curl_write_callback2)(const char *, size_t, size_t, + const void*); +typedef size_t (_curl_write_callback3)(const char *, size_t, size_t, FILE*); +typedef size_t (_curl_write_callback4)(const void *, size_t, size_t, void*); +typedef size_t (_curl_write_callback5)(const void *, size_t, size_t, + const void*); +typedef size_t (_curl_write_callback6)(const void *, size_t, size_t, FILE*); + +/* evaluates to true if expr is of type curl_ioctl_callback or "similar" */ +#define _curl_is_ioctl_cb(expr) \ + (_curl_is_NULL(expr) || \ + __builtin_types_compatible_p(__typeof__(expr), curl_ioctl_callback) || \ + _curl_callback_compatible((expr), _curl_ioctl_callback1) || \ + _curl_callback_compatible((expr), _curl_ioctl_callback2) || \ + _curl_callback_compatible((expr), _curl_ioctl_callback3) || \ + _curl_callback_compatible((expr), _curl_ioctl_callback4)) +typedef curlioerr (_curl_ioctl_callback1)(CURL *, int, void*); +typedef curlioerr (_curl_ioctl_callback2)(CURL *, int, const void*); +typedef curlioerr (_curl_ioctl_callback3)(CURL *, curliocmd, void*); +typedef curlioerr (_curl_ioctl_callback4)(CURL *, curliocmd, const void*); + +/* evaluates to true if expr is of type curl_sockopt_callback or "similar" */ +#define _curl_is_sockopt_cb(expr) \ + (_curl_is_NULL(expr) || \ + __builtin_types_compatible_p(__typeof__(expr), curl_sockopt_callback) || \ + _curl_callback_compatible((expr), _curl_sockopt_callback1) || \ + _curl_callback_compatible((expr), _curl_sockopt_callback2)) +typedef int (_curl_sockopt_callback1)(void *, curl_socket_t, curlsocktype); +typedef int (_curl_sockopt_callback2)(const void *, curl_socket_t, + curlsocktype); + +/* evaluates to true if expr is of type curl_opensocket_callback or + "similar" */ +#define _curl_is_opensocket_cb(expr) \ + (_curl_is_NULL(expr) || \ + __builtin_types_compatible_p(__typeof__(expr), curl_opensocket_callback) ||\ + _curl_callback_compatible((expr), _curl_opensocket_callback1) || \ + _curl_callback_compatible((expr), _curl_opensocket_callback2) || \ + _curl_callback_compatible((expr), _curl_opensocket_callback3) || \ + _curl_callback_compatible((expr), _curl_opensocket_callback4)) +typedef curl_socket_t (_curl_opensocket_callback1) + (void *, curlsocktype, struct curl_sockaddr *); +typedef curl_socket_t (_curl_opensocket_callback2) + (void *, curlsocktype, const struct curl_sockaddr *); +typedef curl_socket_t (_curl_opensocket_callback3) + (const void *, curlsocktype, struct curl_sockaddr *); +typedef curl_socket_t (_curl_opensocket_callback4) + (const void *, curlsocktype, const struct curl_sockaddr *); + +/* evaluates to true if expr is of type curl_progress_callback or "similar" */ +#define _curl_is_progress_cb(expr) \ + (_curl_is_NULL(expr) || \ + __builtin_types_compatible_p(__typeof__(expr), curl_progress_callback) || \ + _curl_callback_compatible((expr), _curl_progress_callback1) || \ + _curl_callback_compatible((expr), _curl_progress_callback2)) +typedef int (_curl_progress_callback1)(void *, + double, double, double, double); +typedef int (_curl_progress_callback2)(const void *, + double, double, double, double); + +/* evaluates to true if expr is of type curl_debug_callback or "similar" */ +#define _curl_is_debug_cb(expr) \ + (_curl_is_NULL(expr) || \ + __builtin_types_compatible_p(__typeof__(expr), curl_debug_callback) || \ + _curl_callback_compatible((expr), _curl_debug_callback1) || \ + _curl_callback_compatible((expr), _curl_debug_callback2) || \ + _curl_callback_compatible((expr), _curl_debug_callback3) || \ + _curl_callback_compatible((expr), _curl_debug_callback4) || \ + _curl_callback_compatible((expr), _curl_debug_callback5) || \ + _curl_callback_compatible((expr), _curl_debug_callback6) || \ + _curl_callback_compatible((expr), _curl_debug_callback7) || \ + _curl_callback_compatible((expr), _curl_debug_callback8)) +typedef int (_curl_debug_callback1) (CURL *, + curl_infotype, char *, size_t, void *); +typedef int (_curl_debug_callback2) (CURL *, + curl_infotype, char *, size_t, const void *); +typedef int (_curl_debug_callback3) (CURL *, + curl_infotype, const char *, size_t, void *); +typedef int (_curl_debug_callback4) (CURL *, + curl_infotype, const char *, size_t, const void *); +typedef int (_curl_debug_callback5) (CURL *, + curl_infotype, unsigned char *, size_t, void *); +typedef int (_curl_debug_callback6) (CURL *, + curl_infotype, unsigned char *, size_t, const void *); +typedef int (_curl_debug_callback7) (CURL *, + curl_infotype, const unsigned char *, size_t, void *); +typedef int (_curl_debug_callback8) (CURL *, + curl_infotype, const unsigned char *, size_t, const void *); + +/* evaluates to true if expr is of type curl_ssl_ctx_callback or "similar" */ +/* this is getting even messier... */ +#define _curl_is_ssl_ctx_cb(expr) \ + (_curl_is_NULL(expr) || \ + __builtin_types_compatible_p(__typeof__(expr), curl_ssl_ctx_callback) || \ + _curl_callback_compatible((expr), _curl_ssl_ctx_callback1) || \ + _curl_callback_compatible((expr), _curl_ssl_ctx_callback2) || \ + _curl_callback_compatible((expr), _curl_ssl_ctx_callback3) || \ + _curl_callback_compatible((expr), _curl_ssl_ctx_callback4) || \ + _curl_callback_compatible((expr), _curl_ssl_ctx_callback5) || \ + _curl_callback_compatible((expr), _curl_ssl_ctx_callback6) || \ + _curl_callback_compatible((expr), _curl_ssl_ctx_callback7) || \ + _curl_callback_compatible((expr), _curl_ssl_ctx_callback8)) +typedef CURLcode (_curl_ssl_ctx_callback1)(CURL *, void *, void *); +typedef CURLcode (_curl_ssl_ctx_callback2)(CURL *, void *, const void *); +typedef CURLcode (_curl_ssl_ctx_callback3)(CURL *, const void *, void *); +typedef CURLcode (_curl_ssl_ctx_callback4)(CURL *, const void *, const void *); +#ifdef HEADER_SSL_H +/* hack: if we included OpenSSL's ssl.h, we know about SSL_CTX + * this will of course break if we're included before OpenSSL headers... + */ +typedef CURLcode (_curl_ssl_ctx_callback5)(CURL *, SSL_CTX, void *); +typedef CURLcode (_curl_ssl_ctx_callback6)(CURL *, SSL_CTX, const void *); +typedef CURLcode (_curl_ssl_ctx_callback7)(CURL *, const SSL_CTX, void *); +typedef CURLcode (_curl_ssl_ctx_callback8)(CURL *, const SSL_CTX, + const void *); +#else +typedef _curl_ssl_ctx_callback1 _curl_ssl_ctx_callback5; +typedef _curl_ssl_ctx_callback1 _curl_ssl_ctx_callback6; +typedef _curl_ssl_ctx_callback1 _curl_ssl_ctx_callback7; +typedef _curl_ssl_ctx_callback1 _curl_ssl_ctx_callback8; +#endif + +/* evaluates to true if expr is of type curl_conv_callback or "similar" */ +#define _curl_is_conv_cb(expr) \ + (_curl_is_NULL(expr) || \ + __builtin_types_compatible_p(__typeof__(expr), curl_conv_callback) || \ + _curl_callback_compatible((expr), _curl_conv_callback1) || \ + _curl_callback_compatible((expr), _curl_conv_callback2) || \ + _curl_callback_compatible((expr), _curl_conv_callback3) || \ + _curl_callback_compatible((expr), _curl_conv_callback4)) +typedef CURLcode (*_curl_conv_callback1)(char *, size_t length); +typedef CURLcode (*_curl_conv_callback2)(const char *, size_t length); +typedef CURLcode (*_curl_conv_callback3)(void *, size_t length); +typedef CURLcode (*_curl_conv_callback4)(const void *, size_t length); + +/* evaluates to true if expr is of type curl_seek_callback or "similar" */ +#define _curl_is_seek_cb(expr) \ + (_curl_is_NULL(expr) || \ + __builtin_types_compatible_p(__typeof__(expr), curl_seek_callback) || \ + _curl_callback_compatible((expr), _curl_seek_callback1) || \ + _curl_callback_compatible((expr), _curl_seek_callback2)) +typedef CURLcode (*_curl_seek_callback1)(void *, curl_off_t, int); +typedef CURLcode (*_curl_seek_callback2)(const void *, curl_off_t, int); + + +#endif /* __CURL_TYPECHECK_GCC_H */ diff --git a/phonelibs/curl/lib/libcurl.a b/phonelibs/curl/lib/libcurl.a new file mode 100644 index 00000000000000..494ac6c043c192 Binary files /dev/null and b/phonelibs/curl/lib/libcurl.a differ diff --git a/phonelibs/hierarchy/lib/_hierarchy.so b/phonelibs/hierarchy/lib/_hierarchy.so new file mode 100755 index 00000000000000..367b717758b2c8 Binary files /dev/null and b/phonelibs/hierarchy/lib/_hierarchy.so differ diff --git a/phonelibs/json/src/json.c b/phonelibs/json/src/json.c new file mode 100644 index 00000000000000..2f0452aebe5682 --- /dev/null +++ b/phonelibs/json/src/json.c @@ -0,0 +1,1381 @@ +/* + Copyright (C) 2011 Joseph A. Adams (joeyadams3.14159@gmail.com) + All rights reserved. + + 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 "json.h" + +#include +#include +#include +#include +#include + +#define out_of_memory() do { \ + fprintf(stderr, "Out of memory.\n"); \ + exit(EXIT_FAILURE); \ + } while (0) + +/* Sadly, strdup is not portable. */ +static char *json_strdup(const char *str) +{ + char *ret = (char*) malloc(strlen(str) + 1); + if (ret == NULL) + out_of_memory(); + strcpy(ret, str); + return ret; +} + +/* String buffer */ + +typedef struct +{ + char *cur; + char *end; + char *start; +} SB; + +static void sb_init(SB *sb) +{ + sb->start = (char*) malloc(17); + if (sb->start == NULL) + out_of_memory(); + sb->cur = sb->start; + sb->end = sb->start + 16; +} + +/* sb and need may be evaluated multiple times. */ +#define sb_need(sb, need) do { \ + if ((sb)->end - (sb)->cur < (need)) \ + sb_grow(sb, need); \ + } while (0) + +static void sb_grow(SB *sb, int need) +{ + size_t length = sb->cur - sb->start; + size_t alloc = sb->end - sb->start; + + do { + alloc *= 2; + } while (alloc < length + need); + + sb->start = (char*) realloc(sb->start, alloc + 1); + if (sb->start == NULL) + out_of_memory(); + sb->cur = sb->start + length; + sb->end = sb->start + alloc; +} + +static void sb_put(SB *sb, const char *bytes, int count) +{ + sb_need(sb, count); + memcpy(sb->cur, bytes, count); + sb->cur += count; +} + +#define sb_putc(sb, c) do { \ + if ((sb)->cur >= (sb)->end) \ + sb_grow(sb, 1); \ + *(sb)->cur++ = (c); \ + } while (0) + +static void sb_puts(SB *sb, const char *str) +{ + sb_put(sb, str, strlen(str)); +} + +static char *sb_finish(SB *sb) +{ + *sb->cur = 0; + assert(sb->start <= sb->cur && strlen(sb->start) == (size_t)(sb->cur - sb->start)); + return sb->start; +} + +static void sb_free(SB *sb) +{ + free(sb->start); +} + +/* + * Unicode helper functions + * + * These are taken from the ccan/charset module and customized a bit. + * Putting them here means the compiler can (choose to) inline them, + * and it keeps ccan/json from having a dependency. + */ + +/* + * Type for Unicode codepoints. + * We need our own because wchar_t might be 16 bits. + */ +typedef uint32_t uchar_t; + +/* + * Validate a single UTF-8 character starting at @s. + * The string must be null-terminated. + * + * If it's valid, return its length (1 thru 4). + * If it's invalid or clipped, return 0. + * + * This function implements the syntax given in RFC3629, which is + * the same as that given in The Unicode Standard, Version 6.0. + * + * It has the following properties: + * + * * All codepoints U+0000..U+10FFFF may be encoded, + * except for U+D800..U+DFFF, which are reserved + * for UTF-16 surrogate pair encoding. + * * UTF-8 byte sequences longer than 4 bytes are not permitted, + * as they exceed the range of Unicode. + * * The sixty-six Unicode "non-characters" are permitted + * (namely, U+FDD0..U+FDEF, U+xxFFFE, and U+xxFFFF). + */ +static int utf8_validate_cz(const char *s) +{ + unsigned char c = *s++; + + if (c <= 0x7F) { /* 00..7F */ + return 1; + } else if (c <= 0xC1) { /* 80..C1 */ + /* Disallow overlong 2-byte sequence. */ + return 0; + } else if (c <= 0xDF) { /* C2..DF */ + /* Make sure subsequent byte is in the range 0x80..0xBF. */ + if (((unsigned char)*s++ & 0xC0) != 0x80) + return 0; + + return 2; + } else if (c <= 0xEF) { /* E0..EF */ + /* Disallow overlong 3-byte sequence. */ + if (c == 0xE0 && (unsigned char)*s < 0xA0) + return 0; + + /* Disallow U+D800..U+DFFF. */ + if (c == 0xED && (unsigned char)*s > 0x9F) + return 0; + + /* Make sure subsequent bytes are in the range 0x80..0xBF. */ + if (((unsigned char)*s++ & 0xC0) != 0x80) + return 0; + if (((unsigned char)*s++ & 0xC0) != 0x80) + return 0; + + return 3; + } else if (c <= 0xF4) { /* F0..F4 */ + /* Disallow overlong 4-byte sequence. */ + if (c == 0xF0 && (unsigned char)*s < 0x90) + return 0; + + /* Disallow codepoints beyond U+10FFFF. */ + if (c == 0xF4 && (unsigned char)*s > 0x8F) + return 0; + + /* Make sure subsequent bytes are in the range 0x80..0xBF. */ + if (((unsigned char)*s++ & 0xC0) != 0x80) + return 0; + if (((unsigned char)*s++ & 0xC0) != 0x80) + return 0; + if (((unsigned char)*s++ & 0xC0) != 0x80) + return 0; + + return 4; + } else { /* F5..FF */ + return 0; + } +} + +/* Validate a null-terminated UTF-8 string. */ +static bool utf8_validate(const char *s) +{ + int len; + + for (; *s != 0; s += len) { + len = utf8_validate_cz(s); + if (len == 0) + return false; + } + + return true; +} + +/* + * Read a single UTF-8 character starting at @s, + * returning the length, in bytes, of the character read. + * + * This function assumes input is valid UTF-8, + * and that there are enough characters in front of @s. + */ +static int utf8_read_char(const char *s, uchar_t *out) +{ + const unsigned char *c = (const unsigned char*) s; + + assert(utf8_validate_cz(s)); + + if (c[0] <= 0x7F) { + /* 00..7F */ + *out = c[0]; + return 1; + } else if (c[0] <= 0xDF) { + /* C2..DF (unless input is invalid) */ + *out = ((uchar_t)c[0] & 0x1F) << 6 | + ((uchar_t)c[1] & 0x3F); + return 2; + } else if (c[0] <= 0xEF) { + /* E0..EF */ + *out = ((uchar_t)c[0] & 0xF) << 12 | + ((uchar_t)c[1] & 0x3F) << 6 | + ((uchar_t)c[2] & 0x3F); + return 3; + } else { + /* F0..F4 (unless input is invalid) */ + *out = ((uchar_t)c[0] & 0x7) << 18 | + ((uchar_t)c[1] & 0x3F) << 12 | + ((uchar_t)c[2] & 0x3F) << 6 | + ((uchar_t)c[3] & 0x3F); + return 4; + } +} + +/* + * Write a single UTF-8 character to @s, + * returning the length, in bytes, of the character written. + * + * @unicode must be U+0000..U+10FFFF, but not U+D800..U+DFFF. + * + * This function will write up to 4 bytes to @out. + */ +static int utf8_write_char(uchar_t unicode, char *out) +{ + unsigned char *o = (unsigned char*) out; + + assert(unicode <= 0x10FFFF && !(unicode >= 0xD800 && unicode <= 0xDFFF)); + + if (unicode <= 0x7F) { + /* U+0000..U+007F */ + *o++ = unicode; + return 1; + } else if (unicode <= 0x7FF) { + /* U+0080..U+07FF */ + *o++ = 0xC0 | unicode >> 6; + *o++ = 0x80 | (unicode & 0x3F); + return 2; + } else if (unicode <= 0xFFFF) { + /* U+0800..U+FFFF */ + *o++ = 0xE0 | unicode >> 12; + *o++ = 0x80 | (unicode >> 6 & 0x3F); + *o++ = 0x80 | (unicode & 0x3F); + return 3; + } else { + /* U+10000..U+10FFFF */ + *o++ = 0xF0 | unicode >> 18; + *o++ = 0x80 | (unicode >> 12 & 0x3F); + *o++ = 0x80 | (unicode >> 6 & 0x3F); + *o++ = 0x80 | (unicode & 0x3F); + return 4; + } +} + +/* + * Compute the Unicode codepoint of a UTF-16 surrogate pair. + * + * @uc should be 0xD800..0xDBFF, and @lc should be 0xDC00..0xDFFF. + * If they aren't, this function returns false. + */ +static bool from_surrogate_pair(uint16_t uc, uint16_t lc, uchar_t *unicode) +{ + if (uc >= 0xD800 && uc <= 0xDBFF && lc >= 0xDC00 && lc <= 0xDFFF) { + *unicode = 0x10000 + ((((uchar_t)uc & 0x3FF) << 10) | (lc & 0x3FF)); + return true; + } else { + return false; + } +} + +/* + * Construct a UTF-16 surrogate pair given a Unicode codepoint. + * + * @unicode must be U+10000..U+10FFFF. + */ +static void to_surrogate_pair(uchar_t unicode, uint16_t *uc, uint16_t *lc) +{ + uchar_t n; + + assert(unicode >= 0x10000 && unicode <= 0x10FFFF); + + n = unicode - 0x10000; + *uc = ((n >> 10) & 0x3FF) | 0xD800; + *lc = (n & 0x3FF) | 0xDC00; +} + +#define is_space(c) ((c) == '\t' || (c) == '\n' || (c) == '\r' || (c) == ' ') +#define is_digit(c) ((c) >= '0' && (c) <= '9') + +static bool parse_value (const char **sp, JsonNode **out); +static bool parse_string (const char **sp, char **out); +static bool parse_number (const char **sp, double *out); +static bool parse_array (const char **sp, JsonNode **out); +static bool parse_object (const char **sp, JsonNode **out); +static bool parse_hex16 (const char **sp, uint16_t *out); + +static bool expect_literal (const char **sp, const char *str); +static void skip_space (const char **sp); + +static void emit_value (SB *out, const JsonNode *node); +static void emit_value_indented (SB *out, const JsonNode *node, const char *space, int indent_level); +static void emit_string (SB *out, const char *str); +static void emit_number (SB *out, double num); +static void emit_array (SB *out, const JsonNode *array); +static void emit_array_indented (SB *out, const JsonNode *array, const char *space, int indent_level); +static void emit_object (SB *out, const JsonNode *object); +static void emit_object_indented (SB *out, const JsonNode *object, const char *space, int indent_level); + +static int write_hex16(char *out, uint16_t val); + +static JsonNode *mknode(JsonTag tag); +static void append_node(JsonNode *parent, JsonNode *child); +static void prepend_node(JsonNode *parent, JsonNode *child); +static void append_member(JsonNode *object, char *key, JsonNode *value); + +/* Assertion-friendly validity checks */ +static bool tag_is_valid(unsigned int tag); +static bool number_is_valid(const char *num); + +JsonNode *json_decode(const char *json) +{ + const char *s = json; + JsonNode *ret; + + skip_space(&s); + if (!parse_value(&s, &ret)) + return NULL; + + skip_space(&s); + if (*s != 0) { + json_delete(ret); + return NULL; + } + + return ret; +} + +char *json_encode(const JsonNode *node) +{ + return json_stringify(node, NULL); +} + +char *json_encode_string(const char *str) +{ + SB sb; + sb_init(&sb); + + emit_string(&sb, str); + + return sb_finish(&sb); +} + +char *json_stringify(const JsonNode *node, const char *space) +{ + SB sb; + sb_init(&sb); + + if (space != NULL) + emit_value_indented(&sb, node, space, 0); + else + emit_value(&sb, node); + + return sb_finish(&sb); +} + +void json_delete(JsonNode *node) +{ + if (node != NULL) { + json_remove_from_parent(node); + + switch (node->tag) { + case JSON_STRING: + free(node->string_); + break; + case JSON_ARRAY: + case JSON_OBJECT: + { + JsonNode *child, *next; + for (child = node->children.head; child != NULL; child = next) { + next = child->next; + json_delete(child); + } + break; + } + default:; + } + + free(node); + } +} + +bool json_validate(const char *json) +{ + const char *s = json; + + skip_space(&s); + if (!parse_value(&s, NULL)) + return false; + + skip_space(&s); + if (*s != 0) + return false; + + return true; +} + +JsonNode *json_find_element(JsonNode *array, int index) +{ + JsonNode *element; + int i = 0; + + if (array == NULL || array->tag != JSON_ARRAY) + return NULL; + + json_foreach(element, array) { + if (i == index) + return element; + i++; + } + + return NULL; +} + +JsonNode *json_find_member(JsonNode *object, const char *name) +{ + JsonNode *member; + + if (object == NULL || object->tag != JSON_OBJECT) + return NULL; + + json_foreach(member, object) + if (strcmp(member->key, name) == 0) + return member; + + return NULL; +} + +JsonNode *json_first_child(const JsonNode *node) +{ + if (node != NULL && (node->tag == JSON_ARRAY || node->tag == JSON_OBJECT)) + return node->children.head; + return NULL; +} + +static JsonNode *mknode(JsonTag tag) +{ + JsonNode *ret = (JsonNode*) calloc(1, sizeof(JsonNode)); + if (ret == NULL) + out_of_memory(); + ret->tag = tag; + return ret; +} + +JsonNode *json_mknull(void) +{ + return mknode(JSON_NULL); +} + +JsonNode *json_mkbool(bool b) +{ + JsonNode *ret = mknode(JSON_BOOL); + ret->bool_ = b; + return ret; +} + +static JsonNode *mkstring(char *s) +{ + JsonNode *ret = mknode(JSON_STRING); + ret->string_ = s; + return ret; +} + +JsonNode *json_mkstring(const char *s) +{ + return mkstring(json_strdup(s)); +} + +JsonNode *json_mknumber(double n) +{ + JsonNode *node = mknode(JSON_NUMBER); + node->number_ = n; + return node; +} + +JsonNode *json_mkarray(void) +{ + return mknode(JSON_ARRAY); +} + +JsonNode *json_mkobject(void) +{ + return mknode(JSON_OBJECT); +} + +static void append_node(JsonNode *parent, JsonNode *child) +{ + child->parent = parent; + child->prev = parent->children.tail; + child->next = NULL; + + if (parent->children.tail != NULL) + parent->children.tail->next = child; + else + parent->children.head = child; + parent->children.tail = child; +} + +static void prepend_node(JsonNode *parent, JsonNode *child) +{ + child->parent = parent; + child->prev = NULL; + child->next = parent->children.head; + + if (parent->children.head != NULL) + parent->children.head->prev = child; + else + parent->children.tail = child; + parent->children.head = child; +} + +static void append_member(JsonNode *object, char *key, JsonNode *value) +{ + value->key = key; + append_node(object, value); +} + +void json_append_element(JsonNode *array, JsonNode *element) +{ + assert(array->tag == JSON_ARRAY); + assert(element->parent == NULL); + + append_node(array, element); +} + +void json_prepend_element(JsonNode *array, JsonNode *element) +{ + assert(array->tag == JSON_ARRAY); + assert(element->parent == NULL); + + prepend_node(array, element); +} + +void json_append_member(JsonNode *object, const char *key, JsonNode *value) +{ + assert(object->tag == JSON_OBJECT); + assert(value->parent == NULL); + + append_member(object, json_strdup(key), value); +} + +void json_prepend_member(JsonNode *object, const char *key, JsonNode *value) +{ + assert(object->tag == JSON_OBJECT); + assert(value->parent == NULL); + + value->key = json_strdup(key); + prepend_node(object, value); +} + +void json_remove_from_parent(JsonNode *node) +{ + JsonNode *parent = node->parent; + + if (parent != NULL) { + if (node->prev != NULL) + node->prev->next = node->next; + else + parent->children.head = node->next; + if (node->next != NULL) + node->next->prev = node->prev; + else + parent->children.tail = node->prev; + + free(node->key); + + node->parent = NULL; + node->prev = node->next = NULL; + node->key = NULL; + } +} + +static bool parse_value(const char **sp, JsonNode **out) +{ + const char *s = *sp; + + switch (*s) { + case 'n': + if (expect_literal(&s, "null")) { + if (out) + *out = json_mknull(); + *sp = s; + return true; + } + return false; + + case 'f': + if (expect_literal(&s, "false")) { + if (out) + *out = json_mkbool(false); + *sp = s; + return true; + } + return false; + + case 't': + if (expect_literal(&s, "true")) { + if (out) + *out = json_mkbool(true); + *sp = s; + return true; + } + return false; + + case '"': { + char *str; + if (parse_string(&s, out ? &str : NULL)) { + if (out) + *out = mkstring(str); + *sp = s; + return true; + } + return false; + } + + case '[': + if (parse_array(&s, out)) { + *sp = s; + return true; + } + return false; + + case '{': + if (parse_object(&s, out)) { + *sp = s; + return true; + } + return false; + + default: { + double num; + if (parse_number(&s, out ? &num : NULL)) { + if (out) + *out = json_mknumber(num); + *sp = s; + return true; + } + return false; + } + } +} + +static bool parse_array(const char **sp, JsonNode **out) +{ + const char *s = *sp; + JsonNode *ret = out ? json_mkarray() : NULL; + JsonNode *element; + + if (*s++ != '[') + goto failure; + skip_space(&s); + + if (*s == ']') { + s++; + goto success; + } + + for (;;) { + if (!parse_value(&s, out ? &element : NULL)) + goto failure; + skip_space(&s); + + if (out) + json_append_element(ret, element); + + if (*s == ']') { + s++; + goto success; + } + + if (*s++ != ',') + goto failure; + skip_space(&s); + } + +success: + *sp = s; + if (out) + *out = ret; + return true; + +failure: + json_delete(ret); + return false; +} + +static bool parse_object(const char **sp, JsonNode **out) +{ + const char *s = *sp; + JsonNode *ret = out ? json_mkobject() : NULL; + char *key; + JsonNode *value; + + if (*s++ != '{') + goto failure; + skip_space(&s); + + if (*s == '}') { + s++; + goto success; + } + + for (;;) { + if (!parse_string(&s, out ? &key : NULL)) + goto failure; + skip_space(&s); + + if (*s++ != ':') + goto failure_free_key; + skip_space(&s); + + if (!parse_value(&s, out ? &value : NULL)) + goto failure_free_key; + skip_space(&s); + + if (out) + append_member(ret, key, value); + + if (*s == '}') { + s++; + goto success; + } + + if (*s++ != ',') + goto failure; + skip_space(&s); + } + +success: + *sp = s; + if (out) + *out = ret; + return true; + +failure_free_key: + if (out) + free(key); +failure: + json_delete(ret); + return false; +} + +bool parse_string(const char **sp, char **out) +{ + const char *s = *sp; + SB sb; + char throwaway_buffer[4]; + /* enough space for a UTF-8 character */ + char *b; + + if (*s++ != '"') + return false; + + if (out) { + sb_init(&sb); + sb_need(&sb, 4); + b = sb.cur; + } else { + b = throwaway_buffer; + } + + while (*s != '"') { + unsigned char c = *s++; + + /* Parse next character, and write it to b. */ + if (c == '\\') { + c = *s++; + switch (c) { + case '"': + case '\\': + case '/': + *b++ = c; + break; + case 'b': + *b++ = '\b'; + break; + case 'f': + *b++ = '\f'; + break; + case 'n': + *b++ = '\n'; + break; + case 'r': + *b++ = '\r'; + break; + case 't': + *b++ = '\t'; + break; + case 'u': + { + uint16_t uc, lc; + uchar_t unicode; + + if (!parse_hex16(&s, &uc)) + goto failed; + + if (uc >= 0xD800 && uc <= 0xDFFF) { + /* Handle UTF-16 surrogate pair. */ + if (*s++ != '\\' || *s++ != 'u' || !parse_hex16(&s, &lc)) + goto failed; /* Incomplete surrogate pair. */ + if (!from_surrogate_pair(uc, lc, &unicode)) + goto failed; /* Invalid surrogate pair. */ + } else if (uc == 0) { + /* Disallow "\u0000". */ + goto failed; + } else { + unicode = uc; + } + + b += utf8_write_char(unicode, b); + break; + } + default: + /* Invalid escape */ + goto failed; + } + } else if (c <= 0x1F) { + /* Control characters are not allowed in string literals. */ + goto failed; + } else { + /* Validate and echo a UTF-8 character. */ + int len; + + s--; + len = utf8_validate_cz(s); + if (len == 0) + goto failed; /* Invalid UTF-8 character. */ + + while (len--) + *b++ = *s++; + } + + /* + * Update sb to know about the new bytes, + * and set up b to write another character. + */ + if (out) { + sb.cur = b; + sb_need(&sb, 4); + b = sb.cur; + } else { + b = throwaway_buffer; + } + } + s++; + + if (out) + *out = sb_finish(&sb); + *sp = s; + return true; + +failed: + if (out) + sb_free(&sb); + return false; +} + +/* + * The JSON spec says that a number shall follow this precise pattern + * (spaces and quotes added for readability): + * '-'? (0 | [1-9][0-9]*) ('.' [0-9]+)? ([Ee] [+-]? [0-9]+)? + * + * However, some JSON parsers are more liberal. For instance, PHP accepts + * '.5' and '1.'. JSON.parse accepts '+3'. + * + * This function takes the strict approach. + */ +bool parse_number(const char **sp, double *out) +{ + const char *s = *sp; + + /* '-'? */ + if (*s == '-') + s++; + + /* (0 | [1-9][0-9]*) */ + if (*s == '0') { + s++; + } else { + if (!is_digit(*s)) + return false; + do { + s++; + } while (is_digit(*s)); + } + + /* ('.' [0-9]+)? */ + if (*s == '.') { + s++; + if (!is_digit(*s)) + return false; + do { + s++; + } while (is_digit(*s)); + } + + /* ([Ee] [+-]? [0-9]+)? */ + if (*s == 'E' || *s == 'e') { + s++; + if (*s == '+' || *s == '-') + s++; + if (!is_digit(*s)) + return false; + do { + s++; + } while (is_digit(*s)); + } + + if (out) + *out = strtod(*sp, NULL); + + *sp = s; + return true; +} + +static void skip_space(const char **sp) +{ + const char *s = *sp; + while (is_space(*s)) + s++; + *sp = s; +} + +static void emit_value(SB *out, const JsonNode *node) +{ + assert(tag_is_valid(node->tag)); + switch (node->tag) { + case JSON_NULL: + sb_puts(out, "null"); + break; + case JSON_BOOL: + sb_puts(out, node->bool_ ? "true" : "false"); + break; + case JSON_STRING: + emit_string(out, node->string_); + break; + case JSON_NUMBER: + emit_number(out, node->number_); + break; + case JSON_ARRAY: + emit_array(out, node); + break; + case JSON_OBJECT: + emit_object(out, node); + break; + default: + assert(false); + } +} + +void emit_value_indented(SB *out, const JsonNode *node, const char *space, int indent_level) +{ + assert(tag_is_valid(node->tag)); + switch (node->tag) { + case JSON_NULL: + sb_puts(out, "null"); + break; + case JSON_BOOL: + sb_puts(out, node->bool_ ? "true" : "false"); + break; + case JSON_STRING: + emit_string(out, node->string_); + break; + case JSON_NUMBER: + emit_number(out, node->number_); + break; + case JSON_ARRAY: + emit_array_indented(out, node, space, indent_level); + break; + case JSON_OBJECT: + emit_object_indented(out, node, space, indent_level); + break; + default: + assert(false); + } +} + +static void emit_array(SB *out, const JsonNode *array) +{ + const JsonNode *element; + + sb_putc(out, '['); + json_foreach(element, array) { + emit_value(out, element); + if (element->next != NULL) + sb_putc(out, ','); + } + sb_putc(out, ']'); +} + +static void emit_array_indented(SB *out, const JsonNode *array, const char *space, int indent_level) +{ + const JsonNode *element = array->children.head; + int i; + + if (element == NULL) { + sb_puts(out, "[]"); + return; + } + + sb_puts(out, "[\n"); + while (element != NULL) { + for (i = 0; i < indent_level + 1; i++) + sb_puts(out, space); + emit_value_indented(out, element, space, indent_level + 1); + + element = element->next; + sb_puts(out, element != NULL ? ",\n" : "\n"); + } + for (i = 0; i < indent_level; i++) + sb_puts(out, space); + sb_putc(out, ']'); +} + +static void emit_object(SB *out, const JsonNode *object) +{ + const JsonNode *member; + + sb_putc(out, '{'); + json_foreach(member, object) { + emit_string(out, member->key); + sb_putc(out, ':'); + emit_value(out, member); + if (member->next != NULL) + sb_putc(out, ','); + } + sb_putc(out, '}'); +} + +static void emit_object_indented(SB *out, const JsonNode *object, const char *space, int indent_level) +{ + const JsonNode *member = object->children.head; + int i; + + if (member == NULL) { + sb_puts(out, "{}"); + return; + } + + sb_puts(out, "{\n"); + while (member != NULL) { + for (i = 0; i < indent_level + 1; i++) + sb_puts(out, space); + emit_string(out, member->key); + sb_puts(out, ": "); + emit_value_indented(out, member, space, indent_level + 1); + + member = member->next; + sb_puts(out, member != NULL ? ",\n" : "\n"); + } + for (i = 0; i < indent_level; i++) + sb_puts(out, space); + sb_putc(out, '}'); +} + +void emit_string(SB *out, const char *str) +{ + bool escape_unicode = false; + const char *s = str; + char *b; + + assert(utf8_validate(str)); + + /* + * 14 bytes is enough space to write up to two + * \uXXXX escapes and two quotation marks. + */ + sb_need(out, 14); + b = out->cur; + + *b++ = '"'; + while (*s != 0) { + unsigned char c = *s++; + + /* Encode the next character, and write it to b. */ + switch (c) { + case '"': + *b++ = '\\'; + *b++ = '"'; + break; + case '\\': + *b++ = '\\'; + *b++ = '\\'; + break; + case '\b': + *b++ = '\\'; + *b++ = 'b'; + break; + case '\f': + *b++ = '\\'; + *b++ = 'f'; + break; + case '\n': + *b++ = '\\'; + *b++ = 'n'; + break; + case '\r': + *b++ = '\\'; + *b++ = 'r'; + break; + case '\t': + *b++ = '\\'; + *b++ = 't'; + break; + default: { + int len; + + s--; + len = utf8_validate_cz(s); + + if (len == 0) { + /* + * Handle invalid UTF-8 character gracefully in production + * by writing a replacement character (U+FFFD) + * and skipping a single byte. + * + * This should never happen when assertions are enabled + * due to the assertion at the beginning of this function. + */ + assert(false); + if (escape_unicode) { + strcpy(b, "\\uFFFD"); + b += 6; + } else { + *b++ = 0xEF; + *b++ = 0xBF; + *b++ = 0xBD; + } + s++; + } else if (c < 0x1F || (c >= 0x80 && escape_unicode)) { + /* Encode using \u.... */ + uint32_t unicode; + + s += utf8_read_char(s, &unicode); + + if (unicode <= 0xFFFF) { + *b++ = '\\'; + *b++ = 'u'; + b += write_hex16(b, unicode); + } else { + /* Produce a surrogate pair. */ + uint16_t uc, lc; + assert(unicode <= 0x10FFFF); + to_surrogate_pair(unicode, &uc, &lc); + *b++ = '\\'; + *b++ = 'u'; + b += write_hex16(b, uc); + *b++ = '\\'; + *b++ = 'u'; + b += write_hex16(b, lc); + } + } else { + /* Write the character directly. */ + while (len--) + *b++ = *s++; + } + + break; + } + } + + /* + * Update *out to know about the new bytes, + * and set up b to write another encoded character. + */ + out->cur = b; + sb_need(out, 14); + b = out->cur; + } + *b++ = '"'; + + out->cur = b; +} + +static void emit_number(SB *out, double num) +{ + /* + * This isn't exactly how JavaScript renders numbers, + * but it should produce valid JSON for reasonable numbers + * preserve precision well enough, and avoid some oddities + * like 0.3 -> 0.299999999999999988898 . + */ + char buf[64]; + sprintf(buf, "%.16g", num); + + if (number_is_valid(buf)) + sb_puts(out, buf); + else + sb_puts(out, "null"); +} + +static bool tag_is_valid(unsigned int tag) +{ + return (/* tag >= JSON_NULL && */ tag <= JSON_OBJECT); +} + +static bool number_is_valid(const char *num) +{ + return (parse_number(&num, NULL) && *num == '\0'); +} + +static bool expect_literal(const char **sp, const char *str) +{ + const char *s = *sp; + + while (*str != '\0') + if (*s++ != *str++) + return false; + + *sp = s; + return true; +} + +/* + * Parses exactly 4 hex characters (capital or lowercase). + * Fails if any input chars are not [0-9A-Fa-f]. + */ +static bool parse_hex16(const char **sp, uint16_t *out) +{ + const char *s = *sp; + uint16_t ret = 0; + uint16_t i; + uint16_t tmp; + char c; + + for (i = 0; i < 4; i++) { + c = *s++; + if (c >= '0' && c <= '9') + tmp = c - '0'; + else if (c >= 'A' && c <= 'F') + tmp = c - 'A' + 10; + else if (c >= 'a' && c <= 'f') + tmp = c - 'a' + 10; + else + return false; + + ret <<= 4; + ret += tmp; + } + + if (out) + *out = ret; + *sp = s; + return true; +} + +/* + * Encodes a 16-bit number into hexadecimal, + * writing exactly 4 hex chars. + */ +static int write_hex16(char *out, uint16_t val) +{ + const char *hex = "0123456789ABCDEF"; + + *out++ = hex[(val >> 12) & 0xF]; + *out++ = hex[(val >> 8) & 0xF]; + *out++ = hex[(val >> 4) & 0xF]; + *out++ = hex[ val & 0xF]; + + return 4; +} + +bool json_check(const JsonNode *node, char errmsg[256]) +{ + #define problem(...) do { \ + if (errmsg != NULL) \ + snprintf(errmsg, 256, __VA_ARGS__); \ + return false; \ + } while (0) + + if (node->key != NULL && !utf8_validate(node->key)) + problem("key contains invalid UTF-8"); + + if (!tag_is_valid(node->tag)) + problem("tag is invalid (%u)", node->tag); + + if (node->tag == JSON_BOOL) { + if (node->bool_ != false && node->bool_ != true) + problem("bool_ is neither false (%d) nor true (%d)", (int)false, (int)true); + } else if (node->tag == JSON_STRING) { + if (node->string_ == NULL) + problem("string_ is NULL"); + if (!utf8_validate(node->string_)) + problem("string_ contains invalid UTF-8"); + } else if (node->tag == JSON_ARRAY || node->tag == JSON_OBJECT) { + JsonNode *head = node->children.head; + JsonNode *tail = node->children.tail; + + if (head == NULL || tail == NULL) { + if (head != NULL) + problem("tail is NULL, but head is not"); + if (tail != NULL) + problem("head is NULL, but tail is not"); + } else { + JsonNode *child; + JsonNode *last = NULL; + + if (head->prev != NULL) + problem("First child's prev pointer is not NULL"); + + for (child = head; child != NULL; last = child, child = child->next) { + if (child == node) + problem("node is its own child"); + if (child->next == child) + problem("child->next == child (cycle)"); + if (child->next == head) + problem("child->next == head (cycle)"); + + if (child->parent != node) + problem("child does not point back to parent"); + if (child->next != NULL && child->next->prev != child) + problem("child->next does not point back to child"); + + if (node->tag == JSON_ARRAY && child->key != NULL) + problem("Array element's key is not NULL"); + if (node->tag == JSON_OBJECT && child->key == NULL) + problem("Object member's key is NULL"); + + if (!json_check(child, errmsg)) + return false; + } + + if (last != tail) + problem("tail does not match pointer found by starting at head and following next links"); + } + } + + return true; + + #undef problem +} diff --git a/phonelibs/json/src/json.h b/phonelibs/json/src/json.h new file mode 100644 index 00000000000000..ed5255e682dae1 --- /dev/null +++ b/phonelibs/json/src/json.h @@ -0,0 +1,117 @@ +/* + Copyright (C) 2011 Joseph A. Adams (joeyadams3.14159@gmail.com) + All rights reserved. + + Permission is hereby granted, free of charge, to any person obtaining a copy + of this software and associated documentation files (the "Software"), to deal + in the Software without restriction, including without limitation the rights + to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + copies of the Software, and to permit persons to whom the Software is + furnished to do so, subject to the following conditions: + + The above copyright notice and this permission notice shall be included in + all copies or substantial portions of the Software. + + THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + THE SOFTWARE. +*/ + +#ifndef CCAN_JSON_H +#define CCAN_JSON_H + +#include +#include + +typedef enum { + JSON_NULL, + JSON_BOOL, + JSON_STRING, + JSON_NUMBER, + JSON_ARRAY, + JSON_OBJECT, +} JsonTag; + +typedef struct JsonNode JsonNode; + +struct JsonNode +{ + /* only if parent is an object or array (NULL otherwise) */ + JsonNode *parent; + JsonNode *prev, *next; + + /* only if parent is an object (NULL otherwise) */ + char *key; /* Must be valid UTF-8. */ + + JsonTag tag; + union { + /* JSON_BOOL */ + bool bool_; + + /* JSON_STRING */ + char *string_; /* Must be valid UTF-8. */ + + /* JSON_NUMBER */ + double number_; + + /* JSON_ARRAY */ + /* JSON_OBJECT */ + struct { + JsonNode *head, *tail; + } children; + }; +}; + +/*** Encoding, decoding, and validation ***/ + +JsonNode *json_decode (const char *json); +char *json_encode (const JsonNode *node); +char *json_encode_string (const char *str); +char *json_stringify (const JsonNode *node, const char *space); +void json_delete (JsonNode *node); + +bool json_validate (const char *json); + +/*** Lookup and traversal ***/ + +JsonNode *json_find_element (JsonNode *array, int index); +JsonNode *json_find_member (JsonNode *object, const char *key); + +JsonNode *json_first_child (const JsonNode *node); + +#define json_foreach(i, object_or_array) \ + for ((i) = json_first_child(object_or_array); \ + (i) != NULL; \ + (i) = (i)->next) + +/*** Construction and manipulation ***/ + +JsonNode *json_mknull(void); +JsonNode *json_mkbool(bool b); +JsonNode *json_mkstring(const char *s); +JsonNode *json_mknumber(double n); +JsonNode *json_mkarray(void); +JsonNode *json_mkobject(void); + +void json_append_element(JsonNode *array, JsonNode *element); +void json_prepend_element(JsonNode *array, JsonNode *element); +void json_append_member(JsonNode *object, const char *key, JsonNode *value); +void json_prepend_member(JsonNode *object, const char *key, JsonNode *value); + +void json_remove_from_parent(JsonNode *node); + +/*** Debugging ***/ + +/* + * Look for structure and encoding problems in a JsonNode or its descendents. + * + * If a problem is detected, return false, writing a description of the problem + * to errmsg (unless errmsg is NULL). + */ +bool json_check(const JsonNode *node, char errmsg[256]); + +#endif diff --git a/phonelibs/json11/json11.cpp b/phonelibs/json11/json11.cpp new file mode 100644 index 00000000000000..bc4045f07d1954 --- /dev/null +++ b/phonelibs/json11/json11.cpp @@ -0,0 +1,784 @@ +/* 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 + +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/phonelibs/json11/json11.hpp b/phonelibs/json11/json11.hpp new file mode 100644 index 00000000000000..5202ef9323bb79 --- /dev/null +++ b/phonelibs/json11/json11.hpp @@ -0,0 +1,232 @@ +/* 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/phonelibs/json11/json11.o b/phonelibs/json11/json11.o new file mode 100644 index 00000000000000..1e32cca71ffc3b Binary files /dev/null and b/phonelibs/json11/json11.o differ diff --git a/phonelibs/libgralloc/include/gralloc_priv.h b/phonelibs/libgralloc/include/gralloc_priv.h new file mode 100644 index 00000000000000..4aa47541b03c04 --- /dev/null +++ b/phonelibs/libgralloc/include/gralloc_priv.h @@ -0,0 +1,296 @@ +/* + * Copyright (C) 2008 The Android Open Source Project + * Copyright (c) 2011-2015, The Linux Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef GRALLOC_PRIV_H_ +#define GRALLOC_PRIV_H_ + +#include +#include +#include +#include +#include +#include +#include + +#include + +#include + +#define ROUND_UP_PAGESIZE(x) ( (((unsigned long)(x)) + PAGE_SIZE-1) & \ + (~(PAGE_SIZE-1)) ) + +/* Gralloc usage bits indicating the type of allocation that should be used */ +/* SYSTEM heap comes from kernel vmalloc (ION_SYSTEM_HEAP_ID) + * is cached by default and + * is not secured */ + +/* GRALLOC_USAGE_PRIVATE_0 is unused */ + +/* Non linear, Universal Bandwidth Compression */ +#define GRALLOC_USAGE_PRIVATE_ALLOC_UBWC GRALLOC_USAGE_PRIVATE_1 + +/* IOMMU heap comes from manually allocated pages, can be cached/uncached, + * is not secured */ +#define GRALLOC_USAGE_PRIVATE_IOMMU_HEAP GRALLOC_USAGE_PRIVATE_2 + +/* MM heap is a carveout heap for video, can be secured */ +#define GRALLOC_USAGE_PRIVATE_MM_HEAP GRALLOC_USAGE_PRIVATE_3 + +/* ADSP heap is a carveout heap, is not secured */ +#define GRALLOC_USAGE_PRIVATE_ADSP_HEAP 0x01000000 + +/* Set this for allocating uncached memory (using O_DSYNC), + * cannot be used with noncontiguous heaps */ +#define GRALLOC_USAGE_PRIVATE_UNCACHED 0x02000000 + +/* Buffer content should be displayed on an primary display only */ +#define GRALLOC_USAGE_PRIVATE_INTERNAL_ONLY 0x04000000 + +/* Buffer content should be displayed on an external display only */ +#define GRALLOC_USAGE_PRIVATE_EXTERNAL_ONLY 0x08000000 + +/* This flag is set for WFD usecase */ +#define GRALLOC_USAGE_PRIVATE_WFD 0x00200000 + +/* CAMERA heap is a carveout heap for camera, is not secured */ +#define GRALLOC_USAGE_PRIVATE_CAMERA_HEAP 0x00400000 + +/* This flag is used for SECURE display usecase */ +#define GRALLOC_USAGE_PRIVATE_SECURE_DISPLAY 0x00800000 + +/* define Gralloc perform */ +#define GRALLOC_MODULE_PERFORM_CREATE_HANDLE_FROM_BUFFER 1 +// This will be used by the graphics drivers to know if certain features +// are defined in this display HAL. +// Ex: Newer GFX libraries + Older Display HAL +#define GRALLOC_MODULE_PERFORM_GET_STRIDE 2 +#define GRALLOC_MODULE_PERFORM_GET_CUSTOM_STRIDE_FROM_HANDLE 3 +#define GRALLOC_MODULE_PERFORM_GET_CUSTOM_STRIDE_AND_HEIGHT_FROM_HANDLE 4 +#define GRALLOC_MODULE_PERFORM_GET_ATTRIBUTES 5 +#define GRALLOC_MODULE_PERFORM_GET_COLOR_SPACE_FROM_HANDLE 6 +#define GRALLOC_MODULE_PERFORM_GET_YUV_PLANE_INFO 7 +#define GRALLOC_MODULE_PERFORM_GET_MAP_SECURE_BUFFER_INFO 8 +#define GRALLOC_MODULE_PERFORM_GET_UBWC_FLAG 9 +#define GRALLOC_MODULE_PERFORM_GET_RGB_DATA_ADDRESS 10 +#define GRALLOC_MODULE_PERFORM_GET_IGC 11 +#define GRALLOC_MODULE_PERFORM_SET_IGC 12 +#define GRALLOC_MODULE_PERFORM_SET_SINGLE_BUFFER_MODE 13 + +/* OEM specific HAL formats */ + +#define HAL_PIXEL_FORMAT_RGBA_5551 6 +#define HAL_PIXEL_FORMAT_RGBA_4444 7 +#define HAL_PIXEL_FORMAT_NV12_ENCODEABLE 0x102 +#define HAL_PIXEL_FORMAT_YCbCr_420_SP_VENUS 0x7FA30C04 +#define HAL_PIXEL_FORMAT_YCbCr_420_SP_TILED 0x7FA30C03 +#define HAL_PIXEL_FORMAT_YCbCr_420_SP 0x109 +#define HAL_PIXEL_FORMAT_YCrCb_420_SP_ADRENO 0x7FA30C01 +#define HAL_PIXEL_FORMAT_YCrCb_422_SP 0x10B +#define HAL_PIXEL_FORMAT_R_8 0x10D +#define HAL_PIXEL_FORMAT_RG_88 0x10E +#define HAL_PIXEL_FORMAT_YCbCr_444_SP 0x10F +#define HAL_PIXEL_FORMAT_YCrCb_444_SP 0x110 +#define HAL_PIXEL_FORMAT_YCrCb_422_I 0x111 +#define HAL_PIXEL_FORMAT_BGRX_8888 0x112 +#define HAL_PIXEL_FORMAT_NV21_ZSL 0x113 +#define HAL_PIXEL_FORMAT_YCrCb_420_SP_VENUS 0x114 +#define HAL_PIXEL_FORMAT_BGR_565 0x115 +#define HAL_PIXEL_FORMAT_INTERLACE 0x180 + +//v4l2_fourcc('Y', 'U', 'Y', 'L'). 24 bpp YUYV 4:2:2 10 bit per component +#define HAL_PIXEL_FORMAT_YCbCr_422_I_10BIT 0x4C595559 + +//v4l2_fourcc('Y', 'B', 'W', 'C'). 10 bit per component. This compressed +//format reduces the memory access bandwidth +#define HAL_PIXEL_FORMAT_YCbCr_422_I_10BIT_COMPRESSED 0x43574259 + +// UBWC aligned Venus format +#define HAL_PIXEL_FORMAT_YCbCr_420_SP_VENUS_UBWC 0x7FA30C06 + +//Khronos ASTC formats +#define HAL_PIXEL_FORMAT_COMPRESSED_RGBA_ASTC_4x4_KHR 0x93B0 +#define HAL_PIXEL_FORMAT_COMPRESSED_RGBA_ASTC_5x4_KHR 0x93B1 +#define HAL_PIXEL_FORMAT_COMPRESSED_RGBA_ASTC_5x5_KHR 0x93B2 +#define HAL_PIXEL_FORMAT_COMPRESSED_RGBA_ASTC_6x5_KHR 0x93B3 +#define HAL_PIXEL_FORMAT_COMPRESSED_RGBA_ASTC_6x6_KHR 0x93B4 +#define HAL_PIXEL_FORMAT_COMPRESSED_RGBA_ASTC_8x5_KHR 0x93B5 +#define HAL_PIXEL_FORMAT_COMPRESSED_RGBA_ASTC_8x6_KHR 0x93B6 +#define HAL_PIXEL_FORMAT_COMPRESSED_RGBA_ASTC_8x8_KHR 0x93B7 +#define HAL_PIXEL_FORMAT_COMPRESSED_RGBA_ASTC_10x5_KHR 0x93B8 +#define HAL_PIXEL_FORMAT_COMPRESSED_RGBA_ASTC_10x6_KHR 0x93B9 +#define HAL_PIXEL_FORMAT_COMPRESSED_RGBA_ASTC_10x8_KHR 0x93BA +#define HAL_PIXEL_FORMAT_COMPRESSED_RGBA_ASTC_10x10_KHR 0x93BB +#define HAL_PIXEL_FORMAT_COMPRESSED_RGBA_ASTC_12x10_KHR 0x93BC +#define HAL_PIXEL_FORMAT_COMPRESSED_RGBA_ASTC_12x12_KHR 0x93BD +#define HAL_PIXEL_FORMAT_COMPRESSED_SRGB8_ALPHA8_ASTC_4x4_KHR 0x93D0 +#define HAL_PIXEL_FORMAT_COMPRESSED_SRGB8_ALPHA8_ASTC_5x4_KHR 0x93D1 +#define HAL_PIXEL_FORMAT_COMPRESSED_SRGB8_ALPHA8_ASTC_5x5_KHR 0x93D2 +#define HAL_PIXEL_FORMAT_COMPRESSED_SRGB8_ALPHA8_ASTC_6x5_KHR 0x93D3 +#define HAL_PIXEL_FORMAT_COMPRESSED_SRGB8_ALPHA8_ASTC_6x6_KHR 0x93D4 +#define HAL_PIXEL_FORMAT_COMPRESSED_SRGB8_ALPHA8_ASTC_8x5_KHR 0x93D5 +#define HAL_PIXEL_FORMAT_COMPRESSED_SRGB8_ALPHA8_ASTC_8x6_KHR 0x93D6 +#define HAL_PIXEL_FORMAT_COMPRESSED_SRGB8_ALPHA8_ASTC_8x8_KHR 0x93D7 +#define HAL_PIXEL_FORMAT_COMPRESSED_SRGB8_ALPHA8_ASTC_10x5_KHR 0x93D8 +#define HAL_PIXEL_FORMAT_COMPRESSED_SRGB8_ALPHA8_ASTC_10x6_KHR 0x93D9 +#define HAL_PIXEL_FORMAT_COMPRESSED_SRGB8_ALPHA8_ASTC_10x8_KHR 0x93DA +#define HAL_PIXEL_FORMAT_COMPRESSED_SRGB8_ALPHA8_ASTC_10x10_KHR 0x93DB +#define HAL_PIXEL_FORMAT_COMPRESSED_SRGB8_ALPHA8_ASTC_12x10_KHR 0x93DC +#define HAL_PIXEL_FORMAT_COMPRESSED_SRGB8_ALPHA8_ASTC_12x12_KHR 0x93DD + +/* possible values for inverse gamma correction */ +#define HAL_IGC_NOT_SPECIFIED 0 +#define HAL_IGC_s_RGB 1 + +/* possible formats for 3D content*/ +enum { + HAL_NO_3D = 0x0, + HAL_3D_SIDE_BY_SIDE_L_R = 0x1, + HAL_3D_SIDE_BY_SIDE_R_L = 0x2, + HAL_3D_TOP_BOTTOM = 0x4, + HAL_3D_IN_SIDE_BY_SIDE_L_R = 0x10000, //unused legacy format +}; + +enum { + BUFFER_TYPE_UI = 0, + BUFFER_TYPE_VIDEO +}; + +#ifdef __cplusplus +struct private_handle_t : public native_handle { +#else + struct private_handle_t { + native_handle_t nativeHandle; +#endif + enum { + PRIV_FLAGS_FRAMEBUFFER = 0x00000001, + PRIV_FLAGS_USES_ION = 0x00000008, + PRIV_FLAGS_USES_ASHMEM = 0x00000010, + PRIV_FLAGS_NEEDS_FLUSH = 0x00000020, + PRIV_FLAGS_INTERNAL_ONLY = 0x00000040, + PRIV_FLAGS_NON_CPU_WRITER = 0x00000080, + PRIV_FLAGS_NONCONTIGUOUS_MEM = 0x00000100, + PRIV_FLAGS_CACHED = 0x00000200, + PRIV_FLAGS_SECURE_BUFFER = 0x00000400, + // Display on external only + PRIV_FLAGS_EXTERNAL_ONLY = 0x00002000, + // Set by HWC for protected non secure buffers + PRIV_FLAGS_PROTECTED_BUFFER = 0x00004000, + PRIV_FLAGS_VIDEO_ENCODER = 0x00010000, + PRIV_FLAGS_CAMERA_WRITE = 0x00020000, + PRIV_FLAGS_CAMERA_READ = 0x00040000, + PRIV_FLAGS_HW_COMPOSER = 0x00080000, + PRIV_FLAGS_HW_TEXTURE = 0x00100000, + PRIV_FLAGS_ITU_R_601 = 0x00200000, //Unused from display + PRIV_FLAGS_ITU_R_601_FR = 0x00400000, //Unused from display + PRIV_FLAGS_ITU_R_709 = 0x00800000, //Unused from display + PRIV_FLAGS_SECURE_DISPLAY = 0x01000000, + // Buffer is rendered in Tile Format + PRIV_FLAGS_TILE_RENDERED = 0x02000000, + // Buffer rendered using CPU/SW renderer + PRIV_FLAGS_CPU_RENDERED = 0x04000000, + // Buffer is allocated with UBWC alignment + PRIV_FLAGS_UBWC_ALIGNED = 0x08000000, + // Buffer allocated will be consumed by SF/HWC + PRIV_FLAGS_DISP_CONSUMER = 0x10000000 + }; + + // file-descriptors + int fd; + int fd_metadata; // fd for the meta-data + // ints + int magic; + int flags; + unsigned int size; + unsigned int offset; + int bufferType; + uint64_t base __attribute__((aligned(8))); + unsigned int offset_metadata; + // The gpu address mapped into the mmu. + uint64_t gpuaddr __attribute__((aligned(8))); + int format; + int width; // specifies aligned width + int height; // specifies aligned height + int real_width; + int real_height; + uint64_t base_metadata __attribute__((aligned(8))); + +#ifdef __cplusplus + static const int sNumFds = 2; + static inline int sNumInts() { + return ((sizeof(private_handle_t) - sizeof(native_handle_t)) / + sizeof(int)) - sNumFds; + } + static const int sMagic = 'gmsm'; + + private_handle_t(int fd, unsigned int size, int flags, int bufferType, + int format, int aligned_width, int aligned_height, + int width, int height, int eFd = -1, + unsigned int eOffset = 0, uint64_t eBase = 0) : + fd(fd), fd_metadata(eFd), magic(sMagic), + flags(flags), size(size), offset(0), bufferType(bufferType), + base(0), offset_metadata(eOffset), gpuaddr(0), + format(format), width(aligned_width), height(aligned_height), + real_width(width), real_height(height), base_metadata(eBase) + { + version = (int) sizeof(native_handle); + numInts = sNumInts(); + numFds = sNumFds; + } + ~private_handle_t() { + magic = 0; + } + + static int validate(const native_handle* h) { + const private_handle_t* hnd = (const private_handle_t*)h; + if (!h || h->version != sizeof(native_handle) || + h->numInts != sNumInts() || h->numFds != sNumFds || + hnd->magic != sMagic) + { + ALOGD("Invalid gralloc handle (at %p): " + "ver(%d/%zu) ints(%d/%d) fds(%d/%d)" + "magic(%c%c%c%c/%c%c%c%c)", + h, + h ? h->version : -1, sizeof(native_handle), + h ? h->numInts : -1, sNumInts(), + h ? h->numFds : -1, sNumFds, + hnd ? (((hnd->magic >> 24) & 0xFF)? + ((hnd->magic >> 24) & 0xFF) : '-') : '?', + hnd ? (((hnd->magic >> 16) & 0xFF)? + ((hnd->magic >> 16) & 0xFF) : '-') : '?', + hnd ? (((hnd->magic >> 8) & 0xFF)? + ((hnd->magic >> 8) & 0xFF) : '-') : '?', + hnd ? (((hnd->magic >> 0) & 0xFF)? + ((hnd->magic >> 0) & 0xFF) : '-') : '?', + (sMagic >> 24) & 0xFF, + (sMagic >> 16) & 0xFF, + (sMagic >> 8) & 0xFF, + (sMagic >> 0) & 0xFF); + return -EINVAL; + } + return 0; + } + + static private_handle_t* dynamicCast(const native_handle* in) { + if (validate(in) == 0) { + return (private_handle_t*) in; + } + return NULL; + } +#endif + }; + +#endif /* GRALLOC_PRIV_H_ */ diff --git a/phonelibs/libyuv/build.txt b/phonelibs/libyuv/build.txt new file mode 100644 index 00000000000000..376e981ec723c5 --- /dev/null +++ b/phonelibs/libyuv/build.txt @@ -0,0 +1,4 @@ +git clone https://chromium.googlesource.com/libyuv/libyuv +cd libyuv +git reset --hard 4a14cb2e81235ecd656e799aecaaf139db8ce4a2 +cmake . diff --git a/phonelibs/libyuv/include/libyuv.h b/phonelibs/libyuv/include/libyuv.h new file mode 100644 index 00000000000000..aeffd5ef7a4ca2 --- /dev/null +++ b/phonelibs/libyuv/include/libyuv.h @@ -0,0 +1,32 @@ +/* + * Copyright 2011 The LibYuv Project Authors. All rights reserved. + * + * Use of this source code is governed by a BSD-style license + * that can be found in the LICENSE file in the root of the source + * tree. An additional intellectual property rights grant can be found + * in the file PATENTS. All contributing project authors may + * be found in the AUTHORS file in the root of the source tree. + */ + +#ifndef INCLUDE_LIBYUV_H_ +#define INCLUDE_LIBYUV_H_ + +#include "libyuv/basic_types.h" +#include "libyuv/compare.h" +#include "libyuv/convert.h" +#include "libyuv/convert_argb.h" +#include "libyuv/convert_from.h" +#include "libyuv/convert_from_argb.h" +#include "libyuv/cpu_id.h" +#include "libyuv/mjpeg_decoder.h" +#include "libyuv/planar_functions.h" +#include "libyuv/rotate.h" +#include "libyuv/rotate_argb.h" +#include "libyuv/row.h" +#include "libyuv/scale.h" +#include "libyuv/scale_argb.h" +#include "libyuv/scale_row.h" +#include "libyuv/version.h" +#include "libyuv/video_common.h" + +#endif // INCLUDE_LIBYUV_H_ diff --git a/phonelibs/libyuv/include/libyuv/basic_types.h b/phonelibs/libyuv/include/libyuv/basic_types.h new file mode 100644 index 00000000000000..5b760ee0d4d4a2 --- /dev/null +++ b/phonelibs/libyuv/include/libyuv/basic_types.h @@ -0,0 +1,118 @@ +/* + * Copyright 2011 The LibYuv Project Authors. All rights reserved. + * + * Use of this source code is governed by a BSD-style license + * that can be found in the LICENSE file in the root of the source + * tree. An additional intellectual property rights grant can be found + * in the file PATENTS. All contributing project authors may + * be found in the AUTHORS file in the root of the source tree. + */ + +#ifndef INCLUDE_LIBYUV_BASIC_TYPES_H_ +#define INCLUDE_LIBYUV_BASIC_TYPES_H_ + +#include // for NULL, size_t + +#if defined(_MSC_VER) && (_MSC_VER < 1600) +#include // for uintptr_t on x86 +#else +#include // for uintptr_t +#endif + +#ifndef GG_LONGLONG +#ifndef INT_TYPES_DEFINED +#define INT_TYPES_DEFINED +#ifdef COMPILER_MSVC +typedef unsigned __int64 uint64; +typedef __int64 int64; +#ifndef INT64_C +#define INT64_C(x) x ## I64 +#endif +#ifndef UINT64_C +#define UINT64_C(x) x ## UI64 +#endif +#define INT64_F "I64" +#else // COMPILER_MSVC +#if defined(__LP64__) && !defined(__OpenBSD__) && !defined(__APPLE__) +typedef unsigned long uint64; // NOLINT +typedef long int64; // NOLINT +#ifndef INT64_C +#define INT64_C(x) x ## L +#endif +#ifndef UINT64_C +#define UINT64_C(x) x ## UL +#endif +#define INT64_F "l" +#else // defined(__LP64__) && !defined(__OpenBSD__) && !defined(__APPLE__) +typedef unsigned long long uint64; // NOLINT +typedef long long int64; // NOLINT +#ifndef INT64_C +#define INT64_C(x) x ## LL +#endif +#ifndef UINT64_C +#define UINT64_C(x) x ## ULL +#endif +#define INT64_F "ll" +#endif // __LP64__ +#endif // COMPILER_MSVC +typedef unsigned int uint32; +typedef int int32; +typedef unsigned short uint16; // NOLINT +typedef short int16; // NOLINT +typedef unsigned char uint8; +typedef signed char int8; +#endif // INT_TYPES_DEFINED +#endif // GG_LONGLONG + +// Detect compiler is for x86 or x64. +#if defined(__x86_64__) || defined(_M_X64) || \ + defined(__i386__) || defined(_M_IX86) +#define CPU_X86 1 +#endif +// Detect compiler is for ARM. +#if defined(__arm__) || defined(_M_ARM) +#define CPU_ARM 1 +#endif + +#ifndef ALIGNP +#ifdef __cplusplus +#define ALIGNP(p, t) \ + (reinterpret_cast(((reinterpret_cast(p) + \ + ((t) - 1)) & ~((t) - 1)))) +#else +#define ALIGNP(p, t) \ + ((uint8*)((((uintptr_t)(p) + ((t) - 1)) & ~((t) - 1)))) /* NOLINT */ +#endif +#endif + +#if !defined(LIBYUV_API) +#if defined(_WIN32) || defined(__CYGWIN__) +#if defined(LIBYUV_BUILDING_SHARED_LIBRARY) +#define LIBYUV_API __declspec(dllexport) +#elif defined(LIBYUV_USING_SHARED_LIBRARY) +#define LIBYUV_API __declspec(dllimport) +#else +#define LIBYUV_API +#endif // LIBYUV_BUILDING_SHARED_LIBRARY +#elif defined(__GNUC__) && (__GNUC__ >= 4) && !defined(__APPLE__) && \ + (defined(LIBYUV_BUILDING_SHARED_LIBRARY) || \ + defined(LIBYUV_USING_SHARED_LIBRARY)) +#define LIBYUV_API __attribute__ ((visibility ("default"))) +#else +#define LIBYUV_API +#endif // __GNUC__ +#endif // LIBYUV_API + +#define LIBYUV_BOOL int +#define LIBYUV_FALSE 0 +#define LIBYUV_TRUE 1 + +// Visual C x86 or GCC little endian. +#if defined(__x86_64__) || defined(_M_X64) || \ + defined(__i386__) || defined(_M_IX86) || \ + defined(__arm__) || defined(_M_ARM) || \ + (defined(__BYTE_ORDER__) && __BYTE_ORDER__ == __ORDER_LITTLE_ENDIAN__) +#define LIBYUV_LITTLE_ENDIAN +#endif + +#endif // INCLUDE_LIBYUV_BASIC_TYPES_H_ diff --git a/phonelibs/libyuv/include/libyuv/compare.h b/phonelibs/libyuv/include/libyuv/compare.h new file mode 100644 index 00000000000000..550712de6e589b --- /dev/null +++ b/phonelibs/libyuv/include/libyuv/compare.h @@ -0,0 +1,78 @@ +/* + * Copyright 2011 The LibYuv Project Authors. All rights reserved. + * + * Use of this source code is governed by a BSD-style license + * that can be found in the LICENSE file in the root of the source + * tree. An additional intellectual property rights grant can be found + * in the file PATENTS. All contributing project authors may + * be found in the AUTHORS file in the root of the source tree. + */ + +#ifndef INCLUDE_LIBYUV_COMPARE_H_ +#define INCLUDE_LIBYUV_COMPARE_H_ + +#include "libyuv/basic_types.h" + +#ifdef __cplusplus +namespace libyuv { +extern "C" { +#endif + +// Compute a hash for specified memory. Seed of 5381 recommended. +LIBYUV_API +uint32 HashDjb2(const uint8* src, uint64 count, uint32 seed); + +// Scan an opaque argb image and return fourcc based on alpha offset. +// Returns FOURCC_ARGB, FOURCC_BGRA, or 0 if unknown. +LIBYUV_API +uint32 ARGBDetect(const uint8* argb, int stride_argb, int width, int height); + +// Sum Square Error - used to compute Mean Square Error or PSNR. +LIBYUV_API +uint64 ComputeSumSquareError(const uint8* src_a, + const uint8* src_b, int count); + +LIBYUV_API +uint64 ComputeSumSquareErrorPlane(const uint8* src_a, int stride_a, + const uint8* src_b, int stride_b, + int width, int height); + +static const int kMaxPsnr = 128; + +LIBYUV_API +double SumSquareErrorToPsnr(uint64 sse, uint64 count); + +LIBYUV_API +double CalcFramePsnr(const uint8* src_a, int stride_a, + const uint8* src_b, int stride_b, + int width, int height); + +LIBYUV_API +double I420Psnr(const uint8* src_y_a, int stride_y_a, + const uint8* src_u_a, int stride_u_a, + const uint8* src_v_a, int stride_v_a, + const uint8* src_y_b, int stride_y_b, + const uint8* src_u_b, int stride_u_b, + const uint8* src_v_b, int stride_v_b, + int width, int height); + +LIBYUV_API +double CalcFrameSsim(const uint8* src_a, int stride_a, + const uint8* src_b, int stride_b, + int width, int height); + +LIBYUV_API +double I420Ssim(const uint8* src_y_a, int stride_y_a, + const uint8* src_u_a, int stride_u_a, + const uint8* src_v_a, int stride_v_a, + const uint8* src_y_b, int stride_y_b, + const uint8* src_u_b, int stride_u_b, + const uint8* src_v_b, int stride_v_b, + int width, int height); + +#ifdef __cplusplus +} // extern "C" +} // namespace libyuv +#endif + +#endif // INCLUDE_LIBYUV_COMPARE_H_ diff --git a/phonelibs/libyuv/include/libyuv/compare_row.h b/phonelibs/libyuv/include/libyuv/compare_row.h new file mode 100644 index 00000000000000..781cad3e65aba0 --- /dev/null +++ b/phonelibs/libyuv/include/libyuv/compare_row.h @@ -0,0 +1,84 @@ +/* + * Copyright 2013 The LibYuv Project Authors. All rights reserved. + * + * Use of this source code is governed by a BSD-style license + * that can be found in the LICENSE file in the root of the source + * tree. An additional intellectual property rights grant can be found + * in the file PATENTS. All contributing project authors may + * be found in the AUTHORS file in the root of the source tree. + */ + +#ifndef INCLUDE_LIBYUV_COMPARE_ROW_H_ +#define INCLUDE_LIBYUV_COMPARE_ROW_H_ + +#include "libyuv/basic_types.h" + +#ifdef __cplusplus +namespace libyuv { +extern "C" { +#endif + +#if defined(__pnacl__) || defined(__CLR_VER) || \ + (defined(__i386__) && !defined(__SSE2__)) +#define LIBYUV_DISABLE_X86 +#endif +// MemorySanitizer does not support assembly code yet. http://crbug.com/344505 +#if defined(__has_feature) +#if __has_feature(memory_sanitizer) +#define LIBYUV_DISABLE_X86 +#endif +#endif + +// Visual C 2012 required for AVX2. +#if defined(_M_IX86) && !defined(__clang__) && \ + defined(_MSC_VER) && _MSC_VER >= 1700 +#define VISUALC_HAS_AVX2 1 +#endif // VisualStudio >= 2012 + +// clang >= 3.4.0 required for AVX2. +#if defined(__clang__) && (defined(__x86_64__) || defined(__i386__)) +#if (__clang_major__ > 3) || (__clang_major__ == 3 && (__clang_minor__ >= 4)) +#define CLANG_HAS_AVX2 1 +#endif // clang >= 3.4 +#endif // __clang__ + +#if !defined(LIBYUV_DISABLE_X86) && \ + defined(_M_IX86) && (defined(VISUALC_HAS_AVX2) || defined(CLANG_HAS_AVX2)) +#define HAS_HASHDJB2_AVX2 +#endif + +// The following are available for Visual C and GCC: +#if !defined(LIBYUV_DISABLE_X86) && \ + (defined(__x86_64__) || (defined(__i386__) || defined(_M_IX86))) +#define HAS_HASHDJB2_SSE41 +#define HAS_SUMSQUAREERROR_SSE2 +#endif + +// The following are available for Visual C and clangcl 32 bit: +#if !defined(LIBYUV_DISABLE_X86) && defined(_M_IX86) && \ + (defined(VISUALC_HAS_AVX2) || defined(CLANG_HAS_AVX2)) +#define HAS_HASHDJB2_AVX2 +#define HAS_SUMSQUAREERROR_AVX2 +#endif + +// The following are available for Neon: +#if !defined(LIBYUV_DISABLE_NEON) && \ + (defined(__ARM_NEON__) || defined(LIBYUV_NEON) || defined(__aarch64__)) +#define HAS_SUMSQUAREERROR_NEON +#endif + +uint32 SumSquareError_C(const uint8* src_a, const uint8* src_b, int count); +uint32 SumSquareError_SSE2(const uint8* src_a, const uint8* src_b, int count); +uint32 SumSquareError_AVX2(const uint8* src_a, const uint8* src_b, int count); +uint32 SumSquareError_NEON(const uint8* src_a, const uint8* src_b, int count); + +uint32 HashDjb2_C(const uint8* src, int count, uint32 seed); +uint32 HashDjb2_SSE41(const uint8* src, int count, uint32 seed); +uint32 HashDjb2_AVX2(const uint8* src, int count, uint32 seed); + +#ifdef __cplusplus +} // extern "C" +} // namespace libyuv +#endif + +#endif // INCLUDE_LIBYUV_COMPARE_ROW_H_ diff --git a/phonelibs/libyuv/include/libyuv/convert.h b/phonelibs/libyuv/include/libyuv/convert.h new file mode 100644 index 00000000000000..d44485847be1d6 --- /dev/null +++ b/phonelibs/libyuv/include/libyuv/convert.h @@ -0,0 +1,259 @@ +/* + * Copyright 2011 The LibYuv Project Authors. All rights reserved. + * + * Use of this source code is governed by a BSD-style license + * that can be found in the LICENSE file in the root of the source + * tree. An additional intellectual property rights grant can be found + * in the file PATENTS. All contributing project authors may + * be found in the AUTHORS file in the root of the source tree. + */ + +#ifndef INCLUDE_LIBYUV_CONVERT_H_ +#define INCLUDE_LIBYUV_CONVERT_H_ + +#include "libyuv/basic_types.h" + +#include "libyuv/rotate.h" // For enum RotationMode. + +// TODO(fbarchard): fix WebRTC source to include following libyuv headers: +#include "libyuv/convert_argb.h" // For WebRTC I420ToARGB. b/620 +#include "libyuv/convert_from.h" // For WebRTC ConvertFromI420. b/620 +#include "libyuv/planar_functions.h" // For WebRTC I420Rect, CopyPlane. b/618 + +#ifdef __cplusplus +namespace libyuv { +extern "C" { +#endif + +// Convert I444 to I420. +LIBYUV_API +int I444ToI420(const uint8* src_y, int src_stride_y, + const uint8* src_u, int src_stride_u, + const uint8* src_v, int src_stride_v, + uint8* dst_y, int dst_stride_y, + uint8* dst_u, int dst_stride_u, + uint8* dst_v, int dst_stride_v, + int width, int height); + +// Convert I422 to I420. +LIBYUV_API +int I422ToI420(const uint8* src_y, int src_stride_y, + const uint8* src_u, int src_stride_u, + const uint8* src_v, int src_stride_v, + uint8* dst_y, int dst_stride_y, + uint8* dst_u, int dst_stride_u, + uint8* dst_v, int dst_stride_v, + int width, int height); + +// Convert I411 to I420. +LIBYUV_API +int I411ToI420(const uint8* src_y, int src_stride_y, + const uint8* src_u, int src_stride_u, + const uint8* src_v, int src_stride_v, + uint8* dst_y, int dst_stride_y, + uint8* dst_u, int dst_stride_u, + uint8* dst_v, int dst_stride_v, + int width, int height); + +// Copy I420 to I420. +#define I420ToI420 I420Copy +LIBYUV_API +int I420Copy(const uint8* src_y, int src_stride_y, + const uint8* src_u, int src_stride_u, + const uint8* src_v, int src_stride_v, + uint8* dst_y, int dst_stride_y, + uint8* dst_u, int dst_stride_u, + uint8* dst_v, int dst_stride_v, + int width, int height); + +// Convert I400 (grey) to I420. +LIBYUV_API +int I400ToI420(const uint8* src_y, int src_stride_y, + uint8* dst_y, int dst_stride_y, + uint8* dst_u, int dst_stride_u, + uint8* dst_v, int dst_stride_v, + int width, int height); + +#define J400ToJ420 I400ToI420 + +// Convert NV12 to I420. +LIBYUV_API +int NV12ToI420(const uint8* src_y, int src_stride_y, + const uint8* src_uv, int src_stride_uv, + uint8* dst_y, int dst_stride_y, + uint8* dst_u, int dst_stride_u, + uint8* dst_v, int dst_stride_v, + int width, int height); + +// Convert NV21 to I420. +LIBYUV_API +int NV21ToI420(const uint8* src_y, int src_stride_y, + const uint8* src_vu, int src_stride_vu, + uint8* dst_y, int dst_stride_y, + uint8* dst_u, int dst_stride_u, + uint8* dst_v, int dst_stride_v, + int width, int height); + +// Convert YUY2 to I420. +LIBYUV_API +int YUY2ToI420(const uint8* src_yuy2, int src_stride_yuy2, + uint8* dst_y, int dst_stride_y, + uint8* dst_u, int dst_stride_u, + uint8* dst_v, int dst_stride_v, + int width, int height); + +// Convert UYVY to I420. +LIBYUV_API +int UYVYToI420(const uint8* src_uyvy, int src_stride_uyvy, + uint8* dst_y, int dst_stride_y, + uint8* dst_u, int dst_stride_u, + uint8* dst_v, int dst_stride_v, + int width, int height); + +// Convert M420 to I420. +LIBYUV_API +int M420ToI420(const uint8* src_m420, int src_stride_m420, + uint8* dst_y, int dst_stride_y, + uint8* dst_u, int dst_stride_u, + uint8* dst_v, int dst_stride_v, + int width, int height); + +// Convert Android420 to I420. +LIBYUV_API +int Android420ToI420(const uint8* src_y, int src_stride_y, + const uint8* src_u, int src_stride_u, + const uint8* src_v, int src_stride_v, + int pixel_stride_uv, + uint8* dst_y, int dst_stride_y, + uint8* dst_u, int dst_stride_u, + uint8* dst_v, int dst_stride_v, + int width, int height); + +// ARGB little endian (bgra in memory) to I420. +LIBYUV_API +int ARGBToI420(const uint8* src_frame, int src_stride_frame, + uint8* dst_y, int dst_stride_y, + uint8* dst_u, int dst_stride_u, + uint8* dst_v, int dst_stride_v, + int width, int height); + +// BGRA little endian (argb in memory) to I420. +LIBYUV_API +int BGRAToI420(const uint8* src_frame, int src_stride_frame, + uint8* dst_y, int dst_stride_y, + uint8* dst_u, int dst_stride_u, + uint8* dst_v, int dst_stride_v, + int width, int height); + +// ABGR little endian (rgba in memory) to I420. +LIBYUV_API +int ABGRToI420(const uint8* src_frame, int src_stride_frame, + uint8* dst_y, int dst_stride_y, + uint8* dst_u, int dst_stride_u, + uint8* dst_v, int dst_stride_v, + int width, int height); + +// RGBA little endian (abgr in memory) to I420. +LIBYUV_API +int RGBAToI420(const uint8* src_frame, int src_stride_frame, + uint8* dst_y, int dst_stride_y, + uint8* dst_u, int dst_stride_u, + uint8* dst_v, int dst_stride_v, + int width, int height); + +// RGB little endian (bgr in memory) to I420. +LIBYUV_API +int RGB24ToI420(const uint8* src_frame, int src_stride_frame, + uint8* dst_y, int dst_stride_y, + uint8* dst_u, int dst_stride_u, + uint8* dst_v, int dst_stride_v, + int width, int height); + +// RGB big endian (rgb in memory) to I420. +LIBYUV_API +int RAWToI420(const uint8* src_frame, int src_stride_frame, + uint8* dst_y, int dst_stride_y, + uint8* dst_u, int dst_stride_u, + uint8* dst_v, int dst_stride_v, + int width, int height); + +// RGB16 (RGBP fourcc) little endian to I420. +LIBYUV_API +int RGB565ToI420(const uint8* src_frame, int src_stride_frame, + uint8* dst_y, int dst_stride_y, + uint8* dst_u, int dst_stride_u, + uint8* dst_v, int dst_stride_v, + int width, int height); + +// RGB15 (RGBO fourcc) little endian to I420. +LIBYUV_API +int ARGB1555ToI420(const uint8* src_frame, int src_stride_frame, + uint8* dst_y, int dst_stride_y, + uint8* dst_u, int dst_stride_u, + uint8* dst_v, int dst_stride_v, + int width, int height); + +// RGB12 (R444 fourcc) little endian to I420. +LIBYUV_API +int ARGB4444ToI420(const uint8* src_frame, int src_stride_frame, + uint8* dst_y, int dst_stride_y, + uint8* dst_u, int dst_stride_u, + uint8* dst_v, int dst_stride_v, + int width, int height); + +#ifdef HAVE_JPEG +// src_width/height provided by capture. +// dst_width/height for clipping determine final size. +LIBYUV_API +int MJPGToI420(const uint8* sample, size_t sample_size, + uint8* dst_y, int dst_stride_y, + uint8* dst_u, int dst_stride_u, + uint8* dst_v, int dst_stride_v, + int src_width, int src_height, + int dst_width, int dst_height); + +// Query size of MJPG in pixels. +LIBYUV_API +int MJPGSize(const uint8* sample, size_t sample_size, + int* width, int* height); +#endif + +// Convert camera sample to I420 with cropping, rotation and vertical flip. +// "src_size" is needed to parse MJPG. +// "dst_stride_y" number of bytes in a row of the dst_y plane. +// Normally this would be the same as dst_width, with recommended alignment +// to 16 bytes for better efficiency. +// If rotation of 90 or 270 is used, stride is affected. The caller should +// allocate the I420 buffer according to rotation. +// "dst_stride_u" number of bytes in a row of the dst_u plane. +// Normally this would be the same as (dst_width + 1) / 2, with +// recommended alignment to 16 bytes for better efficiency. +// If rotation of 90 or 270 is used, stride is affected. +// "crop_x" and "crop_y" are starting position for cropping. +// To center, crop_x = (src_width - dst_width) / 2 +// crop_y = (src_height - dst_height) / 2 +// "src_width" / "src_height" is size of src_frame in pixels. +// "src_height" can be negative indicating a vertically flipped image source. +// "crop_width" / "crop_height" is the size to crop the src to. +// Must be less than or equal to src_width/src_height +// Cropping parameters are pre-rotation. +// "rotation" can be 0, 90, 180 or 270. +// "format" is a fourcc. ie 'I420', 'YUY2' +// Returns 0 for successful; -1 for invalid parameter. Non-zero for failure. +LIBYUV_API +int ConvertToI420(const uint8* src_frame, size_t src_size, + uint8* dst_y, int dst_stride_y, + uint8* dst_u, int dst_stride_u, + uint8* dst_v, int dst_stride_v, + int crop_x, int crop_y, + int src_width, int src_height, + int crop_width, int crop_height, + enum RotationMode rotation, + uint32 format); + +#ifdef __cplusplus +} // extern "C" +} // namespace libyuv +#endif + +#endif // INCLUDE_LIBYUV_CONVERT_H_ diff --git a/phonelibs/libyuv/include/libyuv/convert_argb.h b/phonelibs/libyuv/include/libyuv/convert_argb.h new file mode 100644 index 00000000000000..dc03ac8d5dc4e1 --- /dev/null +++ b/phonelibs/libyuv/include/libyuv/convert_argb.h @@ -0,0 +1,319 @@ +/* + * Copyright 2012 The LibYuv Project Authors. All rights reserved. + * + * Use of this source code is governed by a BSD-style license + * that can be found in the LICENSE file in the root of the source + * tree. An additional intellectual property rights grant can be found + * in the file PATENTS. All contributing project authors may + * be found in the AUTHORS file in the root of the source tree. + */ + +#ifndef INCLUDE_LIBYUV_CONVERT_ARGB_H_ +#define INCLUDE_LIBYUV_CONVERT_ARGB_H_ + +#include "libyuv/basic_types.h" + +#include "libyuv/rotate.h" // For enum RotationMode. + +// TODO(fbarchard): This set of functions should exactly match convert.h +// TODO(fbarchard): Add tests. Create random content of right size and convert +// with C vs Opt and or to I420 and compare. +// TODO(fbarchard): Some of these functions lack parameter setting. + +#ifdef __cplusplus +namespace libyuv { +extern "C" { +#endif + +// Alias. +#define ARGBToARGB ARGBCopy + +// Copy ARGB to ARGB. +LIBYUV_API +int ARGBCopy(const uint8* src_argb, int src_stride_argb, + uint8* dst_argb, int dst_stride_argb, + int width, int height); + +// Convert I420 to ARGB. +LIBYUV_API +int I420ToARGB(const uint8* src_y, int src_stride_y, + const uint8* src_u, int src_stride_u, + const uint8* src_v, int src_stride_v, + uint8* dst_argb, int dst_stride_argb, + int width, int height); + +// Duplicate prototype for function in convert_from.h for remoting. +LIBYUV_API +int I420ToABGR(const uint8* src_y, int src_stride_y, + const uint8* src_u, int src_stride_u, + const uint8* src_v, int src_stride_v, + uint8* dst_argb, int dst_stride_argb, + int width, int height); + +// Convert I422 to ARGB. +LIBYUV_API +int I422ToARGB(const uint8* src_y, int src_stride_y, + const uint8* src_u, int src_stride_u, + const uint8* src_v, int src_stride_v, + uint8* dst_argb, int dst_stride_argb, + int width, int height); + +// Convert I444 to ARGB. +LIBYUV_API +int I444ToARGB(const uint8* src_y, int src_stride_y, + const uint8* src_u, int src_stride_u, + const uint8* src_v, int src_stride_v, + uint8* dst_argb, int dst_stride_argb, + int width, int height); + +// Convert J444 to ARGB. +LIBYUV_API +int J444ToARGB(const uint8* src_y, int src_stride_y, + const uint8* src_u, int src_stride_u, + const uint8* src_v, int src_stride_v, + uint8* dst_argb, int dst_stride_argb, + int width, int height); + +// Convert I444 to ABGR. +LIBYUV_API +int I444ToABGR(const uint8* src_y, int src_stride_y, + const uint8* src_u, int src_stride_u, + const uint8* src_v, int src_stride_v, + uint8* dst_abgr, int dst_stride_abgr, + int width, int height); + +// Convert I411 to ARGB. +LIBYUV_API +int I411ToARGB(const uint8* src_y, int src_stride_y, + const uint8* src_u, int src_stride_u, + const uint8* src_v, int src_stride_v, + uint8* dst_argb, int dst_stride_argb, + int width, int height); + +// Convert I420 with Alpha to preattenuated ARGB. +LIBYUV_API +int I420AlphaToARGB(const uint8* src_y, int src_stride_y, + const uint8* src_u, int src_stride_u, + const uint8* src_v, int src_stride_v, + const uint8* src_a, int src_stride_a, + uint8* dst_argb, int dst_stride_argb, + int width, int height, int attenuate); + +// Convert I420 with Alpha to preattenuated ABGR. +LIBYUV_API +int I420AlphaToABGR(const uint8* src_y, int src_stride_y, + const uint8* src_u, int src_stride_u, + const uint8* src_v, int src_stride_v, + const uint8* src_a, int src_stride_a, + uint8* dst_abgr, int dst_stride_abgr, + int width, int height, int attenuate); + +// Convert I400 (grey) to ARGB. Reverse of ARGBToI400. +LIBYUV_API +int I400ToARGB(const uint8* src_y, int src_stride_y, + uint8* dst_argb, int dst_stride_argb, + int width, int height); + +// Convert J400 (jpeg grey) to ARGB. +LIBYUV_API +int J400ToARGB(const uint8* src_y, int src_stride_y, + uint8* dst_argb, int dst_stride_argb, + int width, int height); + +// Alias. +#define YToARGB I400ToARGB + +// Convert NV12 to ARGB. +LIBYUV_API +int NV12ToARGB(const uint8* src_y, int src_stride_y, + const uint8* src_uv, int src_stride_uv, + uint8* dst_argb, int dst_stride_argb, + int width, int height); + +// Convert NV21 to ARGB. +LIBYUV_API +int NV21ToARGB(const uint8* src_y, int src_stride_y, + const uint8* src_vu, int src_stride_vu, + uint8* dst_argb, int dst_stride_argb, + int width, int height); + +// Convert M420 to ARGB. +LIBYUV_API +int M420ToARGB(const uint8* src_m420, int src_stride_m420, + uint8* dst_argb, int dst_stride_argb, + int width, int height); + +// Convert YUY2 to ARGB. +LIBYUV_API +int YUY2ToARGB(const uint8* src_yuy2, int src_stride_yuy2, + uint8* dst_argb, int dst_stride_argb, + int width, int height); + +// Convert UYVY to ARGB. +LIBYUV_API +int UYVYToARGB(const uint8* src_uyvy, int src_stride_uyvy, + uint8* dst_argb, int dst_stride_argb, + int width, int height); + +// Convert J420 to ARGB. +LIBYUV_API +int J420ToARGB(const uint8* src_y, int src_stride_y, + const uint8* src_u, int src_stride_u, + const uint8* src_v, int src_stride_v, + uint8* dst_argb, int dst_stride_argb, + int width, int height); + +// Convert J422 to ARGB. +LIBYUV_API +int J422ToARGB(const uint8* src_y, int src_stride_y, + const uint8* src_u, int src_stride_u, + const uint8* src_v, int src_stride_v, + uint8* dst_argb, int dst_stride_argb, + int width, int height); + +// Convert J420 to ABGR. +LIBYUV_API +int J420ToABGR(const uint8* src_y, int src_stride_y, + const uint8* src_u, int src_stride_u, + const uint8* src_v, int src_stride_v, + uint8* dst_abgr, int dst_stride_abgr, + int width, int height); + +// Convert J422 to ABGR. +LIBYUV_API +int J422ToABGR(const uint8* src_y, int src_stride_y, + const uint8* src_u, int src_stride_u, + const uint8* src_v, int src_stride_v, + uint8* dst_abgr, int dst_stride_abgr, + int width, int height); + +// Convert H420 to ARGB. +LIBYUV_API +int H420ToARGB(const uint8* src_y, int src_stride_y, + const uint8* src_u, int src_stride_u, + const uint8* src_v, int src_stride_v, + uint8* dst_argb, int dst_stride_argb, + int width, int height); + +// Convert H422 to ARGB. +LIBYUV_API +int H422ToARGB(const uint8* src_y, int src_stride_y, + const uint8* src_u, int src_stride_u, + const uint8* src_v, int src_stride_v, + uint8* dst_argb, int dst_stride_argb, + int width, int height); + +// Convert H420 to ABGR. +LIBYUV_API +int H420ToABGR(const uint8* src_y, int src_stride_y, + const uint8* src_u, int src_stride_u, + const uint8* src_v, int src_stride_v, + uint8* dst_abgr, int dst_stride_abgr, + int width, int height); + +// Convert H422 to ABGR. +LIBYUV_API +int H422ToABGR(const uint8* src_y, int src_stride_y, + const uint8* src_u, int src_stride_u, + const uint8* src_v, int src_stride_v, + uint8* dst_abgr, int dst_stride_abgr, + int width, int height); + +// BGRA little endian (argb in memory) to ARGB. +LIBYUV_API +int BGRAToARGB(const uint8* src_frame, int src_stride_frame, + uint8* dst_argb, int dst_stride_argb, + int width, int height); + +// ABGR little endian (rgba in memory) to ARGB. +LIBYUV_API +int ABGRToARGB(const uint8* src_frame, int src_stride_frame, + uint8* dst_argb, int dst_stride_argb, + int width, int height); + +// RGBA little endian (abgr in memory) to ARGB. +LIBYUV_API +int RGBAToARGB(const uint8* src_frame, int src_stride_frame, + uint8* dst_argb, int dst_stride_argb, + int width, int height); + +// Deprecated function name. +#define BG24ToARGB RGB24ToARGB + +// RGB little endian (bgr in memory) to ARGB. +LIBYUV_API +int RGB24ToARGB(const uint8* src_frame, int src_stride_frame, + uint8* dst_argb, int dst_stride_argb, + int width, int height); + +// RGB big endian (rgb in memory) to ARGB. +LIBYUV_API +int RAWToARGB(const uint8* src_frame, int src_stride_frame, + uint8* dst_argb, int dst_stride_argb, + int width, int height); + +// RGB16 (RGBP fourcc) little endian to ARGB. +LIBYUV_API +int RGB565ToARGB(const uint8* src_frame, int src_stride_frame, + uint8* dst_argb, int dst_stride_argb, + int width, int height); + +// RGB15 (RGBO fourcc) little endian to ARGB. +LIBYUV_API +int ARGB1555ToARGB(const uint8* src_frame, int src_stride_frame, + uint8* dst_argb, int dst_stride_argb, + int width, int height); + +// RGB12 (R444 fourcc) little endian to ARGB. +LIBYUV_API +int ARGB4444ToARGB(const uint8* src_frame, int src_stride_frame, + uint8* dst_argb, int dst_stride_argb, + int width, int height); + +#ifdef HAVE_JPEG +// src_width/height provided by capture +// dst_width/height for clipping determine final size. +LIBYUV_API +int MJPGToARGB(const uint8* sample, size_t sample_size, + uint8* dst_argb, int dst_stride_argb, + int src_width, int src_height, + int dst_width, int dst_height); +#endif + +// Convert camera sample to ARGB with cropping, rotation and vertical flip. +// "src_size" is needed to parse MJPG. +// "dst_stride_argb" number of bytes in a row of the dst_argb plane. +// Normally this would be the same as dst_width, with recommended alignment +// to 16 bytes for better efficiency. +// If rotation of 90 or 270 is used, stride is affected. The caller should +// allocate the I420 buffer according to rotation. +// "dst_stride_u" number of bytes in a row of the dst_u plane. +// Normally this would be the same as (dst_width + 1) / 2, with +// recommended alignment to 16 bytes for better efficiency. +// If rotation of 90 or 270 is used, stride is affected. +// "crop_x" and "crop_y" are starting position for cropping. +// To center, crop_x = (src_width - dst_width) / 2 +// crop_y = (src_height - dst_height) / 2 +// "src_width" / "src_height" is size of src_frame in pixels. +// "src_height" can be negative indicating a vertically flipped image source. +// "crop_width" / "crop_height" is the size to crop the src to. +// Must be less than or equal to src_width/src_height +// Cropping parameters are pre-rotation. +// "rotation" can be 0, 90, 180 or 270. +// "format" is a fourcc. ie 'I420', 'YUY2' +// Returns 0 for successful; -1 for invalid parameter. Non-zero for failure. +LIBYUV_API +int ConvertToARGB(const uint8* src_frame, size_t src_size, + uint8* dst_argb, int dst_stride_argb, + int crop_x, int crop_y, + int src_width, int src_height, + int crop_width, int crop_height, + enum RotationMode rotation, + uint32 format); + +#ifdef __cplusplus +} // extern "C" +} // namespace libyuv +#endif + +#endif // INCLUDE_LIBYUV_CONVERT_ARGB_H_ diff --git a/phonelibs/libyuv/include/libyuv/convert_from.h b/phonelibs/libyuv/include/libyuv/convert_from.h new file mode 100644 index 00000000000000..59c40474f1ef24 --- /dev/null +++ b/phonelibs/libyuv/include/libyuv/convert_from.h @@ -0,0 +1,179 @@ +/* + * Copyright 2011 The LibYuv Project Authors. All rights reserved. + * + * Use of this source code is governed by a BSD-style license + * that can be found in the LICENSE file in the root of the source + * tree. An additional intellectual property rights grant can be found + * in the file PATENTS. All contributing project authors may + * be found in the AUTHORS file in the root of the source tree. + */ + +#ifndef INCLUDE_LIBYUV_CONVERT_FROM_H_ +#define INCLUDE_LIBYUV_CONVERT_FROM_H_ + +#include "libyuv/basic_types.h" +#include "libyuv/rotate.h" + +#ifdef __cplusplus +namespace libyuv { +extern "C" { +#endif + +// See Also convert.h for conversions from formats to I420. + +// I420Copy in convert to I420ToI420. + +LIBYUV_API +int I420ToI422(const uint8* src_y, int src_stride_y, + const uint8* src_u, int src_stride_u, + const uint8* src_v, int src_stride_v, + uint8* dst_y, int dst_stride_y, + uint8* dst_u, int dst_stride_u, + uint8* dst_v, int dst_stride_v, + int width, int height); + +LIBYUV_API +int I420ToI444(const uint8* src_y, int src_stride_y, + const uint8* src_u, int src_stride_u, + const uint8* src_v, int src_stride_v, + uint8* dst_y, int dst_stride_y, + uint8* dst_u, int dst_stride_u, + uint8* dst_v, int dst_stride_v, + int width, int height); + +LIBYUV_API +int I420ToI411(const uint8* src_y, int src_stride_y, + const uint8* src_u, int src_stride_u, + const uint8* src_v, int src_stride_v, + uint8* dst_y, int dst_stride_y, + uint8* dst_u, int dst_stride_u, + uint8* dst_v, int dst_stride_v, + int width, int height); + +// Copy to I400. Source can be I420, I422, I444, I400, NV12 or NV21. +LIBYUV_API +int I400Copy(const uint8* src_y, int src_stride_y, + uint8* dst_y, int dst_stride_y, + int width, int height); + +LIBYUV_API +int I420ToNV12(const uint8* src_y, int src_stride_y, + const uint8* src_u, int src_stride_u, + const uint8* src_v, int src_stride_v, + uint8* dst_y, int dst_stride_y, + uint8* dst_uv, int dst_stride_uv, + int width, int height); + +LIBYUV_API +int I420ToNV21(const uint8* src_y, int src_stride_y, + const uint8* src_u, int src_stride_u, + const uint8* src_v, int src_stride_v, + uint8* dst_y, int dst_stride_y, + uint8* dst_vu, int dst_stride_vu, + int width, int height); + +LIBYUV_API +int I420ToYUY2(const uint8* src_y, int src_stride_y, + const uint8* src_u, int src_stride_u, + const uint8* src_v, int src_stride_v, + uint8* dst_frame, int dst_stride_frame, + int width, int height); + +LIBYUV_API +int I420ToUYVY(const uint8* src_y, int src_stride_y, + const uint8* src_u, int src_stride_u, + const uint8* src_v, int src_stride_v, + uint8* dst_frame, int dst_stride_frame, + int width, int height); + +LIBYUV_API +int I420ToARGB(const uint8* src_y, int src_stride_y, + const uint8* src_u, int src_stride_u, + const uint8* src_v, int src_stride_v, + uint8* dst_argb, int dst_stride_argb, + int width, int height); + +LIBYUV_API +int I420ToBGRA(const uint8* src_y, int src_stride_y, + const uint8* src_u, int src_stride_u, + const uint8* src_v, int src_stride_v, + uint8* dst_argb, int dst_stride_argb, + int width, int height); + +LIBYUV_API +int I420ToABGR(const uint8* src_y, int src_stride_y, + const uint8* src_u, int src_stride_u, + const uint8* src_v, int src_stride_v, + uint8* dst_argb, int dst_stride_argb, + int width, int height); + +LIBYUV_API +int I420ToRGBA(const uint8* src_y, int src_stride_y, + const uint8* src_u, int src_stride_u, + const uint8* src_v, int src_stride_v, + uint8* dst_rgba, int dst_stride_rgba, + int width, int height); + +LIBYUV_API +int I420ToRGB24(const uint8* src_y, int src_stride_y, + const uint8* src_u, int src_stride_u, + const uint8* src_v, int src_stride_v, + uint8* dst_frame, int dst_stride_frame, + int width, int height); + +LIBYUV_API +int I420ToRAW(const uint8* src_y, int src_stride_y, + const uint8* src_u, int src_stride_u, + const uint8* src_v, int src_stride_v, + uint8* dst_frame, int dst_stride_frame, + int width, int height); + +LIBYUV_API +int I420ToRGB565(const uint8* src_y, int src_stride_y, + const uint8* src_u, int src_stride_u, + const uint8* src_v, int src_stride_v, + uint8* dst_frame, int dst_stride_frame, + int width, int height); + +// Convert I420 To RGB565 with 4x4 dither matrix (16 bytes). +// Values in dither matrix from 0 to 7 recommended. +// The order of the dither matrix is first byte is upper left. + +LIBYUV_API +int I420ToRGB565Dither(const uint8* src_y, int src_stride_y, + const uint8* src_u, int src_stride_u, + const uint8* src_v, int src_stride_v, + uint8* dst_frame, int dst_stride_frame, + const uint8* dither4x4, int width, int height); + +LIBYUV_API +int I420ToARGB1555(const uint8* src_y, int src_stride_y, + const uint8* src_u, int src_stride_u, + const uint8* src_v, int src_stride_v, + uint8* dst_frame, int dst_stride_frame, + int width, int height); + +LIBYUV_API +int I420ToARGB4444(const uint8* src_y, int src_stride_y, + const uint8* src_u, int src_stride_u, + const uint8* src_v, int src_stride_v, + uint8* dst_frame, int dst_stride_frame, + int width, int height); + +// Convert I420 to specified format. +// "dst_sample_stride" is bytes in a row for the destination. Pass 0 if the +// buffer has contiguous rows. Can be negative. A multiple of 16 is optimal. +LIBYUV_API +int ConvertFromI420(const uint8* y, int y_stride, + const uint8* u, int u_stride, + const uint8* v, int v_stride, + uint8* dst_sample, int dst_sample_stride, + int width, int height, + uint32 format); + +#ifdef __cplusplus +} // extern "C" +} // namespace libyuv +#endif + +#endif // INCLUDE_LIBYUV_CONVERT_FROM_H_ diff --git a/phonelibs/libyuv/include/libyuv/convert_from_argb.h b/phonelibs/libyuv/include/libyuv/convert_from_argb.h new file mode 100644 index 00000000000000..8d7f02f8c4dde6 --- /dev/null +++ b/phonelibs/libyuv/include/libyuv/convert_from_argb.h @@ -0,0 +1,190 @@ +/* + * Copyright 2012 The LibYuv Project Authors. All rights reserved. + * + * Use of this source code is governed by a BSD-style license + * that can be found in the LICENSE file in the root of the source + * tree. An additional intellectual property rights grant can be found + * in the file PATENTS. All contributing project authors may + * be found in the AUTHORS file in the root of the source tree. + */ + +#ifndef INCLUDE_LIBYUV_CONVERT_FROM_ARGB_H_ +#define INCLUDE_LIBYUV_CONVERT_FROM_ARGB_H_ + +#include "libyuv/basic_types.h" + +#ifdef __cplusplus +namespace libyuv { +extern "C" { +#endif + +// Copy ARGB to ARGB. +#define ARGBToARGB ARGBCopy +LIBYUV_API +int ARGBCopy(const uint8* src_argb, int src_stride_argb, + uint8* dst_argb, int dst_stride_argb, + int width, int height); + +// Convert ARGB To BGRA. +LIBYUV_API +int ARGBToBGRA(const uint8* src_argb, int src_stride_argb, + uint8* dst_bgra, int dst_stride_bgra, + int width, int height); + +// Convert ARGB To ABGR. +LIBYUV_API +int ARGBToABGR(const uint8* src_argb, int src_stride_argb, + uint8* dst_abgr, int dst_stride_abgr, + int width, int height); + +// Convert ARGB To RGBA. +LIBYUV_API +int ARGBToRGBA(const uint8* src_argb, int src_stride_argb, + uint8* dst_rgba, int dst_stride_rgba, + int width, int height); + +// Convert ARGB To RGB24. +LIBYUV_API +int ARGBToRGB24(const uint8* src_argb, int src_stride_argb, + uint8* dst_rgb24, int dst_stride_rgb24, + int width, int height); + +// Convert ARGB To RAW. +LIBYUV_API +int ARGBToRAW(const uint8* src_argb, int src_stride_argb, + uint8* dst_rgb, int dst_stride_rgb, + int width, int height); + +// Convert ARGB To RGB565. +LIBYUV_API +int ARGBToRGB565(const uint8* src_argb, int src_stride_argb, + uint8* dst_rgb565, int dst_stride_rgb565, + int width, int height); + +// Convert ARGB To RGB565 with 4x4 dither matrix (16 bytes). +// Values in dither matrix from 0 to 7 recommended. +// The order of the dither matrix is first byte is upper left. +// TODO(fbarchard): Consider pointer to 2d array for dither4x4. +// const uint8(*dither)[4][4]; +LIBYUV_API +int ARGBToRGB565Dither(const uint8* src_argb, int src_stride_argb, + uint8* dst_rgb565, int dst_stride_rgb565, + const uint8* dither4x4, int width, int height); + +// Convert ARGB To ARGB1555. +LIBYUV_API +int ARGBToARGB1555(const uint8* src_argb, int src_stride_argb, + uint8* dst_argb1555, int dst_stride_argb1555, + int width, int height); + +// Convert ARGB To ARGB4444. +LIBYUV_API +int ARGBToARGB4444(const uint8* src_argb, int src_stride_argb, + uint8* dst_argb4444, int dst_stride_argb4444, + int width, int height); + +// Convert ARGB To I444. +LIBYUV_API +int ARGBToI444(const uint8* src_argb, int src_stride_argb, + uint8* dst_y, int dst_stride_y, + uint8* dst_u, int dst_stride_u, + uint8* dst_v, int dst_stride_v, + int width, int height); + +// Convert ARGB To I422. +LIBYUV_API +int ARGBToI422(const uint8* src_argb, int src_stride_argb, + uint8* dst_y, int dst_stride_y, + uint8* dst_u, int dst_stride_u, + uint8* dst_v, int dst_stride_v, + int width, int height); + +// Convert ARGB To I420. (also in convert.h) +LIBYUV_API +int ARGBToI420(const uint8* src_argb, int src_stride_argb, + uint8* dst_y, int dst_stride_y, + uint8* dst_u, int dst_stride_u, + uint8* dst_v, int dst_stride_v, + int width, int height); + +// Convert ARGB to J420. (JPeg full range I420). +LIBYUV_API +int ARGBToJ420(const uint8* src_argb, int src_stride_argb, + uint8* dst_yj, int dst_stride_yj, + uint8* dst_u, int dst_stride_u, + uint8* dst_v, int dst_stride_v, + int width, int height); + +// Convert ARGB to J422. +LIBYUV_API +int ARGBToJ422(const uint8* src_argb, int src_stride_argb, + uint8* dst_yj, int dst_stride_yj, + uint8* dst_u, int dst_stride_u, + uint8* dst_v, int dst_stride_v, + int width, int height); + +// Convert ARGB To I411. +LIBYUV_API +int ARGBToI411(const uint8* src_argb, int src_stride_argb, + uint8* dst_y, int dst_stride_y, + uint8* dst_u, int dst_stride_u, + uint8* dst_v, int dst_stride_v, + int width, int height); + +// Convert ARGB to J400. (JPeg full range). +LIBYUV_API +int ARGBToJ400(const uint8* src_argb, int src_stride_argb, + uint8* dst_yj, int dst_stride_yj, + int width, int height); + +// Convert ARGB to I400. +LIBYUV_API +int ARGBToI400(const uint8* src_argb, int src_stride_argb, + uint8* dst_y, int dst_stride_y, + int width, int height); + +// Convert ARGB to G. (Reverse of J400toARGB, which replicates G back to ARGB) +LIBYUV_API +int ARGBToG(const uint8* src_argb, int src_stride_argb, + uint8* dst_g, int dst_stride_g, + int width, int height); + +// Convert ARGB To NV12. +LIBYUV_API +int ARGBToNV12(const uint8* src_argb, int src_stride_argb, + uint8* dst_y, int dst_stride_y, + uint8* dst_uv, int dst_stride_uv, + int width, int height); + +// Convert ARGB To NV21. +LIBYUV_API +int ARGBToNV21(const uint8* src_argb, int src_stride_argb, + uint8* dst_y, int dst_stride_y, + uint8* dst_vu, int dst_stride_vu, + int width, int height); + +// Convert ARGB To NV21. +LIBYUV_API +int ARGBToNV21(const uint8* src_argb, int src_stride_argb, + uint8* dst_y, int dst_stride_y, + uint8* dst_vu, int dst_stride_vu, + int width, int height); + +// Convert ARGB To YUY2. +LIBYUV_API +int ARGBToYUY2(const uint8* src_argb, int src_stride_argb, + uint8* dst_yuy2, int dst_stride_yuy2, + int width, int height); + +// Convert ARGB To UYVY. +LIBYUV_API +int ARGBToUYVY(const uint8* src_argb, int src_stride_argb, + uint8* dst_uyvy, int dst_stride_uyvy, + int width, int height); + +#ifdef __cplusplus +} // extern "C" +} // namespace libyuv +#endif + +#endif // INCLUDE_LIBYUV_CONVERT_FROM_ARGB_H_ diff --git a/phonelibs/libyuv/include/libyuv/cpu_id.h b/phonelibs/libyuv/include/libyuv/cpu_id.h new file mode 100644 index 00000000000000..7c6c9aeb00515d --- /dev/null +++ b/phonelibs/libyuv/include/libyuv/cpu_id.h @@ -0,0 +1,81 @@ +/* + * Copyright 2011 The LibYuv Project Authors. All rights reserved. + * + * Use of this source code is governed by a BSD-style license + * that can be found in the LICENSE file in the root of the source + * tree. An additional intellectual property rights grant can be found + * in the file PATENTS. All contributing project authors may + * be found in the AUTHORS file in the root of the source tree. + */ + +#ifndef INCLUDE_LIBYUV_CPU_ID_H_ +#define INCLUDE_LIBYUV_CPU_ID_H_ + +#include "libyuv/basic_types.h" + +#ifdef __cplusplus +namespace libyuv { +extern "C" { +#endif + +// Internal flag to indicate cpuid requires initialization. +static const int kCpuInitialized = 0x1; + +// These flags are only valid on ARM processors. +static const int kCpuHasARM = 0x2; +static const int kCpuHasNEON = 0x4; +// 0x8 reserved for future ARM flag. + +// These flags are only valid on x86 processors. +static const int kCpuHasX86 = 0x10; +static const int kCpuHasSSE2 = 0x20; +static const int kCpuHasSSSE3 = 0x40; +static const int kCpuHasSSE41 = 0x80; +static const int kCpuHasSSE42 = 0x100; +static const int kCpuHasAVX = 0x200; +static const int kCpuHasAVX2 = 0x400; +static const int kCpuHasERMS = 0x800; +static const int kCpuHasFMA3 = 0x1000; +static const int kCpuHasAVX3 = 0x2000; +// 0x2000, 0x4000, 0x8000 reserved for future X86 flags. + +// These flags are only valid on MIPS processors. +static const int kCpuHasMIPS = 0x10000; +static const int kCpuHasDSPR2 = 0x20000; +static const int kCpuHasMSA = 0x40000; + +// Internal function used to auto-init. +LIBYUV_API +int InitCpuFlags(void); + +// Internal function for parsing /proc/cpuinfo. +LIBYUV_API +int ArmCpuCaps(const char* cpuinfo_name); + +// Detect CPU has SSE2 etc. +// Test_flag parameter should be one of kCpuHas constants above. +// returns non-zero if instruction set is detected +static __inline int TestCpuFlag(int test_flag) { + LIBYUV_API extern int cpu_info_; + return (!cpu_info_ ? InitCpuFlags() : cpu_info_) & test_flag; +} + +// For testing, allow CPU flags to be disabled. +// ie MaskCpuFlags(~kCpuHasSSSE3) to disable SSSE3. +// MaskCpuFlags(-1) to enable all cpu specific optimizations. +// MaskCpuFlags(1) to disable all cpu specific optimizations. +LIBYUV_API +void MaskCpuFlags(int enable_flags); + +// Low level cpuid for X86. Returns zeros on other CPUs. +// eax is the info type that you want. +// ecx is typically the cpu number, and should normally be zero. +LIBYUV_API +void CpuId(uint32 eax, uint32 ecx, uint32* cpu_info); + +#ifdef __cplusplus +} // extern "C" +} // namespace libyuv +#endif + +#endif // INCLUDE_LIBYUV_CPU_ID_H_ diff --git a/phonelibs/libyuv/include/libyuv/macros_msa.h b/phonelibs/libyuv/include/libyuv/macros_msa.h new file mode 100644 index 00000000000000..92ed21c38532d4 --- /dev/null +++ b/phonelibs/libyuv/include/libyuv/macros_msa.h @@ -0,0 +1,76 @@ +/* + * Copyright 2016 The LibYuv Project Authors. All rights reserved. + * + * Use of this source code is governed by a BSD-style license + * that can be found in the LICENSE file in the root of the source + * tree. An additional intellectual property rights grant can be found + * in the file PATENTS. All contributing project authors may + * be found in the AUTHORS file in the root of the source tree. + */ + +#ifndef INCLUDE_LIBYUV_MACROS_MSA_H_ +#define INCLUDE_LIBYUV_MACROS_MSA_H_ + +#if !defined(LIBYUV_DISABLE_MSA) && defined(__mips_msa) +#include +#include + +#define LD_B(RTYPE, psrc) *((RTYPE*)(psrc)) /* NOLINT */ +#define LD_UB(...) LD_B(v16u8, __VA_ARGS__) + +#define ST_B(RTYPE, in, pdst) *((RTYPE*)(pdst)) = (in) /* NOLINT */ +#define ST_UB(...) ST_B(v16u8, __VA_ARGS__) + +/* Description : Load two vectors with 16 'byte' sized elements + Arguments : Inputs - psrc, stride + Outputs - out0, out1 + Return Type - as per RTYPE + Details : Load 16 byte elements in 'out0' from (psrc) + Load 16 byte elements in 'out1' from (psrc + stride) +*/ +#define LD_B2(RTYPE, psrc, stride, out0, out1) { \ + out0 = LD_B(RTYPE, (psrc)); \ + out1 = LD_B(RTYPE, (psrc) + stride); \ +} +#define LD_UB2(...) LD_B2(v16u8, __VA_ARGS__) + +#define LD_B4(RTYPE, psrc, stride, out0, out1, out2, out3) { \ + LD_B2(RTYPE, (psrc), stride, out0, out1); \ + LD_B2(RTYPE, (psrc) + 2 * stride , stride, out2, out3); \ +} +#define LD_UB4(...) LD_B4(v16u8, __VA_ARGS__) + +/* Description : Store two vectors with stride each having 16 'byte' sized + elements + Arguments : Inputs - in0, in1, pdst, stride + Details : Store 16 byte elements from 'in0' to (pdst) + Store 16 byte elements from 'in1' to (pdst + stride) +*/ +#define ST_B2(RTYPE, in0, in1, pdst, stride) { \ + ST_B(RTYPE, in0, (pdst)); \ + ST_B(RTYPE, in1, (pdst) + stride); \ +} +#define ST_UB2(...) ST_B2(v16u8, __VA_ARGS__) +# +#define ST_B4(RTYPE, in0, in1, in2, in3, pdst, stride) { \ + ST_B2(RTYPE, in0, in1, (pdst), stride); \ + ST_B2(RTYPE, in2, in3, (pdst) + 2 * stride, stride); \ +} +#define ST_UB4(...) ST_B4(v16u8, __VA_ARGS__) +# +/* Description : Shuffle byte vector elements as per mask vector + Arguments : Inputs - in0, in1, in2, in3, mask0, mask1 + Outputs - out0, out1 + Return Type - as per RTYPE + Details : Byte elements from 'in0' & 'in1' are copied selectively to + 'out0' as per control vector 'mask0' +*/ +#define VSHF_B2(RTYPE, in0, in1, in2, in3, mask0, mask1, out0, out1) { \ + out0 = (RTYPE) __msa_vshf_b((v16i8) mask0, (v16i8) in1, (v16i8) in0); \ + out1 = (RTYPE) __msa_vshf_b((v16i8) mask1, (v16i8) in3, (v16i8) in2); \ +} +#define VSHF_B2_UB(...) VSHF_B2(v16u8, __VA_ARGS__) + +#endif /* !defined(LIBYUV_DISABLE_MSA) && defined(__mips_msa) */ + +#endif // INCLUDE_LIBYUV_MACROS_MSA_H_ diff --git a/phonelibs/libyuv/include/libyuv/mjpeg_decoder.h b/phonelibs/libyuv/include/libyuv/mjpeg_decoder.h new file mode 100644 index 00000000000000..4975bae5b76ef1 --- /dev/null +++ b/phonelibs/libyuv/include/libyuv/mjpeg_decoder.h @@ -0,0 +1,192 @@ +/* + * Copyright 2012 The LibYuv Project Authors. All rights reserved. + * + * Use of this source code is governed by a BSD-style license + * that can be found in the LICENSE file in the root of the source + * tree. An additional intellectual property rights grant can be found + * in the file PATENTS. All contributing project authors may + * be found in the AUTHORS file in the root of the source tree. + */ + +#ifndef INCLUDE_LIBYUV_MJPEG_DECODER_H_ +#define INCLUDE_LIBYUV_MJPEG_DECODER_H_ + +#include "libyuv/basic_types.h" + +#ifdef __cplusplus +// NOTE: For a simplified public API use convert.h MJPGToI420(). + +struct jpeg_common_struct; +struct jpeg_decompress_struct; +struct jpeg_source_mgr; + +namespace libyuv { + +#ifdef __cplusplus +extern "C" { +#endif + +LIBYUV_BOOL ValidateJpeg(const uint8* sample, size_t sample_size); + +#ifdef __cplusplus +} // extern "C" +#endif + +static const uint32 kUnknownDataSize = 0xFFFFFFFF; + +enum JpegSubsamplingType { + kJpegYuv420, + kJpegYuv422, + kJpegYuv411, + kJpegYuv444, + kJpegYuv400, + kJpegUnknown +}; + +struct Buffer { + const uint8* data; + int len; +}; + +struct BufferVector { + Buffer* buffers; + int len; + int pos; +}; + +struct SetJmpErrorMgr; + +// MJPEG ("Motion JPEG") is a pseudo-standard video codec where the frames are +// simply independent JPEG images with a fixed huffman table (which is omitted). +// It is rarely used in video transmission, but is common as a camera capture +// format, especially in Logitech devices. This class implements a decoder for +// MJPEG frames. +// +// See http://tools.ietf.org/html/rfc2435 +class LIBYUV_API MJpegDecoder { + public: + typedef void (*CallbackFunction)(void* opaque, + const uint8* const* data, + const int* strides, + int rows); + + static const int kColorSpaceUnknown; + static const int kColorSpaceGrayscale; + static const int kColorSpaceRgb; + static const int kColorSpaceYCbCr; + static const int kColorSpaceCMYK; + static const int kColorSpaceYCCK; + + MJpegDecoder(); + ~MJpegDecoder(); + + // Loads a new frame, reads its headers, and determines the uncompressed + // image format. + // Returns LIBYUV_TRUE if image looks valid and format is supported. + // If return value is LIBYUV_TRUE, then the values for all the following + // getters are populated. + // src_len is the size of the compressed mjpeg frame in bytes. + LIBYUV_BOOL LoadFrame(const uint8* src, size_t src_len); + + // Returns width of the last loaded frame in pixels. + int GetWidth(); + + // Returns height of the last loaded frame in pixels. + int GetHeight(); + + // Returns format of the last loaded frame. The return value is one of the + // kColorSpace* constants. + int GetColorSpace(); + + // Number of color components in the color space. + int GetNumComponents(); + + // Sample factors of the n-th component. + int GetHorizSampFactor(int component); + + int GetVertSampFactor(int component); + + int GetHorizSubSampFactor(int component); + + int GetVertSubSampFactor(int component); + + // Public for testability. + int GetImageScanlinesPerImcuRow(); + + // Public for testability. + int GetComponentScanlinesPerImcuRow(int component); + + // Width of a component in bytes. + int GetComponentWidth(int component); + + // Height of a component. + int GetComponentHeight(int component); + + // Width of a component in bytes with padding for DCTSIZE. Public for testing. + int GetComponentStride(int component); + + // Size of a component in bytes. + int GetComponentSize(int component); + + // Call this after LoadFrame() if you decide you don't want to decode it + // after all. + LIBYUV_BOOL UnloadFrame(); + + // Decodes the entire image into a one-buffer-per-color-component format. + // dst_width must match exactly. dst_height must be <= to image height; if + // less, the image is cropped. "planes" must have size equal to at least + // GetNumComponents() and they must point to non-overlapping buffers of size + // at least GetComponentSize(i). The pointers in planes are incremented + // to point to after the end of the written data. + // TODO(fbarchard): Add dst_x, dst_y to allow specific rect to be decoded. + LIBYUV_BOOL DecodeToBuffers(uint8** planes, int dst_width, int dst_height); + + // Decodes the entire image and passes the data via repeated calls to a + // callback function. Each call will get the data for a whole number of + // image scanlines. + // TODO(fbarchard): Add dst_x, dst_y to allow specific rect to be decoded. + LIBYUV_BOOL DecodeToCallback(CallbackFunction fn, void* opaque, + int dst_width, int dst_height); + + // The helper function which recognizes the jpeg sub-sampling type. + static JpegSubsamplingType JpegSubsamplingTypeHelper( + int* subsample_x, int* subsample_y, int number_of_components); + + private: + void AllocOutputBuffers(int num_outbufs); + void DestroyOutputBuffers(); + + LIBYUV_BOOL StartDecode(); + LIBYUV_BOOL FinishDecode(); + + void SetScanlinePointers(uint8** data); + LIBYUV_BOOL DecodeImcuRow(); + + int GetComponentScanlinePadding(int component); + + // A buffer holding the input data for a frame. + Buffer buf_; + BufferVector buf_vec_; + + jpeg_decompress_struct* decompress_struct_; + jpeg_source_mgr* source_mgr_; + SetJmpErrorMgr* error_mgr_; + + // LIBYUV_TRUE iff at least one component has scanline padding. (i.e., + // GetComponentScanlinePadding() != 0.) + LIBYUV_BOOL has_scanline_padding_; + + // Temporaries used to point to scanline outputs. + int num_outbufs_; // Outermost size of all arrays below. + uint8*** scanlines_; + int* scanlines_sizes_; + // Temporary buffer used for decoding when we can't decode directly to the + // output buffers. Large enough for just one iMCU row. + uint8** databuf_; + int* databuf_strides_; +}; + +} // namespace libyuv + +#endif // __cplusplus +#endif // INCLUDE_LIBYUV_MJPEG_DECODER_H_ diff --git a/phonelibs/libyuv/include/libyuv/planar_functions.h b/phonelibs/libyuv/include/libyuv/planar_functions.h new file mode 100644 index 00000000000000..1b57b29261eeb3 --- /dev/null +++ b/phonelibs/libyuv/include/libyuv/planar_functions.h @@ -0,0 +1,529 @@ +/* + * Copyright 2011 The LibYuv Project Authors. All rights reserved. + * + * Use of this source code is governed by a BSD-style license + * that can be found in the LICENSE file in the root of the source + * tree. An additional intellectual property rights grant can be found + * in the file PATENTS. All contributing project authors may + * be found in the AUTHORS file in the root of the source tree. + */ + +#ifndef INCLUDE_LIBYUV_PLANAR_FUNCTIONS_H_ +#define INCLUDE_LIBYUV_PLANAR_FUNCTIONS_H_ + +#include "libyuv/basic_types.h" + +// TODO(fbarchard): Remove the following headers includes. +#include "libyuv/convert.h" +#include "libyuv/convert_argb.h" + +#ifdef __cplusplus +namespace libyuv { +extern "C" { +#endif + +// Copy a plane of data. +LIBYUV_API +void CopyPlane(const uint8* src_y, int src_stride_y, + uint8* dst_y, int dst_stride_y, + int width, int height); + +LIBYUV_API +void CopyPlane_16(const uint16* src_y, int src_stride_y, + uint16* dst_y, int dst_stride_y, + int width, int height); + +// Set a plane of data to a 32 bit value. +LIBYUV_API +void SetPlane(uint8* dst_y, int dst_stride_y, + int width, int height, + uint32 value); + +// Split interleaved UV plane into separate U and V planes. +LIBYUV_API +void SplitUVPlane(const uint8* src_uv, int src_stride_uv, + uint8* dst_u, int dst_stride_u, + uint8* dst_v, int dst_stride_v, + int width, int height); + +// Merge separate U and V planes into one interleaved UV plane. +LIBYUV_API +void MergeUVPlane(const uint8* src_u, int src_stride_u, + const uint8* src_v, int src_stride_v, + uint8* dst_uv, int dst_stride_uv, + int width, int height); + +// Copy I400. Supports inverting. +LIBYUV_API +int I400ToI400(const uint8* src_y, int src_stride_y, + uint8* dst_y, int dst_stride_y, + int width, int height); + +#define J400ToJ400 I400ToI400 + +// Copy I422 to I422. +#define I422ToI422 I422Copy +LIBYUV_API +int I422Copy(const uint8* src_y, int src_stride_y, + const uint8* src_u, int src_stride_u, + const uint8* src_v, int src_stride_v, + uint8* dst_y, int dst_stride_y, + uint8* dst_u, int dst_stride_u, + uint8* dst_v, int dst_stride_v, + int width, int height); + +// Copy I444 to I444. +#define I444ToI444 I444Copy +LIBYUV_API +int I444Copy(const uint8* src_y, int src_stride_y, + const uint8* src_u, int src_stride_u, + const uint8* src_v, int src_stride_v, + uint8* dst_y, int dst_stride_y, + uint8* dst_u, int dst_stride_u, + uint8* dst_v, int dst_stride_v, + int width, int height); + +// Convert YUY2 to I422. +LIBYUV_API +int YUY2ToI422(const uint8* src_yuy2, int src_stride_yuy2, + uint8* dst_y, int dst_stride_y, + uint8* dst_u, int dst_stride_u, + uint8* dst_v, int dst_stride_v, + int width, int height); + +// Convert UYVY to I422. +LIBYUV_API +int UYVYToI422(const uint8* src_uyvy, int src_stride_uyvy, + uint8* dst_y, int dst_stride_y, + uint8* dst_u, int dst_stride_u, + uint8* dst_v, int dst_stride_v, + int width, int height); + +LIBYUV_API +int YUY2ToNV12(const uint8* src_yuy2, int src_stride_yuy2, + uint8* dst_y, int dst_stride_y, + uint8* dst_uv, int dst_stride_uv, + int width, int height); + +LIBYUV_API +int UYVYToNV12(const uint8* src_uyvy, int src_stride_uyvy, + uint8* dst_y, int dst_stride_y, + uint8* dst_uv, int dst_stride_uv, + int width, int height); + +// Convert I420 to I400. (calls CopyPlane ignoring u/v). +LIBYUV_API +int I420ToI400(const uint8* src_y, int src_stride_y, + const uint8* src_u, int src_stride_u, + const uint8* src_v, int src_stride_v, + uint8* dst_y, int dst_stride_y, + int width, int height); + +// Alias +#define J420ToJ400 I420ToI400 +#define I420ToI420Mirror I420Mirror + +// I420 mirror. +LIBYUV_API +int I420Mirror(const uint8* src_y, int src_stride_y, + const uint8* src_u, int src_stride_u, + const uint8* src_v, int src_stride_v, + uint8* dst_y, int dst_stride_y, + uint8* dst_u, int dst_stride_u, + uint8* dst_v, int dst_stride_v, + int width, int height); + +// Alias +#define I400ToI400Mirror I400Mirror + +// I400 mirror. A single plane is mirrored horizontally. +// Pass negative height to achieve 180 degree rotation. +LIBYUV_API +int I400Mirror(const uint8* src_y, int src_stride_y, + uint8* dst_y, int dst_stride_y, + int width, int height); + +// Alias +#define ARGBToARGBMirror ARGBMirror + +// ARGB mirror. +LIBYUV_API +int ARGBMirror(const uint8* src_argb, int src_stride_argb, + uint8* dst_argb, int dst_stride_argb, + int width, int height); + +// Convert NV12 to RGB565. +LIBYUV_API +int NV12ToRGB565(const uint8* src_y, int src_stride_y, + const uint8* src_uv, int src_stride_uv, + uint8* dst_rgb565, int dst_stride_rgb565, + int width, int height); + +// I422ToARGB is in convert_argb.h +// Convert I422 to BGRA. +LIBYUV_API +int I422ToBGRA(const uint8* src_y, int src_stride_y, + const uint8* src_u, int src_stride_u, + const uint8* src_v, int src_stride_v, + uint8* dst_bgra, int dst_stride_bgra, + int width, int height); + +// Convert I422 to ABGR. +LIBYUV_API +int I422ToABGR(const uint8* src_y, int src_stride_y, + const uint8* src_u, int src_stride_u, + const uint8* src_v, int src_stride_v, + uint8* dst_abgr, int dst_stride_abgr, + int width, int height); + +// Convert I422 to RGBA. +LIBYUV_API +int I422ToRGBA(const uint8* src_y, int src_stride_y, + const uint8* src_u, int src_stride_u, + const uint8* src_v, int src_stride_v, + uint8* dst_rgba, int dst_stride_rgba, + int width, int height); + +// Alias +#define RGB24ToRAW RAWToRGB24 + +LIBYUV_API +int RAWToRGB24(const uint8* src_raw, int src_stride_raw, + uint8* dst_rgb24, int dst_stride_rgb24, + int width, int height); + +// Draw a rectangle into I420. +LIBYUV_API +int I420Rect(uint8* dst_y, int dst_stride_y, + uint8* dst_u, int dst_stride_u, + uint8* dst_v, int dst_stride_v, + int x, int y, int width, int height, + int value_y, int value_u, int value_v); + +// Draw a rectangle into ARGB. +LIBYUV_API +int ARGBRect(uint8* dst_argb, int dst_stride_argb, + int x, int y, int width, int height, uint32 value); + +// Convert ARGB to gray scale ARGB. +LIBYUV_API +int ARGBGrayTo(const uint8* src_argb, int src_stride_argb, + uint8* dst_argb, int dst_stride_argb, + int width, int height); + +// Make a rectangle of ARGB gray scale. +LIBYUV_API +int ARGBGray(uint8* dst_argb, int dst_stride_argb, + int x, int y, int width, int height); + +// Make a rectangle of ARGB Sepia tone. +LIBYUV_API +int ARGBSepia(uint8* dst_argb, int dst_stride_argb, + int x, int y, int width, int height); + +// Apply a matrix rotation to each ARGB pixel. +// matrix_argb is 4 signed ARGB values. -128 to 127 representing -2 to 2. +// The first 4 coefficients apply to B, G, R, A and produce B of the output. +// The next 4 coefficients apply to B, G, R, A and produce G of the output. +// The next 4 coefficients apply to B, G, R, A and produce R of the output. +// The last 4 coefficients apply to B, G, R, A and produce A of the output. +LIBYUV_API +int ARGBColorMatrix(const uint8* src_argb, int src_stride_argb, + uint8* dst_argb, int dst_stride_argb, + const int8* matrix_argb, + int width, int height); + +// Deprecated. Use ARGBColorMatrix instead. +// Apply a matrix rotation to each ARGB pixel. +// matrix_argb is 3 signed ARGB values. -128 to 127 representing -1 to 1. +// The first 4 coefficients apply to B, G, R, A and produce B of the output. +// The next 4 coefficients apply to B, G, R, A and produce G of the output. +// The last 4 coefficients apply to B, G, R, A and produce R of the output. +LIBYUV_API +int RGBColorMatrix(uint8* dst_argb, int dst_stride_argb, + const int8* matrix_rgb, + int x, int y, int width, int height); + +// Apply a color table each ARGB pixel. +// Table contains 256 ARGB values. +LIBYUV_API +int ARGBColorTable(uint8* dst_argb, int dst_stride_argb, + const uint8* table_argb, + int x, int y, int width, int height); + +// Apply a color table each ARGB pixel but preserve destination alpha. +// Table contains 256 ARGB values. +LIBYUV_API +int RGBColorTable(uint8* dst_argb, int dst_stride_argb, + const uint8* table_argb, + int x, int y, int width, int height); + +// Apply a luma/color table each ARGB pixel but preserve destination alpha. +// Table contains 32768 values indexed by [Y][C] where 7 it 7 bit luma from +// RGB (YJ style) and C is an 8 bit color component (R, G or B). +LIBYUV_API +int ARGBLumaColorTable(const uint8* src_argb, int src_stride_argb, + uint8* dst_argb, int dst_stride_argb, + const uint8* luma_rgb_table, + int width, int height); + +// Apply a 3 term polynomial to ARGB values. +// poly points to a 4x4 matrix. The first row is constants. The 2nd row is +// coefficients for b, g, r and a. The 3rd row is coefficients for b squared, +// g squared, r squared and a squared. The 4rd row is coefficients for b to +// the 3, g to the 3, r to the 3 and a to the 3. The values are summed and +// result clamped to 0 to 255. +// A polynomial approximation can be dirived using software such as 'R'. + +LIBYUV_API +int ARGBPolynomial(const uint8* src_argb, int src_stride_argb, + uint8* dst_argb, int dst_stride_argb, + const float* poly, + int width, int height); + +// Convert plane of 16 bit shorts to half floats. +// Source values are multiplied by scale before storing as half float. +LIBYUV_API +int HalfFloatPlane(const uint16* src_y, int src_stride_y, + uint16* dst_y, int dst_stride_y, + float scale, + int width, int height); + +// Quantize a rectangle of ARGB. Alpha unaffected. +// scale is a 16 bit fractional fixed point scaler between 0 and 65535. +// interval_size should be a value between 1 and 255. +// interval_offset should be a value between 0 and 255. +LIBYUV_API +int ARGBQuantize(uint8* dst_argb, int dst_stride_argb, + int scale, int interval_size, int interval_offset, + int x, int y, int width, int height); + +// Copy ARGB to ARGB. +LIBYUV_API +int ARGBCopy(const uint8* src_argb, int src_stride_argb, + uint8* dst_argb, int dst_stride_argb, + int width, int height); + +// Copy Alpha channel of ARGB to alpha of ARGB. +LIBYUV_API +int ARGBCopyAlpha(const uint8* src_argb, int src_stride_argb, + uint8* dst_argb, int dst_stride_argb, + int width, int height); + +// Extract the alpha channel from ARGB. +LIBYUV_API +int ARGBExtractAlpha(const uint8* src_argb, int src_stride_argb, + uint8* dst_a, int dst_stride_a, + int width, int height); + +// Copy Y channel to Alpha of ARGB. +LIBYUV_API +int ARGBCopyYToAlpha(const uint8* src_y, int src_stride_y, + uint8* dst_argb, int dst_stride_argb, + int width, int height); + +typedef void (*ARGBBlendRow)(const uint8* src_argb0, const uint8* src_argb1, + uint8* dst_argb, int width); + +// Get function to Alpha Blend ARGB pixels and store to destination. +LIBYUV_API +ARGBBlendRow GetARGBBlend(); + +// Alpha Blend ARGB images and store to destination. +// Source is pre-multiplied by alpha using ARGBAttenuate. +// Alpha of destination is set to 255. +LIBYUV_API +int ARGBBlend(const uint8* src_argb0, int src_stride_argb0, + const uint8* src_argb1, int src_stride_argb1, + uint8* dst_argb, int dst_stride_argb, + int width, int height); + +// Alpha Blend plane and store to destination. +// Source is not pre-multiplied by alpha. +LIBYUV_API +int BlendPlane(const uint8* src_y0, int src_stride_y0, + const uint8* src_y1, int src_stride_y1, + const uint8* alpha, int alpha_stride, + uint8* dst_y, int dst_stride_y, + int width, int height); + +// Alpha Blend YUV images and store to destination. +// Source is not pre-multiplied by alpha. +// Alpha is full width x height and subsampled to half size to apply to UV. +LIBYUV_API +int I420Blend(const uint8* src_y0, int src_stride_y0, + const uint8* src_u0, int src_stride_u0, + const uint8* src_v0, int src_stride_v0, + const uint8* src_y1, int src_stride_y1, + const uint8* src_u1, int src_stride_u1, + const uint8* src_v1, int src_stride_v1, + const uint8* alpha, int alpha_stride, + uint8* dst_y, int dst_stride_y, + uint8* dst_u, int dst_stride_u, + uint8* dst_v, int dst_stride_v, + int width, int height); + +// Multiply ARGB image by ARGB image. Shifted down by 8. Saturates to 255. +LIBYUV_API +int ARGBMultiply(const uint8* src_argb0, int src_stride_argb0, + const uint8* src_argb1, int src_stride_argb1, + uint8* dst_argb, int dst_stride_argb, + int width, int height); + +// Add ARGB image with ARGB image. Saturates to 255. +LIBYUV_API +int ARGBAdd(const uint8* src_argb0, int src_stride_argb0, + const uint8* src_argb1, int src_stride_argb1, + uint8* dst_argb, int dst_stride_argb, + int width, int height); + +// Subtract ARGB image (argb1) from ARGB image (argb0). Saturates to 0. +LIBYUV_API +int ARGBSubtract(const uint8* src_argb0, int src_stride_argb0, + const uint8* src_argb1, int src_stride_argb1, + uint8* dst_argb, int dst_stride_argb, + int width, int height); + +// Convert I422 to YUY2. +LIBYUV_API +int I422ToYUY2(const uint8* src_y, int src_stride_y, + const uint8* src_u, int src_stride_u, + const uint8* src_v, int src_stride_v, + uint8* dst_frame, int dst_stride_frame, + int width, int height); + +// Convert I422 to UYVY. +LIBYUV_API +int I422ToUYVY(const uint8* src_y, int src_stride_y, + const uint8* src_u, int src_stride_u, + const uint8* src_v, int src_stride_v, + uint8* dst_frame, int dst_stride_frame, + int width, int height); + +// Convert unattentuated ARGB to preattenuated ARGB. +LIBYUV_API +int ARGBAttenuate(const uint8* src_argb, int src_stride_argb, + uint8* dst_argb, int dst_stride_argb, + int width, int height); + +// Convert preattentuated ARGB to unattenuated ARGB. +LIBYUV_API +int ARGBUnattenuate(const uint8* src_argb, int src_stride_argb, + uint8* dst_argb, int dst_stride_argb, + int width, int height); + +// Internal function - do not call directly. +// Computes table of cumulative sum for image where the value is the sum +// of all values above and to the left of the entry. Used by ARGBBlur. +LIBYUV_API +int ARGBComputeCumulativeSum(const uint8* src_argb, int src_stride_argb, + int32* dst_cumsum, int dst_stride32_cumsum, + int width, int height); + +// Blur ARGB image. +// dst_cumsum table of width * (height + 1) * 16 bytes aligned to +// 16 byte boundary. +// dst_stride32_cumsum is number of ints in a row (width * 4). +// radius is number of pixels around the center. e.g. 1 = 3x3. 2=5x5. +// Blur is optimized for radius of 5 (11x11) or less. +LIBYUV_API +int ARGBBlur(const uint8* src_argb, int src_stride_argb, + uint8* dst_argb, int dst_stride_argb, + int32* dst_cumsum, int dst_stride32_cumsum, + int width, int height, int radius); + +// Multiply ARGB image by ARGB value. +LIBYUV_API +int ARGBShade(const uint8* src_argb, int src_stride_argb, + uint8* dst_argb, int dst_stride_argb, + int width, int height, uint32 value); + +// Interpolate between two images using specified amount of interpolation +// (0 to 255) and store to destination. +// 'interpolation' is specified as 8 bit fraction where 0 means 100% src0 +// and 255 means 1% src0 and 99% src1. +LIBYUV_API +int InterpolatePlane(const uint8* src0, int src_stride0, + const uint8* src1, int src_stride1, + uint8* dst, int dst_stride, + int width, int height, int interpolation); + +// Interpolate between two ARGB images using specified amount of interpolation +// Internally calls InterpolatePlane with width * 4 (bpp). +LIBYUV_API +int ARGBInterpolate(const uint8* src_argb0, int src_stride_argb0, + const uint8* src_argb1, int src_stride_argb1, + uint8* dst_argb, int dst_stride_argb, + int width, int height, int interpolation); + +// Interpolate between two YUV images using specified amount of interpolation +// Internally calls InterpolatePlane on each plane where the U and V planes +// are half width and half height. +LIBYUV_API +int I420Interpolate(const uint8* src0_y, int src0_stride_y, + const uint8* src0_u, int src0_stride_u, + const uint8* src0_v, int src0_stride_v, + const uint8* src1_y, int src1_stride_y, + const uint8* src1_u, int src1_stride_u, + const uint8* src1_v, int src1_stride_v, + uint8* dst_y, int dst_stride_y, + uint8* dst_u, int dst_stride_u, + uint8* dst_v, int dst_stride_v, + int width, int height, int interpolation); + +#if defined(__pnacl__) || defined(__CLR_VER) || \ + (defined(__i386__) && !defined(__SSE2__)) +#define LIBYUV_DISABLE_X86 +#endif +// MemorySanitizer does not support assembly code yet. http://crbug.com/344505 +#if defined(__has_feature) +#if __has_feature(memory_sanitizer) +#define LIBYUV_DISABLE_X86 +#endif +#endif +// The following are available on all x86 platforms: +#if !defined(LIBYUV_DISABLE_X86) && \ + (defined(_M_IX86) || defined(__x86_64__) || defined(__i386__)) +#define HAS_ARGBAFFINEROW_SSE2 +#endif + +// Row function for copying pixels from a source with a slope to a row +// of destination. Useful for scaling, rotation, mirror, texture mapping. +LIBYUV_API +void ARGBAffineRow_C(const uint8* src_argb, int src_argb_stride, + uint8* dst_argb, const float* uv_dudv, int width); +LIBYUV_API +void ARGBAffineRow_SSE2(const uint8* src_argb, int src_argb_stride, + uint8* dst_argb, const float* uv_dudv, int width); + +// Shuffle ARGB channel order. e.g. BGRA to ARGB. +// shuffler is 16 bytes and must be aligned. +LIBYUV_API +int ARGBShuffle(const uint8* src_bgra, int src_stride_bgra, + uint8* dst_argb, int dst_stride_argb, + const uint8* shuffler, int width, int height); + +// Sobel ARGB effect with planar output. +LIBYUV_API +int ARGBSobelToPlane(const uint8* src_argb, int src_stride_argb, + uint8* dst_y, int dst_stride_y, + int width, int height); + +// Sobel ARGB effect. +LIBYUV_API +int ARGBSobel(const uint8* src_argb, int src_stride_argb, + uint8* dst_argb, int dst_stride_argb, + int width, int height); + +// Sobel ARGB effect w/ Sobel X, Sobel, Sobel Y in ARGB. +LIBYUV_API +int ARGBSobelXY(const uint8* src_argb, int src_stride_argb, + uint8* dst_argb, int dst_stride_argb, + int width, int height); + +#ifdef __cplusplus +} // extern "C" +} // namespace libyuv +#endif + +#endif // INCLUDE_LIBYUV_PLANAR_FUNCTIONS_H_ diff --git a/phonelibs/libyuv/include/libyuv/rotate.h b/phonelibs/libyuv/include/libyuv/rotate.h new file mode 100644 index 00000000000000..8a2da9a5aad5c5 --- /dev/null +++ b/phonelibs/libyuv/include/libyuv/rotate.h @@ -0,0 +1,117 @@ +/* + * Copyright 2011 The LibYuv Project Authors. All rights reserved. + * + * Use of this source code is governed by a BSD-style license + * that can be found in the LICENSE file in the root of the source + * tree. An additional intellectual property rights grant can be found + * in the file PATENTS. All contributing project authors may + * be found in the AUTHORS file in the root of the source tree. + */ + +#ifndef INCLUDE_LIBYUV_ROTATE_H_ +#define INCLUDE_LIBYUV_ROTATE_H_ + +#include "libyuv/basic_types.h" + +#ifdef __cplusplus +namespace libyuv { +extern "C" { +#endif + +// Supported rotation. +typedef enum RotationMode { + kRotate0 = 0, // No rotation. + kRotate90 = 90, // Rotate 90 degrees clockwise. + kRotate180 = 180, // Rotate 180 degrees. + kRotate270 = 270, // Rotate 270 degrees clockwise. + + // Deprecated. + kRotateNone = 0, + kRotateClockwise = 90, + kRotateCounterClockwise = 270, +} RotationModeEnum; + +// Rotate I420 frame. +LIBYUV_API +int I420Rotate(const uint8* src_y, int src_stride_y, + const uint8* src_u, int src_stride_u, + const uint8* src_v, int src_stride_v, + uint8* dst_y, int dst_stride_y, + uint8* dst_u, int dst_stride_u, + uint8* dst_v, int dst_stride_v, + int src_width, int src_height, enum RotationMode mode); + +// Rotate NV12 input and store in I420. +LIBYUV_API +int NV12ToI420Rotate(const uint8* src_y, int src_stride_y, + const uint8* src_uv, int src_stride_uv, + uint8* dst_y, int dst_stride_y, + uint8* dst_u, int dst_stride_u, + uint8* dst_v, int dst_stride_v, + int src_width, int src_height, enum RotationMode mode); + +// Rotate a plane by 0, 90, 180, or 270. +LIBYUV_API +int RotatePlane(const uint8* src, int src_stride, + uint8* dst, int dst_stride, + int src_width, int src_height, enum RotationMode mode); + +// Rotate planes by 90, 180, 270. Deprecated. +LIBYUV_API +void RotatePlane90(const uint8* src, int src_stride, + uint8* dst, int dst_stride, + int width, int height); + +LIBYUV_API +void RotatePlane180(const uint8* src, int src_stride, + uint8* dst, int dst_stride, + int width, int height); + +LIBYUV_API +void RotatePlane270(const uint8* src, int src_stride, + uint8* dst, int dst_stride, + int width, int height); + +LIBYUV_API +void RotateUV90(const uint8* src, int src_stride, + uint8* dst_a, int dst_stride_a, + uint8* dst_b, int dst_stride_b, + int width, int height); + +// Rotations for when U and V are interleaved. +// These functions take one input pointer and +// split the data into two buffers while +// rotating them. Deprecated. +LIBYUV_API +void RotateUV180(const uint8* src, int src_stride, + uint8* dst_a, int dst_stride_a, + uint8* dst_b, int dst_stride_b, + int width, int height); + +LIBYUV_API +void RotateUV270(const uint8* src, int src_stride, + uint8* dst_a, int dst_stride_a, + uint8* dst_b, int dst_stride_b, + int width, int height); + +// The 90 and 270 functions are based on transposes. +// Doing a transpose with reversing the read/write +// order will result in a rotation by +- 90 degrees. +// Deprecated. +LIBYUV_API +void TransposePlane(const uint8* src, int src_stride, + uint8* dst, int dst_stride, + int width, int height); + +LIBYUV_API +void TransposeUV(const uint8* src, int src_stride, + uint8* dst_a, int dst_stride_a, + uint8* dst_b, int dst_stride_b, + int width, int height); + +#ifdef __cplusplus +} // extern "C" +} // namespace libyuv +#endif + +#endif // INCLUDE_LIBYUV_ROTATE_H_ diff --git a/phonelibs/libyuv/include/libyuv/rotate_argb.h b/phonelibs/libyuv/include/libyuv/rotate_argb.h new file mode 100644 index 00000000000000..21fe7e1807c334 --- /dev/null +++ b/phonelibs/libyuv/include/libyuv/rotate_argb.h @@ -0,0 +1,33 @@ +/* + * Copyright 2012 The LibYuv Project Authors. All rights reserved. + * + * Use of this source code is governed by a BSD-style license + * that can be found in the LICENSE file in the root of the source + * tree. An additional intellectual property rights grant can be found + * in the file PATENTS. All contributing project authors may + * be found in the AUTHORS file in the root of the source tree. + */ + +#ifndef INCLUDE_LIBYUV_ROTATE_ARGB_H_ +#define INCLUDE_LIBYUV_ROTATE_ARGB_H_ + +#include "libyuv/basic_types.h" +#include "libyuv/rotate.h" // For RotationMode. + +#ifdef __cplusplus +namespace libyuv { +extern "C" { +#endif + +// Rotate ARGB frame +LIBYUV_API +int ARGBRotate(const uint8* src_argb, int src_stride_argb, + uint8* dst_argb, int dst_stride_argb, + int src_width, int src_height, enum RotationMode mode); + +#ifdef __cplusplus +} // extern "C" +} // namespace libyuv +#endif + +#endif // INCLUDE_LIBYUV_ROTATE_ARGB_H_ diff --git a/phonelibs/libyuv/include/libyuv/rotate_row.h b/phonelibs/libyuv/include/libyuv/rotate_row.h new file mode 100644 index 00000000000000..6abd201677460b --- /dev/null +++ b/phonelibs/libyuv/include/libyuv/rotate_row.h @@ -0,0 +1,121 @@ +/* + * Copyright 2013 The LibYuv Project Authors. All rights reserved. + * + * Use of this source code is governed by a BSD-style license + * that can be found in the LICENSE file in the root of the source + * tree. An additional intellectual property rights grant can be found + * in the file PATENTS. All contributing project authors may + * be found in the AUTHORS file in the root of the source tree. + */ + +#ifndef INCLUDE_LIBYUV_ROTATE_ROW_H_ +#define INCLUDE_LIBYUV_ROTATE_ROW_H_ + +#include "libyuv/basic_types.h" + +#ifdef __cplusplus +namespace libyuv { +extern "C" { +#endif + +#if defined(__pnacl__) || defined(__CLR_VER) || \ + (defined(__i386__) && !defined(__SSE2__)) +#define LIBYUV_DISABLE_X86 +#endif +// MemorySanitizer does not support assembly code yet. http://crbug.com/344505 +#if defined(__has_feature) +#if __has_feature(memory_sanitizer) +#define LIBYUV_DISABLE_X86 +#endif +#endif +// The following are available for Visual C and clangcl 32 bit: +#if !defined(LIBYUV_DISABLE_X86) && defined(_M_IX86) +#define HAS_TRANSPOSEWX8_SSSE3 +#define HAS_TRANSPOSEUVWX8_SSE2 +#endif + +// The following are available for GCC 32 or 64 bit but not NaCL for 64 bit: +#if !defined(LIBYUV_DISABLE_X86) && \ + (defined(__i386__) || (defined(__x86_64__) && !defined(__native_client__))) +#define HAS_TRANSPOSEWX8_SSSE3 +#endif + +// The following are available for 64 bit GCC but not NaCL: +#if !defined(LIBYUV_DISABLE_X86) && !defined(__native_client__) && \ + defined(__x86_64__) +#define HAS_TRANSPOSEWX8_FAST_SSSE3 +#define HAS_TRANSPOSEUVWX8_SSE2 +#endif + +#if !defined(LIBYUV_DISABLE_NEON) && !defined(__native_client__) && \ + (defined(__ARM_NEON__) || defined(LIBYUV_NEON) || defined(__aarch64__)) +#define HAS_TRANSPOSEWX8_NEON +#define HAS_TRANSPOSEUVWX8_NEON +#endif + +#if !defined(LIBYUV_DISABLE_MIPS) && !defined(__native_client__) && \ + defined(__mips__) && \ + defined(__mips_dsp) && (__mips_dsp_rev >= 2) +#define HAS_TRANSPOSEWX8_DSPR2 +#define HAS_TRANSPOSEUVWX8_DSPR2 +#endif // defined(__mips__) + +void TransposeWxH_C(const uint8* src, int src_stride, + uint8* dst, int dst_stride, int width, int height); + +void TransposeWx8_C(const uint8* src, int src_stride, + uint8* dst, int dst_stride, int width); +void TransposeWx8_NEON(const uint8* src, int src_stride, + uint8* dst, int dst_stride, int width); +void TransposeWx8_SSSE3(const uint8* src, int src_stride, + uint8* dst, int dst_stride, int width); +void TransposeWx8_Fast_SSSE3(const uint8* src, int src_stride, + uint8* dst, int dst_stride, int width); +void TransposeWx8_DSPR2(const uint8* src, int src_stride, + uint8* dst, int dst_stride, int width); +void TransposeWx8_Fast_DSPR2(const uint8* src, int src_stride, + uint8* dst, int dst_stride, int width); + +void TransposeWx8_Any_NEON(const uint8* src, int src_stride, + uint8* dst, int dst_stride, int width); +void TransposeWx8_Any_SSSE3(const uint8* src, int src_stride, + uint8* dst, int dst_stride, int width); +void TransposeWx8_Fast_Any_SSSE3(const uint8* src, int src_stride, + uint8* dst, int dst_stride, int width); +void TransposeWx8_Any_DSPR2(const uint8* src, int src_stride, + uint8* dst, int dst_stride, int width); + +void TransposeUVWxH_C(const uint8* src, int src_stride, + uint8* dst_a, int dst_stride_a, + uint8* dst_b, int dst_stride_b, + int width, int height); + +void TransposeUVWx8_C(const uint8* src, int src_stride, + uint8* dst_a, int dst_stride_a, + uint8* dst_b, int dst_stride_b, int width); +void TransposeUVWx8_SSE2(const uint8* src, int src_stride, + uint8* dst_a, int dst_stride_a, + uint8* dst_b, int dst_stride_b, int width); +void TransposeUVWx8_NEON(const uint8* src, int src_stride, + uint8* dst_a, int dst_stride_a, + uint8* dst_b, int dst_stride_b, int width); +void TransposeUVWx8_DSPR2(const uint8* src, int src_stride, + uint8* dst_a, int dst_stride_a, + uint8* dst_b, int dst_stride_b, int width); + +void TransposeUVWx8_Any_SSE2(const uint8* src, int src_stride, + uint8* dst_a, int dst_stride_a, + uint8* dst_b, int dst_stride_b, int width); +void TransposeUVWx8_Any_NEON(const uint8* src, int src_stride, + uint8* dst_a, int dst_stride_a, + uint8* dst_b, int dst_stride_b, int width); +void TransposeUVWx8_Any_DSPR2(const uint8* src, int src_stride, + uint8* dst_a, int dst_stride_a, + uint8* dst_b, int dst_stride_b, int width); + +#ifdef __cplusplus +} // extern "C" +} // namespace libyuv +#endif + +#endif // INCLUDE_LIBYUV_ROTATE_ROW_H_ diff --git a/phonelibs/libyuv/include/libyuv/row.h b/phonelibs/libyuv/include/libyuv/row.h new file mode 100644 index 00000000000000..b810221ec7a787 --- /dev/null +++ b/phonelibs/libyuv/include/libyuv/row.h @@ -0,0 +1,1963 @@ +/* + * Copyright 2011 The LibYuv Project Authors. All rights reserved. + * + * Use of this source code is governed by a BSD-style license + * that can be found in the LICENSE file in the root of the source + * tree. An additional intellectual property rights grant can be found + * in the file PATENTS. All contributing project authors may + * be found in the AUTHORS file in the root of the source tree. + */ + +#ifndef INCLUDE_LIBYUV_ROW_H_ +#define INCLUDE_LIBYUV_ROW_H_ + +#include // For malloc. + +#include "libyuv/basic_types.h" + +#ifdef __cplusplus +namespace libyuv { +extern "C" { +#endif + +#define IS_ALIGNED(p, a) (!((uintptr_t)(p) & ((a) - 1))) + +#define align_buffer_64(var, size) \ + uint8* var##_mem = (uint8*)(malloc((size) + 63)); /* NOLINT */ \ + uint8* var = (uint8*)(((intptr_t)(var##_mem) + 63) & ~63) /* NOLINT */ + +#define free_aligned_buffer_64(var) \ + free(var##_mem); \ + var = 0 + +#if defined(__pnacl__) || defined(__CLR_VER) || \ + (defined(__i386__) && !defined(__SSE2__)) +#define LIBYUV_DISABLE_X86 +#endif +// MemorySanitizer does not support assembly code yet. http://crbug.com/344505 +#if defined(__has_feature) +#if __has_feature(memory_sanitizer) +#define LIBYUV_DISABLE_X86 +#endif +#endif +// True if compiling for SSSE3 as a requirement. +#if defined(__SSSE3__) || (defined(_M_IX86_FP) && (_M_IX86_FP >= 3)) +#define LIBYUV_SSSE3_ONLY +#endif + +#if defined(__native_client__) +#define LIBYUV_DISABLE_NEON +#endif +// clang >= 3.5.0 required for Arm64. +#if defined(__clang__) && defined(__aarch64__) && !defined(LIBYUV_DISABLE_NEON) +#if (__clang_major__ < 3) || (__clang_major__ == 3 && (__clang_minor__ < 5)) +#define LIBYUV_DISABLE_NEON +#endif // clang >= 3.5 +#endif // __clang__ + +// GCC >= 4.7.0 required for AVX2. +#if defined(__GNUC__) && (defined(__x86_64__) || defined(__i386__)) +#if (__GNUC__ > 4) || (__GNUC__ == 4 && (__GNUC_MINOR__ >= 7)) +#define GCC_HAS_AVX2 1 +#endif // GNUC >= 4.7 +#endif // __GNUC__ + +// clang >= 3.4.0 required for AVX2. +#if defined(__clang__) && (defined(__x86_64__) || defined(__i386__)) +#if (__clang_major__ > 3) || (__clang_major__ == 3 && (__clang_minor__ >= 4)) +#define CLANG_HAS_AVX2 1 +#endif // clang >= 3.4 +#endif // __clang__ + +// Visual C 2012 required for AVX2. +#if defined(_M_IX86) && !defined(__clang__) && \ + defined(_MSC_VER) && _MSC_VER >= 1700 +#define VISUALC_HAS_AVX2 1 +#endif // VisualStudio >= 2012 + +// The following are available on all x86 platforms: +#if !defined(LIBYUV_DISABLE_X86) && \ + (defined(_M_IX86) || defined(__x86_64__) || defined(__i386__)) +// Conversions: +#define HAS_ABGRTOUVROW_SSSE3 +#define HAS_ABGRTOYROW_SSSE3 +#define HAS_ARGB1555TOARGBROW_SSE2 +#define HAS_ARGB4444TOARGBROW_SSE2 +#define HAS_ARGBSETROW_X86 +#define HAS_ARGBSHUFFLEROW_SSE2 +#define HAS_ARGBSHUFFLEROW_SSSE3 +#define HAS_ARGBTOARGB1555ROW_SSE2 +#define HAS_ARGBTOARGB4444ROW_SSE2 +#define HAS_ARGBTORAWROW_SSSE3 +#define HAS_ARGBTORGB24ROW_SSSE3 +#define HAS_ARGBTORGB565DITHERROW_SSE2 +#define HAS_ARGBTORGB565ROW_SSE2 +#define HAS_ARGBTOUV444ROW_SSSE3 +#define HAS_ARGBTOUVJROW_SSSE3 +#define HAS_ARGBTOUVROW_SSSE3 +#define HAS_ARGBTOYJROW_SSSE3 +#define HAS_ARGBTOYROW_SSSE3 +#define HAS_ARGBEXTRACTALPHAROW_SSE2 +#define HAS_BGRATOUVROW_SSSE3 +#define HAS_BGRATOYROW_SSSE3 +#define HAS_COPYROW_ERMS +#define HAS_COPYROW_SSE2 +#define HAS_H422TOARGBROW_SSSE3 +#define HAS_I400TOARGBROW_SSE2 +#define HAS_I422TOARGB1555ROW_SSSE3 +#define HAS_I422TOARGB4444ROW_SSSE3 +#define HAS_I422TOARGBROW_SSSE3 +#define HAS_I422TORGB24ROW_SSSE3 +#define HAS_I422TORGB565ROW_SSSE3 +#define HAS_I422TORGBAROW_SSSE3 +#define HAS_I422TOUYVYROW_SSE2 +#define HAS_I422TOYUY2ROW_SSE2 +#define HAS_I444TOARGBROW_SSSE3 +#define HAS_J400TOARGBROW_SSE2 +#define HAS_J422TOARGBROW_SSSE3 +#define HAS_MERGEUVROW_SSE2 +#define HAS_MIRRORROW_SSSE3 +#define HAS_MIRRORUVROW_SSSE3 +#define HAS_NV12TOARGBROW_SSSE3 +#define HAS_NV12TORGB565ROW_SSSE3 +#define HAS_NV21TOARGBROW_SSSE3 +#define HAS_RAWTOARGBROW_SSSE3 +#define HAS_RAWTORGB24ROW_SSSE3 +#define HAS_RAWTOYROW_SSSE3 +#define HAS_RGB24TOARGBROW_SSSE3 +#define HAS_RGB24TOYROW_SSSE3 +#define HAS_RGB565TOARGBROW_SSE2 +#define HAS_RGBATOUVROW_SSSE3 +#define HAS_RGBATOYROW_SSSE3 +#define HAS_SETROW_ERMS +#define HAS_SETROW_X86 +#define HAS_SPLITUVROW_SSE2 +#define HAS_UYVYTOARGBROW_SSSE3 +#define HAS_UYVYTOUV422ROW_SSE2 +#define HAS_UYVYTOUVROW_SSE2 +#define HAS_UYVYTOYROW_SSE2 +#define HAS_YUY2TOARGBROW_SSSE3 +#define HAS_YUY2TOUV422ROW_SSE2 +#define HAS_YUY2TOUVROW_SSE2 +#define HAS_YUY2TOYROW_SSE2 + +// Effects: +#define HAS_ARGBADDROW_SSE2 +#define HAS_ARGBAFFINEROW_SSE2 +#define HAS_ARGBATTENUATEROW_SSSE3 +#define HAS_ARGBBLENDROW_SSSE3 +#define HAS_ARGBCOLORMATRIXROW_SSSE3 +#define HAS_ARGBCOLORTABLEROW_X86 +#define HAS_ARGBCOPYALPHAROW_SSE2 +#define HAS_ARGBCOPYYTOALPHAROW_SSE2 +#define HAS_ARGBGRAYROW_SSSE3 +#define HAS_ARGBLUMACOLORTABLEROW_SSSE3 +#define HAS_ARGBMIRRORROW_SSE2 +#define HAS_ARGBMULTIPLYROW_SSE2 +#define HAS_ARGBPOLYNOMIALROW_SSE2 +#define HAS_ARGBQUANTIZEROW_SSE2 +#define HAS_ARGBSEPIAROW_SSSE3 +#define HAS_ARGBSHADEROW_SSE2 +#define HAS_ARGBSUBTRACTROW_SSE2 +#define HAS_ARGBUNATTENUATEROW_SSE2 +#define HAS_BLENDPLANEROW_SSSE3 +#define HAS_COMPUTECUMULATIVESUMROW_SSE2 +#define HAS_CUMULATIVESUMTOAVERAGEROW_SSE2 +#define HAS_INTERPOLATEROW_SSSE3 +#define HAS_RGBCOLORTABLEROW_X86 +#define HAS_SOBELROW_SSE2 +#define HAS_SOBELTOPLANEROW_SSE2 +#define HAS_SOBELXROW_SSE2 +#define HAS_SOBELXYROW_SSE2 +#define HAS_SOBELYROW_SSE2 + +// The following functions fail on gcc/clang 32 bit with fpic and framepointer. +// caveat: clangcl uses row_win.cc which works. +#if defined(NDEBUG) || !(defined(_DEBUG) && defined(__i386__)) || \ + !defined(__i386__) || defined(_MSC_VER) +// TODO(fbarchard): fix build error on x86 debug +// https://code.google.com/p/libyuv/issues/detail?id=524 +#define HAS_I411TOARGBROW_SSSE3 +// TODO(fbarchard): fix build error on android_full_debug=1 +// https://code.google.com/p/libyuv/issues/detail?id=517 +#define HAS_I422ALPHATOARGBROW_SSSE3 +#endif +#endif + +// The following are available on all x86 platforms, but +// require VS2012, clang 3.4 or gcc 4.7. +// The code supports NaCL but requires a new compiler and validator. +#if !defined(LIBYUV_DISABLE_X86) && (defined(VISUALC_HAS_AVX2) || \ + defined(CLANG_HAS_AVX2) || defined(GCC_HAS_AVX2)) +#define HAS_ARGBCOPYALPHAROW_AVX2 +#define HAS_ARGBCOPYYTOALPHAROW_AVX2 +#define HAS_ARGBMIRRORROW_AVX2 +#define HAS_ARGBPOLYNOMIALROW_AVX2 +#define HAS_ARGBSHUFFLEROW_AVX2 +#define HAS_ARGBTORGB565DITHERROW_AVX2 +#define HAS_ARGBTOUVJROW_AVX2 +#define HAS_ARGBTOUVROW_AVX2 +#define HAS_ARGBTOYJROW_AVX2 +#define HAS_ARGBTOYROW_AVX2 +#define HAS_COPYROW_AVX +#define HAS_H422TOARGBROW_AVX2 +#define HAS_I400TOARGBROW_AVX2 +#if !(defined(_DEBUG) && defined(__i386__)) +// TODO(fbarchard): fix build error on android_full_debug=1 +// https://code.google.com/p/libyuv/issues/detail?id=517 +#define HAS_I422ALPHATOARGBROW_AVX2 +#endif +#define HAS_I411TOARGBROW_AVX2 +#define HAS_I422TOARGB1555ROW_AVX2 +#define HAS_I422TOARGB4444ROW_AVX2 +#define HAS_I422TOARGBROW_AVX2 +#define HAS_I422TORGB24ROW_AVX2 +#define HAS_I422TORGB565ROW_AVX2 +#define HAS_I422TORGBAROW_AVX2 +#define HAS_I444TOARGBROW_AVX2 +#define HAS_INTERPOLATEROW_AVX2 +#define HAS_J422TOARGBROW_AVX2 +#define HAS_MERGEUVROW_AVX2 +#define HAS_MIRRORROW_AVX2 +#define HAS_NV12TOARGBROW_AVX2 +#define HAS_NV12TORGB565ROW_AVX2 +#define HAS_NV21TOARGBROW_AVX2 +#define HAS_SPLITUVROW_AVX2 +#define HAS_UYVYTOARGBROW_AVX2 +#define HAS_UYVYTOUV422ROW_AVX2 +#define HAS_UYVYTOUVROW_AVX2 +#define HAS_UYVYTOYROW_AVX2 +#define HAS_YUY2TOARGBROW_AVX2 +#define HAS_YUY2TOUV422ROW_AVX2 +#define HAS_YUY2TOUVROW_AVX2 +#define HAS_YUY2TOYROW_AVX2 +#define HAS_HALFFLOATROW_AVX2 + +// Effects: +#define HAS_ARGBADDROW_AVX2 +#define HAS_ARGBATTENUATEROW_AVX2 +#define HAS_ARGBMULTIPLYROW_AVX2 +#define HAS_ARGBSUBTRACTROW_AVX2 +#define HAS_ARGBUNATTENUATEROW_AVX2 +#define HAS_BLENDPLANEROW_AVX2 +#endif + +// The following are available for AVX2 Visual C and clangcl 32 bit: +// TODO(fbarchard): Port to gcc. +#if !defined(LIBYUV_DISABLE_X86) && defined(_M_IX86) && \ + (defined(VISUALC_HAS_AVX2) || defined(CLANG_HAS_AVX2)) +#define HAS_ARGB1555TOARGBROW_AVX2 +#define HAS_ARGB4444TOARGBROW_AVX2 +#define HAS_ARGBTOARGB1555ROW_AVX2 +#define HAS_ARGBTOARGB4444ROW_AVX2 +#define HAS_ARGBTORGB565ROW_AVX2 +#define HAS_J400TOARGBROW_AVX2 +#define HAS_RGB565TOARGBROW_AVX2 +#endif + +// The following are also available on x64 Visual C. +#if !defined(LIBYUV_DISABLE_X86) && defined(_MSC_VER) && defined(_M_X64) && \ + (!defined(__clang__) || defined(__SSSE3__)) +#define HAS_I422ALPHATOARGBROW_SSSE3 +#define HAS_I422TOARGBROW_SSSE3 +#endif + +// The following are available on gcc x86 platforms: +// TODO(fbarchard): Port to Visual C. +#if !defined(LIBYUV_DISABLE_X86) && \ + (defined(__x86_64__) || (defined(__i386__) && !defined(_MSC_VER))) +#define HAS_HALFFLOATROW_SSE2 +#endif + +// The following are available on Neon platforms: +#if !defined(LIBYUV_DISABLE_NEON) && \ + (defined(__aarch64__) || defined(__ARM_NEON__) || defined(LIBYUV_NEON)) +#define HAS_ABGRTOUVROW_NEON +#define HAS_ABGRTOYROW_NEON +#define HAS_ARGB1555TOARGBROW_NEON +#define HAS_ARGB1555TOUVROW_NEON +#define HAS_ARGB1555TOYROW_NEON +#define HAS_ARGB4444TOARGBROW_NEON +#define HAS_ARGB4444TOUVROW_NEON +#define HAS_ARGB4444TOYROW_NEON +#define HAS_ARGBSETROW_NEON +#define HAS_ARGBTOARGB1555ROW_NEON +#define HAS_ARGBTOARGB4444ROW_NEON +#define HAS_ARGBTORAWROW_NEON +#define HAS_ARGBTORGB24ROW_NEON +#define HAS_ARGBTORGB565DITHERROW_NEON +#define HAS_ARGBTORGB565ROW_NEON +#define HAS_ARGBTOUV411ROW_NEON +#define HAS_ARGBTOUV444ROW_NEON +#define HAS_ARGBTOUVJROW_NEON +#define HAS_ARGBTOUVROW_NEON +#define HAS_ARGBTOYJROW_NEON +#define HAS_ARGBTOYROW_NEON +#define HAS_ARGBEXTRACTALPHAROW_NEON +#define HAS_BGRATOUVROW_NEON +#define HAS_BGRATOYROW_NEON +#define HAS_COPYROW_NEON +#define HAS_I400TOARGBROW_NEON +#define HAS_I411TOARGBROW_NEON +#define HAS_I422ALPHATOARGBROW_NEON +#define HAS_I422TOARGB1555ROW_NEON +#define HAS_I422TOARGB4444ROW_NEON +#define HAS_I422TOARGBROW_NEON +#define HAS_I422TORGB24ROW_NEON +#define HAS_I422TORGB565ROW_NEON +#define HAS_I422TORGBAROW_NEON +#define HAS_I422TOUYVYROW_NEON +#define HAS_I422TOYUY2ROW_NEON +#define HAS_I444TOARGBROW_NEON +#define HAS_J400TOARGBROW_NEON +#define HAS_MERGEUVROW_NEON +#define HAS_MIRRORROW_NEON +#define HAS_MIRRORUVROW_NEON +#define HAS_NV12TOARGBROW_NEON +#define HAS_NV12TORGB565ROW_NEON +#define HAS_NV21TOARGBROW_NEON +#define HAS_RAWTOARGBROW_NEON +#define HAS_RAWTORGB24ROW_NEON +#define HAS_RAWTOUVROW_NEON +#define HAS_RAWTOYROW_NEON +#define HAS_RGB24TOARGBROW_NEON +#define HAS_RGB24TOUVROW_NEON +#define HAS_RGB24TOYROW_NEON +#define HAS_RGB565TOARGBROW_NEON +#define HAS_RGB565TOUVROW_NEON +#define HAS_RGB565TOYROW_NEON +#define HAS_RGBATOUVROW_NEON +#define HAS_RGBATOYROW_NEON +#define HAS_SETROW_NEON +#define HAS_SPLITUVROW_NEON +#define HAS_UYVYTOARGBROW_NEON +#define HAS_UYVYTOUV422ROW_NEON +#define HAS_UYVYTOUVROW_NEON +#define HAS_UYVYTOYROW_NEON +#define HAS_YUY2TOARGBROW_NEON +#define HAS_YUY2TOUV422ROW_NEON +#define HAS_YUY2TOUVROW_NEON +#define HAS_YUY2TOYROW_NEON + +// Effects: +#define HAS_ARGBADDROW_NEON +#define HAS_ARGBATTENUATEROW_NEON +#define HAS_ARGBBLENDROW_NEON +#define HAS_ARGBCOLORMATRIXROW_NEON +#define HAS_ARGBGRAYROW_NEON +#define HAS_ARGBMIRRORROW_NEON +#define HAS_ARGBMULTIPLYROW_NEON +#define HAS_ARGBQUANTIZEROW_NEON +#define HAS_ARGBSEPIAROW_NEON +#define HAS_ARGBSHADEROW_NEON +#define HAS_ARGBSHUFFLEROW_NEON +#define HAS_ARGBSUBTRACTROW_NEON +#define HAS_INTERPOLATEROW_NEON +#define HAS_SOBELROW_NEON +#define HAS_SOBELTOPLANEROW_NEON +#define HAS_SOBELXROW_NEON +#define HAS_SOBELXYROW_NEON +#define HAS_SOBELYROW_NEON +#endif + +// The following are available on Mips platforms: +#if !defined(LIBYUV_DISABLE_MIPS) && defined(__mips__) && \ + (_MIPS_SIM == _MIPS_SIM_ABI32) && (__mips_isa_rev < 6) +#define HAS_COPYROW_MIPS +#if defined(__mips_dsp) && (__mips_dsp_rev >= 2) +#define HAS_I422TOARGBROW_DSPR2 +#define HAS_INTERPOLATEROW_DSPR2 +#define HAS_MIRRORROW_DSPR2 +#define HAS_MIRRORUVROW_DSPR2 +#define HAS_SPLITUVROW_DSPR2 +#endif +#endif + +#if !defined(LIBYUV_DISABLE_MSA) && defined(__mips_msa) +#define HAS_MIRRORROW_MSA +#define HAS_ARGBMIRRORROW_MSA +#endif + +#if defined(_MSC_VER) && !defined(__CLR_VER) && !defined(__clang__) +#if defined(VISUALC_HAS_AVX2) +#define SIMD_ALIGNED(var) __declspec(align(32)) var +#else +#define SIMD_ALIGNED(var) __declspec(align(16)) var +#endif +typedef __declspec(align(16)) int16 vec16[8]; +typedef __declspec(align(16)) int32 vec32[4]; +typedef __declspec(align(16)) int8 vec8[16]; +typedef __declspec(align(16)) uint16 uvec16[8]; +typedef __declspec(align(16)) uint32 uvec32[4]; +typedef __declspec(align(16)) uint8 uvec8[16]; +typedef __declspec(align(32)) int16 lvec16[16]; +typedef __declspec(align(32)) int32 lvec32[8]; +typedef __declspec(align(32)) int8 lvec8[32]; +typedef __declspec(align(32)) uint16 ulvec16[16]; +typedef __declspec(align(32)) uint32 ulvec32[8]; +typedef __declspec(align(32)) uint8 ulvec8[32]; +#elif !defined(__pnacl__) && (defined(__GNUC__) || defined(__clang__)) +// Caveat GCC 4.2 to 4.7 have a known issue using vectors with const. +#if defined(CLANG_HAS_AVX2) || defined(GCC_HAS_AVX2) +#define SIMD_ALIGNED(var) var __attribute__((aligned(32))) +#else +#define SIMD_ALIGNED(var) var __attribute__((aligned(16))) +#endif +typedef int16 __attribute__((vector_size(16))) vec16; +typedef int32 __attribute__((vector_size(16))) vec32; +typedef int8 __attribute__((vector_size(16))) vec8; +typedef uint16 __attribute__((vector_size(16))) uvec16; +typedef uint32 __attribute__((vector_size(16))) uvec32; +typedef uint8 __attribute__((vector_size(16))) uvec8; +typedef int16 __attribute__((vector_size(32))) lvec16; +typedef int32 __attribute__((vector_size(32))) lvec32; +typedef int8 __attribute__((vector_size(32))) lvec8; +typedef uint16 __attribute__((vector_size(32))) ulvec16; +typedef uint32 __attribute__((vector_size(32))) ulvec32; +typedef uint8 __attribute__((vector_size(32))) ulvec8; +#else +#define SIMD_ALIGNED(var) var +typedef int16 vec16[8]; +typedef int32 vec32[4]; +typedef int8 vec8[16]; +typedef uint16 uvec16[8]; +typedef uint32 uvec32[4]; +typedef uint8 uvec8[16]; +typedef int16 lvec16[16]; +typedef int32 lvec32[8]; +typedef int8 lvec8[32]; +typedef uint16 ulvec16[16]; +typedef uint32 ulvec32[8]; +typedef uint8 ulvec8[32]; +#endif + +#if defined(__aarch64__) +// This struct is for Arm64 color conversion. +struct YuvConstants { + uvec16 kUVToRB; + uvec16 kUVToRB2; + uvec16 kUVToG; + uvec16 kUVToG2; + vec16 kUVBiasBGR; + vec32 kYToRgb; +}; +#elif defined(__arm__) +// This struct is for ArmV7 color conversion. +struct YuvConstants { + uvec8 kUVToRB; + uvec8 kUVToG; + vec16 kUVBiasBGR; + vec32 kYToRgb; +}; +#else +// This struct is for Intel color conversion. +struct YuvConstants { + int8 kUVToB[32]; + int8 kUVToG[32]; + int8 kUVToR[32]; + int16 kUVBiasB[16]; + int16 kUVBiasG[16]; + int16 kUVBiasR[16]; + int16 kYToRgb[16]; +}; + +// Offsets into YuvConstants structure +#define KUVTOB 0 +#define KUVTOG 32 +#define KUVTOR 64 +#define KUVBIASB 96 +#define KUVBIASG 128 +#define KUVBIASR 160 +#define KYTORGB 192 +#endif + +// Conversion matrix for YUV to RGB +extern const struct YuvConstants SIMD_ALIGNED(kYuvI601Constants); // BT.601 +extern const struct YuvConstants SIMD_ALIGNED(kYuvJPEGConstants); // JPeg +extern const struct YuvConstants SIMD_ALIGNED(kYuvH709Constants); // BT.709 + +// Conversion matrix for YVU to BGR +extern const struct YuvConstants SIMD_ALIGNED(kYvuI601Constants); // BT.601 +extern const struct YuvConstants SIMD_ALIGNED(kYvuJPEGConstants); // JPeg +extern const struct YuvConstants SIMD_ALIGNED(kYvuH709Constants); // BT.709 + +#if defined(__APPLE__) || defined(__x86_64__) || defined(__llvm__) +#define OMITFP +#else +#define OMITFP __attribute__((optimize("omit-frame-pointer"))) +#endif + +// NaCL macros for GCC x86 and x64. +#if defined(__native_client__) +#define LABELALIGN ".p2align 5\n" +#else +#define LABELALIGN +#endif +#if defined(__native_client__) && defined(__x86_64__) +// r14 is used for MEMOP macros. +#define NACL_R14 "r14", +#define BUNDLELOCK ".bundle_lock\n" +#define BUNDLEUNLOCK ".bundle_unlock\n" +#define MEMACCESS(base) "%%nacl:(%%r15,%q" #base ")" +#define MEMACCESS2(offset, base) "%%nacl:" #offset "(%%r15,%q" #base ")" +#define MEMLEA(offset, base) #offset "(%q" #base ")" +#define MEMLEA3(offset, index, scale) \ + #offset "(,%q" #index "," #scale ")" +#define MEMLEA4(offset, base, index, scale) \ + #offset "(%q" #base ",%q" #index "," #scale ")" +#define MEMMOVESTRING(s, d) "%%nacl:(%q" #s "),%%nacl:(%q" #d "), %%r15" +#define MEMSTORESTRING(reg, d) "%%" #reg ",%%nacl:(%q" #d "), %%r15" +#define MEMOPREG(opcode, offset, base, index, scale, reg) \ + BUNDLELOCK \ + "lea " #offset "(%q" #base ",%q" #index "," #scale "),%%r14d\n" \ + #opcode " (%%r15,%%r14),%%" #reg "\n" \ + BUNDLEUNLOCK +#define MEMOPMEM(opcode, reg, offset, base, index, scale) \ + BUNDLELOCK \ + "lea " #offset "(%q" #base ",%q" #index "," #scale "),%%r14d\n" \ + #opcode " %%" #reg ",(%%r15,%%r14)\n" \ + BUNDLEUNLOCK +#define MEMOPARG(opcode, offset, base, index, scale, arg) \ + BUNDLELOCK \ + "lea " #offset "(%q" #base ",%q" #index "," #scale "),%%r14d\n" \ + #opcode " (%%r15,%%r14),%" #arg "\n" \ + BUNDLEUNLOCK +#define VMEMOPREG(opcode, offset, base, index, scale, reg1, reg2) \ + BUNDLELOCK \ + "lea " #offset "(%q" #base ",%q" #index "," #scale "),%%r14d\n" \ + #opcode " (%%r15,%%r14),%%" #reg1 ",%%" #reg2 "\n" \ + BUNDLEUNLOCK +#define VEXTOPMEM(op, sel, reg, offset, base, index, scale) \ + BUNDLELOCK \ + "lea " #offset "(%q" #base ",%q" #index "," #scale "),%%r14d\n" \ + #op " $" #sel ",%%" #reg ",(%%r15,%%r14)\n" \ + BUNDLEUNLOCK +#else // defined(__native_client__) && defined(__x86_64__) +#define NACL_R14 +#define BUNDLEALIGN +#define MEMACCESS(base) "(%" #base ")" +#define MEMACCESS2(offset, base) #offset "(%" #base ")" +#define MEMLEA(offset, base) #offset "(%" #base ")" +#define MEMLEA3(offset, index, scale) \ + #offset "(,%" #index "," #scale ")" +#define MEMLEA4(offset, base, index, scale) \ + #offset "(%" #base ",%" #index "," #scale ")" +#define MEMMOVESTRING(s, d) +#define MEMSTORESTRING(reg, d) +#define MEMOPREG(opcode, offset, base, index, scale, reg) \ + #opcode " " #offset "(%" #base ",%" #index "," #scale "),%%" #reg "\n" +#define MEMOPMEM(opcode, reg, offset, base, index, scale) \ + #opcode " %%" #reg ","#offset "(%" #base ",%" #index "," #scale ")\n" +#define MEMOPARG(opcode, offset, base, index, scale, arg) \ + #opcode " " #offset "(%" #base ",%" #index "," #scale "),%" #arg "\n" +#define VMEMOPREG(opcode, offset, base, index, scale, reg1, reg2) \ + #opcode " " #offset "(%" #base ",%" #index "," #scale "),%%" #reg1 ",%%" \ + #reg2 "\n" +#define VEXTOPMEM(op, sel, reg, offset, base, index, scale) \ + #op " $" #sel ",%%" #reg ","#offset "(%" #base ",%" #index "," #scale ")\n" +#endif // defined(__native_client__) && defined(__x86_64__) + +#if defined(__arm__) || defined(__aarch64__) +#undef MEMACCESS +#if defined(__native_client__) +#define MEMACCESS(base) ".p2align 3\nbic %" #base ", #0xc0000000\n" +#else +#define MEMACCESS(base) +#endif +#endif + +void I444ToARGBRow_NEON(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void I422ToARGBRow_NEON(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void I422AlphaToARGBRow_NEON(const uint8* y_buf, + const uint8* u_buf, + const uint8* v_buf, + const uint8* a_buf, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void I422ToARGBRow_NEON(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void I411ToARGBRow_NEON(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void I422ToRGBARow_NEON(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_rgba, + const struct YuvConstants* yuvconstants, + int width); +void I422ToRGB24Row_NEON(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_rgb24, + const struct YuvConstants* yuvconstants, + int width); +void I422ToRGB565Row_NEON(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_rgb565, + const struct YuvConstants* yuvconstants, + int width); +void I422ToARGB1555Row_NEON(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_argb1555, + const struct YuvConstants* yuvconstants, + int width); +void I422ToARGB4444Row_NEON(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_argb4444, + const struct YuvConstants* yuvconstants, + int width); +void NV12ToARGBRow_NEON(const uint8* src_y, + const uint8* src_uv, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void NV12ToRGB565Row_NEON(const uint8* src_y, + const uint8* src_uv, + uint8* dst_rgb565, + const struct YuvConstants* yuvconstants, + int width); +void NV21ToARGBRow_NEON(const uint8* src_y, + const uint8* src_vu, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void YUY2ToARGBRow_NEON(const uint8* src_yuy2, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void UYVYToARGBRow_NEON(const uint8* src_uyvy, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); + +void ARGBToYRow_AVX2(const uint8* src_argb, uint8* dst_y, int width); +void ARGBToYRow_Any_AVX2(const uint8* src_argb, uint8* dst_y, int width); +void ARGBToYRow_SSSE3(const uint8* src_argb, uint8* dst_y, int width); +void ARGBToYJRow_AVX2(const uint8* src_argb, uint8* dst_y, int width); +void ARGBToYJRow_Any_AVX2(const uint8* src_argb, uint8* dst_y, int width); +void ARGBToYJRow_SSSE3(const uint8* src_argb, uint8* dst_y, int width); +void BGRAToYRow_SSSE3(const uint8* src_bgra, uint8* dst_y, int width); +void ABGRToYRow_SSSE3(const uint8* src_abgr, uint8* dst_y, int width); +void RGBAToYRow_SSSE3(const uint8* src_rgba, uint8* dst_y, int width); +void RGB24ToYRow_SSSE3(const uint8* src_rgb24, uint8* dst_y, int width); +void RAWToYRow_SSSE3(const uint8* src_raw, uint8* dst_y, int width); +void ARGBToYRow_NEON(const uint8* src_argb, uint8* dst_y, int width); +void ARGBToYJRow_NEON(const uint8* src_argb, uint8* dst_y, int width); +void ARGBToUV444Row_NEON(const uint8* src_argb, uint8* dst_u, uint8* dst_v, + int width); +void ARGBToUV411Row_NEON(const uint8* src_argb, uint8* dst_u, uint8* dst_v, + int width); +void ARGBToUVRow_NEON(const uint8* src_argb, int src_stride_argb, + uint8* dst_u, uint8* dst_v, int width); +void ARGBToUVJRow_NEON(const uint8* src_argb, int src_stride_argb, + uint8* dst_u, uint8* dst_v, int width); +void BGRAToUVRow_NEON(const uint8* src_bgra, int src_stride_bgra, + uint8* dst_u, uint8* dst_v, int width); +void ABGRToUVRow_NEON(const uint8* src_abgr, int src_stride_abgr, + uint8* dst_u, uint8* dst_v, int width); +void RGBAToUVRow_NEON(const uint8* src_rgba, int src_stride_rgba, + uint8* dst_u, uint8* dst_v, int width); +void RGB24ToUVRow_NEON(const uint8* src_rgb24, int src_stride_rgb24, + uint8* dst_u, uint8* dst_v, int width); +void RAWToUVRow_NEON(const uint8* src_raw, int src_stride_raw, + uint8* dst_u, uint8* dst_v, int width); +void RGB565ToUVRow_NEON(const uint8* src_rgb565, int src_stride_rgb565, + uint8* dst_u, uint8* dst_v, int width); +void ARGB1555ToUVRow_NEON(const uint8* src_argb1555, int src_stride_argb1555, + uint8* dst_u, uint8* dst_v, int width); +void ARGB4444ToUVRow_NEON(const uint8* src_argb4444, int src_stride_argb4444, + uint8* dst_u, uint8* dst_v, int width); +void BGRAToYRow_NEON(const uint8* src_bgra, uint8* dst_y, int width); +void ABGRToYRow_NEON(const uint8* src_abgr, uint8* dst_y, int width); +void RGBAToYRow_NEON(const uint8* src_rgba, uint8* dst_y, int width); +void RGB24ToYRow_NEON(const uint8* src_rgb24, uint8* dst_y, int width); +void RAWToYRow_NEON(const uint8* src_raw, uint8* dst_y, int width); +void RGB565ToYRow_NEON(const uint8* src_rgb565, uint8* dst_y, int width); +void ARGB1555ToYRow_NEON(const uint8* src_argb1555, uint8* dst_y, int width); +void ARGB4444ToYRow_NEON(const uint8* src_argb4444, uint8* dst_y, int width); +void ARGBToYRow_C(const uint8* src_argb, uint8* dst_y, int width); +void ARGBToYJRow_C(const uint8* src_argb, uint8* dst_y, int width); +void BGRAToYRow_C(const uint8* src_bgra, uint8* dst_y, int width); +void ABGRToYRow_C(const uint8* src_abgr, uint8* dst_y, int width); +void RGBAToYRow_C(const uint8* src_rgba, uint8* dst_y, int width); +void RGB24ToYRow_C(const uint8* src_rgb24, uint8* dst_y, int width); +void RAWToYRow_C(const uint8* src_raw, uint8* dst_y, int width); +void RGB565ToYRow_C(const uint8* src_rgb565, uint8* dst_y, int width); +void ARGB1555ToYRow_C(const uint8* src_argb1555, uint8* dst_y, int width); +void ARGB4444ToYRow_C(const uint8* src_argb4444, uint8* dst_y, int width); +void ARGBToYRow_Any_SSSE3(const uint8* src_argb, uint8* dst_y, int width); +void ARGBToYJRow_Any_SSSE3(const uint8* src_argb, uint8* dst_y, int width); +void BGRAToYRow_Any_SSSE3(const uint8* src_bgra, uint8* dst_y, int width); +void ABGRToYRow_Any_SSSE3(const uint8* src_abgr, uint8* dst_y, int width); +void RGBAToYRow_Any_SSSE3(const uint8* src_rgba, uint8* dst_y, int width); +void RGB24ToYRow_Any_SSSE3(const uint8* src_rgb24, uint8* dst_y, int width); +void RAWToYRow_Any_SSSE3(const uint8* src_raw, uint8* dst_y, int width); +void ARGBToYRow_Any_NEON(const uint8* src_argb, uint8* dst_y, int width); +void ARGBToYJRow_Any_NEON(const uint8* src_argb, uint8* dst_y, int width); +void BGRAToYRow_Any_NEON(const uint8* src_bgra, uint8* dst_y, int width); +void ABGRToYRow_Any_NEON(const uint8* src_abgr, uint8* dst_y, int width); +void RGBAToYRow_Any_NEON(const uint8* src_rgba, uint8* dst_y, int width); +void RGB24ToYRow_Any_NEON(const uint8* src_rgb24, uint8* dst_y, int width); +void RAWToYRow_Any_NEON(const uint8* src_raw, uint8* dst_y, int width); +void RGB565ToYRow_Any_NEON(const uint8* src_rgb565, uint8* dst_y, int width); +void ARGB1555ToYRow_Any_NEON(const uint8* src_argb1555, uint8* dst_y, + int width); +void ARGB4444ToYRow_Any_NEON(const uint8* src_argb4444, uint8* dst_y, + int width); + +void ARGBToUVRow_AVX2(const uint8* src_argb, int src_stride_argb, + uint8* dst_u, uint8* dst_v, int width); +void ARGBToUVJRow_AVX2(const uint8* src_argb, int src_stride_argb, + uint8* dst_u, uint8* dst_v, int width); +void ARGBToUVRow_SSSE3(const uint8* src_argb, int src_stride_argb, + uint8* dst_u, uint8* dst_v, int width); +void ARGBToUVJRow_SSSE3(const uint8* src_argb, int src_stride_argb, + uint8* dst_u, uint8* dst_v, int width); +void BGRAToUVRow_SSSE3(const uint8* src_bgra, int src_stride_bgra, + uint8* dst_u, uint8* dst_v, int width); +void ABGRToUVRow_SSSE3(const uint8* src_abgr, int src_stride_abgr, + uint8* dst_u, uint8* dst_v, int width); +void RGBAToUVRow_SSSE3(const uint8* src_rgba, int src_stride_rgba, + uint8* dst_u, uint8* dst_v, int width); +void ARGBToUVRow_Any_AVX2(const uint8* src_argb, int src_stride_argb, + uint8* dst_u, uint8* dst_v, int width); +void ARGBToUVJRow_Any_AVX2(const uint8* src_argb, int src_stride_argb, + uint8* dst_u, uint8* dst_v, int width); +void ARGBToUVRow_Any_SSSE3(const uint8* src_argb, int src_stride_argb, + uint8* dst_u, uint8* dst_v, int width); +void ARGBToUVJRow_Any_SSSE3(const uint8* src_argb, int src_stride_argb, + uint8* dst_u, uint8* dst_v, int width); +void BGRAToUVRow_Any_SSSE3(const uint8* src_bgra, int src_stride_bgra, + uint8* dst_u, uint8* dst_v, int width); +void ABGRToUVRow_Any_SSSE3(const uint8* src_abgr, int src_stride_abgr, + uint8* dst_u, uint8* dst_v, int width); +void RGBAToUVRow_Any_SSSE3(const uint8* src_rgba, int src_stride_rgba, + uint8* dst_u, uint8* dst_v, int width); +void ARGBToUV444Row_Any_NEON(const uint8* src_argb, uint8* dst_u, uint8* dst_v, + int width); +void ARGBToUV411Row_Any_NEON(const uint8* src_argb, uint8* dst_u, uint8* dst_v, + int width); +void ARGBToUVRow_Any_NEON(const uint8* src_argb, int src_stride_argb, + uint8* dst_u, uint8* dst_v, int width); +void ARGBToUVJRow_Any_NEON(const uint8* src_argb, int src_stride_argb, + uint8* dst_u, uint8* dst_v, int width); +void BGRAToUVRow_Any_NEON(const uint8* src_bgra, int src_stride_bgra, + uint8* dst_u, uint8* dst_v, int width); +void ABGRToUVRow_Any_NEON(const uint8* src_abgr, int src_stride_abgr, + uint8* dst_u, uint8* dst_v, int width); +void RGBAToUVRow_Any_NEON(const uint8* src_rgba, int src_stride_rgba, + uint8* dst_u, uint8* dst_v, int width); +void RGB24ToUVRow_Any_NEON(const uint8* src_rgb24, int src_stride_rgb24, + uint8* dst_u, uint8* dst_v, int width); +void RAWToUVRow_Any_NEON(const uint8* src_raw, int src_stride_raw, + uint8* dst_u, uint8* dst_v, int width); +void RGB565ToUVRow_Any_NEON(const uint8* src_rgb565, int src_stride_rgb565, + uint8* dst_u, uint8* dst_v, int width); +void ARGB1555ToUVRow_Any_NEON(const uint8* src_argb1555, + int src_stride_argb1555, + uint8* dst_u, uint8* dst_v, int width); +void ARGB4444ToUVRow_Any_NEON(const uint8* src_argb4444, + int src_stride_argb4444, + uint8* dst_u, uint8* dst_v, int width); +void ARGBToUVRow_C(const uint8* src_argb, int src_stride_argb, + uint8* dst_u, uint8* dst_v, int width); +void ARGBToUVJRow_C(const uint8* src_argb, int src_stride_argb, + uint8* dst_u, uint8* dst_v, int width); +void BGRAToUVRow_C(const uint8* src_bgra, int src_stride_bgra, + uint8* dst_u, uint8* dst_v, int width); +void ABGRToUVRow_C(const uint8* src_abgr, int src_stride_abgr, + uint8* dst_u, uint8* dst_v, int width); +void RGBAToUVRow_C(const uint8* src_rgba, int src_stride_rgba, + uint8* dst_u, uint8* dst_v, int width); +void RGB24ToUVRow_C(const uint8* src_rgb24, int src_stride_rgb24, + uint8* dst_u, uint8* dst_v, int width); +void RAWToUVRow_C(const uint8* src_raw, int src_stride_raw, + uint8* dst_u, uint8* dst_v, int width); +void RGB565ToUVRow_C(const uint8* src_rgb565, int src_stride_rgb565, + uint8* dst_u, uint8* dst_v, int width); +void ARGB1555ToUVRow_C(const uint8* src_argb1555, int src_stride_argb1555, + uint8* dst_u, uint8* dst_v, int width); +void ARGB4444ToUVRow_C(const uint8* src_argb4444, int src_stride_argb4444, + uint8* dst_u, uint8* dst_v, int width); + +void ARGBToUV444Row_SSSE3(const uint8* src_argb, + uint8* dst_u, uint8* dst_v, int width); +void ARGBToUV444Row_Any_SSSE3(const uint8* src_argb, + uint8* dst_u, uint8* dst_v, int width); + +void ARGBToUV444Row_C(const uint8* src_argb, + uint8* dst_u, uint8* dst_v, int width); +void ARGBToUV411Row_C(const uint8* src_argb, + uint8* dst_u, uint8* dst_v, int width); + +void MirrorRow_AVX2(const uint8* src, uint8* dst, int width); +void MirrorRow_SSSE3(const uint8* src, uint8* dst, int width); +void MirrorRow_NEON(const uint8* src, uint8* dst, int width); +void MirrorRow_DSPR2(const uint8* src, uint8* dst, int width); +void MirrorRow_MSA(const uint8* src, uint8* dst, int width); +void MirrorRow_C(const uint8* src, uint8* dst, int width); +void MirrorRow_Any_AVX2(const uint8* src, uint8* dst, int width); +void MirrorRow_Any_SSSE3(const uint8* src, uint8* dst, int width); +void MirrorRow_Any_SSE2(const uint8* src, uint8* dst, int width); +void MirrorRow_Any_NEON(const uint8* src, uint8* dst, int width); +void MirrorRow_Any_MSA(const uint8* src, uint8* dst, int width); + +void MirrorUVRow_SSSE3(const uint8* src_uv, uint8* dst_u, uint8* dst_v, + int width); +void MirrorUVRow_NEON(const uint8* src_uv, uint8* dst_u, uint8* dst_v, + int width); +void MirrorUVRow_DSPR2(const uint8* src_uv, uint8* dst_u, uint8* dst_v, + int width); +void MirrorUVRow_C(const uint8* src_uv, uint8* dst_u, uint8* dst_v, int width); + +void ARGBMirrorRow_AVX2(const uint8* src, uint8* dst, int width); +void ARGBMirrorRow_SSE2(const uint8* src, uint8* dst, int width); +void ARGBMirrorRow_NEON(const uint8* src, uint8* dst, int width); +void ARGBMirrorRow_MSA(const uint8* src, uint8* dst, int width); +void ARGBMirrorRow_C(const uint8* src, uint8* dst, int width); +void ARGBMirrorRow_Any_AVX2(const uint8* src, uint8* dst, int width); +void ARGBMirrorRow_Any_SSE2(const uint8* src, uint8* dst, int width); +void ARGBMirrorRow_Any_NEON(const uint8* src, uint8* dst, int width); +void ARGBMirrorRow_Any_MSA(const uint8* src, uint8* dst, int width); + +void SplitUVRow_C(const uint8* src_uv, uint8* dst_u, uint8* dst_v, int width); +void SplitUVRow_SSE2(const uint8* src_uv, uint8* dst_u, uint8* dst_v, + int width); +void SplitUVRow_AVX2(const uint8* src_uv, uint8* dst_u, uint8* dst_v, + int width); +void SplitUVRow_NEON(const uint8* src_uv, uint8* dst_u, uint8* dst_v, + int width); +void SplitUVRow_DSPR2(const uint8* src_uv, uint8* dst_u, uint8* dst_v, + int width); +void SplitUVRow_Any_SSE2(const uint8* src_uv, uint8* dst_u, uint8* dst_v, + int width); +void SplitUVRow_Any_AVX2(const uint8* src_uv, uint8* dst_u, uint8* dst_v, + int width); +void SplitUVRow_Any_NEON(const uint8* src_uv, uint8* dst_u, uint8* dst_v, + int width); +void SplitUVRow_Any_DSPR2(const uint8* src_uv, uint8* dst_u, uint8* dst_v, + int width); + +void MergeUVRow_C(const uint8* src_u, const uint8* src_v, uint8* dst_uv, + int width); +void MergeUVRow_SSE2(const uint8* src_u, const uint8* src_v, uint8* dst_uv, + int width); +void MergeUVRow_AVX2(const uint8* src_u, const uint8* src_v, uint8* dst_uv, + int width); +void MergeUVRow_NEON(const uint8* src_u, const uint8* src_v, uint8* dst_uv, + int width); +void MergeUVRow_Any_SSE2(const uint8* src_u, const uint8* src_v, uint8* dst_uv, + int width); +void MergeUVRow_Any_AVX2(const uint8* src_u, const uint8* src_v, uint8* dst_uv, + int width); +void MergeUVRow_Any_NEON(const uint8* src_u, const uint8* src_v, uint8* dst_uv, + int width); + +void CopyRow_SSE2(const uint8* src, uint8* dst, int count); +void CopyRow_AVX(const uint8* src, uint8* dst, int count); +void CopyRow_ERMS(const uint8* src, uint8* dst, int count); +void CopyRow_NEON(const uint8* src, uint8* dst, int count); +void CopyRow_MIPS(const uint8* src, uint8* dst, int count); +void CopyRow_C(const uint8* src, uint8* dst, int count); +void CopyRow_Any_SSE2(const uint8* src, uint8* dst, int count); +void CopyRow_Any_AVX(const uint8* src, uint8* dst, int count); +void CopyRow_Any_NEON(const uint8* src, uint8* dst, int count); + +void CopyRow_16_C(const uint16* src, uint16* dst, int count); + +void ARGBCopyAlphaRow_C(const uint8* src_argb, uint8* dst_argb, int width); +void ARGBCopyAlphaRow_SSE2(const uint8* src_argb, uint8* dst_argb, int width); +void ARGBCopyAlphaRow_AVX2(const uint8* src_argb, uint8* dst_argb, int width); +void ARGBCopyAlphaRow_Any_SSE2(const uint8* src_argb, uint8* dst_argb, + int width); +void ARGBCopyAlphaRow_Any_AVX2(const uint8* src_argb, uint8* dst_argb, + int width); + +void ARGBExtractAlphaRow_C(const uint8* src_argb, uint8* dst_a, int width); +void ARGBExtractAlphaRow_SSE2(const uint8* src_argb, uint8* dst_a, int width); +void ARGBExtractAlphaRow_NEON(const uint8* src_argb, uint8* dst_a, int width); +void ARGBExtractAlphaRow_Any_SSE2(const uint8* src_argb, uint8* dst_a, + int width); +void ARGBExtractAlphaRow_Any_NEON(const uint8* src_argb, uint8* dst_a, + int width); + +void ARGBCopyYToAlphaRow_C(const uint8* src_y, uint8* dst_argb, int width); +void ARGBCopyYToAlphaRow_SSE2(const uint8* src_y, uint8* dst_argb, int width); +void ARGBCopyYToAlphaRow_AVX2(const uint8* src_y, uint8* dst_argb, int width); +void ARGBCopyYToAlphaRow_Any_SSE2(const uint8* src_y, uint8* dst_argb, + int width); +void ARGBCopyYToAlphaRow_Any_AVX2(const uint8* src_y, uint8* dst_argb, + int width); + +void SetRow_C(uint8* dst, uint8 v8, int count); +void SetRow_X86(uint8* dst, uint8 v8, int count); +void SetRow_ERMS(uint8* dst, uint8 v8, int count); +void SetRow_NEON(uint8* dst, uint8 v8, int count); +void SetRow_Any_X86(uint8* dst, uint8 v8, int count); +void SetRow_Any_NEON(uint8* dst, uint8 v8, int count); + +void ARGBSetRow_C(uint8* dst_argb, uint32 v32, int count); +void ARGBSetRow_X86(uint8* dst_argb, uint32 v32, int count); +void ARGBSetRow_NEON(uint8* dst_argb, uint32 v32, int count); +void ARGBSetRow_Any_NEON(uint8* dst_argb, uint32 v32, int count); + +// ARGBShufflers for BGRAToARGB etc. +void ARGBShuffleRow_C(const uint8* src_argb, uint8* dst_argb, + const uint8* shuffler, int width); +void ARGBShuffleRow_SSE2(const uint8* src_argb, uint8* dst_argb, + const uint8* shuffler, int width); +void ARGBShuffleRow_SSSE3(const uint8* src_argb, uint8* dst_argb, + const uint8* shuffler, int width); +void ARGBShuffleRow_AVX2(const uint8* src_argb, uint8* dst_argb, + const uint8* shuffler, int width); +void ARGBShuffleRow_NEON(const uint8* src_argb, uint8* dst_argb, + const uint8* shuffler, int width); +void ARGBShuffleRow_Any_SSE2(const uint8* src_argb, uint8* dst_argb, + const uint8* shuffler, int width); +void ARGBShuffleRow_Any_SSSE3(const uint8* src_argb, uint8* dst_argb, + const uint8* shuffler, int width); +void ARGBShuffleRow_Any_AVX2(const uint8* src_argb, uint8* dst_argb, + const uint8* shuffler, int width); +void ARGBShuffleRow_Any_NEON(const uint8* src_argb, uint8* dst_argb, + const uint8* shuffler, int width); + +void RGB24ToARGBRow_SSSE3(const uint8* src_rgb24, uint8* dst_argb, int width); +void RAWToARGBRow_SSSE3(const uint8* src_raw, uint8* dst_argb, int width); +void RAWToRGB24Row_SSSE3(const uint8* src_raw, uint8* dst_rgb24, int width); +void RGB565ToARGBRow_SSE2(const uint8* src_rgb565, uint8* dst_argb, int width); +void ARGB1555ToARGBRow_SSE2(const uint8* src_argb1555, uint8* dst_argb, + int width); +void ARGB4444ToARGBRow_SSE2(const uint8* src_argb4444, uint8* dst_argb, + int width); +void RGB565ToARGBRow_AVX2(const uint8* src_rgb565, uint8* dst_argb, int width); +void ARGB1555ToARGBRow_AVX2(const uint8* src_argb1555, uint8* dst_argb, + int width); +void ARGB4444ToARGBRow_AVX2(const uint8* src_argb4444, uint8* dst_argb, + int width); + +void RGB24ToARGBRow_NEON(const uint8* src_rgb24, uint8* dst_argb, int width); +void RAWToARGBRow_NEON(const uint8* src_raw, uint8* dst_argb, int width); +void RAWToRGB24Row_NEON(const uint8* src_raw, uint8* dst_rgb24, int width); +void RGB565ToARGBRow_NEON(const uint8* src_rgb565, uint8* dst_argb, int width); +void ARGB1555ToARGBRow_NEON(const uint8* src_argb1555, uint8* dst_argb, + int width); +void ARGB4444ToARGBRow_NEON(const uint8* src_argb4444, uint8* dst_argb, + int width); +void RGB24ToARGBRow_C(const uint8* src_rgb24, uint8* dst_argb, int width); +void RAWToARGBRow_C(const uint8* src_raw, uint8* dst_argb, int width); +void RAWToRGB24Row_C(const uint8* src_raw, uint8* dst_rgb24, int width); +void RGB565ToARGBRow_C(const uint8* src_rgb, uint8* dst_argb, int width); +void ARGB1555ToARGBRow_C(const uint8* src_argb, uint8* dst_argb, int width); +void ARGB4444ToARGBRow_C(const uint8* src_argb, uint8* dst_argb, int width); +void RGB24ToARGBRow_Any_SSSE3(const uint8* src_rgb24, uint8* dst_argb, + int width); +void RAWToARGBRow_Any_SSSE3(const uint8* src_raw, uint8* dst_argb, int width); +void RAWToRGB24Row_Any_SSSE3(const uint8* src_raw, uint8* dst_rgb24, int width); + +void RGB565ToARGBRow_Any_SSE2(const uint8* src_rgb565, uint8* dst_argb, + int width); +void ARGB1555ToARGBRow_Any_SSE2(const uint8* src_argb1555, uint8* dst_argb, + int width); +void ARGB4444ToARGBRow_Any_SSE2(const uint8* src_argb4444, uint8* dst_argb, + int width); +void RGB565ToARGBRow_Any_AVX2(const uint8* src_rgb565, uint8* dst_argb, + int width); +void ARGB1555ToARGBRow_Any_AVX2(const uint8* src_argb1555, uint8* dst_argb, + int width); +void ARGB4444ToARGBRow_Any_AVX2(const uint8* src_argb4444, uint8* dst_argb, + int width); + +void RGB24ToARGBRow_Any_NEON(const uint8* src_rgb24, uint8* dst_argb, + int width); +void RAWToARGBRow_Any_NEON(const uint8* src_raw, uint8* dst_argb, int width); +void RAWToRGB24Row_Any_NEON(const uint8* src_raw, uint8* dst_rgb24, int width); +void RGB565ToARGBRow_Any_NEON(const uint8* src_rgb565, uint8* dst_argb, + int width); +void ARGB1555ToARGBRow_Any_NEON(const uint8* src_argb1555, uint8* dst_argb, + int width); +void ARGB4444ToARGBRow_Any_NEON(const uint8* src_argb4444, uint8* dst_argb, + int width); + +void ARGBToRGB24Row_SSSE3(const uint8* src_argb, uint8* dst_rgb, int width); +void ARGBToRAWRow_SSSE3(const uint8* src_argb, uint8* dst_rgb, int width); +void ARGBToRGB565Row_SSE2(const uint8* src_argb, uint8* dst_rgb, int width); +void ARGBToARGB1555Row_SSE2(const uint8* src_argb, uint8* dst_rgb, int width); +void ARGBToARGB4444Row_SSE2(const uint8* src_argb, uint8* dst_rgb, int width); + +void ARGBToRGB565DitherRow_C(const uint8* src_argb, uint8* dst_rgb, + const uint32 dither4, int width); +void ARGBToRGB565DitherRow_SSE2(const uint8* src_argb, uint8* dst_rgb, + const uint32 dither4, int width); +void ARGBToRGB565DitherRow_AVX2(const uint8* src_argb, uint8* dst_rgb, + const uint32 dither4, int width); + +void ARGBToRGB565Row_AVX2(const uint8* src_argb, uint8* dst_rgb, int width); +void ARGBToARGB1555Row_AVX2(const uint8* src_argb, uint8* dst_rgb, int width); +void ARGBToARGB4444Row_AVX2(const uint8* src_argb, uint8* dst_rgb, int width); + +void ARGBToRGB24Row_NEON(const uint8* src_argb, uint8* dst_rgb, int width); +void ARGBToRAWRow_NEON(const uint8* src_argb, uint8* dst_rgb, int width); +void ARGBToRGB565Row_NEON(const uint8* src_argb, uint8* dst_rgb, int width); +void ARGBToARGB1555Row_NEON(const uint8* src_argb, uint8* dst_rgb, int width); +void ARGBToARGB4444Row_NEON(const uint8* src_argb, uint8* dst_rgb, int width); +void ARGBToRGB565DitherRow_NEON(const uint8* src_argb, uint8* dst_rgb, + const uint32 dither4, int width); + +void ARGBToRGBARow_C(const uint8* src_argb, uint8* dst_rgb, int width); +void ARGBToRGB24Row_C(const uint8* src_argb, uint8* dst_rgb, int width); +void ARGBToRAWRow_C(const uint8* src_argb, uint8* dst_rgb, int width); +void ARGBToRGB565Row_C(const uint8* src_argb, uint8* dst_rgb, int width); +void ARGBToARGB1555Row_C(const uint8* src_argb, uint8* dst_rgb, int width); +void ARGBToARGB4444Row_C(const uint8* src_argb, uint8* dst_rgb, int width); + +void J400ToARGBRow_SSE2(const uint8* src_y, uint8* dst_argb, int width); +void J400ToARGBRow_AVX2(const uint8* src_y, uint8* dst_argb, int width); +void J400ToARGBRow_NEON(const uint8* src_y, uint8* dst_argb, int width); +void J400ToARGBRow_C(const uint8* src_y, uint8* dst_argb, int width); +void J400ToARGBRow_Any_SSE2(const uint8* src_y, uint8* dst_argb, int width); +void J400ToARGBRow_Any_AVX2(const uint8* src_y, uint8* dst_argb, int width); +void J400ToARGBRow_Any_NEON(const uint8* src_y, uint8* dst_argb, int width); + +void I444ToARGBRow_C(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void I422ToARGBRow_C(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void I422ToARGBRow_C(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void I422AlphaToARGBRow_C(const uint8* y_buf, + const uint8* u_buf, + const uint8* v_buf, + const uint8* a_buf, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void I411ToARGBRow_C(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void NV12ToARGBRow_C(const uint8* src_y, + const uint8* src_uv, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void NV12ToRGB565Row_C(const uint8* src_y, + const uint8* src_uv, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void NV21ToARGBRow_C(const uint8* src_y, + const uint8* src_uv, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void YUY2ToARGBRow_C(const uint8* src_yuy2, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void UYVYToARGBRow_C(const uint8* src_uyvy, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void I422ToRGBARow_C(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_rgba, + const struct YuvConstants* yuvconstants, + int width); +void I422ToRGB24Row_C(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_rgb24, + const struct YuvConstants* yuvconstants, + int width); +void I422ToARGB4444Row_C(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_argb4444, + const struct YuvConstants* yuvconstants, + int width); +void I422ToARGB1555Row_C(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_argb4444, + const struct YuvConstants* yuvconstants, + int width); +void I422ToRGB565Row_C(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_rgb565, + const struct YuvConstants* yuvconstants, + int width); +void I422ToARGBRow_AVX2(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void I422ToARGBRow_AVX2(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void I422ToRGBARow_AVX2(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void I444ToARGBRow_SSSE3(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void I444ToARGBRow_AVX2(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void I444ToARGBRow_SSSE3(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void I444ToARGBRow_AVX2(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void I422ToARGBRow_SSSE3(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void I422AlphaToARGBRow_SSSE3(const uint8* y_buf, + const uint8* u_buf, + const uint8* v_buf, + const uint8* a_buf, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void I422AlphaToARGBRow_AVX2(const uint8* y_buf, + const uint8* u_buf, + const uint8* v_buf, + const uint8* a_buf, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void I422ToARGBRow_SSSE3(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void I411ToARGBRow_SSSE3(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void I411ToARGBRow_AVX2(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void NV12ToARGBRow_SSSE3(const uint8* src_y, + const uint8* src_uv, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void NV12ToARGBRow_AVX2(const uint8* src_y, + const uint8* src_uv, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void NV12ToRGB565Row_SSSE3(const uint8* src_y, + const uint8* src_uv, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void NV12ToRGB565Row_AVX2(const uint8* src_y, + const uint8* src_uv, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void NV21ToARGBRow_SSSE3(const uint8* src_y, + const uint8* src_uv, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void NV21ToARGBRow_AVX2(const uint8* src_y, + const uint8* src_uv, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void YUY2ToARGBRow_SSSE3(const uint8* src_yuy2, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void UYVYToARGBRow_SSSE3(const uint8* src_uyvy, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void YUY2ToARGBRow_AVX2(const uint8* src_yuy2, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void UYVYToARGBRow_AVX2(const uint8* src_uyvy, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void I422ToRGBARow_SSSE3(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_rgba, + const struct YuvConstants* yuvconstants, + int width); +void I422ToARGB4444Row_SSSE3(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void I422ToARGB4444Row_AVX2(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void I422ToARGB1555Row_SSSE3(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void I422ToARGB1555Row_AVX2(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void I422ToRGB565Row_SSSE3(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void I422ToRGB565Row_AVX2(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void I422ToRGB24Row_SSSE3(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_rgb24, + const struct YuvConstants* yuvconstants, + int width); +void I422ToRGB24Row_AVX2(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_rgb24, + const struct YuvConstants* yuvconstants, + int width); +void I422ToARGBRow_Any_AVX2(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void I422ToRGBARow_Any_AVX2(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void I444ToARGBRow_Any_SSSE3(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void I444ToARGBRow_Any_AVX2(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void I422ToARGBRow_Any_SSSE3(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void I422AlphaToARGBRow_Any_SSSE3(const uint8* y_buf, + const uint8* u_buf, + const uint8* v_buf, + const uint8* a_buf, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void I422AlphaToARGBRow_Any_AVX2(const uint8* y_buf, + const uint8* u_buf, + const uint8* v_buf, + const uint8* a_buf, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void I411ToARGBRow_Any_SSSE3(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void I411ToARGBRow_Any_AVX2(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void NV12ToARGBRow_Any_SSSE3(const uint8* src_y, + const uint8* src_uv, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void NV12ToARGBRow_Any_AVX2(const uint8* src_y, + const uint8* src_uv, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void NV21ToARGBRow_Any_SSSE3(const uint8* src_y, + const uint8* src_vu, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void NV21ToARGBRow_Any_AVX2(const uint8* src_y, + const uint8* src_vu, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void NV12ToRGB565Row_Any_SSSE3(const uint8* src_y, + const uint8* src_uv, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void NV12ToRGB565Row_Any_AVX2(const uint8* src_y, + const uint8* src_uv, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void YUY2ToARGBRow_Any_SSSE3(const uint8* src_yuy2, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void UYVYToARGBRow_Any_SSSE3(const uint8* src_uyvy, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void YUY2ToARGBRow_Any_AVX2(const uint8* src_yuy2, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void UYVYToARGBRow_Any_AVX2(const uint8* src_uyvy, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void I422ToRGBARow_Any_SSSE3(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_rgba, + const struct YuvConstants* yuvconstants, + int width); +void I422ToARGB4444Row_Any_SSSE3(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_rgba, + const struct YuvConstants* yuvconstants, + int width); +void I422ToARGB4444Row_Any_AVX2(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_rgba, + const struct YuvConstants* yuvconstants, + int width); +void I422ToARGB1555Row_Any_SSSE3(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_rgba, + const struct YuvConstants* yuvconstants, + int width); +void I422ToARGB1555Row_Any_AVX2(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_rgba, + const struct YuvConstants* yuvconstants, + int width); +void I422ToRGB565Row_Any_SSSE3(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_rgba, + const struct YuvConstants* yuvconstants, + int width); +void I422ToRGB565Row_Any_AVX2(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_rgba, + const struct YuvConstants* yuvconstants, + int width); +void I422ToRGB24Row_Any_SSSE3(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void I422ToRGB24Row_Any_AVX2(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); + +void I400ToARGBRow_C(const uint8* src_y, uint8* dst_argb, int width); +void I400ToARGBRow_SSE2(const uint8* src_y, uint8* dst_argb, int width); +void I400ToARGBRow_AVX2(const uint8* src_y, uint8* dst_argb, int width); +void I400ToARGBRow_NEON(const uint8* src_y, uint8* dst_argb, int width); +void I400ToARGBRow_Any_SSE2(const uint8* src_y, uint8* dst_argb, int width); +void I400ToARGBRow_Any_AVX2(const uint8* src_y, uint8* dst_argb, int width); +void I400ToARGBRow_Any_NEON(const uint8* src_y, uint8* dst_argb, int width); + +// ARGB preattenuated alpha blend. +void ARGBBlendRow_SSSE3(const uint8* src_argb, const uint8* src_argb1, + uint8* dst_argb, int width); +void ARGBBlendRow_NEON(const uint8* src_argb, const uint8* src_argb1, + uint8* dst_argb, int width); +void ARGBBlendRow_C(const uint8* src_argb, const uint8* src_argb1, + uint8* dst_argb, int width); + +// Unattenuated planar alpha blend. +void BlendPlaneRow_SSSE3(const uint8* src0, const uint8* src1, + const uint8* alpha, uint8* dst, int width); +void BlendPlaneRow_Any_SSSE3(const uint8* src0, const uint8* src1, + const uint8* alpha, uint8* dst, int width); +void BlendPlaneRow_AVX2(const uint8* src0, const uint8* src1, + const uint8* alpha, uint8* dst, int width); +void BlendPlaneRow_Any_AVX2(const uint8* src0, const uint8* src1, + const uint8* alpha, uint8* dst, int width); +void BlendPlaneRow_C(const uint8* src0, const uint8* src1, + const uint8* alpha, uint8* dst, int width); + +// ARGB multiply images. Same API as Blend, but these require +// pointer and width alignment for SSE2. +void ARGBMultiplyRow_C(const uint8* src_argb, const uint8* src_argb1, + uint8* dst_argb, int width); +void ARGBMultiplyRow_SSE2(const uint8* src_argb, const uint8* src_argb1, + uint8* dst_argb, int width); +void ARGBMultiplyRow_Any_SSE2(const uint8* src_argb, const uint8* src_argb1, + uint8* dst_argb, int width); +void ARGBMultiplyRow_AVX2(const uint8* src_argb, const uint8* src_argb1, + uint8* dst_argb, int width); +void ARGBMultiplyRow_Any_AVX2(const uint8* src_argb, const uint8* src_argb1, + uint8* dst_argb, int width); +void ARGBMultiplyRow_NEON(const uint8* src_argb, const uint8* src_argb1, + uint8* dst_argb, int width); +void ARGBMultiplyRow_Any_NEON(const uint8* src_argb, const uint8* src_argb1, + uint8* dst_argb, int width); + +// ARGB add images. +void ARGBAddRow_C(const uint8* src_argb, const uint8* src_argb1, + uint8* dst_argb, int width); +void ARGBAddRow_SSE2(const uint8* src_argb, const uint8* src_argb1, + uint8* dst_argb, int width); +void ARGBAddRow_Any_SSE2(const uint8* src_argb, const uint8* src_argb1, + uint8* dst_argb, int width); +void ARGBAddRow_AVX2(const uint8* src_argb, const uint8* src_argb1, + uint8* dst_argb, int width); +void ARGBAddRow_Any_AVX2(const uint8* src_argb, const uint8* src_argb1, + uint8* dst_argb, int width); +void ARGBAddRow_NEON(const uint8* src_argb, const uint8* src_argb1, + uint8* dst_argb, int width); +void ARGBAddRow_Any_NEON(const uint8* src_argb, const uint8* src_argb1, + uint8* dst_argb, int width); + +// ARGB subtract images. Same API as Blend, but these require +// pointer and width alignment for SSE2. +void ARGBSubtractRow_C(const uint8* src_argb, const uint8* src_argb1, + uint8* dst_argb, int width); +void ARGBSubtractRow_SSE2(const uint8* src_argb, const uint8* src_argb1, + uint8* dst_argb, int width); +void ARGBSubtractRow_Any_SSE2(const uint8* src_argb, const uint8* src_argb1, + uint8* dst_argb, int width); +void ARGBSubtractRow_AVX2(const uint8* src_argb, const uint8* src_argb1, + uint8* dst_argb, int width); +void ARGBSubtractRow_Any_AVX2(const uint8* src_argb, const uint8* src_argb1, + uint8* dst_argb, int width); +void ARGBSubtractRow_NEON(const uint8* src_argb, const uint8* src_argb1, + uint8* dst_argb, int width); +void ARGBSubtractRow_Any_NEON(const uint8* src_argb, const uint8* src_argb1, + uint8* dst_argb, int width); + +void ARGBToRGB24Row_Any_SSSE3(const uint8* src_argb, uint8* dst_rgb, int width); +void ARGBToRAWRow_Any_SSSE3(const uint8* src_argb, uint8* dst_rgb, int width); +void ARGBToRGB565Row_Any_SSE2(const uint8* src_argb, uint8* dst_rgb, int width); +void ARGBToARGB1555Row_Any_SSE2(const uint8* src_argb, uint8* dst_rgb, + int width); +void ARGBToARGB4444Row_Any_SSE2(const uint8* src_argb, uint8* dst_rgb, + int width); + +void ARGBToRGB565DitherRow_Any_SSE2(const uint8* src_argb, uint8* dst_rgb, + const uint32 dither4, int width); +void ARGBToRGB565DitherRow_Any_AVX2(const uint8* src_argb, uint8* dst_rgb, + const uint32 dither4, int width); + +void ARGBToRGB565Row_Any_AVX2(const uint8* src_argb, uint8* dst_rgb, int width); +void ARGBToARGB1555Row_Any_AVX2(const uint8* src_argb, uint8* dst_rgb, + int width); +void ARGBToARGB4444Row_Any_AVX2(const uint8* src_argb, uint8* dst_rgb, + int width); + +void ARGBToRGB24Row_Any_NEON(const uint8* src_argb, uint8* dst_rgb, int width); +void ARGBToRAWRow_Any_NEON(const uint8* src_argb, uint8* dst_rgb, int width); +void ARGBToRGB565Row_Any_NEON(const uint8* src_argb, uint8* dst_rgb, int width); +void ARGBToARGB1555Row_Any_NEON(const uint8* src_argb, uint8* dst_rgb, + int width); +void ARGBToARGB4444Row_Any_NEON(const uint8* src_argb, uint8* dst_rgb, + int width); +void ARGBToRGB565DitherRow_Any_NEON(const uint8* src_argb, uint8* dst_rgb, + const uint32 dither4, int width); + +void I444ToARGBRow_Any_NEON(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void I422ToARGBRow_Any_NEON(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void I422AlphaToARGBRow_Any_NEON(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + const uint8* src_a, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void I411ToARGBRow_Any_NEON(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void I422ToRGBARow_Any_NEON(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void I422ToRGB24Row_Any_NEON(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void I422ToARGB4444Row_Any_NEON(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void I422ToARGB1555Row_Any_NEON(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void I422ToRGB565Row_Any_NEON(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void NV12ToARGBRow_Any_NEON(const uint8* src_y, + const uint8* src_uv, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void NV21ToARGBRow_Any_NEON(const uint8* src_y, + const uint8* src_vu, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void NV12ToRGB565Row_Any_NEON(const uint8* src_y, + const uint8* src_uv, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void YUY2ToARGBRow_Any_NEON(const uint8* src_yuy2, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void UYVYToARGBRow_Any_NEON(const uint8* src_uyvy, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void I422ToARGBRow_DSPR2(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); +void I422ToARGBRow_DSPR2(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_argb, + const struct YuvConstants* yuvconstants, + int width); + +void YUY2ToYRow_AVX2(const uint8* src_yuy2, uint8* dst_y, int width); +void YUY2ToUVRow_AVX2(const uint8* src_yuy2, int stride_yuy2, + uint8* dst_u, uint8* dst_v, int width); +void YUY2ToUV422Row_AVX2(const uint8* src_yuy2, + uint8* dst_u, uint8* dst_v, int width); +void YUY2ToYRow_SSE2(const uint8* src_yuy2, uint8* dst_y, int width); +void YUY2ToUVRow_SSE2(const uint8* src_yuy2, int stride_yuy2, + uint8* dst_u, uint8* dst_v, int width); +void YUY2ToUV422Row_SSE2(const uint8* src_yuy2, + uint8* dst_u, uint8* dst_v, int width); +void YUY2ToYRow_NEON(const uint8* src_yuy2, uint8* dst_y, int width); +void YUY2ToUVRow_NEON(const uint8* src_yuy2, int stride_yuy2, + uint8* dst_u, uint8* dst_v, int width); +void YUY2ToUV422Row_NEON(const uint8* src_yuy2, + uint8* dst_u, uint8* dst_v, int width); +void YUY2ToYRow_C(const uint8* src_yuy2, uint8* dst_y, int width); +void YUY2ToUVRow_C(const uint8* src_yuy2, int stride_yuy2, + uint8* dst_u, uint8* dst_v, int width); +void YUY2ToUV422Row_C(const uint8* src_yuy2, + uint8* dst_u, uint8* dst_v, int width); +void YUY2ToYRow_Any_AVX2(const uint8* src_yuy2, uint8* dst_y, int width); +void YUY2ToUVRow_Any_AVX2(const uint8* src_yuy2, int stride_yuy2, + uint8* dst_u, uint8* dst_v, int width); +void YUY2ToUV422Row_Any_AVX2(const uint8* src_yuy2, + uint8* dst_u, uint8* dst_v, int width); +void YUY2ToYRow_Any_SSE2(const uint8* src_yuy2, uint8* dst_y, int width); +void YUY2ToUVRow_Any_SSE2(const uint8* src_yuy2, int stride_yuy2, + uint8* dst_u, uint8* dst_v, int width); +void YUY2ToUV422Row_Any_SSE2(const uint8* src_yuy2, + uint8* dst_u, uint8* dst_v, int width); +void YUY2ToYRow_Any_NEON(const uint8* src_yuy2, uint8* dst_y, int width); +void YUY2ToUVRow_Any_NEON(const uint8* src_yuy2, int stride_yuy2, + uint8* dst_u, uint8* dst_v, int width); +void YUY2ToUV422Row_Any_NEON(const uint8* src_yuy2, + uint8* dst_u, uint8* dst_v, int width); +void UYVYToYRow_AVX2(const uint8* src_uyvy, uint8* dst_y, int width); +void UYVYToUVRow_AVX2(const uint8* src_uyvy, int stride_uyvy, + uint8* dst_u, uint8* dst_v, int width); +void UYVYToUV422Row_AVX2(const uint8* src_uyvy, + uint8* dst_u, uint8* dst_v, int width); +void UYVYToYRow_SSE2(const uint8* src_uyvy, uint8* dst_y, int width); +void UYVYToUVRow_SSE2(const uint8* src_uyvy, int stride_uyvy, + uint8* dst_u, uint8* dst_v, int width); +void UYVYToUV422Row_SSE2(const uint8* src_uyvy, + uint8* dst_u, uint8* dst_v, int width); +void UYVYToYRow_AVX2(const uint8* src_uyvy, uint8* dst_y, int width); +void UYVYToUVRow_AVX2(const uint8* src_uyvy, int stride_uyvy, + uint8* dst_u, uint8* dst_v, int width); +void UYVYToUV422Row_AVX2(const uint8* src_uyvy, + uint8* dst_u, uint8* dst_v, int width); +void UYVYToYRow_NEON(const uint8* src_uyvy, uint8* dst_y, int width); +void UYVYToUVRow_NEON(const uint8* src_uyvy, int stride_uyvy, + uint8* dst_u, uint8* dst_v, int width); +void UYVYToUV422Row_NEON(const uint8* src_uyvy, + uint8* dst_u, uint8* dst_v, int width); + +void UYVYToYRow_C(const uint8* src_uyvy, uint8* dst_y, int width); +void UYVYToUVRow_C(const uint8* src_uyvy, int stride_uyvy, + uint8* dst_u, uint8* dst_v, int width); +void UYVYToUV422Row_C(const uint8* src_uyvy, + uint8* dst_u, uint8* dst_v, int width); +void UYVYToYRow_Any_AVX2(const uint8* src_uyvy, uint8* dst_y, int width); +void UYVYToUVRow_Any_AVX2(const uint8* src_uyvy, int stride_uyvy, + uint8* dst_u, uint8* dst_v, int width); +void UYVYToUV422Row_Any_AVX2(const uint8* src_uyvy, + uint8* dst_u, uint8* dst_v, int width); +void UYVYToYRow_Any_SSE2(const uint8* src_uyvy, uint8* dst_y, int width); +void UYVYToUVRow_Any_SSE2(const uint8* src_uyvy, int stride_uyvy, + uint8* dst_u, uint8* dst_v, int width); +void UYVYToUV422Row_Any_SSE2(const uint8* src_uyvy, + uint8* dst_u, uint8* dst_v, int width); +void UYVYToYRow_Any_NEON(const uint8* src_uyvy, uint8* dst_y, int width); +void UYVYToUVRow_Any_NEON(const uint8* src_uyvy, int stride_uyvy, + uint8* dst_u, uint8* dst_v, int width); +void UYVYToUV422Row_Any_NEON(const uint8* src_uyvy, + uint8* dst_u, uint8* dst_v, int width); + +void I422ToYUY2Row_C(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_yuy2, int width); +void I422ToUYVYRow_C(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_uyvy, int width); +void I422ToYUY2Row_SSE2(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_yuy2, int width); +void I422ToUYVYRow_SSE2(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_uyvy, int width); +void I422ToYUY2Row_Any_SSE2(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_yuy2, int width); +void I422ToUYVYRow_Any_SSE2(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_uyvy, int width); +void I422ToYUY2Row_NEON(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_yuy2, int width); +void I422ToUYVYRow_NEON(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_uyvy, int width); +void I422ToYUY2Row_Any_NEON(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_yuy2, int width); +void I422ToUYVYRow_Any_NEON(const uint8* src_y, + const uint8* src_u, + const uint8* src_v, + uint8* dst_uyvy, int width); + +// Effects related row functions. +void ARGBAttenuateRow_C(const uint8* src_argb, uint8* dst_argb, int width); +void ARGBAttenuateRow_SSSE3(const uint8* src_argb, uint8* dst_argb, int width); +void ARGBAttenuateRow_AVX2(const uint8* src_argb, uint8* dst_argb, int width); +void ARGBAttenuateRow_NEON(const uint8* src_argb, uint8* dst_argb, int width); +void ARGBAttenuateRow_Any_SSE2(const uint8* src_argb, uint8* dst_argb, + int width); +void ARGBAttenuateRow_Any_SSSE3(const uint8* src_argb, uint8* dst_argb, + int width); +void ARGBAttenuateRow_Any_AVX2(const uint8* src_argb, uint8* dst_argb, + int width); +void ARGBAttenuateRow_Any_NEON(const uint8* src_argb, uint8* dst_argb, + int width); + +// Inverse table for unattenuate, shared by C and SSE2. +extern const uint32 fixed_invtbl8[256]; +void ARGBUnattenuateRow_C(const uint8* src_argb, uint8* dst_argb, int width); +void ARGBUnattenuateRow_SSE2(const uint8* src_argb, uint8* dst_argb, int width); +void ARGBUnattenuateRow_AVX2(const uint8* src_argb, uint8* dst_argb, int width); +void ARGBUnattenuateRow_Any_SSE2(const uint8* src_argb, uint8* dst_argb, + int width); +void ARGBUnattenuateRow_Any_AVX2(const uint8* src_argb, uint8* dst_argb, + int width); + +void ARGBGrayRow_C(const uint8* src_argb, uint8* dst_argb, int width); +void ARGBGrayRow_SSSE3(const uint8* src_argb, uint8* dst_argb, int width); +void ARGBGrayRow_NEON(const uint8* src_argb, uint8* dst_argb, int width); + +void ARGBSepiaRow_C(uint8* dst_argb, int width); +void ARGBSepiaRow_SSSE3(uint8* dst_argb, int width); +void ARGBSepiaRow_NEON(uint8* dst_argb, int width); + +void ARGBColorMatrixRow_C(const uint8* src_argb, uint8* dst_argb, + const int8* matrix_argb, int width); +void ARGBColorMatrixRow_SSSE3(const uint8* src_argb, uint8* dst_argb, + const int8* matrix_argb, int width); +void ARGBColorMatrixRow_NEON(const uint8* src_argb, uint8* dst_argb, + const int8* matrix_argb, int width); + +void ARGBColorTableRow_C(uint8* dst_argb, const uint8* table_argb, int width); +void ARGBColorTableRow_X86(uint8* dst_argb, const uint8* table_argb, int width); + +void RGBColorTableRow_C(uint8* dst_argb, const uint8* table_argb, int width); +void RGBColorTableRow_X86(uint8* dst_argb, const uint8* table_argb, int width); + +void ARGBQuantizeRow_C(uint8* dst_argb, int scale, int interval_size, + int interval_offset, int width); +void ARGBQuantizeRow_SSE2(uint8* dst_argb, int scale, int interval_size, + int interval_offset, int width); +void ARGBQuantizeRow_NEON(uint8* dst_argb, int scale, int interval_size, + int interval_offset, int width); + +void ARGBShadeRow_C(const uint8* src_argb, uint8* dst_argb, int width, + uint32 value); +void ARGBShadeRow_SSE2(const uint8* src_argb, uint8* dst_argb, int width, + uint32 value); +void ARGBShadeRow_NEON(const uint8* src_argb, uint8* dst_argb, int width, + uint32 value); + +// Used for blur. +void CumulativeSumToAverageRow_SSE2(const int32* topleft, const int32* botleft, + int width, int area, uint8* dst, int count); +void ComputeCumulativeSumRow_SSE2(const uint8* row, int32* cumsum, + const int32* previous_cumsum, int width); + +void CumulativeSumToAverageRow_C(const int32* topleft, const int32* botleft, + int width, int area, uint8* dst, int count); +void ComputeCumulativeSumRow_C(const uint8* row, int32* cumsum, + const int32* previous_cumsum, int width); + +LIBYUV_API +void ARGBAffineRow_C(const uint8* src_argb, int src_argb_stride, + uint8* dst_argb, const float* uv_dudv, int width); +LIBYUV_API +void ARGBAffineRow_SSE2(const uint8* src_argb, int src_argb_stride, + uint8* dst_argb, const float* uv_dudv, int width); + +// Used for I420Scale, ARGBScale, and ARGBInterpolate. +void InterpolateRow_C(uint8* dst_ptr, const uint8* src_ptr, + ptrdiff_t src_stride_ptr, + int width, int source_y_fraction); +void InterpolateRow_SSSE3(uint8* dst_ptr, const uint8* src_ptr, + ptrdiff_t src_stride_ptr, int width, + int source_y_fraction); +void InterpolateRow_AVX2(uint8* dst_ptr, const uint8* src_ptr, + ptrdiff_t src_stride_ptr, int width, + int source_y_fraction); +void InterpolateRow_NEON(uint8* dst_ptr, const uint8* src_ptr, + ptrdiff_t src_stride_ptr, int width, + int source_y_fraction); +void InterpolateRow_DSPR2(uint8* dst_ptr, const uint8* src_ptr, + ptrdiff_t src_stride_ptr, int width, + int source_y_fraction); +void InterpolateRow_Any_NEON(uint8* dst_ptr, const uint8* src_ptr, + ptrdiff_t src_stride_ptr, int width, + int source_y_fraction); +void InterpolateRow_Any_SSSE3(uint8* dst_ptr, const uint8* src_ptr, + ptrdiff_t src_stride_ptr, int width, + int source_y_fraction); +void InterpolateRow_Any_AVX2(uint8* dst_ptr, const uint8* src_ptr, + ptrdiff_t src_stride_ptr, int width, + int source_y_fraction); +void InterpolateRow_Any_DSPR2(uint8* dst_ptr, const uint8* src_ptr, + ptrdiff_t src_stride_ptr, int width, + int source_y_fraction); + +void InterpolateRow_16_C(uint16* dst_ptr, const uint16* src_ptr, + ptrdiff_t src_stride_ptr, + int width, int source_y_fraction); + +// Sobel images. +void SobelXRow_C(const uint8* src_y0, const uint8* src_y1, const uint8* src_y2, + uint8* dst_sobelx, int width); +void SobelXRow_SSE2(const uint8* src_y0, const uint8* src_y1, + const uint8* src_y2, uint8* dst_sobelx, int width); +void SobelXRow_NEON(const uint8* src_y0, const uint8* src_y1, + const uint8* src_y2, uint8* dst_sobelx, int width); +void SobelYRow_C(const uint8* src_y0, const uint8* src_y1, + uint8* dst_sobely, int width); +void SobelYRow_SSE2(const uint8* src_y0, const uint8* src_y1, + uint8* dst_sobely, int width); +void SobelYRow_NEON(const uint8* src_y0, const uint8* src_y1, + uint8* dst_sobely, int width); +void SobelRow_C(const uint8* src_sobelx, const uint8* src_sobely, + uint8* dst_argb, int width); +void SobelRow_SSE2(const uint8* src_sobelx, const uint8* src_sobely, + uint8* dst_argb, int width); +void SobelRow_NEON(const uint8* src_sobelx, const uint8* src_sobely, + uint8* dst_argb, int width); +void SobelToPlaneRow_C(const uint8* src_sobelx, const uint8* src_sobely, + uint8* dst_y, int width); +void SobelToPlaneRow_SSE2(const uint8* src_sobelx, const uint8* src_sobely, + uint8* dst_y, int width); +void SobelToPlaneRow_NEON(const uint8* src_sobelx, const uint8* src_sobely, + uint8* dst_y, int width); +void SobelXYRow_C(const uint8* src_sobelx, const uint8* src_sobely, + uint8* dst_argb, int width); +void SobelXYRow_SSE2(const uint8* src_sobelx, const uint8* src_sobely, + uint8* dst_argb, int width); +void SobelXYRow_NEON(const uint8* src_sobelx, const uint8* src_sobely, + uint8* dst_argb, int width); +void SobelRow_Any_SSE2(const uint8* src_sobelx, const uint8* src_sobely, + uint8* dst_argb, int width); +void SobelRow_Any_NEON(const uint8* src_sobelx, const uint8* src_sobely, + uint8* dst_argb, int width); +void SobelToPlaneRow_Any_SSE2(const uint8* src_sobelx, const uint8* src_sobely, + uint8* dst_y, int width); +void SobelToPlaneRow_Any_NEON(const uint8* src_sobelx, const uint8* src_sobely, + uint8* dst_y, int width); +void SobelXYRow_Any_SSE2(const uint8* src_sobelx, const uint8* src_sobely, + uint8* dst_argb, int width); +void SobelXYRow_Any_NEON(const uint8* src_sobelx, const uint8* src_sobely, + uint8* dst_argb, int width); + +void ARGBPolynomialRow_C(const uint8* src_argb, + uint8* dst_argb, const float* poly, + int width); +void ARGBPolynomialRow_SSE2(const uint8* src_argb, + uint8* dst_argb, const float* poly, + int width); +void ARGBPolynomialRow_AVX2(const uint8* src_argb, + uint8* dst_argb, const float* poly, + int width); + +// Scale and convert to half float. +void HalfFloatRow_C(const uint16* src, uint16* dst, float scale, int width); +void HalfFloatRow_AVX2(const uint16* src, uint16* dst, float scale, int width); +void HalfFloatRow_Any_AVX2(const uint16* src, uint16* dst, float scale, + int width); +void HalfFloatRow_SSE2(const uint16* src, uint16* dst, float scale, int width); +void HalfFloatRow_Any_SSE2(const uint16* src, uint16* dst, float scale, + int width); + +void ARGBLumaColorTableRow_C(const uint8* src_argb, uint8* dst_argb, int width, + const uint8* luma, uint32 lumacoeff); +void ARGBLumaColorTableRow_SSSE3(const uint8* src_argb, uint8* dst_argb, + int width, + const uint8* luma, uint32 lumacoeff); + +#ifdef __cplusplus +} // extern "C" +} // namespace libyuv +#endif + +#endif // INCLUDE_LIBYUV_ROW_H_ diff --git a/phonelibs/libyuv/include/libyuv/scale.h b/phonelibs/libyuv/include/libyuv/scale.h new file mode 100644 index 00000000000000..ae14694598b2cc --- /dev/null +++ b/phonelibs/libyuv/include/libyuv/scale.h @@ -0,0 +1,103 @@ +/* + * Copyright 2011 The LibYuv Project Authors. All rights reserved. + * + * Use of this source code is governed by a BSD-style license + * that can be found in the LICENSE file in the root of the source + * tree. An additional intellectual property rights grant can be found + * in the file PATENTS. All contributing project authors may + * be found in the AUTHORS file in the root of the source tree. + */ + +#ifndef INCLUDE_LIBYUV_SCALE_H_ +#define INCLUDE_LIBYUV_SCALE_H_ + +#include "libyuv/basic_types.h" + +#ifdef __cplusplus +namespace libyuv { +extern "C" { +#endif + +// Supported filtering. +typedef enum FilterMode { + kFilterNone = 0, // Point sample; Fastest. + kFilterLinear = 1, // Filter horizontally only. + kFilterBilinear = 2, // Faster than box, but lower quality scaling down. + kFilterBox = 3 // Highest quality. +} FilterModeEnum; + +// Scale a YUV plane. +LIBYUV_API +void ScalePlane(const uint8* src, int src_stride, + int src_width, int src_height, + uint8* dst, int dst_stride, + int dst_width, int dst_height, + enum FilterMode filtering); + +LIBYUV_API +void ScalePlane_16(const uint16* src, int src_stride, + int src_width, int src_height, + uint16* dst, int dst_stride, + int dst_width, int dst_height, + enum FilterMode filtering); + +// Scales a YUV 4:2:0 image from the src width and height to the +// dst width and height. +// If filtering is kFilterNone, a simple nearest-neighbor algorithm is +// used. This produces basic (blocky) quality at the fastest speed. +// If filtering is kFilterBilinear, interpolation is used to produce a better +// quality image, at the expense of speed. +// If filtering is kFilterBox, averaging is used to produce ever better +// quality image, at further expense of speed. +// Returns 0 if successful. + +LIBYUV_API +int I420Scale(const uint8* src_y, int src_stride_y, + const uint8* src_u, int src_stride_u, + const uint8* src_v, int src_stride_v, + int src_width, int src_height, + uint8* dst_y, int dst_stride_y, + uint8* dst_u, int dst_stride_u, + uint8* dst_v, int dst_stride_v, + int dst_width, int dst_height, + enum FilterMode filtering); + +LIBYUV_API +int I420Scale_16(const uint16* src_y, int src_stride_y, + const uint16* src_u, int src_stride_u, + const uint16* src_v, int src_stride_v, + int src_width, int src_height, + uint16* dst_y, int dst_stride_y, + uint16* dst_u, int dst_stride_u, + uint16* dst_v, int dst_stride_v, + int dst_width, int dst_height, + enum FilterMode filtering); + +#ifdef __cplusplus +// Legacy API. Deprecated. +LIBYUV_API +int Scale(const uint8* src_y, const uint8* src_u, const uint8* src_v, + int src_stride_y, int src_stride_u, int src_stride_v, + int src_width, int src_height, + uint8* dst_y, uint8* dst_u, uint8* dst_v, + int dst_stride_y, int dst_stride_u, int dst_stride_v, + int dst_width, int dst_height, + LIBYUV_BOOL interpolate); + +// Legacy API. Deprecated. +LIBYUV_API +int ScaleOffset(const uint8* src_i420, int src_width, int src_height, + uint8* dst_i420, int dst_width, int dst_height, int dst_yoffset, + LIBYUV_BOOL interpolate); + +// For testing, allow disabling of specialized scalers. +LIBYUV_API +void SetUseReferenceImpl(LIBYUV_BOOL use); +#endif // __cplusplus + +#ifdef __cplusplus +} // extern "C" +} // namespace libyuv +#endif + +#endif // INCLUDE_LIBYUV_SCALE_H_ diff --git a/phonelibs/libyuv/include/libyuv/scale_argb.h b/phonelibs/libyuv/include/libyuv/scale_argb.h new file mode 100644 index 00000000000000..35cd191c0f6123 --- /dev/null +++ b/phonelibs/libyuv/include/libyuv/scale_argb.h @@ -0,0 +1,56 @@ +/* + * Copyright 2012 The LibYuv Project Authors. All rights reserved. + * + * Use of this source code is governed by a BSD-style license + * that can be found in the LICENSE file in the root of the source + * tree. An additional intellectual property rights grant can be found + * in the file PATENTS. All contributing project authors may + * be found in the AUTHORS file in the root of the source tree. + */ + +#ifndef INCLUDE_LIBYUV_SCALE_ARGB_H_ +#define INCLUDE_LIBYUV_SCALE_ARGB_H_ + +#include "libyuv/basic_types.h" +#include "libyuv/scale.h" // For FilterMode + +#ifdef __cplusplus +namespace libyuv { +extern "C" { +#endif + +LIBYUV_API +int ARGBScale(const uint8* src_argb, int src_stride_argb, + int src_width, int src_height, + uint8* dst_argb, int dst_stride_argb, + int dst_width, int dst_height, + enum FilterMode filtering); + +// Clipped scale takes destination rectangle coordinates for clip values. +LIBYUV_API +int ARGBScaleClip(const uint8* src_argb, int src_stride_argb, + int src_width, int src_height, + uint8* dst_argb, int dst_stride_argb, + int dst_width, int dst_height, + int clip_x, int clip_y, int clip_width, int clip_height, + enum FilterMode filtering); + +// Scale with YUV conversion to ARGB and clipping. +LIBYUV_API +int YUVToARGBScaleClip(const uint8* src_y, int src_stride_y, + const uint8* src_u, int src_stride_u, + const uint8* src_v, int src_stride_v, + uint32 src_fourcc, + int src_width, int src_height, + uint8* dst_argb, int dst_stride_argb, + uint32 dst_fourcc, + int dst_width, int dst_height, + int clip_x, int clip_y, int clip_width, int clip_height, + enum FilterMode filtering); + +#ifdef __cplusplus +} // extern "C" +} // namespace libyuv +#endif + +#endif // INCLUDE_LIBYUV_SCALE_ARGB_H_ diff --git a/phonelibs/libyuv/include/libyuv/scale_row.h b/phonelibs/libyuv/include/libyuv/scale_row.h new file mode 100644 index 00000000000000..791fbf7d0538fb --- /dev/null +++ b/phonelibs/libyuv/include/libyuv/scale_row.h @@ -0,0 +1,503 @@ +/* + * Copyright 2013 The LibYuv Project Authors. All rights reserved. + * + * Use of this source code is governed by a BSD-style license + * that can be found in the LICENSE file in the root of the source + * tree. An additional intellectual property rights grant can be found + * in the file PATENTS. All contributing project authors may + * be found in the AUTHORS file in the root of the source tree. + */ + +#ifndef INCLUDE_LIBYUV_SCALE_ROW_H_ +#define INCLUDE_LIBYUV_SCALE_ROW_H_ + +#include "libyuv/basic_types.h" +#include "libyuv/scale.h" + +#ifdef __cplusplus +namespace libyuv { +extern "C" { +#endif + +#if defined(__pnacl__) || defined(__CLR_VER) || \ + (defined(__i386__) && !defined(__SSE2__)) +#define LIBYUV_DISABLE_X86 +#endif +// MemorySanitizer does not support assembly code yet. http://crbug.com/344505 +#if defined(__has_feature) +#if __has_feature(memory_sanitizer) +#define LIBYUV_DISABLE_X86 +#endif +#endif + +// GCC >= 4.7.0 required for AVX2. +#if defined(__GNUC__) && (defined(__x86_64__) || defined(__i386__)) +#if (__GNUC__ > 4) || (__GNUC__ == 4 && (__GNUC_MINOR__ >= 7)) +#define GCC_HAS_AVX2 1 +#endif // GNUC >= 4.7 +#endif // __GNUC__ + +// clang >= 3.4.0 required for AVX2. +#if defined(__clang__) && (defined(__x86_64__) || defined(__i386__)) +#if (__clang_major__ > 3) || (__clang_major__ == 3 && (__clang_minor__ >= 4)) +#define CLANG_HAS_AVX2 1 +#endif // clang >= 3.4 +#endif // __clang__ + +// Visual C 2012 required for AVX2. +#if defined(_M_IX86) && !defined(__clang__) && \ + defined(_MSC_VER) && _MSC_VER >= 1700 +#define VISUALC_HAS_AVX2 1 +#endif // VisualStudio >= 2012 + +// The following are available on all x86 platforms: +#if !defined(LIBYUV_DISABLE_X86) && \ + (defined(_M_IX86) || defined(__x86_64__) || defined(__i386__)) +#define HAS_FIXEDDIV1_X86 +#define HAS_FIXEDDIV_X86 +#define HAS_SCALEARGBCOLS_SSE2 +#define HAS_SCALEARGBCOLSUP2_SSE2 +#define HAS_SCALEARGBFILTERCOLS_SSSE3 +#define HAS_SCALEARGBROWDOWN2_SSE2 +#define HAS_SCALEARGBROWDOWNEVEN_SSE2 +#define HAS_SCALECOLSUP2_SSE2 +#define HAS_SCALEFILTERCOLS_SSSE3 +#define HAS_SCALEROWDOWN2_SSSE3 +#define HAS_SCALEROWDOWN34_SSSE3 +#define HAS_SCALEROWDOWN38_SSSE3 +#define HAS_SCALEROWDOWN4_SSSE3 +#define HAS_SCALEADDROW_SSE2 +#endif + +// The following are available on all x86 platforms, but +// require VS2012, clang 3.4 or gcc 4.7. +// The code supports NaCL but requires a new compiler and validator. +#if !defined(LIBYUV_DISABLE_X86) && (defined(VISUALC_HAS_AVX2) || \ + defined(CLANG_HAS_AVX2) || defined(GCC_HAS_AVX2)) +#define HAS_SCALEADDROW_AVX2 +#define HAS_SCALEROWDOWN2_AVX2 +#define HAS_SCALEROWDOWN4_AVX2 +#endif + +// The following are available on Neon platforms: +#if !defined(LIBYUV_DISABLE_NEON) && !defined(__native_client__) && \ + (defined(__ARM_NEON__) || defined(LIBYUV_NEON) || defined(__aarch64__)) +#define HAS_SCALEARGBCOLS_NEON +#define HAS_SCALEARGBROWDOWN2_NEON +#define HAS_SCALEARGBROWDOWNEVEN_NEON +#define HAS_SCALEFILTERCOLS_NEON +#define HAS_SCALEROWDOWN2_NEON +#define HAS_SCALEROWDOWN34_NEON +#define HAS_SCALEROWDOWN38_NEON +#define HAS_SCALEROWDOWN4_NEON +#define HAS_SCALEARGBFILTERCOLS_NEON +#endif + +// The following are available on Mips platforms: +#if !defined(LIBYUV_DISABLE_MIPS) && !defined(__native_client__) && \ + defined(__mips__) && defined(__mips_dsp) && (__mips_dsp_rev >= 2) +#define HAS_SCALEROWDOWN2_DSPR2 +#define HAS_SCALEROWDOWN4_DSPR2 +#define HAS_SCALEROWDOWN34_DSPR2 +#define HAS_SCALEROWDOWN38_DSPR2 +#endif + +// Scale ARGB vertically with bilinear interpolation. +void ScalePlaneVertical(int src_height, + int dst_width, int dst_height, + int src_stride, int dst_stride, + const uint8* src_argb, uint8* dst_argb, + int x, int y, int dy, + int bpp, enum FilterMode filtering); + +void ScalePlaneVertical_16(int src_height, + int dst_width, int dst_height, + int src_stride, int dst_stride, + const uint16* src_argb, uint16* dst_argb, + int x, int y, int dy, + int wpp, enum FilterMode filtering); + +// Simplify the filtering based on scale factors. +enum FilterMode ScaleFilterReduce(int src_width, int src_height, + int dst_width, int dst_height, + enum FilterMode filtering); + +// Divide num by div and return as 16.16 fixed point result. +int FixedDiv_C(int num, int div); +int FixedDiv_X86(int num, int div); +// Divide num - 1 by div - 1 and return as 16.16 fixed point result. +int FixedDiv1_C(int num, int div); +int FixedDiv1_X86(int num, int div); +#ifdef HAS_FIXEDDIV_X86 +#define FixedDiv FixedDiv_X86 +#define FixedDiv1 FixedDiv1_X86 +#else +#define FixedDiv FixedDiv_C +#define FixedDiv1 FixedDiv1_C +#endif + +// Compute slope values for stepping. +void ScaleSlope(int src_width, int src_height, + int dst_width, int dst_height, + enum FilterMode filtering, + int* x, int* y, int* dx, int* dy); + +void ScaleRowDown2_C(const uint8* src_ptr, ptrdiff_t src_stride, + uint8* dst, int dst_width); +void ScaleRowDown2_16_C(const uint16* src_ptr, ptrdiff_t src_stride, + uint16* dst, int dst_width); +void ScaleRowDown2Linear_C(const uint8* src_ptr, ptrdiff_t src_stride, + uint8* dst, int dst_width); +void ScaleRowDown2Linear_16_C(const uint16* src_ptr, ptrdiff_t src_stride, + uint16* dst, int dst_width); +void ScaleRowDown2Box_C(const uint8* src_ptr, ptrdiff_t src_stride, + uint8* dst, int dst_width); +void ScaleRowDown2Box_Odd_C(const uint8* src_ptr, ptrdiff_t src_stride, + uint8* dst, int dst_width); +void ScaleRowDown2Box_16_C(const uint16* src_ptr, ptrdiff_t src_stride, + uint16* dst, int dst_width); +void ScaleRowDown4_C(const uint8* src_ptr, ptrdiff_t src_stride, + uint8* dst, int dst_width); +void ScaleRowDown4_16_C(const uint16* src_ptr, ptrdiff_t src_stride, + uint16* dst, int dst_width); +void ScaleRowDown4Box_C(const uint8* src_ptr, ptrdiff_t src_stride, + uint8* dst, int dst_width); +void ScaleRowDown4Box_16_C(const uint16* src_ptr, ptrdiff_t src_stride, + uint16* dst, int dst_width); +void ScaleRowDown34_C(const uint8* src_ptr, ptrdiff_t src_stride, + uint8* dst, int dst_width); +void ScaleRowDown34_16_C(const uint16* src_ptr, ptrdiff_t src_stride, + uint16* dst, int dst_width); +void ScaleRowDown34_0_Box_C(const uint8* src_ptr, ptrdiff_t src_stride, + uint8* d, int dst_width); +void ScaleRowDown34_0_Box_16_C(const uint16* src_ptr, ptrdiff_t src_stride, + uint16* d, int dst_width); +void ScaleRowDown34_1_Box_C(const uint8* src_ptr, ptrdiff_t src_stride, + uint8* d, int dst_width); +void ScaleRowDown34_1_Box_16_C(const uint16* src_ptr, ptrdiff_t src_stride, + uint16* d, int dst_width); +void ScaleCols_C(uint8* dst_ptr, const uint8* src_ptr, + int dst_width, int x, int dx); +void ScaleCols_16_C(uint16* dst_ptr, const uint16* src_ptr, + int dst_width, int x, int dx); +void ScaleColsUp2_C(uint8* dst_ptr, const uint8* src_ptr, + int dst_width, int, int); +void ScaleColsUp2_16_C(uint16* dst_ptr, const uint16* src_ptr, + int dst_width, int, int); +void ScaleFilterCols_C(uint8* dst_ptr, const uint8* src_ptr, + int dst_width, int x, int dx); +void ScaleFilterCols_16_C(uint16* dst_ptr, const uint16* src_ptr, + int dst_width, int x, int dx); +void ScaleFilterCols64_C(uint8* dst_ptr, const uint8* src_ptr, + int dst_width, int x, int dx); +void ScaleFilterCols64_16_C(uint16* dst_ptr, const uint16* src_ptr, + int dst_width, int x, int dx); +void ScaleRowDown38_C(const uint8* src_ptr, ptrdiff_t src_stride, + uint8* dst, int dst_width); +void ScaleRowDown38_16_C(const uint16* src_ptr, ptrdiff_t src_stride, + uint16* dst, int dst_width); +void ScaleRowDown38_3_Box_C(const uint8* src_ptr, + ptrdiff_t src_stride, + uint8* dst_ptr, int dst_width); +void ScaleRowDown38_3_Box_16_C(const uint16* src_ptr, + ptrdiff_t src_stride, + uint16* dst_ptr, int dst_width); +void ScaleRowDown38_2_Box_C(const uint8* src_ptr, ptrdiff_t src_stride, + uint8* dst_ptr, int dst_width); +void ScaleRowDown38_2_Box_16_C(const uint16* src_ptr, ptrdiff_t src_stride, + uint16* dst_ptr, int dst_width); +void ScaleAddRow_C(const uint8* src_ptr, uint16* dst_ptr, int src_width); +void ScaleAddRow_16_C(const uint16* src_ptr, uint32* dst_ptr, int src_width); +void ScaleARGBRowDown2_C(const uint8* src_argb, + ptrdiff_t src_stride, + uint8* dst_argb, int dst_width); +void ScaleARGBRowDown2Linear_C(const uint8* src_argb, + ptrdiff_t src_stride, + uint8* dst_argb, int dst_width); +void ScaleARGBRowDown2Box_C(const uint8* src_argb, ptrdiff_t src_stride, + uint8* dst_argb, int dst_width); +void ScaleARGBRowDownEven_C(const uint8* src_argb, ptrdiff_t src_stride, + int src_stepx, + uint8* dst_argb, int dst_width); +void ScaleARGBRowDownEvenBox_C(const uint8* src_argb, + ptrdiff_t src_stride, + int src_stepx, + uint8* dst_argb, int dst_width); +void ScaleARGBCols_C(uint8* dst_argb, const uint8* src_argb, + int dst_width, int x, int dx); +void ScaleARGBCols64_C(uint8* dst_argb, const uint8* src_argb, + int dst_width, int x, int dx); +void ScaleARGBColsUp2_C(uint8* dst_argb, const uint8* src_argb, + int dst_width, int, int); +void ScaleARGBFilterCols_C(uint8* dst_argb, const uint8* src_argb, + int dst_width, int x, int dx); +void ScaleARGBFilterCols64_C(uint8* dst_argb, const uint8* src_argb, + int dst_width, int x, int dx); + +// Specialized scalers for x86. +void ScaleRowDown2_SSSE3(const uint8* src_ptr, ptrdiff_t src_stride, + uint8* dst_ptr, int dst_width); +void ScaleRowDown2Linear_SSSE3(const uint8* src_ptr, ptrdiff_t src_stride, + uint8* dst_ptr, int dst_width); +void ScaleRowDown2Box_SSSE3(const uint8* src_ptr, ptrdiff_t src_stride, + uint8* dst_ptr, int dst_width); +void ScaleRowDown2_AVX2(const uint8* src_ptr, ptrdiff_t src_stride, + uint8* dst_ptr, int dst_width); +void ScaleRowDown2Linear_AVX2(const uint8* src_ptr, ptrdiff_t src_stride, + uint8* dst_ptr, int dst_width); +void ScaleRowDown2Box_AVX2(const uint8* src_ptr, ptrdiff_t src_stride, + uint8* dst_ptr, int dst_width); +void ScaleRowDown4_SSSE3(const uint8* src_ptr, ptrdiff_t src_stride, + uint8* dst_ptr, int dst_width); +void ScaleRowDown4Box_SSSE3(const uint8* src_ptr, ptrdiff_t src_stride, + uint8* dst_ptr, int dst_width); +void ScaleRowDown4_AVX2(const uint8* src_ptr, ptrdiff_t src_stride, + uint8* dst_ptr, int dst_width); +void ScaleRowDown4Box_AVX2(const uint8* src_ptr, ptrdiff_t src_stride, + uint8* dst_ptr, int dst_width); + +void ScaleRowDown34_SSSE3(const uint8* src_ptr, ptrdiff_t src_stride, + uint8* dst_ptr, int dst_width); +void ScaleRowDown34_1_Box_SSSE3(const uint8* src_ptr, + ptrdiff_t src_stride, + uint8* dst_ptr, int dst_width); +void ScaleRowDown34_0_Box_SSSE3(const uint8* src_ptr, + ptrdiff_t src_stride, + uint8* dst_ptr, int dst_width); +void ScaleRowDown38_SSSE3(const uint8* src_ptr, ptrdiff_t src_stride, + uint8* dst_ptr, int dst_width); +void ScaleRowDown38_3_Box_SSSE3(const uint8* src_ptr, + ptrdiff_t src_stride, + uint8* dst_ptr, int dst_width); +void ScaleRowDown38_2_Box_SSSE3(const uint8* src_ptr, + ptrdiff_t src_stride, + uint8* dst_ptr, int dst_width); +void ScaleRowDown2_Any_SSSE3(const uint8* src_ptr, ptrdiff_t src_stride, + uint8* dst_ptr, int dst_width); +void ScaleRowDown2Linear_Any_SSSE3(const uint8* src_ptr, ptrdiff_t src_stride, + uint8* dst_ptr, int dst_width); +void ScaleRowDown2Box_Any_SSSE3(const uint8* src_ptr, ptrdiff_t src_stride, + uint8* dst_ptr, int dst_width); +void ScaleRowDown2Box_Odd_SSSE3(const uint8* src_ptr, ptrdiff_t src_stride, + uint8* dst_ptr, int dst_width); +void ScaleRowDown2_Any_AVX2(const uint8* src_ptr, ptrdiff_t src_stride, + uint8* dst_ptr, int dst_width); +void ScaleRowDown2Linear_Any_AVX2(const uint8* src_ptr, ptrdiff_t src_stride, + uint8* dst_ptr, int dst_width); +void ScaleRowDown2Box_Any_AVX2(const uint8* src_ptr, ptrdiff_t src_stride, + uint8* dst_ptr, int dst_width); +void ScaleRowDown2Box_Odd_AVX2(const uint8* src_ptr, ptrdiff_t src_stride, + uint8* dst_ptr, int dst_width); +void ScaleRowDown4_Any_SSSE3(const uint8* src_ptr, ptrdiff_t src_stride, + uint8* dst_ptr, int dst_width); +void ScaleRowDown4Box_Any_SSSE3(const uint8* src_ptr, ptrdiff_t src_stride, + uint8* dst_ptr, int dst_width); +void ScaleRowDown4_Any_AVX2(const uint8* src_ptr, ptrdiff_t src_stride, + uint8* dst_ptr, int dst_width); +void ScaleRowDown4Box_Any_AVX2(const uint8* src_ptr, ptrdiff_t src_stride, + uint8* dst_ptr, int dst_width); + +void ScaleRowDown34_Any_SSSE3(const uint8* src_ptr, ptrdiff_t src_stride, + uint8* dst_ptr, int dst_width); +void ScaleRowDown34_1_Box_Any_SSSE3(const uint8* src_ptr, + ptrdiff_t src_stride, + uint8* dst_ptr, int dst_width); +void ScaleRowDown34_0_Box_Any_SSSE3(const uint8* src_ptr, + ptrdiff_t src_stride, + uint8* dst_ptr, int dst_width); +void ScaleRowDown38_Any_SSSE3(const uint8* src_ptr, ptrdiff_t src_stride, + uint8* dst_ptr, int dst_width); +void ScaleRowDown38_3_Box_Any_SSSE3(const uint8* src_ptr, + ptrdiff_t src_stride, + uint8* dst_ptr, int dst_width); +void ScaleRowDown38_2_Box_Any_SSSE3(const uint8* src_ptr, + ptrdiff_t src_stride, + uint8* dst_ptr, int dst_width); + +void ScaleAddRow_SSE2(const uint8* src_ptr, uint16* dst_ptr, int src_width); +void ScaleAddRow_AVX2(const uint8* src_ptr, uint16* dst_ptr, int src_width); +void ScaleAddRow_Any_SSE2(const uint8* src_ptr, uint16* dst_ptr, int src_width); +void ScaleAddRow_Any_AVX2(const uint8* src_ptr, uint16* dst_ptr, int src_width); + +void ScaleFilterCols_SSSE3(uint8* dst_ptr, const uint8* src_ptr, + int dst_width, int x, int dx); +void ScaleColsUp2_SSE2(uint8* dst_ptr, const uint8* src_ptr, + int dst_width, int x, int dx); + + +// ARGB Column functions +void ScaleARGBCols_SSE2(uint8* dst_argb, const uint8* src_argb, + int dst_width, int x, int dx); +void ScaleARGBFilterCols_SSSE3(uint8* dst_argb, const uint8* src_argb, + int dst_width, int x, int dx); +void ScaleARGBColsUp2_SSE2(uint8* dst_argb, const uint8* src_argb, + int dst_width, int x, int dx); +void ScaleARGBFilterCols_NEON(uint8* dst_argb, const uint8* src_argb, + int dst_width, int x, int dx); +void ScaleARGBCols_NEON(uint8* dst_argb, const uint8* src_argb, + int dst_width, int x, int dx); +void ScaleARGBFilterCols_Any_NEON(uint8* dst_argb, const uint8* src_argb, + int dst_width, int x, int dx); +void ScaleARGBCols_Any_NEON(uint8* dst_argb, const uint8* src_argb, + int dst_width, int x, int dx); + +// ARGB Row functions +void ScaleARGBRowDown2_SSE2(const uint8* src_argb, ptrdiff_t src_stride, + uint8* dst_argb, int dst_width); +void ScaleARGBRowDown2Linear_SSE2(const uint8* src_argb, ptrdiff_t src_stride, + uint8* dst_argb, int dst_width); +void ScaleARGBRowDown2Box_SSE2(const uint8* src_argb, ptrdiff_t src_stride, + uint8* dst_argb, int dst_width); +void ScaleARGBRowDown2_NEON(const uint8* src_ptr, ptrdiff_t src_stride, + uint8* dst, int dst_width); +void ScaleARGBRowDown2Linear_NEON(const uint8* src_argb, ptrdiff_t src_stride, + uint8* dst_argb, int dst_width); +void ScaleARGBRowDown2Box_NEON(const uint8* src_ptr, ptrdiff_t src_stride, + uint8* dst, int dst_width); +void ScaleARGBRowDown2_Any_SSE2(const uint8* src_argb, ptrdiff_t src_stride, + uint8* dst_argb, int dst_width); +void ScaleARGBRowDown2Linear_Any_SSE2(const uint8* src_argb, + ptrdiff_t src_stride, + uint8* dst_argb, int dst_width); +void ScaleARGBRowDown2Box_Any_SSE2(const uint8* src_argb, ptrdiff_t src_stride, + uint8* dst_argb, int dst_width); +void ScaleARGBRowDown2_Any_NEON(const uint8* src_ptr, ptrdiff_t src_stride, + uint8* dst, int dst_width); +void ScaleARGBRowDown2Linear_Any_NEON(const uint8* src_argb, + ptrdiff_t src_stride, + uint8* dst_argb, int dst_width); +void ScaleARGBRowDown2Box_Any_NEON(const uint8* src_ptr, ptrdiff_t src_stride, + uint8* dst, int dst_width); + +void ScaleARGBRowDownEven_SSE2(const uint8* src_argb, ptrdiff_t src_stride, + int src_stepx, uint8* dst_argb, int dst_width); +void ScaleARGBRowDownEvenBox_SSE2(const uint8* src_argb, ptrdiff_t src_stride, + int src_stepx, + uint8* dst_argb, int dst_width); +void ScaleARGBRowDownEven_NEON(const uint8* src_argb, ptrdiff_t src_stride, + int src_stepx, + uint8* dst_argb, int dst_width); +void ScaleARGBRowDownEvenBox_NEON(const uint8* src_argb, ptrdiff_t src_stride, + int src_stepx, + uint8* dst_argb, int dst_width); +void ScaleARGBRowDownEven_Any_SSE2(const uint8* src_argb, ptrdiff_t src_stride, + int src_stepx, + uint8* dst_argb, int dst_width); +void ScaleARGBRowDownEvenBox_Any_SSE2(const uint8* src_argb, + ptrdiff_t src_stride, + int src_stepx, + uint8* dst_argb, int dst_width); +void ScaleARGBRowDownEven_Any_NEON(const uint8* src_argb, ptrdiff_t src_stride, + int src_stepx, + uint8* dst_argb, int dst_width); +void ScaleARGBRowDownEvenBox_Any_NEON(const uint8* src_argb, + ptrdiff_t src_stride, + int src_stepx, + uint8* dst_argb, int dst_width); + +// ScaleRowDown2Box also used by planar functions +// NEON downscalers with interpolation. + +// Note - not static due to reuse in convert for 444 to 420. +void ScaleRowDown2_NEON(const uint8* src_ptr, ptrdiff_t src_stride, + uint8* dst, int dst_width); +void ScaleRowDown2Linear_NEON(const uint8* src_ptr, ptrdiff_t src_stride, + uint8* dst, int dst_width); +void ScaleRowDown2Box_NEON(const uint8* src_ptr, ptrdiff_t src_stride, + uint8* dst, int dst_width); + +void ScaleRowDown4_NEON(const uint8* src_ptr, ptrdiff_t src_stride, + uint8* dst_ptr, int dst_width); +void ScaleRowDown4Box_NEON(const uint8* src_ptr, ptrdiff_t src_stride, + uint8* dst_ptr, int dst_width); + +// Down scale from 4 to 3 pixels. Use the neon multilane read/write +// to load up the every 4th pixel into a 4 different registers. +// Point samples 32 pixels to 24 pixels. +void ScaleRowDown34_NEON(const uint8* src_ptr, + ptrdiff_t src_stride, + uint8* dst_ptr, int dst_width); +void ScaleRowDown34_0_Box_NEON(const uint8* src_ptr, + ptrdiff_t src_stride, + uint8* dst_ptr, int dst_width); +void ScaleRowDown34_1_Box_NEON(const uint8* src_ptr, + ptrdiff_t src_stride, + uint8* dst_ptr, int dst_width); + +// 32 -> 12 +void ScaleRowDown38_NEON(const uint8* src_ptr, + ptrdiff_t src_stride, + uint8* dst_ptr, int dst_width); +// 32x3 -> 12x1 +void ScaleRowDown38_3_Box_NEON(const uint8* src_ptr, + ptrdiff_t src_stride, + uint8* dst_ptr, int dst_width); +// 32x2 -> 12x1 +void ScaleRowDown38_2_Box_NEON(const uint8* src_ptr, + ptrdiff_t src_stride, + uint8* dst_ptr, int dst_width); + +void ScaleRowDown2_Any_NEON(const uint8* src_ptr, ptrdiff_t src_stride, + uint8* dst, int dst_width); +void ScaleRowDown2Linear_Any_NEON(const uint8* src_ptr, ptrdiff_t src_stride, + uint8* dst, int dst_width); +void ScaleRowDown2Box_Any_NEON(const uint8* src_ptr, ptrdiff_t src_stride, + uint8* dst, int dst_width); +void ScaleRowDown2Box_Odd_NEON(const uint8* src_ptr, ptrdiff_t src_stride, + uint8* dst, int dst_width); +void ScaleRowDown4_Any_NEON(const uint8* src_ptr, ptrdiff_t src_stride, + uint8* dst_ptr, int dst_width); +void ScaleRowDown4Box_Any_NEON(const uint8* src_ptr, ptrdiff_t src_stride, + uint8* dst_ptr, int dst_width); +void ScaleRowDown34_Any_NEON(const uint8* src_ptr, ptrdiff_t src_stride, + uint8* dst_ptr, int dst_width); +void ScaleRowDown34_0_Box_Any_NEON(const uint8* src_ptr, ptrdiff_t src_stride, + uint8* dst_ptr, int dst_width); +void ScaleRowDown34_1_Box_Any_NEON(const uint8* src_ptr, ptrdiff_t src_stride, + uint8* dst_ptr, int dst_width); +// 32 -> 12 +void ScaleRowDown38_Any_NEON(const uint8* src_ptr, ptrdiff_t src_stride, + uint8* dst_ptr, int dst_width); +// 32x3 -> 12x1 +void ScaleRowDown38_3_Box_Any_NEON(const uint8* src_ptr, ptrdiff_t src_stride, + uint8* dst_ptr, int dst_width); +// 32x2 -> 12x1 +void ScaleRowDown38_2_Box_Any_NEON(const uint8* src_ptr, ptrdiff_t src_stride, + uint8* dst_ptr, int dst_width); + +void ScaleAddRow_NEON(const uint8* src_ptr, uint16* dst_ptr, int src_width); +void ScaleAddRow_Any_NEON(const uint8* src_ptr, uint16* dst_ptr, int src_width); + +void ScaleFilterCols_NEON(uint8* dst_ptr, const uint8* src_ptr, + int dst_width, int x, int dx); + +void ScaleFilterCols_Any_NEON(uint8* dst_ptr, const uint8* src_ptr, + int dst_width, int x, int dx); + +void ScaleRowDown2_DSPR2(const uint8* src_ptr, ptrdiff_t src_stride, + uint8* dst, int dst_width); +void ScaleRowDown2Box_DSPR2(const uint8* src_ptr, ptrdiff_t src_stride, + uint8* dst, int dst_width); +void ScaleRowDown4_DSPR2(const uint8* src_ptr, ptrdiff_t src_stride, + uint8* dst, int dst_width); +void ScaleRowDown4Box_DSPR2(const uint8* src_ptr, ptrdiff_t src_stride, + uint8* dst, int dst_width); +void ScaleRowDown34_DSPR2(const uint8* src_ptr, ptrdiff_t src_stride, + uint8* dst, int dst_width); +void ScaleRowDown34_0_Box_DSPR2(const uint8* src_ptr, ptrdiff_t src_stride, + uint8* d, int dst_width); +void ScaleRowDown34_1_Box_DSPR2(const uint8* src_ptr, ptrdiff_t src_stride, + uint8* d, int dst_width); +void ScaleRowDown38_DSPR2(const uint8* src_ptr, ptrdiff_t src_stride, + uint8* dst, int dst_width); +void ScaleRowDown38_2_Box_DSPR2(const uint8* src_ptr, ptrdiff_t src_stride, + uint8* dst_ptr, int dst_width); +void ScaleRowDown38_3_Box_DSPR2(const uint8* src_ptr, ptrdiff_t src_stride, + uint8* dst_ptr, int dst_width); + +#ifdef __cplusplus +} // extern "C" +} // namespace libyuv +#endif + +#endif // INCLUDE_LIBYUV_SCALE_ROW_H_ diff --git a/phonelibs/libyuv/include/libyuv/version.h b/phonelibs/libyuv/include/libyuv/version.h new file mode 100644 index 00000000000000..3a8f6337ca22cd --- /dev/null +++ b/phonelibs/libyuv/include/libyuv/version.h @@ -0,0 +1,16 @@ +/* + * Copyright 2012 The LibYuv Project Authors. All rights reserved. + * + * Use of this source code is governed by a BSD-style license + * that can be found in the LICENSE file in the root of the source + * tree. An additional intellectual property rights grant can be found + * in the file PATENTS. All contributing project authors may + * be found in the AUTHORS file in the root of the source tree. + */ + +#ifndef INCLUDE_LIBYUV_VERSION_H_ +#define INCLUDE_LIBYUV_VERSION_H_ + +#define LIBYUV_VERSION 1622 + +#endif // INCLUDE_LIBYUV_VERSION_H_ diff --git a/phonelibs/libyuv/include/libyuv/video_common.h b/phonelibs/libyuv/include/libyuv/video_common.h new file mode 100644 index 00000000000000..cb425426a256e0 --- /dev/null +++ b/phonelibs/libyuv/include/libyuv/video_common.h @@ -0,0 +1,184 @@ +/* + * Copyright 2011 The LibYuv Project Authors. All rights reserved. + * + * Use of this source code is governed by a BSD-style license + * that can be found in the LICENSE file in the root of the source + * tree. An additional intellectual property rights grant can be found + * in the file PATENTS. All contributing project authors may + * be found in the AUTHORS file in the root of the source tree. + */ + +// Common definitions for video, including fourcc and VideoFormat. + +#ifndef INCLUDE_LIBYUV_VIDEO_COMMON_H_ +#define INCLUDE_LIBYUV_VIDEO_COMMON_H_ + +#include "libyuv/basic_types.h" + +#ifdef __cplusplus +namespace libyuv { +extern "C" { +#endif + +////////////////////////////////////////////////////////////////////////////// +// Definition of FourCC codes +////////////////////////////////////////////////////////////////////////////// + +// Convert four characters to a FourCC code. +// Needs to be a macro otherwise the OS X compiler complains when the kFormat* +// constants are used in a switch. +#ifdef __cplusplus +#define FOURCC(a, b, c, d) ( \ + (static_cast(a)) | (static_cast(b) << 8) | \ + (static_cast(c) << 16) | (static_cast(d) << 24)) +#else +#define FOURCC(a, b, c, d) ( \ + ((uint32)(a)) | ((uint32)(b) << 8) | /* NOLINT */ \ + ((uint32)(c) << 16) | ((uint32)(d) << 24)) /* NOLINT */ +#endif + +// Some pages discussing FourCC codes: +// http://www.fourcc.org/yuv.php +// http://v4l2spec.bytesex.org/spec/book1.htm +// http://developer.apple.com/quicktime/icefloe/dispatch020.html +// http://msdn.microsoft.com/library/windows/desktop/dd206750.aspx#nv12 +// http://people.xiph.org/~xiphmont/containers/nut/nut4cc.txt + +// FourCC codes grouped according to implementation efficiency. +// Primary formats should convert in 1 efficient step. +// Secondary formats are converted in 2 steps. +// Auxilliary formats call primary converters. +enum FourCC { + // 9 Primary YUV formats: 5 planar, 2 biplanar, 2 packed. + FOURCC_I420 = FOURCC('I', '4', '2', '0'), + FOURCC_I422 = FOURCC('I', '4', '2', '2'), + FOURCC_I444 = FOURCC('I', '4', '4', '4'), + FOURCC_I411 = FOURCC('I', '4', '1', '1'), + FOURCC_I400 = FOURCC('I', '4', '0', '0'), + FOURCC_NV21 = FOURCC('N', 'V', '2', '1'), + FOURCC_NV12 = FOURCC('N', 'V', '1', '2'), + FOURCC_YUY2 = FOURCC('Y', 'U', 'Y', '2'), + FOURCC_UYVY = FOURCC('U', 'Y', 'V', 'Y'), + + // 2 Secondary YUV formats: row biplanar. + FOURCC_M420 = FOURCC('M', '4', '2', '0'), + FOURCC_Q420 = FOURCC('Q', '4', '2', '0'), // deprecated. + + // 9 Primary RGB formats: 4 32 bpp, 2 24 bpp, 3 16 bpp. + FOURCC_ARGB = FOURCC('A', 'R', 'G', 'B'), + FOURCC_BGRA = FOURCC('B', 'G', 'R', 'A'), + FOURCC_ABGR = FOURCC('A', 'B', 'G', 'R'), + FOURCC_24BG = FOURCC('2', '4', 'B', 'G'), + FOURCC_RAW = FOURCC('r', 'a', 'w', ' '), + FOURCC_RGBA = FOURCC('R', 'G', 'B', 'A'), + FOURCC_RGBP = FOURCC('R', 'G', 'B', 'P'), // rgb565 LE. + FOURCC_RGBO = FOURCC('R', 'G', 'B', 'O'), // argb1555 LE. + FOURCC_R444 = FOURCC('R', '4', '4', '4'), // argb4444 LE. + + // 4 Secondary RGB formats: 4 Bayer Patterns. deprecated. + FOURCC_RGGB = FOURCC('R', 'G', 'G', 'B'), + FOURCC_BGGR = FOURCC('B', 'G', 'G', 'R'), + FOURCC_GRBG = FOURCC('G', 'R', 'B', 'G'), + FOURCC_GBRG = FOURCC('G', 'B', 'R', 'G'), + + // 1 Primary Compressed YUV format. + FOURCC_MJPG = FOURCC('M', 'J', 'P', 'G'), + + // 5 Auxiliary YUV variations: 3 with U and V planes are swapped, 1 Alias. + FOURCC_YV12 = FOURCC('Y', 'V', '1', '2'), + FOURCC_YV16 = FOURCC('Y', 'V', '1', '6'), + FOURCC_YV24 = FOURCC('Y', 'V', '2', '4'), + FOURCC_YU12 = FOURCC('Y', 'U', '1', '2'), // Linux version of I420. + FOURCC_J420 = FOURCC('J', '4', '2', '0'), + FOURCC_J400 = FOURCC('J', '4', '0', '0'), // unofficial fourcc + FOURCC_H420 = FOURCC('H', '4', '2', '0'), // unofficial fourcc + + // 14 Auxiliary aliases. CanonicalFourCC() maps these to canonical fourcc. + FOURCC_IYUV = FOURCC('I', 'Y', 'U', 'V'), // Alias for I420. + FOURCC_YU16 = FOURCC('Y', 'U', '1', '6'), // Alias for I422. + FOURCC_YU24 = FOURCC('Y', 'U', '2', '4'), // Alias for I444. + FOURCC_YUYV = FOURCC('Y', 'U', 'Y', 'V'), // Alias for YUY2. + FOURCC_YUVS = FOURCC('y', 'u', 'v', 's'), // Alias for YUY2 on Mac. + FOURCC_HDYC = FOURCC('H', 'D', 'Y', 'C'), // Alias for UYVY. + FOURCC_2VUY = FOURCC('2', 'v', 'u', 'y'), // Alias for UYVY on Mac. + FOURCC_JPEG = FOURCC('J', 'P', 'E', 'G'), // Alias for MJPG. + FOURCC_DMB1 = FOURCC('d', 'm', 'b', '1'), // Alias for MJPG on Mac. + FOURCC_BA81 = FOURCC('B', 'A', '8', '1'), // Alias for BGGR. + FOURCC_RGB3 = FOURCC('R', 'G', 'B', '3'), // Alias for RAW. + FOURCC_BGR3 = FOURCC('B', 'G', 'R', '3'), // Alias for 24BG. + FOURCC_CM32 = FOURCC(0, 0, 0, 32), // Alias for BGRA kCMPixelFormat_32ARGB + FOURCC_CM24 = FOURCC(0, 0, 0, 24), // Alias for RAW kCMPixelFormat_24RGB + FOURCC_L555 = FOURCC('L', '5', '5', '5'), // Alias for RGBO. + FOURCC_L565 = FOURCC('L', '5', '6', '5'), // Alias for RGBP. + FOURCC_5551 = FOURCC('5', '5', '5', '1'), // Alias for RGBO. + + // 1 Auxiliary compressed YUV format set aside for capturer. + FOURCC_H264 = FOURCC('H', '2', '6', '4'), + + // Match any fourcc. + FOURCC_ANY = -1, +}; + +enum FourCCBpp { + // Canonical fourcc codes used in our code. + FOURCC_BPP_I420 = 12, + FOURCC_BPP_I422 = 16, + FOURCC_BPP_I444 = 24, + FOURCC_BPP_I411 = 12, + FOURCC_BPP_I400 = 8, + FOURCC_BPP_NV21 = 12, + FOURCC_BPP_NV12 = 12, + FOURCC_BPP_YUY2 = 16, + FOURCC_BPP_UYVY = 16, + FOURCC_BPP_M420 = 12, + FOURCC_BPP_Q420 = 12, + FOURCC_BPP_ARGB = 32, + FOURCC_BPP_BGRA = 32, + FOURCC_BPP_ABGR = 32, + FOURCC_BPP_RGBA = 32, + FOURCC_BPP_24BG = 24, + FOURCC_BPP_RAW = 24, + FOURCC_BPP_RGBP = 16, + FOURCC_BPP_RGBO = 16, + FOURCC_BPP_R444 = 16, + FOURCC_BPP_RGGB = 8, + FOURCC_BPP_BGGR = 8, + FOURCC_BPP_GRBG = 8, + FOURCC_BPP_GBRG = 8, + FOURCC_BPP_YV12 = 12, + FOURCC_BPP_YV16 = 16, + FOURCC_BPP_YV24 = 24, + FOURCC_BPP_YU12 = 12, + FOURCC_BPP_J420 = 12, + FOURCC_BPP_J400 = 8, + FOURCC_BPP_H420 = 12, + FOURCC_BPP_MJPG = 0, // 0 means unknown. + FOURCC_BPP_H264 = 0, + FOURCC_BPP_IYUV = 12, + FOURCC_BPP_YU16 = 16, + FOURCC_BPP_YU24 = 24, + FOURCC_BPP_YUYV = 16, + FOURCC_BPP_YUVS = 16, + FOURCC_BPP_HDYC = 16, + FOURCC_BPP_2VUY = 16, + FOURCC_BPP_JPEG = 1, + FOURCC_BPP_DMB1 = 1, + FOURCC_BPP_BA81 = 8, + FOURCC_BPP_RGB3 = 24, + FOURCC_BPP_BGR3 = 24, + FOURCC_BPP_CM32 = 32, + FOURCC_BPP_CM24 = 24, + + // Match any fourcc. + FOURCC_BPP_ANY = 0, // 0 means unknown. +}; + +// Converts fourcc aliases into canonical ones. +LIBYUV_API uint32 CanonicalFourCC(uint32 fourcc); + +#ifdef __cplusplus +} // extern "C" +} // namespace libyuv +#endif + +#endif // INCLUDE_LIBYUV_VIDEO_COMMON_H_ diff --git a/phonelibs/libyuv/lib/libyuv.a b/phonelibs/libyuv/lib/libyuv.a new file mode 100644 index 00000000000000..228de4d03e3f13 Binary files /dev/null and b/phonelibs/libyuv/lib/libyuv.a differ diff --git a/phonelibs/libyuv/mac/lib/libyuv.a b/phonelibs/libyuv/mac/lib/libyuv.a new file mode 100644 index 00000000000000..4a1609ca7a6754 Binary files /dev/null and b/phonelibs/libyuv/mac/lib/libyuv.a differ diff --git a/phonelibs/libyuv/tx2/libyuv.a b/phonelibs/libyuv/tx2/libyuv.a new file mode 100644 index 00000000000000..bfe5b5b378a5e4 Binary files /dev/null and b/phonelibs/libyuv/tx2/libyuv.a differ diff --git a/phonelibs/libyuv/x64/include b/phonelibs/libyuv/x64/include new file mode 120000 index 00000000000000..f5030fe8899824 --- /dev/null +++ b/phonelibs/libyuv/x64/include @@ -0,0 +1 @@ +../include \ No newline at end of file diff --git a/phonelibs/libyuv/x64/lib/libyuv.a b/phonelibs/libyuv/x64/lib/libyuv.a new file mode 100644 index 00000000000000..c6afc56433cdce Binary files /dev/null and b/phonelibs/libyuv/x64/lib/libyuv.a differ diff --git a/phonelibs/linux/include/msm_ion.h b/phonelibs/linux/include/msm_ion.h new file mode 100644 index 00000000000000..e41b3170fd438e --- /dev/null +++ b/phonelibs/linux/include/msm_ion.h @@ -0,0 +1,211 @@ +#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 __user *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 __user *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/phonelibs/nanovg/fontstash.h b/phonelibs/nanovg/fontstash.h new file mode 100644 index 00000000000000..35dfb0f6525ea8 --- /dev/null +++ b/phonelibs/nanovg/fontstash.h @@ -0,0 +1,1718 @@ +// +// Copyright (c) 2009-2013 Mikko Mononen memon@inside.org +// +// 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 FONS_H +#define FONS_H + +#define FONS_INVALID -1 + +enum FONSflags { + FONS_ZERO_TOPLEFT = 1, + FONS_ZERO_BOTTOMLEFT = 2, +}; + +enum FONSalign { + // Horizontal align + FONS_ALIGN_LEFT = 1<<0, // Default + FONS_ALIGN_CENTER = 1<<1, + FONS_ALIGN_RIGHT = 1<<2, + // Vertical align + FONS_ALIGN_TOP = 1<<3, + FONS_ALIGN_MIDDLE = 1<<4, + FONS_ALIGN_BOTTOM = 1<<5, + FONS_ALIGN_BASELINE = 1<<6, // Default +}; + +enum FONSerrorCode { + // Font atlas is full. + FONS_ATLAS_FULL = 1, + // Scratch memory used to render glyphs is full, requested size reported in 'val', you may need to bump up FONS_SCRATCH_BUF_SIZE. + FONS_SCRATCH_FULL = 2, + // Calls to fonsPushState has created too large stack, if you need deep state stack bump up FONS_MAX_STATES. + FONS_STATES_OVERFLOW = 3, + // Trying to pop too many states fonsPopState(). + FONS_STATES_UNDERFLOW = 4, +}; + +struct FONSparams { + int width, height; + unsigned char flags; + void* userPtr; + int (*renderCreate)(void* uptr, int width, int height); + int (*renderResize)(void* uptr, int width, int height); + void (*renderUpdate)(void* uptr, int* rect, const unsigned char* data); + void (*renderDraw)(void* uptr, const float* verts, const float* tcoords, const unsigned int* colors, int nverts); + void (*renderDelete)(void* uptr); +}; +typedef struct FONSparams FONSparams; + +struct FONSquad +{ + float x0,y0,s0,t0; + float x1,y1,s1,t1; +}; +typedef struct FONSquad FONSquad; + +struct FONStextIter { + float x, y, nextx, nexty, scale, spacing; + unsigned int codepoint; + short isize, iblur; + struct FONSfont* font; + int prevGlyphIndex; + const char* str; + const char* next; + const char* end; + unsigned int utf8state; +}; +typedef struct FONStextIter FONStextIter; + +typedef struct FONScontext FONScontext; + +// Constructor and destructor. +FONScontext* fonsCreateInternal(FONSparams* params); +void fonsDeleteInternal(FONScontext* s); + +void fonsSetErrorCallback(FONScontext* s, void (*callback)(void* uptr, int error, int val), void* uptr); +// Returns current atlas size. +void fonsGetAtlasSize(FONScontext* s, int* width, int* height); +// Expands the atlas size. +int fonsExpandAtlas(FONScontext* s, int width, int height); +// Resets the whole stash. +int fonsResetAtlas(FONScontext* stash, int width, int height); + +// Add fonts +int fonsAddFont(FONScontext* s, const char* name, const char* path); +int fonsAddFontMem(FONScontext* s, const char* name, unsigned char* data, int ndata, int freeData); +int fonsGetFontByName(FONScontext* s, const char* name); + +// State handling +void fonsPushState(FONScontext* s); +void fonsPopState(FONScontext* s); +void fonsClearState(FONScontext* s); + +// State setting +void fonsSetSize(FONScontext* s, float size); +void fonsSetColor(FONScontext* s, unsigned int color); +void fonsSetSpacing(FONScontext* s, float spacing); +void fonsSetBlur(FONScontext* s, float blur); +void fonsSetAlign(FONScontext* s, int align); +void fonsSetFont(FONScontext* s, int font); + +// Draw text +float fonsDrawText(FONScontext* s, float x, float y, const char* string, const char* end); + +// Measure text +float fonsTextBounds(FONScontext* s, float x, float y, const char* string, const char* end, float* bounds); +void fonsLineBounds(FONScontext* s, float y, float* miny, float* maxy); +void fonsVertMetrics(FONScontext* s, float* ascender, float* descender, float* lineh); + +// Text iterator +int fonsTextIterInit(FONScontext* stash, FONStextIter* iter, float x, float y, const char* str, const char* end); +int fonsTextIterNext(FONScontext* stash, FONStextIter* iter, struct FONSquad* quad); + +// Pull texture changes +const unsigned char* fonsGetTextureData(FONScontext* stash, int* width, int* height); +int fonsValidateTexture(FONScontext* s, int* dirty); + +// Draws the stash texture for debugging +void fonsDrawDebug(FONScontext* s, float x, float y); + +#endif // FONTSTASH_H + + +#ifdef FONTSTASH_IMPLEMENTATION + +#define FONS_NOTUSED(v) (void)sizeof(v) + +#ifdef FONS_USE_FREETYPE + +#include +#include FT_FREETYPE_H +#include FT_ADVANCES_H +#include + +struct FONSttFontImpl { + FT_Face font; +}; +typedef struct FONSttFontImpl FONSttFontImpl; + +static FT_Library ftLibrary; + +int fons__tt_init(FONScontext *context) +{ + FT_Error ftError; + FONS_NOTUSED(context); + ftError = FT_Init_FreeType(&ftLibrary); + return ftError == 0; +} + +int fons__tt_loadFont(FONScontext *context, FONSttFontImpl *font, unsigned char *data, int dataSize) +{ + FT_Error ftError; + FONS_NOTUSED(context); + + //font->font.userdata = stash; + ftError = FT_New_Memory_Face(ftLibrary, (const FT_Byte*)data, dataSize, 0, &font->font); + return ftError == 0; +} + +void fons__tt_getFontVMetrics(FONSttFontImpl *font, int *ascent, int *descent, int *lineGap) +{ + *ascent = font->font->ascender; + *descent = font->font->descender; + *lineGap = font->font->height - (*ascent - *descent); +} + +float fons__tt_getPixelHeightScale(FONSttFontImpl *font, float size) +{ + return size / (font->font->ascender - font->font->descender); +} + +int fons__tt_getGlyphIndex(FONSttFontImpl *font, int codepoint) +{ + return FT_Get_Char_Index(font->font, codepoint); +} + +int fons__tt_buildGlyphBitmap(FONSttFontImpl *font, int glyph, float size, float scale, + int *advance, int *lsb, int *x0, int *y0, int *x1, int *y1) +{ + FT_Error ftError; + FT_GlyphSlot ftGlyph; + FT_Fixed advFixed; + FONS_NOTUSED(scale); + + ftError = FT_Set_Pixel_Sizes(font->font, 0, (FT_UInt)(size * (float)font->font->units_per_EM / (float)(font->font->ascender - font->font->descender))); + if (ftError) return 0; + ftError = FT_Load_Glyph(font->font, glyph, FT_LOAD_RENDER); + if (ftError) return 0; + ftError = FT_Get_Advance(font->font, glyph, FT_LOAD_NO_SCALE, &advFixed); + if (ftError) return 0; + ftGlyph = font->font->glyph; + *advance = (int)advFixed; + *lsb = (int)ftGlyph->metrics.horiBearingX; + *x0 = ftGlyph->bitmap_left; + *x1 = *x0 + ftGlyph->bitmap.width; + *y0 = -ftGlyph->bitmap_top; + *y1 = *y0 + ftGlyph->bitmap.rows; + return 1; +} + +void fons__tt_renderGlyphBitmap(FONSttFontImpl *font, unsigned char *output, int outWidth, int outHeight, int outStride, + float scaleX, float scaleY, int glyph) +{ + FT_GlyphSlot ftGlyph = font->font->glyph; + int ftGlyphOffset = 0; + int x, y; + FONS_NOTUSED(outWidth); + FONS_NOTUSED(outHeight); + FONS_NOTUSED(scaleX); + FONS_NOTUSED(scaleY); + FONS_NOTUSED(glyph); // glyph has already been loaded by fons__tt_buildGlyphBitmap + + for ( y = 0; y < ftGlyph->bitmap.rows; y++ ) { + for ( x = 0; x < ftGlyph->bitmap.width; x++ ) { + output[(y * outStride) + x] = ftGlyph->bitmap.buffer[ftGlyphOffset++]; + } + } +} + +int fons__tt_getGlyphKernAdvance(FONSttFontImpl *font, int glyph1, int glyph2) +{ + FT_Vector ftKerning; + FT_Get_Kerning(font->font, glyph1, glyph2, FT_KERNING_DEFAULT, &ftKerning); + return (int)((ftKerning.x + 32) >> 6); // Round up and convert to integer +} + +#else + +#define STB_TRUETYPE_IMPLEMENTATION +static void* fons__tmpalloc(size_t size, void* up); +static void fons__tmpfree(void* ptr, void* up); +#define STBTT_malloc(x,u) fons__tmpalloc(x,u) +#define STBTT_free(x,u) fons__tmpfree(x,u) +#include "stb_truetype.h" + +struct FONSttFontImpl { + stbtt_fontinfo font; +}; +typedef struct FONSttFontImpl FONSttFontImpl; + +int fons__tt_init(FONScontext *context) +{ + FONS_NOTUSED(context); + return 1; +} + +int fons__tt_loadFont(FONScontext *context, FONSttFontImpl *font, unsigned char *data, int dataSize) +{ + int stbError; + FONS_NOTUSED(dataSize); + + font->font.userdata = context; + stbError = stbtt_InitFont(&font->font, data, 0); + return stbError; +} + +void fons__tt_getFontVMetrics(FONSttFontImpl *font, int *ascent, int *descent, int *lineGap) +{ + stbtt_GetFontVMetrics(&font->font, ascent, descent, lineGap); +} + +float fons__tt_getPixelHeightScale(FONSttFontImpl *font, float size) +{ + return stbtt_ScaleForPixelHeight(&font->font, size); +} + +int fons__tt_getGlyphIndex(FONSttFontImpl *font, int codepoint) +{ + return stbtt_FindGlyphIndex(&font->font, codepoint); +} + +int fons__tt_buildGlyphBitmap(FONSttFontImpl *font, int glyph, float size, float scale, + int *advance, int *lsb, int *x0, int *y0, int *x1, int *y1) +{ + FONS_NOTUSED(size); + stbtt_GetGlyphHMetrics(&font->font, glyph, advance, lsb); + stbtt_GetGlyphBitmapBox(&font->font, glyph, scale, scale, x0, y0, x1, y1); + return 1; +} + +void fons__tt_renderGlyphBitmap(FONSttFontImpl *font, unsigned char *output, int outWidth, int outHeight, int outStride, + float scaleX, float scaleY, int glyph) +{ + stbtt_MakeGlyphBitmap(&font->font, output, outWidth, outHeight, outStride, scaleX, scaleY, glyph); +} + +int fons__tt_getGlyphKernAdvance(FONSttFontImpl *font, int glyph1, int glyph2) +{ + return stbtt_GetGlyphKernAdvance(&font->font, glyph1, glyph2); +} + +#endif + +#ifndef FONS_SCRATCH_BUF_SIZE +# define FONS_SCRATCH_BUF_SIZE 64000 +#endif +#ifndef FONS_HASH_LUT_SIZE +# define FONS_HASH_LUT_SIZE 256 +#endif +#ifndef FONS_INIT_FONTS +# define FONS_INIT_FONTS 4 +#endif +#ifndef FONS_INIT_GLYPHS +# define FONS_INIT_GLYPHS 256 +#endif +#ifndef FONS_INIT_ATLAS_NODES +# define FONS_INIT_ATLAS_NODES 256 +#endif +#ifndef FONS_VERTEX_COUNT +# define FONS_VERTEX_COUNT 1024 +#endif +#ifndef FONS_MAX_STATES +# define FONS_MAX_STATES 20 +#endif +#ifndef FONS_MAX_FALLBACKS +# define FONS_MAX_FALLBACKS 20 +#endif + +static unsigned int fons__hashint(unsigned int a) +{ + a += ~(a<<15); + a ^= (a>>10); + a += (a<<3); + a ^= (a>>6); + a += ~(a<<11); + a ^= (a>>16); + return a; +} + +static int fons__mini(int a, int b) +{ + return a < b ? a : b; +} + +static int fons__maxi(int a, int b) +{ + return a > b ? a : b; +} + +struct FONSglyph +{ + unsigned int codepoint; + int index; + int next; + short size, blur; + short x0,y0,x1,y1; + short xadv,xoff,yoff; +}; +typedef struct FONSglyph FONSglyph; + +struct FONSfont +{ + FONSttFontImpl font; + char name[64]; + unsigned char* data; + int dataSize; + unsigned char freeData; + float ascender; + float descender; + float lineh; + FONSglyph* glyphs; + int cglyphs; + int nglyphs; + int lut[FONS_HASH_LUT_SIZE]; + int fallbacks[FONS_MAX_FALLBACKS]; + int nfallbacks; +}; +typedef struct FONSfont FONSfont; + +struct FONSstate +{ + int font; + int align; + float size; + unsigned int color; + float blur; + float spacing; +}; +typedef struct FONSstate FONSstate; + +struct FONSatlasNode { + short x, y, width; +}; +typedef struct FONSatlasNode FONSatlasNode; + +struct FONSatlas +{ + int width, height; + FONSatlasNode* nodes; + int nnodes; + int cnodes; +}; +typedef struct FONSatlas FONSatlas; + +struct FONScontext +{ + FONSparams params; + float itw,ith; + unsigned char* texData; + int dirtyRect[4]; + FONSfont** fonts; + FONSatlas* atlas; + int cfonts; + int nfonts; + float verts[FONS_VERTEX_COUNT*2]; + float tcoords[FONS_VERTEX_COUNT*2]; + unsigned int colors[FONS_VERTEX_COUNT]; + int nverts; + unsigned char* scratch; + int nscratch; + FONSstate states[FONS_MAX_STATES]; + int nstates; + void (*handleError)(void* uptr, int error, int val); + void* errorUptr; +}; + +#ifdef STB_TRUETYPE_IMPLEMENTATION + +static void* fons__tmpalloc(size_t size, void* up) +{ + unsigned char* ptr; + FONScontext* stash = (FONScontext*)up; + + // 16-byte align the returned pointer + size = (size + 0xf) & ~0xf; + + if (stash->nscratch+(int)size > FONS_SCRATCH_BUF_SIZE) { + if (stash->handleError) + stash->handleError(stash->errorUptr, FONS_SCRATCH_FULL, stash->nscratch+(int)size); + return NULL; + } + ptr = stash->scratch + stash->nscratch; + stash->nscratch += (int)size; + return ptr; +} + +static void fons__tmpfree(void* ptr, void* up) +{ + (void)ptr; + (void)up; + // empty +} + +#endif // STB_TRUETYPE_IMPLEMENTATION + +// Copyright (c) 2008-2010 Bjoern Hoehrmann +// See http://bjoern.hoehrmann.de/utf-8/decoder/dfa/ for details. + +#define FONS_UTF8_ACCEPT 0 +#define FONS_UTF8_REJECT 12 + +static unsigned int fons__decutf8(unsigned int* state, unsigned int* codep, unsigned int byte) +{ + static const unsigned char utf8d[] = { + // The first part of the table maps bytes to character classes that + // to reduce the size of the transition table and create bitmasks. + 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0, 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0, + 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0, 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0, + 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0, 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0, + 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0, 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0, + 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1, 9,9,9,9,9,9,9,9,9,9,9,9,9,9,9,9, + 7,7,7,7,7,7,7,7,7,7,7,7,7,7,7,7, 7,7,7,7,7,7,7,7,7,7,7,7,7,7,7,7, + 8,8,2,2,2,2,2,2,2,2,2,2,2,2,2,2, 2,2,2,2,2,2,2,2,2,2,2,2,2,2,2,2, + 10,3,3,3,3,3,3,3,3,3,3,3,3,4,3,3, 11,6,6,6,5,8,8,8,8,8,8,8,8,8,8,8, + + // The second part is a transition table that maps a combination + // of a state of the automaton and a character class to a state. + 0,12,24,36,60,96,84,12,12,12,48,72, 12,12,12,12,12,12,12,12,12,12,12,12, + 12, 0,12,12,12,12,12, 0,12, 0,12,12, 12,24,12,12,12,12,12,24,12,24,12,12, + 12,12,12,12,12,12,12,24,12,12,12,12, 12,24,12,12,12,12,12,12,12,24,12,12, + 12,12,12,12,12,12,12,36,12,36,12,12, 12,36,12,12,12,12,12,36,12,36,12,12, + 12,36,12,12,12,12,12,12,12,12,12,12, + }; + + unsigned int type = utf8d[byte]; + + *codep = (*state != FONS_UTF8_ACCEPT) ? + (byte & 0x3fu) | (*codep << 6) : + (0xff >> type) & (byte); + + *state = utf8d[256 + *state + type]; + return *state; +} + +// Atlas based on Skyline Bin Packer by Jukka Jylänki + +static void fons__deleteAtlas(FONSatlas* atlas) +{ + if (atlas == NULL) return; + if (atlas->nodes != NULL) free(atlas->nodes); + free(atlas); +} + +static FONSatlas* fons__allocAtlas(int w, int h, int nnodes) +{ + FONSatlas* atlas = NULL; + + // Allocate memory for the font stash. + atlas = (FONSatlas*)malloc(sizeof(FONSatlas)); + if (atlas == NULL) goto error; + memset(atlas, 0, sizeof(FONSatlas)); + + atlas->width = w; + atlas->height = h; + + // Allocate space for skyline nodes + atlas->nodes = (FONSatlasNode*)malloc(sizeof(FONSatlasNode) * nnodes); + if (atlas->nodes == NULL) goto error; + memset(atlas->nodes, 0, sizeof(FONSatlasNode) * nnodes); + atlas->nnodes = 0; + atlas->cnodes = nnodes; + + // Init root node. + atlas->nodes[0].x = 0; + atlas->nodes[0].y = 0; + atlas->nodes[0].width = (short)w; + atlas->nnodes++; + + return atlas; + +error: + if (atlas) fons__deleteAtlas(atlas); + return NULL; +} + +static int fons__atlasInsertNode(FONSatlas* atlas, int idx, int x, int y, int w) +{ + int i; + // Insert node + if (atlas->nnodes+1 > atlas->cnodes) { + atlas->cnodes = atlas->cnodes == 0 ? 8 : atlas->cnodes * 2; + atlas->nodes = (FONSatlasNode*)realloc(atlas->nodes, sizeof(FONSatlasNode) * atlas->cnodes); + if (atlas->nodes == NULL) + return 0; + } + for (i = atlas->nnodes; i > idx; i--) + atlas->nodes[i] = atlas->nodes[i-1]; + atlas->nodes[idx].x = (short)x; + atlas->nodes[idx].y = (short)y; + atlas->nodes[idx].width = (short)w; + atlas->nnodes++; + + return 1; +} + +static void fons__atlasRemoveNode(FONSatlas* atlas, int idx) +{ + int i; + if (atlas->nnodes == 0) return; + for (i = idx; i < atlas->nnodes-1; i++) + atlas->nodes[i] = atlas->nodes[i+1]; + atlas->nnodes--; +} + +static void fons__atlasExpand(FONSatlas* atlas, int w, int h) +{ + // Insert node for empty space + if (w > atlas->width) + fons__atlasInsertNode(atlas, atlas->nnodes, atlas->width, 0, w - atlas->width); + atlas->width = w; + atlas->height = h; +} + +static void fons__atlasReset(FONSatlas* atlas, int w, int h) +{ + atlas->width = w; + atlas->height = h; + atlas->nnodes = 0; + + // Init root node. + atlas->nodes[0].x = 0; + atlas->nodes[0].y = 0; + atlas->nodes[0].width = (short)w; + atlas->nnodes++; +} + +static int fons__atlasAddSkylineLevel(FONSatlas* atlas, int idx, int x, int y, int w, int h) +{ + int i; + + // Insert new node + if (fons__atlasInsertNode(atlas, idx, x, y+h, w) == 0) + return 0; + + // Delete skyline segments that fall under the shadow of the new segment. + for (i = idx+1; i < atlas->nnodes; i++) { + if (atlas->nodes[i].x < atlas->nodes[i-1].x + atlas->nodes[i-1].width) { + int shrink = atlas->nodes[i-1].x + atlas->nodes[i-1].width - atlas->nodes[i].x; + atlas->nodes[i].x += (short)shrink; + atlas->nodes[i].width -= (short)shrink; + if (atlas->nodes[i].width <= 0) { + fons__atlasRemoveNode(atlas, i); + i--; + } else { + break; + } + } else { + break; + } + } + + // Merge same height skyline segments that are next to each other. + for (i = 0; i < atlas->nnodes-1; i++) { + if (atlas->nodes[i].y == atlas->nodes[i+1].y) { + atlas->nodes[i].width += atlas->nodes[i+1].width; + fons__atlasRemoveNode(atlas, i+1); + i--; + } + } + + return 1; +} + +static int fons__atlasRectFits(FONSatlas* atlas, int i, int w, int h) +{ + // Checks if there is enough space at the location of skyline span 'i', + // and return the max height of all skyline spans under that at that location, + // (think tetris block being dropped at that position). Or -1 if no space found. + int x = atlas->nodes[i].x; + int y = atlas->nodes[i].y; + int spaceLeft; + if (x + w > atlas->width) + return -1; + spaceLeft = w; + while (spaceLeft > 0) { + if (i == atlas->nnodes) return -1; + y = fons__maxi(y, atlas->nodes[i].y); + if (y + h > atlas->height) return -1; + spaceLeft -= atlas->nodes[i].width; + ++i; + } + return y; +} + +static int fons__atlasAddRect(FONSatlas* atlas, int rw, int rh, int* rx, int* ry) +{ + int besth = atlas->height, bestw = atlas->width, besti = -1; + int bestx = -1, besty = -1, i; + + // Bottom left fit heuristic. + for (i = 0; i < atlas->nnodes; i++) { + int y = fons__atlasRectFits(atlas, i, rw, rh); + if (y != -1) { + if (y + rh < besth || (y + rh == besth && atlas->nodes[i].width < bestw)) { + besti = i; + bestw = atlas->nodes[i].width; + besth = y + rh; + bestx = atlas->nodes[i].x; + besty = y; + } + } + } + + if (besti == -1) + return 0; + + // Perform the actual packing. + if (fons__atlasAddSkylineLevel(atlas, besti, bestx, besty, rw, rh) == 0) + return 0; + + *rx = bestx; + *ry = besty; + + return 1; +} + +static void fons__addWhiteRect(FONScontext* stash, int w, int h) +{ + int x, y, gx, gy; + unsigned char* dst; + if (fons__atlasAddRect(stash->atlas, w, h, &gx, &gy) == 0) + return; + + // Rasterize + dst = &stash->texData[gx + gy * stash->params.width]; + for (y = 0; y < h; y++) { + for (x = 0; x < w; x++) + dst[x] = 0xff; + dst += stash->params.width; + } + + stash->dirtyRect[0] = fons__mini(stash->dirtyRect[0], gx); + stash->dirtyRect[1] = fons__mini(stash->dirtyRect[1], gy); + stash->dirtyRect[2] = fons__maxi(stash->dirtyRect[2], gx+w); + stash->dirtyRect[3] = fons__maxi(stash->dirtyRect[3], gy+h); +} + +FONScontext* fonsCreateInternal(FONSparams* params) +{ + FONScontext* stash = NULL; + + // Allocate memory for the font stash. + stash = (FONScontext*)malloc(sizeof(FONScontext)); + if (stash == NULL) goto error; + memset(stash, 0, sizeof(FONScontext)); + + stash->params = *params; + + // Allocate scratch buffer. + stash->scratch = (unsigned char*)malloc(FONS_SCRATCH_BUF_SIZE); + if (stash->scratch == NULL) goto error; + + // Initialize implementation library + if (!fons__tt_init(stash)) goto error; + + if (stash->params.renderCreate != NULL) { + if (stash->params.renderCreate(stash->params.userPtr, stash->params.width, stash->params.height) == 0) + goto error; + } + + stash->atlas = fons__allocAtlas(stash->params.width, stash->params.height, FONS_INIT_ATLAS_NODES); + if (stash->atlas == NULL) goto error; + + // Allocate space for fonts. + stash->fonts = (FONSfont**)malloc(sizeof(FONSfont*) * FONS_INIT_FONTS); + if (stash->fonts == NULL) goto error; + memset(stash->fonts, 0, sizeof(FONSfont*) * FONS_INIT_FONTS); + stash->cfonts = FONS_INIT_FONTS; + stash->nfonts = 0; + + // Create texture for the cache. + stash->itw = 1.0f/stash->params.width; + stash->ith = 1.0f/stash->params.height; + stash->texData = (unsigned char*)malloc(stash->params.width * stash->params.height); + if (stash->texData == NULL) goto error; + memset(stash->texData, 0, stash->params.width * stash->params.height); + + stash->dirtyRect[0] = stash->params.width; + stash->dirtyRect[1] = stash->params.height; + stash->dirtyRect[2] = 0; + stash->dirtyRect[3] = 0; + + // Add white rect at 0,0 for debug drawing. + fons__addWhiteRect(stash, 2,2); + + fonsPushState(stash); + fonsClearState(stash); + + return stash; + +error: + fonsDeleteInternal(stash); + return NULL; +} + +static FONSstate* fons__getState(FONScontext* stash) +{ + return &stash->states[stash->nstates-1]; +} + +int fonsAddFallbackFont(FONScontext* stash, int base, int fallback) +{ + FONSfont* baseFont = stash->fonts[base]; + if (baseFont->nfallbacks < FONS_MAX_FALLBACKS) { + baseFont->fallbacks[baseFont->nfallbacks++] = fallback; + return 1; + } + return 0; +} + +void fonsSetSize(FONScontext* stash, float size) +{ + fons__getState(stash)->size = size; +} + +void fonsSetColor(FONScontext* stash, unsigned int color) +{ + fons__getState(stash)->color = color; +} + +void fonsSetSpacing(FONScontext* stash, float spacing) +{ + fons__getState(stash)->spacing = spacing; +} + +void fonsSetBlur(FONScontext* stash, float blur) +{ + fons__getState(stash)->blur = blur; +} + +void fonsSetAlign(FONScontext* stash, int align) +{ + fons__getState(stash)->align = align; +} + +void fonsSetFont(FONScontext* stash, int font) +{ + fons__getState(stash)->font = font; +} + +void fonsPushState(FONScontext* stash) +{ + if (stash->nstates >= FONS_MAX_STATES) { + if (stash->handleError) + stash->handleError(stash->errorUptr, FONS_STATES_OVERFLOW, 0); + return; + } + if (stash->nstates > 0) + memcpy(&stash->states[stash->nstates], &stash->states[stash->nstates-1], sizeof(FONSstate)); + stash->nstates++; +} + +void fonsPopState(FONScontext* stash) +{ + if (stash->nstates <= 1) { + if (stash->handleError) + stash->handleError(stash->errorUptr, FONS_STATES_UNDERFLOW, 0); + return; + } + stash->nstates--; +} + +void fonsClearState(FONScontext* stash) +{ + FONSstate* state = fons__getState(stash); + state->size = 12.0f; + state->color = 0xffffffff; + state->font = 0; + state->blur = 0; + state->spacing = 0; + state->align = FONS_ALIGN_LEFT | FONS_ALIGN_BASELINE; +} + +static void fons__freeFont(FONSfont* font) +{ + if (font == NULL) return; + if (font->glyphs) free(font->glyphs); + if (font->freeData && font->data) free(font->data); + free(font); +} + +static int fons__allocFont(FONScontext* stash) +{ + FONSfont* font = NULL; + if (stash->nfonts+1 > stash->cfonts) { + stash->cfonts = stash->cfonts == 0 ? 8 : stash->cfonts * 2; + stash->fonts = (FONSfont**)realloc(stash->fonts, sizeof(FONSfont*) * stash->cfonts); + if (stash->fonts == NULL) + return -1; + } + font = (FONSfont*)malloc(sizeof(FONSfont)); + if (font == NULL) goto error; + memset(font, 0, sizeof(FONSfont)); + + font->glyphs = (FONSglyph*)malloc(sizeof(FONSglyph) * FONS_INIT_GLYPHS); + if (font->glyphs == NULL) goto error; + font->cglyphs = FONS_INIT_GLYPHS; + font->nglyphs = 0; + + stash->fonts[stash->nfonts++] = font; + return stash->nfonts-1; + +error: + fons__freeFont(font); + + return FONS_INVALID; +} + +int fonsAddFont(FONScontext* stash, const char* name, const char* path) +{ + FILE* fp = 0; + int dataSize = 0; + unsigned char* data = NULL; + + // Read in the font data. + fp = fopen(path, "rb"); + if (fp == NULL) goto error; + fseek(fp,0,SEEK_END); + dataSize = (int)ftell(fp); + fseek(fp,0,SEEK_SET); + data = (unsigned char*)malloc(dataSize); + if (data == NULL) goto error; + fread(data, 1, dataSize, fp); + fclose(fp); + fp = 0; + + return fonsAddFontMem(stash, name, data, dataSize, 1); + +error: + if (data) free(data); + if (fp) fclose(fp); + return FONS_INVALID; +} + +int fonsAddFontMem(FONScontext* stash, const char* name, unsigned char* data, int dataSize, int freeData) +{ + int i, ascent, descent, fh, lineGap; + FONSfont* font; + + int idx = fons__allocFont(stash); + if (idx == FONS_INVALID) + return FONS_INVALID; + + font = stash->fonts[idx]; + + strncpy(font->name, name, sizeof(font->name)); + font->name[sizeof(font->name)-1] = '\0'; + + // Init hash lookup. + for (i = 0; i < FONS_HASH_LUT_SIZE; ++i) + font->lut[i] = -1; + + // Read in the font data. + font->dataSize = dataSize; + font->data = data; + font->freeData = (unsigned char)freeData; + + // Init font + stash->nscratch = 0; + if (!fons__tt_loadFont(stash, &font->font, data, dataSize)) goto error; + + // Store normalized line height. The real line height is got + // by multiplying the lineh by font size. + fons__tt_getFontVMetrics( &font->font, &ascent, &descent, &lineGap); + fh = ascent - descent; + font->ascender = (float)ascent / (float)fh; + font->descender = (float)descent / (float)fh; + font->lineh = (float)(fh + lineGap) / (float)fh; + + return idx; + +error: + fons__freeFont(font); + stash->nfonts--; + return FONS_INVALID; +} + +int fonsGetFontByName(FONScontext* s, const char* name) +{ + int i; + for (i = 0; i < s->nfonts; i++) { + if (strcmp(s->fonts[i]->name, name) == 0) + return i; + } + return FONS_INVALID; +} + + +static FONSglyph* fons__allocGlyph(FONSfont* font) +{ + if (font->nglyphs+1 > font->cglyphs) { + font->cglyphs = font->cglyphs == 0 ? 8 : font->cglyphs * 2; + font->glyphs = (FONSglyph*)realloc(font->glyphs, sizeof(FONSglyph) * font->cglyphs); + if (font->glyphs == NULL) return NULL; + } + font->nglyphs++; + return &font->glyphs[font->nglyphs-1]; +} + + +// Based on Exponential blur, Jani Huhtanen, 2006 + +#define APREC 16 +#define ZPREC 7 + +static void fons__blurCols(unsigned char* dst, int w, int h, int dstStride, int alpha) +{ + int x, y; + for (y = 0; y < h; y++) { + int z = 0; // force zero border + for (x = 1; x < w; x++) { + z += (alpha * (((int)(dst[x]) << ZPREC) - z)) >> APREC; + dst[x] = (unsigned char)(z >> ZPREC); + } + dst[w-1] = 0; // force zero border + z = 0; + for (x = w-2; x >= 0; x--) { + z += (alpha * (((int)(dst[x]) << ZPREC) - z)) >> APREC; + dst[x] = (unsigned char)(z >> ZPREC); + } + dst[0] = 0; // force zero border + dst += dstStride; + } +} + +static void fons__blurRows(unsigned char* dst, int w, int h, int dstStride, int alpha) +{ + int x, y; + for (x = 0; x < w; x++) { + int z = 0; // force zero border + for (y = dstStride; y < h*dstStride; y += dstStride) { + z += (alpha * (((int)(dst[y]) << ZPREC) - z)) >> APREC; + dst[y] = (unsigned char)(z >> ZPREC); + } + dst[(h-1)*dstStride] = 0; // force zero border + z = 0; + for (y = (h-2)*dstStride; y >= 0; y -= dstStride) { + z += (alpha * (((int)(dst[y]) << ZPREC) - z)) >> APREC; + dst[y] = (unsigned char)(z >> ZPREC); + } + dst[0] = 0; // force zero border + dst++; + } +} + + +static void fons__blur(FONScontext* stash, unsigned char* dst, int w, int h, int dstStride, int blur) +{ + int alpha; + float sigma; + (void)stash; + + if (blur < 1) + return; + // Calculate the alpha such that 90% of the kernel is within the radius. (Kernel extends to infinity) + sigma = (float)blur * 0.57735f; // 1 / sqrt(3) + alpha = (int)((1< 20) iblur = 20; + pad = iblur+2; + + // Reset allocator. + stash->nscratch = 0; + + // Find code point and size. + h = fons__hashint(codepoint) & (FONS_HASH_LUT_SIZE-1); + i = font->lut[h]; + while (i != -1) { + if (font->glyphs[i].codepoint == codepoint && font->glyphs[i].size == isize && font->glyphs[i].blur == iblur) + return &font->glyphs[i]; + i = font->glyphs[i].next; + } + + // Could not find glyph, create it. + scale = fons__tt_getPixelHeightScale(&font->font, size); + g = fons__tt_getGlyphIndex(&font->font, codepoint); + // Try to find the glyph in fallback fonts. + if (g == 0) { + for (i = 0; i < font->nfallbacks; ++i) { + FONSglyph* fallbackGlyph = fons__getGlyph(stash, stash->fonts[font->fallbacks[i]], codepoint, isize, iblur); + if (fallbackGlyph != NULL && fallbackGlyph->index != 0) { + return fallbackGlyph; + } + } + } + fons__tt_buildGlyphBitmap(&font->font, g, size, scale, &advance, &lsb, &x0, &y0, &x1, &y1); + gw = x1-x0 + pad*2; + gh = y1-y0 + pad*2; + + // Find free spot for the rect in the atlas + added = fons__atlasAddRect(stash->atlas, gw, gh, &gx, &gy); + if (added == 0 && stash->handleError != NULL) { + // Atlas is full, let the user to resize the atlas (or not), and try again. + stash->handleError(stash->errorUptr, FONS_ATLAS_FULL, 0); + added = fons__atlasAddRect(stash->atlas, gw, gh, &gx, &gy); + } + if (added == 0) return NULL; + + // Init glyph. + glyph = fons__allocGlyph(font); + glyph->codepoint = codepoint; + glyph->size = isize; + glyph->blur = iblur; + glyph->index = g; + glyph->x0 = (short)gx; + glyph->y0 = (short)gy; + glyph->x1 = (short)(glyph->x0+gw); + glyph->y1 = (short)(glyph->y0+gh); + glyph->xadv = (short)(scale * advance * 10.0f); + glyph->xoff = (short)(x0 - pad); + glyph->yoff = (short)(y0 - pad); + glyph->next = 0; + + // Insert char to hash lookup. + glyph->next = font->lut[h]; + font->lut[h] = font->nglyphs-1; + + // Rasterize + dst = &stash->texData[(glyph->x0+pad) + (glyph->y0+pad) * stash->params.width]; + fons__tt_renderGlyphBitmap(&font->font, dst, gw-pad*2,gh-pad*2, stash->params.width, scale,scale, g); + + // Make sure there is one pixel empty border. + dst = &stash->texData[glyph->x0 + glyph->y0 * stash->params.width]; + for (y = 0; y < gh; y++) { + dst[y*stash->params.width] = 0; + dst[gw-1 + y*stash->params.width] = 0; + } + for (x = 0; x < gw; x++) { + dst[x] = 0; + dst[x + (gh-1)*stash->params.width] = 0; + } + + // Debug code to color the glyph background +/* unsigned char* fdst = &stash->texData[glyph->x0 + glyph->y0 * stash->params.width]; + for (y = 0; y < gh; y++) { + for (x = 0; x < gw; x++) { + int a = (int)fdst[x+y*stash->params.width] + 20; + if (a > 255) a = 255; + fdst[x+y*stash->params.width] = a; + } + }*/ + + // Blur + if (iblur > 0) { + stash->nscratch = 0; + bdst = &stash->texData[glyph->x0 + glyph->y0 * stash->params.width]; + fons__blur(stash, bdst, gw,gh, stash->params.width, iblur); + } + + stash->dirtyRect[0] = fons__mini(stash->dirtyRect[0], glyph->x0); + stash->dirtyRect[1] = fons__mini(stash->dirtyRect[1], glyph->y0); + stash->dirtyRect[2] = fons__maxi(stash->dirtyRect[2], glyph->x1); + stash->dirtyRect[3] = fons__maxi(stash->dirtyRect[3], glyph->y1); + + return glyph; +} + +static void fons__getQuad(FONScontext* stash, FONSfont* font, + int prevGlyphIndex, FONSglyph* glyph, + float scale, float spacing, float* x, float* y, FONSquad* q) +{ + float rx,ry,xoff,yoff,x0,y0,x1,y1; + + if (prevGlyphIndex != -1) { + float adv = fons__tt_getGlyphKernAdvance(&font->font, prevGlyphIndex, glyph->index) * scale; + *x += (int)(adv + spacing + 0.5f); + } + + // Each glyph has 2px border to allow good interpolation, + // one pixel to prevent leaking, and one to allow good interpolation for rendering. + // Inset the texture region by one pixel for correct interpolation. + xoff = (short)(glyph->xoff+1); + yoff = (short)(glyph->yoff+1); + x0 = (float)(glyph->x0+1); + y0 = (float)(glyph->y0+1); + x1 = (float)(glyph->x1-1); + y1 = (float)(glyph->y1-1); + + if (stash->params.flags & FONS_ZERO_TOPLEFT) { + rx = (float)(int)(*x + xoff); + ry = (float)(int)(*y + yoff); + + q->x0 = rx; + q->y0 = ry; + q->x1 = rx + x1 - x0; + q->y1 = ry + y1 - y0; + + q->s0 = x0 * stash->itw; + q->t0 = y0 * stash->ith; + q->s1 = x1 * stash->itw; + q->t1 = y1 * stash->ith; + } else { + rx = (float)(int)(*x + xoff); + ry = (float)(int)(*y - yoff); + + q->x0 = rx; + q->y0 = ry; + q->x1 = rx + x1 - x0; + q->y1 = ry - y1 + y0; + + q->s0 = x0 * stash->itw; + q->t0 = y0 * stash->ith; + q->s1 = x1 * stash->itw; + q->t1 = y1 * stash->ith; + } + + *x += (int)(glyph->xadv / 10.0f + 0.5f); +} + +static void fons__flush(FONScontext* stash) +{ + // Flush texture + if (stash->dirtyRect[0] < stash->dirtyRect[2] && stash->dirtyRect[1] < stash->dirtyRect[3]) { + if (stash->params.renderUpdate != NULL) + stash->params.renderUpdate(stash->params.userPtr, stash->dirtyRect, stash->texData); + // Reset dirty rect + stash->dirtyRect[0] = stash->params.width; + stash->dirtyRect[1] = stash->params.height; + stash->dirtyRect[2] = 0; + stash->dirtyRect[3] = 0; + } + + // Flush triangles + if (stash->nverts > 0) { + if (stash->params.renderDraw != NULL) + stash->params.renderDraw(stash->params.userPtr, stash->verts, stash->tcoords, stash->colors, stash->nverts); + stash->nverts = 0; + } +} + +static __inline void fons__vertex(FONScontext* stash, float x, float y, float s, float t, unsigned int c) +{ + stash->verts[stash->nverts*2+0] = x; + stash->verts[stash->nverts*2+1] = y; + stash->tcoords[stash->nverts*2+0] = s; + stash->tcoords[stash->nverts*2+1] = t; + stash->colors[stash->nverts] = c; + stash->nverts++; +} + +static float fons__getVertAlign(FONScontext* stash, FONSfont* font, int align, short isize) +{ + if (stash->params.flags & FONS_ZERO_TOPLEFT) { + if (align & FONS_ALIGN_TOP) { + return font->ascender * (float)isize/10.0f; + } else if (align & FONS_ALIGN_MIDDLE) { + return (font->ascender + font->descender) / 2.0f * (float)isize/10.0f; + } else if (align & FONS_ALIGN_BASELINE) { + return 0.0f; + } else if (align & FONS_ALIGN_BOTTOM) { + return font->descender * (float)isize/10.0f; + } + } else { + if (align & FONS_ALIGN_TOP) { + return -font->ascender * (float)isize/10.0f; + } else if (align & FONS_ALIGN_MIDDLE) { + return -(font->ascender + font->descender) / 2.0f * (float)isize/10.0f; + } else if (align & FONS_ALIGN_BASELINE) { + return 0.0f; + } else if (align & FONS_ALIGN_BOTTOM) { + return -font->descender * (float)isize/10.0f; + } + } + return 0.0; +} + +float fonsDrawText(FONScontext* stash, + float x, float y, + const char* str, const char* end) +{ + FONSstate* state = fons__getState(stash); + unsigned int codepoint; + unsigned int utf8state = 0; + FONSglyph* glyph = NULL; + FONSquad q; + int prevGlyphIndex = -1; + short isize = (short)(state->size*10.0f); + short iblur = (short)state->blur; + float scale; + FONSfont* font; + float width; + + if (stash == NULL) return x; + if (state->font < 0 || state->font >= stash->nfonts) return x; + font = stash->fonts[state->font]; + if (font->data == NULL) return x; + + scale = fons__tt_getPixelHeightScale(&font->font, (float)isize/10.0f); + + if (end == NULL) + end = str + strlen(str); + + // Align horizontally + if (state->align & FONS_ALIGN_LEFT) { + // empty + } else if (state->align & FONS_ALIGN_RIGHT) { + width = fonsTextBounds(stash, x,y, str, end, NULL); + x -= width; + } else if (state->align & FONS_ALIGN_CENTER) { + width = fonsTextBounds(stash, x,y, str, end, NULL); + x -= width * 0.5f; + } + // Align vertically. + y += fons__getVertAlign(stash, font, state->align, isize); + + for (; str != end; ++str) { + if (fons__decutf8(&utf8state, &codepoint, *(const unsigned char*)str)) + continue; + glyph = fons__getGlyph(stash, font, codepoint, isize, iblur); + if (glyph != NULL) { + fons__getQuad(stash, font, prevGlyphIndex, glyph, scale, state->spacing, &x, &y, &q); + + if (stash->nverts+6 > FONS_VERTEX_COUNT) + fons__flush(stash); + + fons__vertex(stash, q.x0, q.y0, q.s0, q.t0, state->color); + fons__vertex(stash, q.x1, q.y1, q.s1, q.t1, state->color); + fons__vertex(stash, q.x1, q.y0, q.s1, q.t0, state->color); + + fons__vertex(stash, q.x0, q.y0, q.s0, q.t0, state->color); + fons__vertex(stash, q.x0, q.y1, q.s0, q.t1, state->color); + fons__vertex(stash, q.x1, q.y1, q.s1, q.t1, state->color); + } + prevGlyphIndex = glyph != NULL ? glyph->index : -1; + } + fons__flush(stash); + + return x; +} + +int fonsTextIterInit(FONScontext* stash, FONStextIter* iter, + float x, float y, const char* str, const char* end) +{ + FONSstate* state = fons__getState(stash); + float width; + + memset(iter, 0, sizeof(*iter)); + + if (stash == NULL) return 0; + if (state->font < 0 || state->font >= stash->nfonts) return 0; + iter->font = stash->fonts[state->font]; + if (iter->font->data == NULL) return 0; + + iter->isize = (short)(state->size*10.0f); + iter->iblur = (short)state->blur; + iter->scale = fons__tt_getPixelHeightScale(&iter->font->font, (float)iter->isize/10.0f); + + // Align horizontally + if (state->align & FONS_ALIGN_LEFT) { + // empty + } else if (state->align & FONS_ALIGN_RIGHT) { + width = fonsTextBounds(stash, x,y, str, end, NULL); + x -= width; + } else if (state->align & FONS_ALIGN_CENTER) { + width = fonsTextBounds(stash, x,y, str, end, NULL); + x -= width * 0.5f; + } + // Align vertically. + y += fons__getVertAlign(stash, iter->font, state->align, iter->isize); + + if (end == NULL) + end = str + strlen(str); + + iter->x = iter->nextx = x; + iter->y = iter->nexty = y; + iter->spacing = state->spacing; + iter->str = str; + iter->next = str; + iter->end = end; + iter->codepoint = 0; + iter->prevGlyphIndex = -1; + + return 1; +} + +int fonsTextIterNext(FONScontext* stash, FONStextIter* iter, FONSquad* quad) +{ + FONSglyph* glyph = NULL; + const char* str = iter->next; + iter->str = iter->next; + + if (str == iter->end) + return 0; + + for (; str != iter->end; str++) { + if (fons__decutf8(&iter->utf8state, &iter->codepoint, *(const unsigned char*)str)) + continue; + str++; + // Get glyph and quad + iter->x = iter->nextx; + iter->y = iter->nexty; + glyph = fons__getGlyph(stash, iter->font, iter->codepoint, iter->isize, iter->iblur); + if (glyph != NULL) + fons__getQuad(stash, iter->font, iter->prevGlyphIndex, glyph, iter->scale, iter->spacing, &iter->nextx, &iter->nexty, quad); + iter->prevGlyphIndex = glyph != NULL ? glyph->index : -1; + break; + } + iter->next = str; + + return 1; +} + +void fonsDrawDebug(FONScontext* stash, float x, float y) +{ + int i; + int w = stash->params.width; + int h = stash->params.height; + float u = w == 0 ? 0 : (1.0f / w); + float v = h == 0 ? 0 : (1.0f / h); + + if (stash->nverts+6+6 > FONS_VERTEX_COUNT) + fons__flush(stash); + + // Draw background + fons__vertex(stash, x+0, y+0, u, v, 0x0fffffff); + fons__vertex(stash, x+w, y+h, u, v, 0x0fffffff); + fons__vertex(stash, x+w, y+0, u, v, 0x0fffffff); + + fons__vertex(stash, x+0, y+0, u, v, 0x0fffffff); + fons__vertex(stash, x+0, y+h, u, v, 0x0fffffff); + fons__vertex(stash, x+w, y+h, u, v, 0x0fffffff); + + // Draw texture + fons__vertex(stash, x+0, y+0, 0, 0, 0xffffffff); + fons__vertex(stash, x+w, y+h, 1, 1, 0xffffffff); + fons__vertex(stash, x+w, y+0, 1, 0, 0xffffffff); + + fons__vertex(stash, x+0, y+0, 0, 0, 0xffffffff); + fons__vertex(stash, x+0, y+h, 0, 1, 0xffffffff); + fons__vertex(stash, x+w, y+h, 1, 1, 0xffffffff); + + // Drawbug draw atlas + for (i = 0; i < stash->atlas->nnodes; i++) { + FONSatlasNode* n = &stash->atlas->nodes[i]; + + if (stash->nverts+6 > FONS_VERTEX_COUNT) + fons__flush(stash); + + fons__vertex(stash, x+n->x+0, y+n->y+0, u, v, 0xc00000ff); + fons__vertex(stash, x+n->x+n->width, y+n->y+1, u, v, 0xc00000ff); + fons__vertex(stash, x+n->x+n->width, y+n->y+0, u, v, 0xc00000ff); + + fons__vertex(stash, x+n->x+0, y+n->y+0, u, v, 0xc00000ff); + fons__vertex(stash, x+n->x+0, y+n->y+1, u, v, 0xc00000ff); + fons__vertex(stash, x+n->x+n->width, y+n->y+1, u, v, 0xc00000ff); + } + + fons__flush(stash); +} + +float fonsTextBounds(FONScontext* stash, + float x, float y, + const char* str, const char* end, + float* bounds) +{ + FONSstate* state = fons__getState(stash); + unsigned int codepoint; + unsigned int utf8state = 0; + FONSquad q; + FONSglyph* glyph = NULL; + int prevGlyphIndex = -1; + short isize = (short)(state->size*10.0f); + short iblur = (short)state->blur; + float scale; + FONSfont* font; + float startx, advance; + float minx, miny, maxx, maxy; + + if (stash == NULL) return 0; + if (state->font < 0 || state->font >= stash->nfonts) return 0; + font = stash->fonts[state->font]; + if (font->data == NULL) return 0; + + scale = fons__tt_getPixelHeightScale(&font->font, (float)isize/10.0f); + + // Align vertically. + y += fons__getVertAlign(stash, font, state->align, isize); + + minx = maxx = x; + miny = maxy = y; + startx = x; + + if (end == NULL) + end = str + strlen(str); + + for (; str != end; ++str) { + if (fons__decutf8(&utf8state, &codepoint, *(const unsigned char*)str)) + continue; + glyph = fons__getGlyph(stash, font, codepoint, isize, iblur); + if (glyph != NULL) { + fons__getQuad(stash, font, prevGlyphIndex, glyph, scale, state->spacing, &x, &y, &q); + if (q.x0 < minx) minx = q.x0; + if (q.x1 > maxx) maxx = q.x1; + if (stash->params.flags & FONS_ZERO_TOPLEFT) { + if (q.y0 < miny) miny = q.y0; + if (q.y1 > maxy) maxy = q.y1; + } else { + if (q.y1 < miny) miny = q.y1; + if (q.y0 > maxy) maxy = q.y0; + } + } + prevGlyphIndex = glyph != NULL ? glyph->index : -1; + } + + advance = x - startx; + + // Align horizontally + if (state->align & FONS_ALIGN_LEFT) { + // empty + } else if (state->align & FONS_ALIGN_RIGHT) { + minx -= advance; + maxx -= advance; + } else if (state->align & FONS_ALIGN_CENTER) { + minx -= advance * 0.5f; + maxx -= advance * 0.5f; + } + + if (bounds) { + bounds[0] = minx; + bounds[1] = miny; + bounds[2] = maxx; + bounds[3] = maxy; + } + + return advance; +} + +void fonsVertMetrics(FONScontext* stash, + float* ascender, float* descender, float* lineh) +{ + FONSfont* font; + FONSstate* state = fons__getState(stash); + short isize; + + if (stash == NULL) return; + if (state->font < 0 || state->font >= stash->nfonts) return; + font = stash->fonts[state->font]; + isize = (short)(state->size*10.0f); + if (font->data == NULL) return; + + if (ascender) + *ascender = font->ascender*isize/10.0f; + if (descender) + *descender = font->descender*isize/10.0f; + if (lineh) + *lineh = font->lineh*isize/10.0f; +} + +void fonsLineBounds(FONScontext* stash, float y, float* miny, float* maxy) +{ + FONSfont* font; + FONSstate* state = fons__getState(stash); + short isize; + + if (stash == NULL) return; + if (state->font < 0 || state->font >= stash->nfonts) return; + font = stash->fonts[state->font]; + isize = (short)(state->size*10.0f); + if (font->data == NULL) return; + + y += fons__getVertAlign(stash, font, state->align, isize); + + if (stash->params.flags & FONS_ZERO_TOPLEFT) { + *miny = y - font->ascender * (float)isize/10.0f; + *maxy = *miny + font->lineh*isize/10.0f; + } else { + *maxy = y + font->descender * (float)isize/10.0f; + *miny = *maxy - font->lineh*isize/10.0f; + } +} + +const unsigned char* fonsGetTextureData(FONScontext* stash, int* width, int* height) +{ + if (width != NULL) + *width = stash->params.width; + if (height != NULL) + *height = stash->params.height; + return stash->texData; +} + +int fonsValidateTexture(FONScontext* stash, int* dirty) +{ + if (stash->dirtyRect[0] < stash->dirtyRect[2] && stash->dirtyRect[1] < stash->dirtyRect[3]) { + dirty[0] = stash->dirtyRect[0]; + dirty[1] = stash->dirtyRect[1]; + dirty[2] = stash->dirtyRect[2]; + dirty[3] = stash->dirtyRect[3]; + // Reset dirty rect + stash->dirtyRect[0] = stash->params.width; + stash->dirtyRect[1] = stash->params.height; + stash->dirtyRect[2] = 0; + stash->dirtyRect[3] = 0; + return 1; + } + return 0; +} + +void fonsDeleteInternal(FONScontext* stash) +{ + int i; + if (stash == NULL) return; + + if (stash->params.renderDelete) + stash->params.renderDelete(stash->params.userPtr); + + for (i = 0; i < stash->nfonts; ++i) + fons__freeFont(stash->fonts[i]); + + if (stash->atlas) fons__deleteAtlas(stash->atlas); + if (stash->fonts) free(stash->fonts); + if (stash->texData) free(stash->texData); + if (stash->scratch) free(stash->scratch); + free(stash); +} + +void fonsSetErrorCallback(FONScontext* stash, void (*callback)(void* uptr, int error, int val), void* uptr) +{ + if (stash == NULL) return; + stash->handleError = callback; + stash->errorUptr = uptr; +} + +void fonsGetAtlasSize(FONScontext* stash, int* width, int* height) +{ + if (stash == NULL) return; + *width = stash->params.width; + *height = stash->params.height; +} + +int fonsExpandAtlas(FONScontext* stash, int width, int height) +{ + int i, maxy = 0; + unsigned char* data = NULL; + if (stash == NULL) return 0; + + width = fons__maxi(width, stash->params.width); + height = fons__maxi(height, stash->params.height); + + if (width == stash->params.width && height == stash->params.height) + return 1; + + // Flush pending glyphs. + fons__flush(stash); + + // Create new texture + if (stash->params.renderResize != NULL) { + if (stash->params.renderResize(stash->params.userPtr, width, height) == 0) + return 0; + } + // Copy old texture data over. + data = (unsigned char*)malloc(width * height); + if (data == NULL) + return 0; + for (i = 0; i < stash->params.height; i++) { + unsigned char* dst = &data[i*width]; + unsigned char* src = &stash->texData[i*stash->params.width]; + memcpy(dst, src, stash->params.width); + if (width > stash->params.width) + memset(dst+stash->params.width, 0, width - stash->params.width); + } + if (height > stash->params.height) + memset(&data[stash->params.height * width], 0, (height - stash->params.height) * width); + + free(stash->texData); + stash->texData = data; + + // Increase atlas size + fons__atlasExpand(stash->atlas, width, height); + + // Add existing data as dirty. + for (i = 0; i < stash->atlas->nnodes; i++) + maxy = fons__maxi(maxy, stash->atlas->nodes[i].y); + stash->dirtyRect[0] = 0; + stash->dirtyRect[1] = 0; + stash->dirtyRect[2] = stash->params.width; + stash->dirtyRect[3] = maxy; + + stash->params.width = width; + stash->params.height = height; + stash->itw = 1.0f/stash->params.width; + stash->ith = 1.0f/stash->params.height; + + return 1; +} + +int fonsResetAtlas(FONScontext* stash, int width, int height) +{ + int i, j; + if (stash == NULL) return 0; + + // Flush pending glyphs. + fons__flush(stash); + + // Create new texture + if (stash->params.renderResize != NULL) { + if (stash->params.renderResize(stash->params.userPtr, width, height) == 0) + return 0; + } + + // Reset atlas + fons__atlasReset(stash->atlas, width, height); + + // Clear texture data. + stash->texData = (unsigned char*)realloc(stash->texData, width * height); + if (stash->texData == NULL) return 0; + memset(stash->texData, 0, width * height); + + // Reset dirty rect + stash->dirtyRect[0] = width; + stash->dirtyRect[1] = height; + stash->dirtyRect[2] = 0; + stash->dirtyRect[3] = 0; + + // Reset cached glyphs + for (i = 0; i < stash->nfonts; i++) { + FONSfont* font = stash->fonts[i]; + font->nglyphs = 0; + for (j = 0; j < FONS_HASH_LUT_SIZE; j++) + font->lut[j] = -1; + } + + stash->params.width = width; + stash->params.height = height; + stash->itw = 1.0f/stash->params.width; + stash->ith = 1.0f/stash->params.height; + + // Add white rect at 0,0 for debug drawing. + fons__addWhiteRect(stash, 2,2); + + return 1; +} + + +#endif diff --git a/phonelibs/nanovg/nanovg.c b/phonelibs/nanovg/nanovg.c new file mode 100644 index 00000000000000..51f972ca5b36d9 --- /dev/null +++ b/phonelibs/nanovg/nanovg.c @@ -0,0 +1,2870 @@ +// +// Copyright (c) 2013 Mikko Mononen memon@inside.org +// +// 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. +// + +#include +#include +#include +#include + +#include "nanovg.h" +#define FONTSTASH_IMPLEMENTATION +#include "fontstash.h" +#define STB_IMAGE_IMPLEMENTATION +#include "stb_image.h" + +#ifdef _MSC_VER +#pragma warning(disable: 4100) // unreferenced formal parameter +#pragma warning(disable: 4127) // conditional expression is constant +#pragma warning(disable: 4204) // nonstandard extension used : non-constant aggregate initializer +#pragma warning(disable: 4706) // assignment within conditional expression +#endif + +#define NVG_INIT_FONTIMAGE_SIZE 512 +#define NVG_MAX_FONTIMAGE_SIZE 2048 +#define NVG_MAX_FONTIMAGES 4 + +#define NVG_INIT_COMMANDS_SIZE 256 +#define NVG_INIT_POINTS_SIZE 128 +#define NVG_INIT_PATHS_SIZE 16 +#define NVG_INIT_VERTS_SIZE 256 +#define NVG_MAX_STATES 32 + +#define NVG_KAPPA90 0.5522847493f // Length proportional to radius of a cubic bezier handle for 90deg arcs. + +#define NVG_COUNTOF(arr) (sizeof(arr) / sizeof(0[arr])) + + +enum NVGcommands { + NVG_MOVETO = 0, + NVG_LINETO = 1, + NVG_BEZIERTO = 2, + NVG_CLOSE = 3, + NVG_WINDING = 4, +}; + +enum NVGpointFlags +{ + NVG_PT_CORNER = 0x01, + NVG_PT_LEFT = 0x02, + NVG_PT_BEVEL = 0x04, + NVG_PR_INNERBEVEL = 0x08, +}; + +struct NVGstate { + NVGcompositeOperationState compositeOperation; + NVGpaint fill; + NVGpaint stroke; + float strokeWidth; + float miterLimit; + int lineJoin; + int lineCap; + float alpha; + float xform[6]; + NVGscissor scissor; + float fontSize; + float letterSpacing; + float lineHeight; + float fontBlur; + int textAlign; + int fontId; +}; +typedef struct NVGstate NVGstate; + +struct NVGpoint { + float x,y; + float dx, dy; + float len; + float dmx, dmy; + unsigned char flags; +}; +typedef struct NVGpoint NVGpoint; + +struct NVGpathCache { + NVGpoint* points; + int npoints; + int cpoints; + NVGpath* paths; + int npaths; + int cpaths; + NVGvertex* verts; + int nverts; + int cverts; + float bounds[4]; +}; +typedef struct NVGpathCache NVGpathCache; + +struct NVGcontext { + NVGparams params; + float* commands; + int ccommands; + int ncommands; + float commandx, commandy; + NVGstate states[NVG_MAX_STATES]; + int nstates; + NVGpathCache* cache; + float tessTol; + float distTol; + float fringeWidth; + float devicePxRatio; + struct FONScontext* fs; + int fontImages[NVG_MAX_FONTIMAGES]; + int fontImageIdx; + int drawCallCount; + int fillTriCount; + int strokeTriCount; + int textTriCount; +}; + +static float nvg__sqrtf(float a) { return sqrtf(a); } +static float nvg__modf(float a, float b) { return fmodf(a, b); } +static float nvg__sinf(float a) { return sinf(a); } +static float nvg__cosf(float a) { return cosf(a); } +static float nvg__tanf(float a) { return tanf(a); } +static float nvg__atan2f(float a,float b) { return atan2f(a, b); } +static float nvg__acosf(float a) { return acosf(a); } + +static int nvg__mini(int a, int b) { return a < b ? a : b; } +static int nvg__maxi(int a, int b) { return a > b ? a : b; } +static int nvg__clampi(int a, int mn, int mx) { return a < mn ? mn : (a > mx ? mx : a); } +static float nvg__minf(float a, float b) { return a < b ? a : b; } +static float nvg__maxf(float a, float b) { return a > b ? a : b; } +static float nvg__absf(float a) { return a >= 0.0f ? a : -a; } +static float nvg__signf(float a) { return a >= 0.0f ? 1.0f : -1.0f; } +static float nvg__clampf(float a, float mn, float mx) { return a < mn ? mn : (a > mx ? mx : a); } +static float nvg__cross(float dx0, float dy0, float dx1, float dy1) { return dx1*dy0 - dx0*dy1; } + +static float nvg__normalize(float *x, float* y) +{ + float d = nvg__sqrtf((*x)*(*x) + (*y)*(*y)); + if (d > 1e-6f) { + float id = 1.0f / d; + *x *= id; + *y *= id; + } + return d; +} + + +static void nvg__deletePathCache(NVGpathCache* c) +{ + if (c == NULL) return; + if (c->points != NULL) free(c->points); + if (c->paths != NULL) free(c->paths); + if (c->verts != NULL) free(c->verts); + free(c); +} + +static NVGpathCache* nvg__allocPathCache(void) +{ + NVGpathCache* c = (NVGpathCache*)malloc(sizeof(NVGpathCache)); + if (c == NULL) goto error; + memset(c, 0, sizeof(NVGpathCache)); + + c->points = (NVGpoint*)malloc(sizeof(NVGpoint)*NVG_INIT_POINTS_SIZE); + if (!c->points) goto error; + c->npoints = 0; + c->cpoints = NVG_INIT_POINTS_SIZE; + + c->paths = (NVGpath*)malloc(sizeof(NVGpath)*NVG_INIT_PATHS_SIZE); + if (!c->paths) goto error; + c->npaths = 0; + c->cpaths = NVG_INIT_PATHS_SIZE; + + c->verts = (NVGvertex*)malloc(sizeof(NVGvertex)*NVG_INIT_VERTS_SIZE); + if (!c->verts) goto error; + c->nverts = 0; + c->cverts = NVG_INIT_VERTS_SIZE; + + return c; +error: + nvg__deletePathCache(c); + return NULL; +} + +static void nvg__setDevicePixelRatio(NVGcontext* ctx, float ratio) +{ + ctx->tessTol = 0.25f / ratio; + ctx->distTol = 0.01f / ratio; + ctx->fringeWidth = 1.0f / ratio; + ctx->devicePxRatio = ratio; +} + +static NVGcompositeOperationState nvg__compositeOperationState(int op) +{ + int sfactor, dfactor; + + if (op == NVG_SOURCE_OVER) + { + sfactor = NVG_ONE; + dfactor = NVG_ONE_MINUS_SRC_ALPHA; + } + else if (op == NVG_SOURCE_IN) + { + sfactor = NVG_DST_ALPHA; + dfactor = NVG_ZERO; + } + else if (op == NVG_SOURCE_OUT) + { + sfactor = NVG_ONE_MINUS_DST_ALPHA; + dfactor = NVG_ZERO; + } + else if (op == NVG_ATOP) + { + sfactor = NVG_DST_ALPHA; + dfactor = NVG_ONE_MINUS_SRC_ALPHA; + } + else if (op == NVG_DESTINATION_OVER) + { + sfactor = NVG_ONE_MINUS_DST_ALPHA; + dfactor = NVG_ONE; + } + else if (op == NVG_DESTINATION_IN) + { + sfactor = NVG_ZERO; + dfactor = NVG_SRC_ALPHA; + } + else if (op == NVG_DESTINATION_OUT) + { + sfactor = NVG_ZERO; + dfactor = NVG_ONE_MINUS_SRC_ALPHA; + } + else if (op == NVG_DESTINATION_ATOP) + { + sfactor = NVG_ONE_MINUS_DST_ALPHA; + dfactor = NVG_SRC_ALPHA; + } + else if (op == NVG_LIGHTER) + { + sfactor = NVG_ONE; + dfactor = NVG_ONE; + } + else if (op == NVG_COPY) + { + sfactor = NVG_ONE; + dfactor = NVG_ZERO; + } + else if (op == NVG_XOR) + { + sfactor = NVG_ONE_MINUS_DST_ALPHA; + dfactor = NVG_ONE_MINUS_SRC_ALPHA; + } + + NVGcompositeOperationState state; + state.srcRGB = sfactor; + state.dstRGB = dfactor; + state.srcAlpha = sfactor; + state.dstAlpha = dfactor; + return state; +} + +static NVGstate* nvg__getState(NVGcontext* ctx) +{ + return &ctx->states[ctx->nstates-1]; +} + +NVGcontext* nvgCreateInternal(NVGparams* params) +{ + FONSparams fontParams; + NVGcontext* ctx = (NVGcontext*)malloc(sizeof(NVGcontext)); + int i; + if (ctx == NULL) goto error; + memset(ctx, 0, sizeof(NVGcontext)); + + ctx->params = *params; + for (i = 0; i < NVG_MAX_FONTIMAGES; i++) + ctx->fontImages[i] = 0; + + ctx->commands = (float*)malloc(sizeof(float)*NVG_INIT_COMMANDS_SIZE); + if (!ctx->commands) goto error; + ctx->ncommands = 0; + ctx->ccommands = NVG_INIT_COMMANDS_SIZE; + + ctx->cache = nvg__allocPathCache(); + if (ctx->cache == NULL) goto error; + + nvgSave(ctx); + nvgReset(ctx); + + nvg__setDevicePixelRatio(ctx, 1.0f); + + if (ctx->params.renderCreate(ctx->params.userPtr) == 0) goto error; + + // Init font rendering + memset(&fontParams, 0, sizeof(fontParams)); + fontParams.width = NVG_INIT_FONTIMAGE_SIZE; + fontParams.height = NVG_INIT_FONTIMAGE_SIZE; + fontParams.flags = FONS_ZERO_TOPLEFT; + fontParams.renderCreate = NULL; + fontParams.renderUpdate = NULL; + fontParams.renderDraw = NULL; + fontParams.renderDelete = NULL; + fontParams.userPtr = NULL; + ctx->fs = fonsCreateInternal(&fontParams); + if (ctx->fs == NULL) goto error; + + // Create font texture + ctx->fontImages[0] = ctx->params.renderCreateTexture(ctx->params.userPtr, NVG_TEXTURE_ALPHA, fontParams.width, fontParams.height, 0, NULL); + if (ctx->fontImages[0] == 0) goto error; + ctx->fontImageIdx = 0; + + return ctx; + +error: + nvgDeleteInternal(ctx); + return 0; +} + +NVGparams* nvgInternalParams(NVGcontext* ctx) +{ + return &ctx->params; +} + +void nvgDeleteInternal(NVGcontext* ctx) +{ + int i; + if (ctx == NULL) return; + if (ctx->commands != NULL) free(ctx->commands); + if (ctx->cache != NULL) nvg__deletePathCache(ctx->cache); + + if (ctx->fs) + fonsDeleteInternal(ctx->fs); + + for (i = 0; i < NVG_MAX_FONTIMAGES; i++) { + if (ctx->fontImages[i] != 0) { + nvgDeleteImage(ctx, ctx->fontImages[i]); + ctx->fontImages[i] = 0; + } + } + + if (ctx->params.renderDelete != NULL) + ctx->params.renderDelete(ctx->params.userPtr); + + free(ctx); +} + +void nvgBeginFrame(NVGcontext* ctx, int windowWidth, int windowHeight, float devicePixelRatio) +{ +/* printf("Tris: draws:%d fill:%d stroke:%d text:%d TOT:%d\n", + ctx->drawCallCount, ctx->fillTriCount, ctx->strokeTriCount, ctx->textTriCount, + ctx->fillTriCount+ctx->strokeTriCount+ctx->textTriCount);*/ + + ctx->nstates = 0; + nvgSave(ctx); + nvgReset(ctx); + + nvg__setDevicePixelRatio(ctx, devicePixelRatio); + + ctx->params.renderViewport(ctx->params.userPtr, windowWidth, windowHeight, devicePixelRatio); + + ctx->drawCallCount = 0; + ctx->fillTriCount = 0; + ctx->strokeTriCount = 0; + ctx->textTriCount = 0; +} + +void nvgCancelFrame(NVGcontext* ctx) +{ + ctx->params.renderCancel(ctx->params.userPtr); +} + +void nvgEndFrame(NVGcontext* ctx) +{ + NVGstate* state = nvg__getState(ctx); + ctx->params.renderFlush(ctx->params.userPtr, state->compositeOperation); + if (ctx->fontImageIdx != 0) { + int fontImage = ctx->fontImages[ctx->fontImageIdx]; + int i, j, iw, ih; + // delete images that smaller than current one + if (fontImage == 0) + return; + nvgImageSize(ctx, fontImage, &iw, &ih); + for (i = j = 0; i < ctx->fontImageIdx; i++) { + if (ctx->fontImages[i] != 0) { + int nw, nh; + nvgImageSize(ctx, ctx->fontImages[i], &nw, &nh); + if (nw < iw || nh < ih) + nvgDeleteImage(ctx, ctx->fontImages[i]); + else + ctx->fontImages[j++] = ctx->fontImages[i]; + } + } + // make current font image to first + ctx->fontImages[j++] = ctx->fontImages[0]; + ctx->fontImages[0] = fontImage; + ctx->fontImageIdx = 0; + // clear all images after j + for (i = j; i < NVG_MAX_FONTIMAGES; i++) + ctx->fontImages[i] = 0; + } +} + +NVGcolor nvgRGB(unsigned char r, unsigned char g, unsigned char b) +{ + return nvgRGBA(r,g,b,255); +} + +NVGcolor nvgRGBf(float r, float g, float b) +{ + return nvgRGBAf(r,g,b,1.0f); +} + +NVGcolor nvgRGBA(unsigned char r, unsigned char g, unsigned char b, unsigned char a) +{ + NVGcolor color; + // Use longer initialization to suppress warning. + color.r = r / 255.0f; + color.g = g / 255.0f; + color.b = b / 255.0f; + color.a = a / 255.0f; + return color; +} + +NVGcolor nvgRGBAf(float r, float g, float b, float a) +{ + NVGcolor color; + // Use longer initialization to suppress warning. + color.r = r; + color.g = g; + color.b = b; + color.a = a; + return color; +} + +NVGcolor nvgTransRGBA(NVGcolor c, unsigned char a) +{ + c.a = a / 255.0f; + return c; +} + +NVGcolor nvgTransRGBAf(NVGcolor c, float a) +{ + c.a = a; + return c; +} + +NVGcolor nvgLerpRGBA(NVGcolor c0, NVGcolor c1, float u) +{ + int i; + float oneminu; + NVGcolor cint = {0}; + + u = nvg__clampf(u, 0.0f, 1.0f); + oneminu = 1.0f - u; + for( i = 0; i <4; i++ ) + { + cint.rgba[i] = c0.rgba[i] * oneminu + c1.rgba[i] * u; + } + + return cint; +} + +NVGcolor nvgHSL(float h, float s, float l) +{ + return nvgHSLA(h,s,l,255); +} + +static float nvg__hue(float h, float m1, float m2) +{ + if (h < 0) h += 1; + if (h > 1) h -= 1; + if (h < 1.0f/6.0f) + return m1 + (m2 - m1) * h * 6.0f; + else if (h < 3.0f/6.0f) + return m2; + else if (h < 4.0f/6.0f) + return m1 + (m2 - m1) * (2.0f/3.0f - h) * 6.0f; + return m1; +} + +NVGcolor nvgHSLA(float h, float s, float l, unsigned char a) +{ + float m1, m2; + NVGcolor col; + h = nvg__modf(h, 1.0f); + if (h < 0.0f) h += 1.0f; + s = nvg__clampf(s, 0.0f, 1.0f); + l = nvg__clampf(l, 0.0f, 1.0f); + m2 = l <= 0.5f ? (l * (1 + s)) : (l + s - l * s); + m1 = 2 * l - m2; + col.r = nvg__clampf(nvg__hue(h + 1.0f/3.0f, m1, m2), 0.0f, 1.0f); + col.g = nvg__clampf(nvg__hue(h, m1, m2), 0.0f, 1.0f); + col.b = nvg__clampf(nvg__hue(h - 1.0f/3.0f, m1, m2), 0.0f, 1.0f); + col.a = a/255.0f; + return col; +} + +void nvgTransformIdentity(float* t) +{ + t[0] = 1.0f; t[1] = 0.0f; + t[2] = 0.0f; t[3] = 1.0f; + t[4] = 0.0f; t[5] = 0.0f; +} + +void nvgTransformTranslate(float* t, float tx, float ty) +{ + t[0] = 1.0f; t[1] = 0.0f; + t[2] = 0.0f; t[3] = 1.0f; + t[4] = tx; t[5] = ty; +} + +void nvgTransformScale(float* t, float sx, float sy) +{ + t[0] = sx; t[1] = 0.0f; + t[2] = 0.0f; t[3] = sy; + t[4] = 0.0f; t[5] = 0.0f; +} + +void nvgTransformRotate(float* t, float a) +{ + float cs = nvg__cosf(a), sn = nvg__sinf(a); + t[0] = cs; t[1] = sn; + t[2] = -sn; t[3] = cs; + t[4] = 0.0f; t[5] = 0.0f; +} + +void nvgTransformSkewX(float* t, float a) +{ + t[0] = 1.0f; t[1] = 0.0f; + t[2] = nvg__tanf(a); t[3] = 1.0f; + t[4] = 0.0f; t[5] = 0.0f; +} + +void nvgTransformSkewY(float* t, float a) +{ + t[0] = 1.0f; t[1] = nvg__tanf(a); + t[2] = 0.0f; t[3] = 1.0f; + t[4] = 0.0f; t[5] = 0.0f; +} + +void nvgTransformMultiply(float* t, const float* s) +{ + float t0 = t[0] * s[0] + t[1] * s[2]; + float t2 = t[2] * s[0] + t[3] * s[2]; + float t4 = t[4] * s[0] + t[5] * s[2] + s[4]; + t[1] = t[0] * s[1] + t[1] * s[3]; + t[3] = t[2] * s[1] + t[3] * s[3]; + t[5] = t[4] * s[1] + t[5] * s[3] + s[5]; + t[0] = t0; + t[2] = t2; + t[4] = t4; +} + +void nvgTransformPremultiply(float* t, const float* s) +{ + float s2[6]; + memcpy(s2, s, sizeof(float)*6); + nvgTransformMultiply(s2, t); + memcpy(t, s2, sizeof(float)*6); +} + +int nvgTransformInverse(float* inv, const float* t) +{ + double invdet, det = (double)t[0] * t[3] - (double)t[2] * t[1]; + if (det > -1e-6 && det < 1e-6) { + nvgTransformIdentity(inv); + return 0; + } + invdet = 1.0 / det; + inv[0] = (float)(t[3] * invdet); + inv[2] = (float)(-t[2] * invdet); + inv[4] = (float)(((double)t[2] * t[5] - (double)t[3] * t[4]) * invdet); + inv[1] = (float)(-t[1] * invdet); + inv[3] = (float)(t[0] * invdet); + inv[5] = (float)(((double)t[1] * t[4] - (double)t[0] * t[5]) * invdet); + return 1; +} + +void nvgTransformPoint(float* dx, float* dy, const float* t, float sx, float sy) +{ + *dx = sx*t[0] + sy*t[2] + t[4]; + *dy = sx*t[1] + sy*t[3] + t[5]; +} + +float nvgDegToRad(float deg) +{ + return deg / 180.0f * NVG_PI; +} + +float nvgRadToDeg(float rad) +{ + return rad / NVG_PI * 180.0f; +} + +static void nvg__setPaintColor(NVGpaint* p, NVGcolor color) +{ + memset(p, 0, sizeof(*p)); + nvgTransformIdentity(p->xform); + p->radius = 0.0f; + p->feather = 1.0f; + p->innerColor = color; + p->outerColor = color; +} + + +// State handling +void nvgSave(NVGcontext* ctx) +{ + if (ctx->nstates >= NVG_MAX_STATES) + return; + if (ctx->nstates > 0) + memcpy(&ctx->states[ctx->nstates], &ctx->states[ctx->nstates-1], sizeof(NVGstate)); + ctx->nstates++; +} + +void nvgRestore(NVGcontext* ctx) +{ + if (ctx->nstates <= 1) + return; + ctx->nstates--; +} + +void nvgReset(NVGcontext* ctx) +{ + NVGstate* state = nvg__getState(ctx); + memset(state, 0, sizeof(*state)); + + nvg__setPaintColor(&state->fill, nvgRGBA(255,255,255,255)); + nvg__setPaintColor(&state->stroke, nvgRGBA(0,0,0,255)); + state->compositeOperation = nvg__compositeOperationState(NVG_SOURCE_OVER); + state->strokeWidth = 1.0f; + state->miterLimit = 10.0f; + state->lineCap = NVG_BUTT; + state->lineJoin = NVG_MITER; + state->alpha = 1.0f; + nvgTransformIdentity(state->xform); + + state->scissor.extent[0] = -1.0f; + state->scissor.extent[1] = -1.0f; + + state->fontSize = 16.0f; + state->letterSpacing = 0.0f; + state->lineHeight = 1.0f; + state->fontBlur = 0.0f; + state->textAlign = NVG_ALIGN_LEFT | NVG_ALIGN_BASELINE; + state->fontId = 0; +} + +// State setting +void nvgStrokeWidth(NVGcontext* ctx, float width) +{ + NVGstate* state = nvg__getState(ctx); + state->strokeWidth = width; +} + +void nvgMiterLimit(NVGcontext* ctx, float limit) +{ + NVGstate* state = nvg__getState(ctx); + state->miterLimit = limit; +} + +void nvgLineCap(NVGcontext* ctx, int cap) +{ + NVGstate* state = nvg__getState(ctx); + state->lineCap = cap; +} + +void nvgLineJoin(NVGcontext* ctx, int join) +{ + NVGstate* state = nvg__getState(ctx); + state->lineJoin = join; +} + +void nvgGlobalAlpha(NVGcontext* ctx, float alpha) +{ + NVGstate* state = nvg__getState(ctx); + state->alpha = alpha; +} + +void nvgTransform(NVGcontext* ctx, float a, float b, float c, float d, float e, float f) +{ + NVGstate* state = nvg__getState(ctx); + float t[6] = { a, b, c, d, e, f }; + nvgTransformPremultiply(state->xform, t); +} + +void nvgResetTransform(NVGcontext* ctx) +{ + NVGstate* state = nvg__getState(ctx); + nvgTransformIdentity(state->xform); +} + +void nvgTranslate(NVGcontext* ctx, float x, float y) +{ + NVGstate* state = nvg__getState(ctx); + float t[6]; + nvgTransformTranslate(t, x,y); + nvgTransformPremultiply(state->xform, t); +} + +void nvgRotate(NVGcontext* ctx, float angle) +{ + NVGstate* state = nvg__getState(ctx); + float t[6]; + nvgTransformRotate(t, angle); + nvgTransformPremultiply(state->xform, t); +} + +void nvgSkewX(NVGcontext* ctx, float angle) +{ + NVGstate* state = nvg__getState(ctx); + float t[6]; + nvgTransformSkewX(t, angle); + nvgTransformPremultiply(state->xform, t); +} + +void nvgSkewY(NVGcontext* ctx, float angle) +{ + NVGstate* state = nvg__getState(ctx); + float t[6]; + nvgTransformSkewY(t, angle); + nvgTransformPremultiply(state->xform, t); +} + +void nvgScale(NVGcontext* ctx, float x, float y) +{ + NVGstate* state = nvg__getState(ctx); + float t[6]; + nvgTransformScale(t, x,y); + nvgTransformPremultiply(state->xform, t); +} + +void nvgCurrentTransform(NVGcontext* ctx, float* xform) +{ + NVGstate* state = nvg__getState(ctx); + if (xform == NULL) return; + memcpy(xform, state->xform, sizeof(float)*6); +} + +void nvgStrokeColor(NVGcontext* ctx, NVGcolor color) +{ + NVGstate* state = nvg__getState(ctx); + nvg__setPaintColor(&state->stroke, color); +} + +void nvgStrokePaint(NVGcontext* ctx, NVGpaint paint) +{ + NVGstate* state = nvg__getState(ctx); + state->stroke = paint; + nvgTransformMultiply(state->stroke.xform, state->xform); +} + +void nvgFillColor(NVGcontext* ctx, NVGcolor color) +{ + NVGstate* state = nvg__getState(ctx); + nvg__setPaintColor(&state->fill, color); +} + +void nvgFillPaint(NVGcontext* ctx, NVGpaint paint) +{ + NVGstate* state = nvg__getState(ctx); + state->fill = paint; + nvgTransformMultiply(state->fill.xform, state->xform); +} + +int nvgCreateImage(NVGcontext* ctx, const char* filename, int imageFlags) +{ + int w, h, n, image; + unsigned char* img; + stbi_set_unpremultiply_on_load(1); + stbi_convert_iphone_png_to_rgb(1); + img = stbi_load(filename, &w, &h, &n, 4); + if (img == NULL) { +// printf("Failed to load %s - %s\n", filename, stbi_failure_reason()); + return 0; + } + image = nvgCreateImageRGBA(ctx, w, h, imageFlags, img); + stbi_image_free(img); + return image; +} + +int nvgCreateImageMem(NVGcontext* ctx, int imageFlags, unsigned char* data, int ndata) +{ + int w, h, n, image; + unsigned char* img = stbi_load_from_memory(data, ndata, &w, &h, &n, 4); + if (img == NULL) { +// printf("Failed to load %s - %s\n", filename, stbi_failure_reason()); + return 0; + } + image = nvgCreateImageRGBA(ctx, w, h, imageFlags, img); + stbi_image_free(img); + return image; +} + +int nvgCreateImageRGBA(NVGcontext* ctx, int w, int h, int imageFlags, const unsigned char* data) +{ + return ctx->params.renderCreateTexture(ctx->params.userPtr, NVG_TEXTURE_RGBA, w, h, imageFlags, data); +} + +void nvgUpdateImage(NVGcontext* ctx, int image, const unsigned char* data) +{ + int w, h; + ctx->params.renderGetTextureSize(ctx->params.userPtr, image, &w, &h); + ctx->params.renderUpdateTexture(ctx->params.userPtr, image, 0,0, w,h, data); +} + +void nvgImageSize(NVGcontext* ctx, int image, int* w, int* h) +{ + ctx->params.renderGetTextureSize(ctx->params.userPtr, image, w, h); +} + +void nvgDeleteImage(NVGcontext* ctx, int image) +{ + ctx->params.renderDeleteTexture(ctx->params.userPtr, image); +} + +NVGpaint nvgLinearGradient(NVGcontext* ctx, + float sx, float sy, float ex, float ey, + NVGcolor icol, NVGcolor ocol) +{ + NVGpaint p; + float dx, dy, d; + const float large = 1e5; + NVG_NOTUSED(ctx); + memset(&p, 0, sizeof(p)); + + // Calculate transform aligned to the line + dx = ex - sx; + dy = ey - sy; + d = sqrtf(dx*dx + dy*dy); + if (d > 0.0001f) { + dx /= d; + dy /= d; + } else { + dx = 0; + dy = 1; + } + + p.xform[0] = dy; p.xform[1] = -dx; + p.xform[2] = dx; p.xform[3] = dy; + p.xform[4] = sx - dx*large; p.xform[5] = sy - dy*large; + + p.extent[0] = large; + p.extent[1] = large + d*0.5f; + + p.radius = 0.0f; + + p.feather = nvg__maxf(1.0f, d); + + p.innerColor = icol; + p.outerColor = ocol; + + return p; +} + +NVGpaint nvgRadialGradient(NVGcontext* ctx, + float cx, float cy, float inr, float outr, + NVGcolor icol, NVGcolor ocol) +{ + NVGpaint p; + float r = (inr+outr)*0.5f; + float f = (outr-inr); + NVG_NOTUSED(ctx); + memset(&p, 0, sizeof(p)); + + nvgTransformIdentity(p.xform); + p.xform[4] = cx; + p.xform[5] = cy; + + p.extent[0] = r; + p.extent[1] = r; + + p.radius = r; + + p.feather = nvg__maxf(1.0f, f); + + p.innerColor = icol; + p.outerColor = ocol; + + return p; +} + +NVGpaint nvgBoxGradient(NVGcontext* ctx, + float x, float y, float w, float h, float r, float f, + NVGcolor icol, NVGcolor ocol) +{ + NVGpaint p; + NVG_NOTUSED(ctx); + memset(&p, 0, sizeof(p)); + + nvgTransformIdentity(p.xform); + p.xform[4] = x+w*0.5f; + p.xform[5] = y+h*0.5f; + + p.extent[0] = w*0.5f; + p.extent[1] = h*0.5f; + + p.radius = r; + + p.feather = nvg__maxf(1.0f, f); + + p.innerColor = icol; + p.outerColor = ocol; + + return p; +} + + +NVGpaint nvgImagePattern(NVGcontext* ctx, + float cx, float cy, float w, float h, float angle, + int image, float alpha) +{ + NVGpaint p; + NVG_NOTUSED(ctx); + memset(&p, 0, sizeof(p)); + + nvgTransformRotate(p.xform, angle); + p.xform[4] = cx; + p.xform[5] = cy; + + p.extent[0] = w; + p.extent[1] = h; + + p.image = image; + + p.innerColor = p.outerColor = nvgRGBAf(1,1,1,alpha); + + return p; +} + +// Scissoring +void nvgScissor(NVGcontext* ctx, float x, float y, float w, float h) +{ + NVGstate* state = nvg__getState(ctx); + + w = nvg__maxf(0.0f, w); + h = nvg__maxf(0.0f, h); + + nvgTransformIdentity(state->scissor.xform); + state->scissor.xform[4] = x+w*0.5f; + state->scissor.xform[5] = y+h*0.5f; + nvgTransformMultiply(state->scissor.xform, state->xform); + + state->scissor.extent[0] = w*0.5f; + state->scissor.extent[1] = h*0.5f; +} + +static void nvg__isectRects(float* dst, + float ax, float ay, float aw, float ah, + float bx, float by, float bw, float bh) +{ + float minx = nvg__maxf(ax, bx); + float miny = nvg__maxf(ay, by); + float maxx = nvg__minf(ax+aw, bx+bw); + float maxy = nvg__minf(ay+ah, by+bh); + dst[0] = minx; + dst[1] = miny; + dst[2] = nvg__maxf(0.0f, maxx - minx); + dst[3] = nvg__maxf(0.0f, maxy - miny); +} + +void nvgIntersectScissor(NVGcontext* ctx, float x, float y, float w, float h) +{ + NVGstate* state = nvg__getState(ctx); + float pxform[6], invxorm[6]; + float rect[4]; + float ex, ey, tex, tey; + + // If no previous scissor has been set, set the scissor as current scissor. + if (state->scissor.extent[0] < 0) { + nvgScissor(ctx, x, y, w, h); + return; + } + + // Transform the current scissor rect into current transform space. + // If there is difference in rotation, this will be approximation. + memcpy(pxform, state->scissor.xform, sizeof(float)*6); + ex = state->scissor.extent[0]; + ey = state->scissor.extent[1]; + nvgTransformInverse(invxorm, state->xform); + nvgTransformMultiply(pxform, invxorm); + tex = ex*nvg__absf(pxform[0]) + ey*nvg__absf(pxform[2]); + tey = ex*nvg__absf(pxform[1]) + ey*nvg__absf(pxform[3]); + + // Intersect rects. + nvg__isectRects(rect, pxform[4]-tex,pxform[5]-tey,tex*2,tey*2, x,y,w,h); + + nvgScissor(ctx, rect[0], rect[1], rect[2], rect[3]); +} + +void nvgResetScissor(NVGcontext* ctx) +{ + NVGstate* state = nvg__getState(ctx); + memset(state->scissor.xform, 0, sizeof(state->scissor.xform)); + state->scissor.extent[0] = -1.0f; + state->scissor.extent[1] = -1.0f; +} + +// Global composite operation. +void nvgGlobalCompositeOperation(NVGcontext* ctx, int op) +{ + NVGstate* state = nvg__getState(ctx); + state->compositeOperation = nvg__compositeOperationState(op); +} + +void nvgGlobalCompositeBlendFunc(NVGcontext* ctx, int sfactor, int dfactor) +{ + nvgGlobalCompositeBlendFuncSeparate(ctx, sfactor, dfactor, sfactor, dfactor); +} + +void nvgGlobalCompositeBlendFuncSeparate(NVGcontext* ctx, int srcRGB, int dstRGB, int srcAlpha, int dstAlpha) +{ + NVGcompositeOperationState op; + op.srcRGB = srcRGB; + op.dstRGB = dstRGB; + op.srcAlpha = srcAlpha; + op.dstAlpha = dstAlpha; + + NVGstate* state = nvg__getState(ctx); + state->compositeOperation = op; +} + +static int nvg__ptEquals(float x1, float y1, float x2, float y2, float tol) +{ + float dx = x2 - x1; + float dy = y2 - y1; + return dx*dx + dy*dy < tol*tol; +} + +static float nvg__distPtSeg(float x, float y, float px, float py, float qx, float qy) +{ + float pqx, pqy, dx, dy, d, t; + pqx = qx-px; + pqy = qy-py; + dx = x-px; + dy = y-py; + d = pqx*pqx + pqy*pqy; + t = pqx*dx + pqy*dy; + if (d > 0) t /= d; + if (t < 0) t = 0; + else if (t > 1) t = 1; + dx = px + t*pqx - x; + dy = py + t*pqy - y; + return dx*dx + dy*dy; +} + +static void nvg__appendCommands(NVGcontext* ctx, float* vals, int nvals) +{ + NVGstate* state = nvg__getState(ctx); + int i; + + if (ctx->ncommands+nvals > ctx->ccommands) { + float* commands; + int ccommands = ctx->ncommands+nvals + ctx->ccommands/2; + commands = (float*)realloc(ctx->commands, sizeof(float)*ccommands); + if (commands == NULL) return; + ctx->commands = commands; + ctx->ccommands = ccommands; + } + + if ((int)vals[0] != NVG_CLOSE && (int)vals[0] != NVG_WINDING) { + ctx->commandx = vals[nvals-2]; + ctx->commandy = vals[nvals-1]; + } + + // transform commands + i = 0; + while (i < nvals) { + int cmd = (int)vals[i]; + switch (cmd) { + case NVG_MOVETO: + nvgTransformPoint(&vals[i+1],&vals[i+2], state->xform, vals[i+1],vals[i+2]); + i += 3; + break; + case NVG_LINETO: + nvgTransformPoint(&vals[i+1],&vals[i+2], state->xform, vals[i+1],vals[i+2]); + i += 3; + break; + case NVG_BEZIERTO: + nvgTransformPoint(&vals[i+1],&vals[i+2], state->xform, vals[i+1],vals[i+2]); + nvgTransformPoint(&vals[i+3],&vals[i+4], state->xform, vals[i+3],vals[i+4]); + nvgTransformPoint(&vals[i+5],&vals[i+6], state->xform, vals[i+5],vals[i+6]); + i += 7; + break; + case NVG_CLOSE: + i++; + break; + case NVG_WINDING: + i += 2; + break; + default: + i++; + } + } + + memcpy(&ctx->commands[ctx->ncommands], vals, nvals*sizeof(float)); + + ctx->ncommands += nvals; +} + + +static void nvg__clearPathCache(NVGcontext* ctx) +{ + ctx->cache->npoints = 0; + ctx->cache->npaths = 0; +} + +static NVGpath* nvg__lastPath(NVGcontext* ctx) +{ + if (ctx->cache->npaths > 0) + return &ctx->cache->paths[ctx->cache->npaths-1]; + return NULL; +} + +static void nvg__addPath(NVGcontext* ctx) +{ + NVGpath* path; + if (ctx->cache->npaths+1 > ctx->cache->cpaths) { + NVGpath* paths; + int cpaths = ctx->cache->npaths+1 + ctx->cache->cpaths/2; + paths = (NVGpath*)realloc(ctx->cache->paths, sizeof(NVGpath)*cpaths); + if (paths == NULL) return; + ctx->cache->paths = paths; + ctx->cache->cpaths = cpaths; + } + path = &ctx->cache->paths[ctx->cache->npaths]; + memset(path, 0, sizeof(*path)); + path->first = ctx->cache->npoints; + path->winding = NVG_CCW; + + ctx->cache->npaths++; +} + +static NVGpoint* nvg__lastPoint(NVGcontext* ctx) +{ + if (ctx->cache->npoints > 0) + return &ctx->cache->points[ctx->cache->npoints-1]; + return NULL; +} + +static void nvg__addPoint(NVGcontext* ctx, float x, float y, int flags) +{ + NVGpath* path = nvg__lastPath(ctx); + NVGpoint* pt; + if (path == NULL) return; + + if (path->count > 0 && ctx->cache->npoints > 0) { + pt = nvg__lastPoint(ctx); + if (nvg__ptEquals(pt->x,pt->y, x,y, ctx->distTol)) { + pt->flags |= flags; + return; + } + } + + if (ctx->cache->npoints+1 > ctx->cache->cpoints) { + NVGpoint* points; + int cpoints = ctx->cache->npoints+1 + ctx->cache->cpoints/2; + points = (NVGpoint*)realloc(ctx->cache->points, sizeof(NVGpoint)*cpoints); + if (points == NULL) return; + ctx->cache->points = points; + ctx->cache->cpoints = cpoints; + } + + pt = &ctx->cache->points[ctx->cache->npoints]; + memset(pt, 0, sizeof(*pt)); + pt->x = x; + pt->y = y; + pt->flags = (unsigned char)flags; + + ctx->cache->npoints++; + path->count++; +} + +static void nvg__closePath(NVGcontext* ctx) +{ + NVGpath* path = nvg__lastPath(ctx); + if (path == NULL) return; + path->closed = 1; +} + +static void nvg__pathWinding(NVGcontext* ctx, int winding) +{ + NVGpath* path = nvg__lastPath(ctx); + if (path == NULL) return; + path->winding = winding; +} + +static float nvg__getAverageScale(float *t) +{ + float sx = sqrtf(t[0]*t[0] + t[2]*t[2]); + float sy = sqrtf(t[1]*t[1] + t[3]*t[3]); + return (sx + sy) * 0.5f; +} + +static NVGvertex* nvg__allocTempVerts(NVGcontext* ctx, int nverts) +{ + if (nverts > ctx->cache->cverts) { + NVGvertex* verts; + int cverts = (nverts + 0xff) & ~0xff; // Round up to prevent allocations when things change just slightly. + verts = (NVGvertex*)realloc(ctx->cache->verts, sizeof(NVGvertex)*cverts); + if (verts == NULL) return NULL; + ctx->cache->verts = verts; + ctx->cache->cverts = cverts; + } + + return ctx->cache->verts; +} + +static float nvg__triarea2(float ax, float ay, float bx, float by, float cx, float cy) +{ + float abx = bx - ax; + float aby = by - ay; + float acx = cx - ax; + float acy = cy - ay; + return acx*aby - abx*acy; +} + +static float nvg__polyArea(NVGpoint* pts, int npts) +{ + int i; + float area = 0; + for (i = 2; i < npts; i++) { + NVGpoint* a = &pts[0]; + NVGpoint* b = &pts[i-1]; + NVGpoint* c = &pts[i]; + area += nvg__triarea2(a->x,a->y, b->x,b->y, c->x,c->y); + } + return area * 0.5f; +} + +static void nvg__polyReverse(NVGpoint* pts, int npts) +{ + NVGpoint tmp; + int i = 0, j = npts-1; + while (i < j) { + tmp = pts[i]; + pts[i] = pts[j]; + pts[j] = tmp; + i++; + j--; + } +} + + +static void nvg__vset(NVGvertex* vtx, float x, float y, float u, float v) +{ + vtx->x = x; + vtx->y = y; + vtx->u = u; + vtx->v = v; +} + +static void nvg__tesselateBezier(NVGcontext* ctx, + float x1, float y1, float x2, float y2, + float x3, float y3, float x4, float y4, + int level, int type) +{ + float x12,y12,x23,y23,x34,y34,x123,y123,x234,y234,x1234,y1234; + float dx,dy,d2,d3; + + if (level > 10) return; + + x12 = (x1+x2)*0.5f; + y12 = (y1+y2)*0.5f; + x23 = (x2+x3)*0.5f; + y23 = (y2+y3)*0.5f; + x34 = (x3+x4)*0.5f; + y34 = (y3+y4)*0.5f; + x123 = (x12+x23)*0.5f; + y123 = (y12+y23)*0.5f; + + dx = x4 - x1; + dy = y4 - y1; + d2 = nvg__absf(((x2 - x4) * dy - (y2 - y4) * dx)); + d3 = nvg__absf(((x3 - x4) * dy - (y3 - y4) * dx)); + + if ((d2 + d3)*(d2 + d3) < ctx->tessTol * (dx*dx + dy*dy)) { + nvg__addPoint(ctx, x4, y4, type); + return; + } + +/* if (nvg__absf(x1+x3-x2-x2) + nvg__absf(y1+y3-y2-y2) + nvg__absf(x2+x4-x3-x3) + nvg__absf(y2+y4-y3-y3) < ctx->tessTol) { + nvg__addPoint(ctx, x4, y4, type); + return; + }*/ + + x234 = (x23+x34)*0.5f; + y234 = (y23+y34)*0.5f; + x1234 = (x123+x234)*0.5f; + y1234 = (y123+y234)*0.5f; + + nvg__tesselateBezier(ctx, x1,y1, x12,y12, x123,y123, x1234,y1234, level+1, 0); + nvg__tesselateBezier(ctx, x1234,y1234, x234,y234, x34,y34, x4,y4, level+1, type); +} + +static void nvg__flattenPaths(NVGcontext* ctx) +{ + NVGpathCache* cache = ctx->cache; +// NVGstate* state = nvg__getState(ctx); + NVGpoint* last; + NVGpoint* p0; + NVGpoint* p1; + NVGpoint* pts; + NVGpath* path; + int i, j; + float* cp1; + float* cp2; + float* p; + float area; + + if (cache->npaths > 0) + return; + + // Flatten + i = 0; + while (i < ctx->ncommands) { + int cmd = (int)ctx->commands[i]; + switch (cmd) { + case NVG_MOVETO: + nvg__addPath(ctx); + p = &ctx->commands[i+1]; + nvg__addPoint(ctx, p[0], p[1], NVG_PT_CORNER); + i += 3; + break; + case NVG_LINETO: + p = &ctx->commands[i+1]; + nvg__addPoint(ctx, p[0], p[1], NVG_PT_CORNER); + i += 3; + break; + case NVG_BEZIERTO: + last = nvg__lastPoint(ctx); + if (last != NULL) { + cp1 = &ctx->commands[i+1]; + cp2 = &ctx->commands[i+3]; + p = &ctx->commands[i+5]; + nvg__tesselateBezier(ctx, last->x,last->y, cp1[0],cp1[1], cp2[0],cp2[1], p[0],p[1], 0, NVG_PT_CORNER); + } + i += 7; + break; + case NVG_CLOSE: + nvg__closePath(ctx); + i++; + break; + case NVG_WINDING: + nvg__pathWinding(ctx, (int)ctx->commands[i+1]); + i += 2; + break; + default: + i++; + } + } + + cache->bounds[0] = cache->bounds[1] = 1e6f; + cache->bounds[2] = cache->bounds[3] = -1e6f; + + // Calculate the direction and length of line segments. + for (j = 0; j < cache->npaths; j++) { + path = &cache->paths[j]; + pts = &cache->points[path->first]; + + // If the first and last points are the same, remove the last, mark as closed path. + p0 = &pts[path->count-1]; + p1 = &pts[0]; + if (nvg__ptEquals(p0->x,p0->y, p1->x,p1->y, ctx->distTol)) { + path->count--; + p0 = &pts[path->count-1]; + path->closed = 1; + } + + // Enforce winding. + if (path->count > 2) { + area = nvg__polyArea(pts, path->count); + if (path->winding == NVG_CCW && area < 0.0f) + nvg__polyReverse(pts, path->count); + if (path->winding == NVG_CW && area > 0.0f) + nvg__polyReverse(pts, path->count); + } + + for(i = 0; i < path->count; i++) { + // Calculate segment direction and length + p0->dx = p1->x - p0->x; + p0->dy = p1->y - p0->y; + p0->len = nvg__normalize(&p0->dx, &p0->dy); + // Update bounds + cache->bounds[0] = nvg__minf(cache->bounds[0], p0->x); + cache->bounds[1] = nvg__minf(cache->bounds[1], p0->y); + cache->bounds[2] = nvg__maxf(cache->bounds[2], p0->x); + cache->bounds[3] = nvg__maxf(cache->bounds[3], p0->y); + // Advance + p0 = p1++; + } + } +} + +static int nvg__curveDivs(float r, float arc, float tol) +{ + float da = acosf(r / (r + tol)) * 2.0f; + return nvg__maxi(2, (int)ceilf(arc / da)); +} + +static void nvg__chooseBevel(int bevel, NVGpoint* p0, NVGpoint* p1, float w, + float* x0, float* y0, float* x1, float* y1) +{ + if (bevel) { + *x0 = p1->x + p0->dy * w; + *y0 = p1->y - p0->dx * w; + *x1 = p1->x + p1->dy * w; + *y1 = p1->y - p1->dx * w; + } else { + *x0 = p1->x + p1->dmx * w; + *y0 = p1->y + p1->dmy * w; + *x1 = p1->x + p1->dmx * w; + *y1 = p1->y + p1->dmy * w; + } +} + +static NVGvertex* nvg__roundJoin(NVGvertex* dst, NVGpoint* p0, NVGpoint* p1, + float lw, float rw, float lu, float ru, int ncap, float fringe) +{ + int i, n; + float dlx0 = p0->dy; + float dly0 = -p0->dx; + float dlx1 = p1->dy; + float dly1 = -p1->dx; + NVG_NOTUSED(fringe); + + if (p1->flags & NVG_PT_LEFT) { + float lx0,ly0,lx1,ly1,a0,a1; + nvg__chooseBevel(p1->flags & NVG_PR_INNERBEVEL, p0, p1, lw, &lx0,&ly0, &lx1,&ly1); + a0 = atan2f(-dly0, -dlx0); + a1 = atan2f(-dly1, -dlx1); + if (a1 > a0) a1 -= NVG_PI*2; + + nvg__vset(dst, lx0, ly0, lu,1); dst++; + nvg__vset(dst, p1->x - dlx0*rw, p1->y - dly0*rw, ru,1); dst++; + + n = nvg__clampi((int)ceilf(((a0 - a1) / NVG_PI) * ncap), 2, ncap); + for (i = 0; i < n; i++) { + float u = i/(float)(n-1); + float a = a0 + u*(a1-a0); + float rx = p1->x + cosf(a) * rw; + float ry = p1->y + sinf(a) * rw; + nvg__vset(dst, p1->x, p1->y, 0.5f,1); dst++; + nvg__vset(dst, rx, ry, ru,1); dst++; + } + + nvg__vset(dst, lx1, ly1, lu,1); dst++; + nvg__vset(dst, p1->x - dlx1*rw, p1->y - dly1*rw, ru,1); dst++; + + } else { + float rx0,ry0,rx1,ry1,a0,a1; + nvg__chooseBevel(p1->flags & NVG_PR_INNERBEVEL, p0, p1, -rw, &rx0,&ry0, &rx1,&ry1); + a0 = atan2f(dly0, dlx0); + a1 = atan2f(dly1, dlx1); + if (a1 < a0) a1 += NVG_PI*2; + + nvg__vset(dst, p1->x + dlx0*rw, p1->y + dly0*rw, lu,1); dst++; + nvg__vset(dst, rx0, ry0, ru,1); dst++; + + n = nvg__clampi((int)ceilf(((a1 - a0) / NVG_PI) * ncap), 2, ncap); + for (i = 0; i < n; i++) { + float u = i/(float)(n-1); + float a = a0 + u*(a1-a0); + float lx = p1->x + cosf(a) * lw; + float ly = p1->y + sinf(a) * lw; + nvg__vset(dst, lx, ly, lu,1); dst++; + nvg__vset(dst, p1->x, p1->y, 0.5f,1); dst++; + } + + nvg__vset(dst, p1->x + dlx1*rw, p1->y + dly1*rw, lu,1); dst++; + nvg__vset(dst, rx1, ry1, ru,1); dst++; + + } + return dst; +} + +static NVGvertex* nvg__bevelJoin(NVGvertex* dst, NVGpoint* p0, NVGpoint* p1, + float lw, float rw, float lu, float ru, float fringe) +{ + float rx0,ry0,rx1,ry1; + float lx0,ly0,lx1,ly1; + float dlx0 = p0->dy; + float dly0 = -p0->dx; + float dlx1 = p1->dy; + float dly1 = -p1->dx; + NVG_NOTUSED(fringe); + + if (p1->flags & NVG_PT_LEFT) { + nvg__chooseBevel(p1->flags & NVG_PR_INNERBEVEL, p0, p1, lw, &lx0,&ly0, &lx1,&ly1); + + nvg__vset(dst, lx0, ly0, lu,1); dst++; + nvg__vset(dst, p1->x - dlx0*rw, p1->y - dly0*rw, ru,1); dst++; + + if (p1->flags & NVG_PT_BEVEL) { + nvg__vset(dst, lx0, ly0, lu,1); dst++; + nvg__vset(dst, p1->x - dlx0*rw, p1->y - dly0*rw, ru,1); dst++; + + nvg__vset(dst, lx1, ly1, lu,1); dst++; + nvg__vset(dst, p1->x - dlx1*rw, p1->y - dly1*rw, ru,1); dst++; + } else { + rx0 = p1->x - p1->dmx * rw; + ry0 = p1->y - p1->dmy * rw; + + nvg__vset(dst, p1->x, p1->y, 0.5f,1); dst++; + nvg__vset(dst, p1->x - dlx0*rw, p1->y - dly0*rw, ru,1); dst++; + + nvg__vset(dst, rx0, ry0, ru,1); dst++; + nvg__vset(dst, rx0, ry0, ru,1); dst++; + + nvg__vset(dst, p1->x, p1->y, 0.5f,1); dst++; + nvg__vset(dst, p1->x - dlx1*rw, p1->y - dly1*rw, ru,1); dst++; + } + + nvg__vset(dst, lx1, ly1, lu,1); dst++; + nvg__vset(dst, p1->x - dlx1*rw, p1->y - dly1*rw, ru,1); dst++; + + } else { + nvg__chooseBevel(p1->flags & NVG_PR_INNERBEVEL, p0, p1, -rw, &rx0,&ry0, &rx1,&ry1); + + nvg__vset(dst, p1->x + dlx0*lw, p1->y + dly0*lw, lu,1); dst++; + nvg__vset(dst, rx0, ry0, ru,1); dst++; + + if (p1->flags & NVG_PT_BEVEL) { + nvg__vset(dst, p1->x + dlx0*lw, p1->y + dly0*lw, lu,1); dst++; + nvg__vset(dst, rx0, ry0, ru,1); dst++; + + nvg__vset(dst, p1->x + dlx1*lw, p1->y + dly1*lw, lu,1); dst++; + nvg__vset(dst, rx1, ry1, ru,1); dst++; + } else { + lx0 = p1->x + p1->dmx * lw; + ly0 = p1->y + p1->dmy * lw; + + nvg__vset(dst, p1->x + dlx0*lw, p1->y + dly0*lw, lu,1); dst++; + nvg__vset(dst, p1->x, p1->y, 0.5f,1); dst++; + + nvg__vset(dst, lx0, ly0, lu,1); dst++; + nvg__vset(dst, lx0, ly0, lu,1); dst++; + + nvg__vset(dst, p1->x + dlx1*lw, p1->y + dly1*lw, lu,1); dst++; + nvg__vset(dst, p1->x, p1->y, 0.5f,1); dst++; + } + + nvg__vset(dst, p1->x + dlx1*lw, p1->y + dly1*lw, lu,1); dst++; + nvg__vset(dst, rx1, ry1, ru,1); dst++; + } + + return dst; +} + +static NVGvertex* nvg__buttCapStart(NVGvertex* dst, NVGpoint* p, + float dx, float dy, float w, float d, float aa) +{ + float px = p->x - dx*d; + float py = p->y - dy*d; + float dlx = dy; + float dly = -dx; + nvg__vset(dst, px + dlx*w - dx*aa, py + dly*w - dy*aa, 0,0); dst++; + nvg__vset(dst, px - dlx*w - dx*aa, py - dly*w - dy*aa, 1,0); dst++; + nvg__vset(dst, px + dlx*w, py + dly*w, 0,1); dst++; + nvg__vset(dst, px - dlx*w, py - dly*w, 1,1); dst++; + return dst; +} + +static NVGvertex* nvg__buttCapEnd(NVGvertex* dst, NVGpoint* p, + float dx, float dy, float w, float d, float aa) +{ + float px = p->x + dx*d; + float py = p->y + dy*d; + float dlx = dy; + float dly = -dx; + nvg__vset(dst, px + dlx*w, py + dly*w, 0,1); dst++; + nvg__vset(dst, px - dlx*w, py - dly*w, 1,1); dst++; + nvg__vset(dst, px + dlx*w + dx*aa, py + dly*w + dy*aa, 0,0); dst++; + nvg__vset(dst, px - dlx*w + dx*aa, py - dly*w + dy*aa, 1,0); dst++; + return dst; +} + + +static NVGvertex* nvg__roundCapStart(NVGvertex* dst, NVGpoint* p, + float dx, float dy, float w, int ncap, float aa) +{ + int i; + float px = p->x; + float py = p->y; + float dlx = dy; + float dly = -dx; + NVG_NOTUSED(aa); + for (i = 0; i < ncap; i++) { + float a = i/(float)(ncap-1)*NVG_PI; + float ax = cosf(a) * w, ay = sinf(a) * w; + nvg__vset(dst, px - dlx*ax - dx*ay, py - dly*ax - dy*ay, 0,1); dst++; + nvg__vset(dst, px, py, 0.5f,1); dst++; + } + nvg__vset(dst, px + dlx*w, py + dly*w, 0,1); dst++; + nvg__vset(dst, px - dlx*w, py - dly*w, 1,1); dst++; + return dst; +} + +static NVGvertex* nvg__roundCapEnd(NVGvertex* dst, NVGpoint* p, + float dx, float dy, float w, int ncap, float aa) +{ + int i; + float px = p->x; + float py = p->y; + float dlx = dy; + float dly = -dx; + NVG_NOTUSED(aa); + nvg__vset(dst, px + dlx*w, py + dly*w, 0,1); dst++; + nvg__vset(dst, px - dlx*w, py - dly*w, 1,1); dst++; + for (i = 0; i < ncap; i++) { + float a = i/(float)(ncap-1)*NVG_PI; + float ax = cosf(a) * w, ay = sinf(a) * w; + nvg__vset(dst, px, py, 0.5f,1); dst++; + nvg__vset(dst, px - dlx*ax + dx*ay, py - dly*ax + dy*ay, 0,1); dst++; + } + return dst; +} + + +static void nvg__calculateJoins(NVGcontext* ctx, float w, int lineJoin, float miterLimit) +{ + NVGpathCache* cache = ctx->cache; + int i, j; + float iw = 0.0f; + + if (w > 0.0f) iw = 1.0f / w; + + // Calculate which joins needs extra vertices to append, and gather vertex count. + for (i = 0; i < cache->npaths; i++) { + NVGpath* path = &cache->paths[i]; + NVGpoint* pts = &cache->points[path->first]; + NVGpoint* p0 = &pts[path->count-1]; + NVGpoint* p1 = &pts[0]; + int nleft = 0; + + path->nbevel = 0; + + for (j = 0; j < path->count; j++) { + float dlx0, dly0, dlx1, dly1, dmr2, cross, limit; + dlx0 = p0->dy; + dly0 = -p0->dx; + dlx1 = p1->dy; + dly1 = -p1->dx; + // Calculate extrusions + p1->dmx = (dlx0 + dlx1) * 0.5f; + p1->dmy = (dly0 + dly1) * 0.5f; + dmr2 = p1->dmx*p1->dmx + p1->dmy*p1->dmy; + if (dmr2 > 0.000001f) { + float scale = 1.0f / dmr2; + if (scale > 600.0f) { + scale = 600.0f; + } + p1->dmx *= scale; + p1->dmy *= scale; + } + + // Clear flags, but keep the corner. + p1->flags = (p1->flags & NVG_PT_CORNER) ? NVG_PT_CORNER : 0; + + // Keep track of left turns. + cross = p1->dx * p0->dy - p0->dx * p1->dy; + if (cross > 0.0f) { + nleft++; + p1->flags |= NVG_PT_LEFT; + } + + // Calculate if we should use bevel or miter for inner join. + limit = nvg__maxf(1.01f, nvg__minf(p0->len, p1->len) * iw); + if ((dmr2 * limit*limit) < 1.0f) + p1->flags |= NVG_PR_INNERBEVEL; + + // Check to see if the corner needs to be beveled. + if (p1->flags & NVG_PT_CORNER) { + if ((dmr2 * miterLimit*miterLimit) < 1.0f || lineJoin == NVG_BEVEL || lineJoin == NVG_ROUND) { + p1->flags |= NVG_PT_BEVEL; + } + } + + if ((p1->flags & (NVG_PT_BEVEL | NVG_PR_INNERBEVEL)) != 0) + path->nbevel++; + + p0 = p1++; + } + + path->convex = (nleft == path->count) ? 1 : 0; + } +} + + +static int nvg__expandStroke(NVGcontext* ctx, float w, int lineCap, int lineJoin, float miterLimit) +{ + NVGpathCache* cache = ctx->cache; + NVGvertex* verts; + NVGvertex* dst; + int cverts, i, j; + float aa = ctx->fringeWidth; + int ncap = nvg__curveDivs(w, NVG_PI, ctx->tessTol); // Calculate divisions per half circle. + + nvg__calculateJoins(ctx, w, lineJoin, miterLimit); + + // Calculate max vertex usage. + cverts = 0; + for (i = 0; i < cache->npaths; i++) { + NVGpath* path = &cache->paths[i]; + int loop = (path->closed == 0) ? 0 : 1; + if (lineJoin == NVG_ROUND) + cverts += (path->count + path->nbevel*(ncap+2) + 1) * 2; // plus one for loop + else + cverts += (path->count + path->nbevel*5 + 1) * 2; // plus one for loop + if (loop == 0) { + // space for caps + if (lineCap == NVG_ROUND) { + cverts += (ncap*2 + 2)*2; + } else { + cverts += (3+3)*2; + } + } + } + + verts = nvg__allocTempVerts(ctx, cverts); + if (verts == NULL) return 0; + + for (i = 0; i < cache->npaths; i++) { + NVGpath* path = &cache->paths[i]; + NVGpoint* pts = &cache->points[path->first]; + NVGpoint* p0; + NVGpoint* p1; + int s, e, loop; + float dx, dy; + + path->fill = 0; + path->nfill = 0; + + // Calculate fringe or stroke + loop = (path->closed == 0) ? 0 : 1; + dst = verts; + path->stroke = dst; + + if (loop) { + // Looping + p0 = &pts[path->count-1]; + p1 = &pts[0]; + s = 0; + e = path->count; + } else { + // Add cap + p0 = &pts[0]; + p1 = &pts[1]; + s = 1; + e = path->count-1; + } + + if (loop == 0) { + // Add cap + dx = p1->x - p0->x; + dy = p1->y - p0->y; + nvg__normalize(&dx, &dy); + if (lineCap == NVG_BUTT) + dst = nvg__buttCapStart(dst, p0, dx, dy, w, -aa*0.5f, aa); + else if (lineCap == NVG_BUTT || lineCap == NVG_SQUARE) + dst = nvg__buttCapStart(dst, p0, dx, dy, w, w-aa, aa); + else if (lineCap == NVG_ROUND) + dst = nvg__roundCapStart(dst, p0, dx, dy, w, ncap, aa); + } + + for (j = s; j < e; ++j) { + if ((p1->flags & (NVG_PT_BEVEL | NVG_PR_INNERBEVEL)) != 0) { + if (lineJoin == NVG_ROUND) { + dst = nvg__roundJoin(dst, p0, p1, w, w, 0, 1, ncap, aa); + } else { + dst = nvg__bevelJoin(dst, p0, p1, w, w, 0, 1, aa); + } + } else { + nvg__vset(dst, p1->x + (p1->dmx * w), p1->y + (p1->dmy * w), 0,1); dst++; + nvg__vset(dst, p1->x - (p1->dmx * w), p1->y - (p1->dmy * w), 1,1); dst++; + } + p0 = p1++; + } + + if (loop) { + // Loop it + nvg__vset(dst, verts[0].x, verts[0].y, 0,1); dst++; + nvg__vset(dst, verts[1].x, verts[1].y, 1,1); dst++; + } else { + // Add cap + dx = p1->x - p0->x; + dy = p1->y - p0->y; + nvg__normalize(&dx, &dy); + if (lineCap == NVG_BUTT) + dst = nvg__buttCapEnd(dst, p1, dx, dy, w, -aa*0.5f, aa); + else if (lineCap == NVG_BUTT || lineCap == NVG_SQUARE) + dst = nvg__buttCapEnd(dst, p1, dx, dy, w, w-aa, aa); + else if (lineCap == NVG_ROUND) + dst = nvg__roundCapEnd(dst, p1, dx, dy, w, ncap, aa); + } + + path->nstroke = (int)(dst - verts); + + verts = dst; + } + + return 1; +} + +static int nvg__expandFill(NVGcontext* ctx, float w, int lineJoin, float miterLimit) +{ + NVGpathCache* cache = ctx->cache; + NVGvertex* verts; + NVGvertex* dst; + int cverts, convex, i, j; + float aa = ctx->fringeWidth; + int fringe = w > 0.0f; + + nvg__calculateJoins(ctx, w, lineJoin, miterLimit); + + // Calculate max vertex usage. + cverts = 0; + for (i = 0; i < cache->npaths; i++) { + NVGpath* path = &cache->paths[i]; + cverts += path->count + path->nbevel + 1; + if (fringe) + cverts += (path->count + path->nbevel*5 + 1) * 2; // plus one for loop + } + + verts = nvg__allocTempVerts(ctx, cverts); + if (verts == NULL) return 0; + + convex = cache->npaths == 1 && cache->paths[0].convex; + + for (i = 0; i < cache->npaths; i++) { + NVGpath* path = &cache->paths[i]; + NVGpoint* pts = &cache->points[path->first]; + NVGpoint* p0; + NVGpoint* p1; + float rw, lw, woff; + float ru, lu; + + // Calculate shape vertices. + woff = 0.5f*aa; + dst = verts; + path->fill = dst; + + if (fringe) { + // Looping + p0 = &pts[path->count-1]; + p1 = &pts[0]; + for (j = 0; j < path->count; ++j) { + if (p1->flags & NVG_PT_BEVEL) { + float dlx0 = p0->dy; + float dly0 = -p0->dx; + float dlx1 = p1->dy; + float dly1 = -p1->dx; + if (p1->flags & NVG_PT_LEFT) { + float lx = p1->x + p1->dmx * woff; + float ly = p1->y + p1->dmy * woff; + nvg__vset(dst, lx, ly, 0.5f,1); dst++; + } else { + float lx0 = p1->x + dlx0 * woff; + float ly0 = p1->y + dly0 * woff; + float lx1 = p1->x + dlx1 * woff; + float ly1 = p1->y + dly1 * woff; + nvg__vset(dst, lx0, ly0, 0.5f,1); dst++; + nvg__vset(dst, lx1, ly1, 0.5f,1); dst++; + } + } else { + nvg__vset(dst, p1->x + (p1->dmx * woff), p1->y + (p1->dmy * woff), 0.5f,1); dst++; + } + p0 = p1++; + } + } else { + for (j = 0; j < path->count; ++j) { + nvg__vset(dst, pts[j].x, pts[j].y, 0.5f,1); + dst++; + } + } + + path->nfill = (int)(dst - verts); + verts = dst; + + // Calculate fringe + if (fringe) { + lw = w + woff; + rw = w - woff; + lu = 0; + ru = 1; + dst = verts; + path->stroke = dst; + + // Create only half a fringe for convex shapes so that + // the shape can be rendered without stenciling. + if (convex) { + lw = woff; // This should generate the same vertex as fill inset above. + lu = 0.5f; // Set outline fade at middle. + } + + // Looping + p0 = &pts[path->count-1]; + p1 = &pts[0]; + + for (j = 0; j < path->count; ++j) { + if ((p1->flags & (NVG_PT_BEVEL | NVG_PR_INNERBEVEL)) != 0) { + dst = nvg__bevelJoin(dst, p0, p1, lw, rw, lu, ru, ctx->fringeWidth); + } else { + nvg__vset(dst, p1->x + (p1->dmx * lw), p1->y + (p1->dmy * lw), lu,1); dst++; + nvg__vset(dst, p1->x - (p1->dmx * rw), p1->y - (p1->dmy * rw), ru,1); dst++; + } + p0 = p1++; + } + + // Loop it + nvg__vset(dst, verts[0].x, verts[0].y, lu,1); dst++; + nvg__vset(dst, verts[1].x, verts[1].y, ru,1); dst++; + + path->nstroke = (int)(dst - verts); + verts = dst; + } else { + path->stroke = NULL; + path->nstroke = 0; + } + } + + return 1; +} + + +// Draw +void nvgBeginPath(NVGcontext* ctx) +{ + ctx->ncommands = 0; + nvg__clearPathCache(ctx); +} + +void nvgMoveTo(NVGcontext* ctx, float x, float y) +{ + float vals[] = { NVG_MOVETO, x, y }; + nvg__appendCommands(ctx, vals, NVG_COUNTOF(vals)); +} + +void nvgLineTo(NVGcontext* ctx, float x, float y) +{ + float vals[] = { NVG_LINETO, x, y }; + nvg__appendCommands(ctx, vals, NVG_COUNTOF(vals)); +} + +void nvgBezierTo(NVGcontext* ctx, float c1x, float c1y, float c2x, float c2y, float x, float y) +{ + float vals[] = { NVG_BEZIERTO, c1x, c1y, c2x, c2y, x, y }; + nvg__appendCommands(ctx, vals, NVG_COUNTOF(vals)); +} + +void nvgQuadTo(NVGcontext* ctx, float cx, float cy, float x, float y) +{ + float x0 = ctx->commandx; + float y0 = ctx->commandy; + float vals[] = { NVG_BEZIERTO, + x0 + 2.0f/3.0f*(cx - x0), y0 + 2.0f/3.0f*(cy - y0), + x + 2.0f/3.0f*(cx - x), y + 2.0f/3.0f*(cy - y), + x, y }; + nvg__appendCommands(ctx, vals, NVG_COUNTOF(vals)); +} + +void nvgArcTo(NVGcontext* ctx, float x1, float y1, float x2, float y2, float radius) +{ + float x0 = ctx->commandx; + float y0 = ctx->commandy; + float dx0,dy0, dx1,dy1, a, d, cx,cy, a0,a1; + int dir; + + if (ctx->ncommands == 0) { + return; + } + + // Handle degenerate cases. + if (nvg__ptEquals(x0,y0, x1,y1, ctx->distTol) || + nvg__ptEquals(x1,y1, x2,y2, ctx->distTol) || + nvg__distPtSeg(x1,y1, x0,y0, x2,y2) < ctx->distTol*ctx->distTol || + radius < ctx->distTol) { + nvgLineTo(ctx, x1,y1); + return; + } + + // Calculate tangential circle to lines (x0,y0)-(x1,y1) and (x1,y1)-(x2,y2). + dx0 = x0-x1; + dy0 = y0-y1; + dx1 = x2-x1; + dy1 = y2-y1; + nvg__normalize(&dx0,&dy0); + nvg__normalize(&dx1,&dy1); + a = nvg__acosf(dx0*dx1 + dy0*dy1); + d = radius / nvg__tanf(a/2.0f); + +// printf("a=%f° d=%f\n", a/NVG_PI*180.0f, d); + + if (d > 10000.0f) { + nvgLineTo(ctx, x1,y1); + return; + } + + if (nvg__cross(dx0,dy0, dx1,dy1) > 0.0f) { + cx = x1 + dx0*d + dy0*radius; + cy = y1 + dy0*d + -dx0*radius; + a0 = nvg__atan2f(dx0, -dy0); + a1 = nvg__atan2f(-dx1, dy1); + dir = NVG_CW; +// printf("CW c=(%f, %f) a0=%f° a1=%f°\n", cx, cy, a0/NVG_PI*180.0f, a1/NVG_PI*180.0f); + } else { + cx = x1 + dx0*d + -dy0*radius; + cy = y1 + dy0*d + dx0*radius; + a0 = nvg__atan2f(-dx0, dy0); + a1 = nvg__atan2f(dx1, -dy1); + dir = NVG_CCW; +// printf("CCW c=(%f, %f) a0=%f° a1=%f°\n", cx, cy, a0/NVG_PI*180.0f, a1/NVG_PI*180.0f); + } + + nvgArc(ctx, cx, cy, radius, a0, a1, dir); +} + +void nvgClosePath(NVGcontext* ctx) +{ + float vals[] = { NVG_CLOSE }; + nvg__appendCommands(ctx, vals, NVG_COUNTOF(vals)); +} + +void nvgPathWinding(NVGcontext* ctx, int dir) +{ + float vals[] = { NVG_WINDING, (float)dir }; + nvg__appendCommands(ctx, vals, NVG_COUNTOF(vals)); +} + +void nvgArc(NVGcontext* ctx, float cx, float cy, float r, float a0, float a1, int dir) +{ + float a = 0, da = 0, hda = 0, kappa = 0; + float dx = 0, dy = 0, x = 0, y = 0, tanx = 0, tany = 0; + float px = 0, py = 0, ptanx = 0, ptany = 0; + float vals[3 + 5*7 + 100]; + int i, ndivs, nvals; + int move = ctx->ncommands > 0 ? NVG_LINETO : NVG_MOVETO; + + // Clamp angles + da = a1 - a0; + if (dir == NVG_CW) { + if (nvg__absf(da) >= NVG_PI*2) { + da = NVG_PI*2; + } else { + while (da < 0.0f) da += NVG_PI*2; + } + } else { + if (nvg__absf(da) >= NVG_PI*2) { + da = -NVG_PI*2; + } else { + while (da > 0.0f) da -= NVG_PI*2; + } + } + + // Split arc into max 90 degree segments. + ndivs = nvg__maxi(1, nvg__mini((int)(nvg__absf(da) / (NVG_PI*0.5f) + 0.5f), 5)); + hda = (da / (float)ndivs) / 2.0f; + kappa = nvg__absf(4.0f / 3.0f * (1.0f - nvg__cosf(hda)) / nvg__sinf(hda)); + + if (dir == NVG_CCW) + kappa = -kappa; + + nvals = 0; + for (i = 0; i <= ndivs; i++) { + a = a0 + da * (i/(float)ndivs); + dx = nvg__cosf(a); + dy = nvg__sinf(a); + x = cx + dx*r; + y = cy + dy*r; + tanx = -dy*r*kappa; + tany = dx*r*kappa; + + if (i == 0) { + vals[nvals++] = (float)move; + vals[nvals++] = x; + vals[nvals++] = y; + } else { + vals[nvals++] = NVG_BEZIERTO; + vals[nvals++] = px+ptanx; + vals[nvals++] = py+ptany; + vals[nvals++] = x-tanx; + vals[nvals++] = y-tany; + vals[nvals++] = x; + vals[nvals++] = y; + } + px = x; + py = y; + ptanx = tanx; + ptany = tany; + } + + nvg__appendCommands(ctx, vals, nvals); +} + +void nvgRect(NVGcontext* ctx, float x, float y, float w, float h) +{ + float vals[] = { + NVG_MOVETO, x,y, + NVG_LINETO, x,y+h, + NVG_LINETO, x+w,y+h, + NVG_LINETO, x+w,y, + NVG_CLOSE + }; + nvg__appendCommands(ctx, vals, NVG_COUNTOF(vals)); +} + +void nvgRoundedRect(NVGcontext* ctx, float x, float y, float w, float h, float r) +{ + nvgRoundedRectVarying(ctx, x, y, w, h, r, r, r, r); +} + +void nvgRoundedRectVarying(NVGcontext* ctx, float x, float y, float w, float h, float radTopLeft, float radTopRight, float radBottomRight, float radBottomLeft) +{ + if(radTopLeft < 0.1f && radTopRight < 0.1f && radBottomRight < 0.1f && radBottomLeft < 0.1f) { + nvgRect(ctx, x, y, w, h); + return; + } else { + float halfw = nvg__absf(w)*0.5f; + float halfh = nvg__absf(h)*0.5f; + float rxBL = nvg__minf(radBottomLeft, halfw) * nvg__signf(w), ryBL = nvg__minf(radBottomLeft, halfh) * nvg__signf(h); + float rxBR = nvg__minf(radBottomRight, halfw) * nvg__signf(w), ryBR = nvg__minf(radBottomRight, halfh) * nvg__signf(h); + float rxTR = nvg__minf(radTopRight, halfw) * nvg__signf(w), ryTR = nvg__minf(radTopRight, halfh) * nvg__signf(h); + float rxTL = nvg__minf(radTopLeft, halfw) * nvg__signf(w), ryTL = nvg__minf(radTopLeft, halfh) * nvg__signf(h); + float vals[] = { + NVG_MOVETO, x, y + ryTL, + NVG_LINETO, x, y + h - ryBL, + NVG_BEZIERTO, x, y + h - ryBL*(1 - NVG_KAPPA90), x + rxBL*(1 - NVG_KAPPA90), y + h, x + rxBL, y + h, + NVG_LINETO, x + w - rxBR, y + h, + NVG_BEZIERTO, x + w - rxBR*(1 - NVG_KAPPA90), y + h, x + w, y + h - ryBR*(1 - NVG_KAPPA90), x + w, y + h - ryBR, + NVG_LINETO, x + w, y + ryTR, + NVG_BEZIERTO, x + w, y + ryTR*(1 - NVG_KAPPA90), x + w - rxTR*(1 - NVG_KAPPA90), y, x + w - rxTR, y, + NVG_LINETO, x + rxTL, y, + NVG_BEZIERTO, x + rxTL*(1 - NVG_KAPPA90), y, x, y + ryTL*(1 - NVG_KAPPA90), x, y + ryTL, + NVG_CLOSE + }; + nvg__appendCommands(ctx, vals, NVG_COUNTOF(vals)); + } +} + +void nvgEllipse(NVGcontext* ctx, float cx, float cy, float rx, float ry) +{ + float vals[] = { + NVG_MOVETO, cx-rx, cy, + NVG_BEZIERTO, cx-rx, cy+ry*NVG_KAPPA90, cx-rx*NVG_KAPPA90, cy+ry, cx, cy+ry, + NVG_BEZIERTO, cx+rx*NVG_KAPPA90, cy+ry, cx+rx, cy+ry*NVG_KAPPA90, cx+rx, cy, + NVG_BEZIERTO, cx+rx, cy-ry*NVG_KAPPA90, cx+rx*NVG_KAPPA90, cy-ry, cx, cy-ry, + NVG_BEZIERTO, cx-rx*NVG_KAPPA90, cy-ry, cx-rx, cy-ry*NVG_KAPPA90, cx-rx, cy, + NVG_CLOSE + }; + nvg__appendCommands(ctx, vals, NVG_COUNTOF(vals)); +} + +void nvgCircle(NVGcontext* ctx, float cx, float cy, float r) +{ + nvgEllipse(ctx, cx,cy, r,r); +} + +void nvgDebugDumpPathCache(NVGcontext* ctx) +{ + const NVGpath* path; + int i, j; + + printf("Dumping %d cached paths\n", ctx->cache->npaths); + for (i = 0; i < ctx->cache->npaths; i++) { + path = &ctx->cache->paths[i]; + printf(" - Path %d\n", i); + if (path->nfill) { + printf(" - fill: %d\n", path->nfill); + for (j = 0; j < path->nfill; j++) + printf("%f\t%f\n", path->fill[j].x, path->fill[j].y); + } + if (path->nstroke) { + printf(" - stroke: %d\n", path->nstroke); + for (j = 0; j < path->nstroke; j++) + printf("%f\t%f\n", path->stroke[j].x, path->stroke[j].y); + } + } +} + +void nvgFill(NVGcontext* ctx) +{ + NVGstate* state = nvg__getState(ctx); + const NVGpath* path; + NVGpaint fillPaint = state->fill; + int i; + + nvg__flattenPaths(ctx); + if (ctx->params.edgeAntiAlias) + nvg__expandFill(ctx, ctx->fringeWidth, NVG_MITER, 2.4f); + else + nvg__expandFill(ctx, 0.0f, NVG_MITER, 2.4f); + + // Apply global alpha + fillPaint.innerColor.a *= state->alpha; + fillPaint.outerColor.a *= state->alpha; + + ctx->params.renderFill(ctx->params.userPtr, &fillPaint, &state->scissor, ctx->fringeWidth, + ctx->cache->bounds, ctx->cache->paths, ctx->cache->npaths); + + // Count triangles + for (i = 0; i < ctx->cache->npaths; i++) { + path = &ctx->cache->paths[i]; + ctx->fillTriCount += path->nfill-2; + ctx->fillTriCount += path->nstroke-2; + ctx->drawCallCount += 2; + } +} + +void nvgStroke(NVGcontext* ctx) +{ + NVGstate* state = nvg__getState(ctx); + float scale = nvg__getAverageScale(state->xform); + float strokeWidth = nvg__clampf(state->strokeWidth * scale, 0.0f, 200.0f); + NVGpaint strokePaint = state->stroke; + const NVGpath* path; + int i; + + if (strokeWidth < ctx->fringeWidth) { + // If the stroke width is less than pixel size, use alpha to emulate coverage. + // Since coverage is area, scale by alpha*alpha. + float alpha = nvg__clampf(strokeWidth / ctx->fringeWidth, 0.0f, 1.0f); + strokePaint.innerColor.a *= alpha*alpha; + strokePaint.outerColor.a *= alpha*alpha; + strokeWidth = ctx->fringeWidth; + } + + // Apply global alpha + strokePaint.innerColor.a *= state->alpha; + strokePaint.outerColor.a *= state->alpha; + + nvg__flattenPaths(ctx); + + if (ctx->params.edgeAntiAlias) + nvg__expandStroke(ctx, strokeWidth*0.5f + ctx->fringeWidth*0.5f, state->lineCap, state->lineJoin, state->miterLimit); + else + nvg__expandStroke(ctx, strokeWidth*0.5f, state->lineCap, state->lineJoin, state->miterLimit); + + ctx->params.renderStroke(ctx->params.userPtr, &strokePaint, &state->scissor, ctx->fringeWidth, + strokeWidth, ctx->cache->paths, ctx->cache->npaths); + + // Count triangles + for (i = 0; i < ctx->cache->npaths; i++) { + path = &ctx->cache->paths[i]; + ctx->strokeTriCount += path->nstroke-2; + ctx->drawCallCount++; + } +} + +// Add fonts +int nvgCreateFont(NVGcontext* ctx, const char* name, const char* path) +{ + return fonsAddFont(ctx->fs, name, path); +} + +int nvgCreateFontMem(NVGcontext* ctx, const char* name, unsigned char* data, int ndata, int freeData) +{ + return fonsAddFontMem(ctx->fs, name, data, ndata, freeData); +} + +int nvgFindFont(NVGcontext* ctx, const char* name) +{ + if (name == NULL) return -1; + return fonsGetFontByName(ctx->fs, name); +} + + +int nvgAddFallbackFontId(NVGcontext* ctx, int baseFont, int fallbackFont) +{ + if(baseFont == -1 || fallbackFont == -1) return 0; + return fonsAddFallbackFont(ctx->fs, baseFont, fallbackFont); +} + +int nvgAddFallbackFont(NVGcontext* ctx, const char* baseFont, const char* fallbackFont) +{ + return nvgAddFallbackFontId(ctx, nvgFindFont(ctx, baseFont), nvgFindFont(ctx, fallbackFont)); +} + +// State setting +void nvgFontSize(NVGcontext* ctx, float size) +{ + NVGstate* state = nvg__getState(ctx); + state->fontSize = size; +} + +void nvgFontBlur(NVGcontext* ctx, float blur) +{ + NVGstate* state = nvg__getState(ctx); + state->fontBlur = blur; +} + +void nvgTextLetterSpacing(NVGcontext* ctx, float spacing) +{ + NVGstate* state = nvg__getState(ctx); + state->letterSpacing = spacing; +} + +void nvgTextLineHeight(NVGcontext* ctx, float lineHeight) +{ + NVGstate* state = nvg__getState(ctx); + state->lineHeight = lineHeight; +} + +void nvgTextAlign(NVGcontext* ctx, int align) +{ + NVGstate* state = nvg__getState(ctx); + state->textAlign = align; +} + +void nvgFontFaceId(NVGcontext* ctx, int font) +{ + NVGstate* state = nvg__getState(ctx); + state->fontId = font; +} + +void nvgFontFace(NVGcontext* ctx, const char* font) +{ + NVGstate* state = nvg__getState(ctx); + state->fontId = fonsGetFontByName(ctx->fs, font); +} + +static float nvg__quantize(float a, float d) +{ + return ((int)(a / d + 0.5f)) * d; +} + +static float nvg__getFontScale(NVGstate* state) +{ + return nvg__minf(nvg__quantize(nvg__getAverageScale(state->xform), 0.01f), 4.0f); +} + +static void nvg__flushTextTexture(NVGcontext* ctx) +{ + int dirty[4]; + + if (fonsValidateTexture(ctx->fs, dirty)) { + int fontImage = ctx->fontImages[ctx->fontImageIdx]; + // Update texture + if (fontImage != 0) { + int iw, ih; + const unsigned char* data = fonsGetTextureData(ctx->fs, &iw, &ih); + int x = dirty[0]; + int y = dirty[1]; + int w = dirty[2] - dirty[0]; + int h = dirty[3] - dirty[1]; + ctx->params.renderUpdateTexture(ctx->params.userPtr, fontImage, x,y, w,h, data); + } + } +} + +static int nvg__allocTextAtlas(NVGcontext* ctx) +{ + int iw, ih; + nvg__flushTextTexture(ctx); + if (ctx->fontImageIdx >= NVG_MAX_FONTIMAGES-1) + return 0; + // if next fontImage already have a texture + if (ctx->fontImages[ctx->fontImageIdx+1] != 0) + nvgImageSize(ctx, ctx->fontImages[ctx->fontImageIdx+1], &iw, &ih); + else { // calculate the new font image size and create it. + nvgImageSize(ctx, ctx->fontImages[ctx->fontImageIdx], &iw, &ih); + if (iw > ih) + ih *= 2; + else + iw *= 2; + if (iw > NVG_MAX_FONTIMAGE_SIZE || ih > NVG_MAX_FONTIMAGE_SIZE) + iw = ih = NVG_MAX_FONTIMAGE_SIZE; + ctx->fontImages[ctx->fontImageIdx+1] = ctx->params.renderCreateTexture(ctx->params.userPtr, NVG_TEXTURE_ALPHA, iw, ih, 0, NULL); + } + ++ctx->fontImageIdx; + fonsResetAtlas(ctx->fs, iw, ih); + return 1; +} + +static void nvg__renderText(NVGcontext* ctx, NVGvertex* verts, int nverts) +{ + NVGstate* state = nvg__getState(ctx); + NVGpaint paint = state->fill; + + // Render triangles. + paint.image = ctx->fontImages[ctx->fontImageIdx]; + + // Apply global alpha + paint.innerColor.a *= state->alpha; + paint.outerColor.a *= state->alpha; + + ctx->params.renderTriangles(ctx->params.userPtr, &paint, &state->scissor, verts, nverts); + + ctx->drawCallCount++; + ctx->textTriCount += nverts/3; +} + +float nvgText(NVGcontext* ctx, float x, float y, const char* string, const char* end) +{ + NVGstate* state = nvg__getState(ctx); + FONStextIter iter, prevIter; + FONSquad q; + NVGvertex* verts; + float scale = nvg__getFontScale(state) * ctx->devicePxRatio; + float invscale = 1.0f / scale; + int cverts = 0; + int nverts = 0; + + if (end == NULL) + end = string + strlen(string); + + if (state->fontId == FONS_INVALID) return x; + + fonsSetSize(ctx->fs, state->fontSize*scale); + fonsSetSpacing(ctx->fs, state->letterSpacing*scale); + fonsSetBlur(ctx->fs, state->fontBlur*scale); + fonsSetAlign(ctx->fs, state->textAlign); + fonsSetFont(ctx->fs, state->fontId); + + cverts = nvg__maxi(2, (int)(end - string)) * 6; // conservative estimate. + verts = nvg__allocTempVerts(ctx, cverts); + if (verts == NULL) return x; + + fonsTextIterInit(ctx->fs, &iter, x*scale, y*scale, string, end); + prevIter = iter; + while (fonsTextIterNext(ctx->fs, &iter, &q)) { + float c[4*2]; + if (iter.prevGlyphIndex == -1) { // can not retrieve glyph? + if (!nvg__allocTextAtlas(ctx)) + break; // no memory :( + if (nverts != 0) { + nvg__renderText(ctx, verts, nverts); + nverts = 0; + } + iter = prevIter; + fonsTextIterNext(ctx->fs, &iter, &q); // try again + if (iter.prevGlyphIndex == -1) // still can not find glyph? + break; + } + prevIter = iter; + // Transform corners. + nvgTransformPoint(&c[0],&c[1], state->xform, q.x0*invscale, q.y0*invscale); + nvgTransformPoint(&c[2],&c[3], state->xform, q.x1*invscale, q.y0*invscale); + nvgTransformPoint(&c[4],&c[5], state->xform, q.x1*invscale, q.y1*invscale); + nvgTransformPoint(&c[6],&c[7], state->xform, q.x0*invscale, q.y1*invscale); + // Create triangles + if (nverts+6 <= cverts) { + nvg__vset(&verts[nverts], c[0], c[1], q.s0, q.t0); nverts++; + nvg__vset(&verts[nverts], c[4], c[5], q.s1, q.t1); nverts++; + nvg__vset(&verts[nverts], c[2], c[3], q.s1, q.t0); nverts++; + nvg__vset(&verts[nverts], c[0], c[1], q.s0, q.t0); nverts++; + nvg__vset(&verts[nverts], c[6], c[7], q.s0, q.t1); nverts++; + nvg__vset(&verts[nverts], c[4], c[5], q.s1, q.t1); nverts++; + } + } + + // TODO: add back-end bit to do this just once per frame. + nvg__flushTextTexture(ctx); + + nvg__renderText(ctx, verts, nverts); + + return iter.x; +} + +void nvgTextBox(NVGcontext* ctx, float x, float y, float breakRowWidth, const char* string, const char* end) +{ + NVGstate* state = nvg__getState(ctx); + NVGtextRow rows[2]; + int nrows = 0, i; + int oldAlign = state->textAlign; + int haling = state->textAlign & (NVG_ALIGN_LEFT | NVG_ALIGN_CENTER | NVG_ALIGN_RIGHT); + int valign = state->textAlign & (NVG_ALIGN_TOP | NVG_ALIGN_MIDDLE | NVG_ALIGN_BOTTOM | NVG_ALIGN_BASELINE); + float lineh = 0; + + if (state->fontId == FONS_INVALID) return; + + nvgTextMetrics(ctx, NULL, NULL, &lineh); + + state->textAlign = NVG_ALIGN_LEFT | valign; + + while ((nrows = nvgTextBreakLines(ctx, string, end, breakRowWidth, rows, 2))) { + for (i = 0; i < nrows; i++) { + NVGtextRow* row = &rows[i]; + if (haling & NVG_ALIGN_LEFT) + nvgText(ctx, x, y, row->start, row->end); + else if (haling & NVG_ALIGN_CENTER) + nvgText(ctx, x + breakRowWidth*0.5f - row->width*0.5f, y, row->start, row->end); + else if (haling & NVG_ALIGN_RIGHT) + nvgText(ctx, x + breakRowWidth - row->width, y, row->start, row->end); + y += lineh * state->lineHeight; + } + string = rows[nrows-1].next; + } + + state->textAlign = oldAlign; +} + +int nvgTextGlyphPositions(NVGcontext* ctx, float x, float y, const char* string, const char* end, NVGglyphPosition* positions, int maxPositions) +{ + NVGstate* state = nvg__getState(ctx); + float scale = nvg__getFontScale(state) * ctx->devicePxRatio; + float invscale = 1.0f / scale; + FONStextIter iter, prevIter; + FONSquad q; + int npos = 0; + + if (state->fontId == FONS_INVALID) return 0; + + if (end == NULL) + end = string + strlen(string); + + if (string == end) + return 0; + + fonsSetSize(ctx->fs, state->fontSize*scale); + fonsSetSpacing(ctx->fs, state->letterSpacing*scale); + fonsSetBlur(ctx->fs, state->fontBlur*scale); + fonsSetAlign(ctx->fs, state->textAlign); + fonsSetFont(ctx->fs, state->fontId); + + fonsTextIterInit(ctx->fs, &iter, x*scale, y*scale, string, end); + prevIter = iter; + while (fonsTextIterNext(ctx->fs, &iter, &q)) { + if (iter.prevGlyphIndex < 0 && nvg__allocTextAtlas(ctx)) { // can not retrieve glyph? + iter = prevIter; + fonsTextIterNext(ctx->fs, &iter, &q); // try again + } + prevIter = iter; + positions[npos].str = iter.str; + positions[npos].x = iter.x * invscale; + positions[npos].minx = nvg__minf(iter.x, q.x0) * invscale; + positions[npos].maxx = nvg__maxf(iter.nextx, q.x1) * invscale; + npos++; + if (npos >= maxPositions) + break; + } + + return npos; +} + +enum NVGcodepointType { + NVG_SPACE, + NVG_NEWLINE, + NVG_CHAR, +}; + +int nvgTextBreakLines(NVGcontext* ctx, const char* string, const char* end, float breakRowWidth, NVGtextRow* rows, int maxRows) +{ + NVGstate* state = nvg__getState(ctx); + float scale = nvg__getFontScale(state) * ctx->devicePxRatio; + float invscale = 1.0f / scale; + FONStextIter iter, prevIter; + FONSquad q; + int nrows = 0; + float rowStartX = 0; + float rowWidth = 0; + float rowMinX = 0; + float rowMaxX = 0; + const char* rowStart = NULL; + const char* rowEnd = NULL; + const char* wordStart = NULL; + float wordStartX = 0; + float wordMinX = 0; + const char* breakEnd = NULL; + float breakWidth = 0; + float breakMaxX = 0; + int type = NVG_SPACE, ptype = NVG_SPACE; + unsigned int pcodepoint = 0; + + if (maxRows == 0) return 0; + if (state->fontId == FONS_INVALID) return 0; + + if (end == NULL) + end = string + strlen(string); + + if (string == end) return 0; + + fonsSetSize(ctx->fs, state->fontSize*scale); + fonsSetSpacing(ctx->fs, state->letterSpacing*scale); + fonsSetBlur(ctx->fs, state->fontBlur*scale); + fonsSetAlign(ctx->fs, state->textAlign); + fonsSetFont(ctx->fs, state->fontId); + + breakRowWidth *= scale; + + fonsTextIterInit(ctx->fs, &iter, 0, 0, string, end); + prevIter = iter; + while (fonsTextIterNext(ctx->fs, &iter, &q)) { + if (iter.prevGlyphIndex < 0 && nvg__allocTextAtlas(ctx)) { // can not retrieve glyph? + iter = prevIter; + fonsTextIterNext(ctx->fs, &iter, &q); // try again + } + prevIter = iter; + switch (iter.codepoint) { + case 9: // \t + case 11: // \v + case 12: // \f + case 32: // space + case 0x00a0: // NBSP + type = NVG_SPACE; + break; + case 10: // \n + type = pcodepoint == 13 ? NVG_SPACE : NVG_NEWLINE; + break; + case 13: // \r + type = pcodepoint == 10 ? NVG_SPACE : NVG_NEWLINE; + break; + case 0x0085: // NEL + type = NVG_NEWLINE; + break; + default: + type = NVG_CHAR; + break; + } + + if (type == NVG_NEWLINE) { + // Always handle new lines. + rows[nrows].start = rowStart != NULL ? rowStart : iter.str; + rows[nrows].end = rowEnd != NULL ? rowEnd : iter.str; + rows[nrows].width = rowWidth * invscale; + rows[nrows].minx = rowMinX * invscale; + rows[nrows].maxx = rowMaxX * invscale; + rows[nrows].next = iter.next; + nrows++; + if (nrows >= maxRows) + return nrows; + // Set null break point + breakEnd = rowStart; + breakWidth = 0.0; + breakMaxX = 0.0; + // Indicate to skip the white space at the beginning of the row. + rowStart = NULL; + rowEnd = NULL; + rowWidth = 0; + rowMinX = rowMaxX = 0; + } else { + if (rowStart == NULL) { + // Skip white space until the beginning of the line + if (type == NVG_CHAR) { + // The current char is the row so far + rowStartX = iter.x; + rowStart = iter.str; + rowEnd = iter.next; + rowWidth = iter.nextx - rowStartX; // q.x1 - rowStartX; + rowMinX = q.x0 - rowStartX; + rowMaxX = q.x1 - rowStartX; + wordStart = iter.str; + wordStartX = iter.x; + wordMinX = q.x0 - rowStartX; + // Set null break point + breakEnd = rowStart; + breakWidth = 0.0; + breakMaxX = 0.0; + } + } else { + float nextWidth = iter.nextx - rowStartX; + + // track last non-white space character + if (type == NVG_CHAR) { + rowEnd = iter.next; + rowWidth = iter.nextx - rowStartX; + rowMaxX = q.x1 - rowStartX; + } + // track last end of a word + if (ptype == NVG_CHAR && type == NVG_SPACE) { + breakEnd = iter.str; + breakWidth = rowWidth; + breakMaxX = rowMaxX; + } + // track last beginning of a word + if (ptype == NVG_SPACE && type == NVG_CHAR) { + wordStart = iter.str; + wordStartX = iter.x; + wordMinX = q.x0 - rowStartX; + } + + // Break to new line when a character is beyond break width. + if (type == NVG_CHAR && nextWidth > breakRowWidth) { + // The run length is too long, need to break to new line. + if (breakEnd == rowStart) { + // The current word is longer than the row length, just break it from here. + rows[nrows].start = rowStart; + rows[nrows].end = iter.str; + rows[nrows].width = rowWidth * invscale; + rows[nrows].minx = rowMinX * invscale; + rows[nrows].maxx = rowMaxX * invscale; + rows[nrows].next = iter.str; + nrows++; + if (nrows >= maxRows) + return nrows; + rowStartX = iter.x; + rowStart = iter.str; + rowEnd = iter.next; + rowWidth = iter.nextx - rowStartX; + rowMinX = q.x0 - rowStartX; + rowMaxX = q.x1 - rowStartX; + wordStart = iter.str; + wordStartX = iter.x; + wordMinX = q.x0 - rowStartX; + } else { + // Break the line from the end of the last word, and start new line from the beginning of the new. + rows[nrows].start = rowStart; + rows[nrows].end = breakEnd; + rows[nrows].width = breakWidth * invscale; + rows[nrows].minx = rowMinX * invscale; + rows[nrows].maxx = breakMaxX * invscale; + rows[nrows].next = wordStart; + nrows++; + if (nrows >= maxRows) + return nrows; + rowStartX = wordStartX; + rowStart = wordStart; + rowEnd = iter.next; + rowWidth = iter.nextx - rowStartX; + rowMinX = wordMinX; + rowMaxX = q.x1 - rowStartX; + // No change to the word start + } + // Set null break point + breakEnd = rowStart; + breakWidth = 0.0; + breakMaxX = 0.0; + } + } + } + + pcodepoint = iter.codepoint; + ptype = type; + } + + // Break the line from the end of the last word, and start new line from the beginning of the new. + if (rowStart != NULL) { + rows[nrows].start = rowStart; + rows[nrows].end = rowEnd; + rows[nrows].width = rowWidth * invscale; + rows[nrows].minx = rowMinX * invscale; + rows[nrows].maxx = rowMaxX * invscale; + rows[nrows].next = end; + nrows++; + } + + return nrows; +} + +float nvgTextBounds(NVGcontext* ctx, float x, float y, const char* string, const char* end, float* bounds) +{ + NVGstate* state = nvg__getState(ctx); + float scale = nvg__getFontScale(state) * ctx->devicePxRatio; + float invscale = 1.0f / scale; + float width; + + if (state->fontId == FONS_INVALID) return 0; + + fonsSetSize(ctx->fs, state->fontSize*scale); + fonsSetSpacing(ctx->fs, state->letterSpacing*scale); + fonsSetBlur(ctx->fs, state->fontBlur*scale); + fonsSetAlign(ctx->fs, state->textAlign); + fonsSetFont(ctx->fs, state->fontId); + + width = fonsTextBounds(ctx->fs, x*scale, y*scale, string, end, bounds); + if (bounds != NULL) { + // Use line bounds for height. + fonsLineBounds(ctx->fs, y*scale, &bounds[1], &bounds[3]); + bounds[0] *= invscale; + bounds[1] *= invscale; + bounds[2] *= invscale; + bounds[3] *= invscale; + } + return width * invscale; +} + +void nvgTextBoxBounds(NVGcontext* ctx, float x, float y, float breakRowWidth, const char* string, const char* end, float* bounds) +{ + NVGstate* state = nvg__getState(ctx); + NVGtextRow rows[2]; + float scale = nvg__getFontScale(state) * ctx->devicePxRatio; + float invscale = 1.0f / scale; + int nrows = 0, i; + int oldAlign = state->textAlign; + int haling = state->textAlign & (NVG_ALIGN_LEFT | NVG_ALIGN_CENTER | NVG_ALIGN_RIGHT); + int valign = state->textAlign & (NVG_ALIGN_TOP | NVG_ALIGN_MIDDLE | NVG_ALIGN_BOTTOM | NVG_ALIGN_BASELINE); + float lineh = 0, rminy = 0, rmaxy = 0; + float minx, miny, maxx, maxy; + + if (state->fontId == FONS_INVALID) { + if (bounds != NULL) + bounds[0] = bounds[1] = bounds[2] = bounds[3] = 0.0f; + return; + } + + nvgTextMetrics(ctx, NULL, NULL, &lineh); + + state->textAlign = NVG_ALIGN_LEFT | valign; + + minx = maxx = x; + miny = maxy = y; + + fonsSetSize(ctx->fs, state->fontSize*scale); + fonsSetSpacing(ctx->fs, state->letterSpacing*scale); + fonsSetBlur(ctx->fs, state->fontBlur*scale); + fonsSetAlign(ctx->fs, state->textAlign); + fonsSetFont(ctx->fs, state->fontId); + fonsLineBounds(ctx->fs, 0, &rminy, &rmaxy); + rminy *= invscale; + rmaxy *= invscale; + + while ((nrows = nvgTextBreakLines(ctx, string, end, breakRowWidth, rows, 2))) { + for (i = 0; i < nrows; i++) { + NVGtextRow* row = &rows[i]; + float rminx, rmaxx, dx = 0; + // Horizontal bounds + if (haling & NVG_ALIGN_LEFT) + dx = 0; + else if (haling & NVG_ALIGN_CENTER) + dx = breakRowWidth*0.5f - row->width*0.5f; + else if (haling & NVG_ALIGN_RIGHT) + dx = breakRowWidth - row->width; + rminx = x + row->minx + dx; + rmaxx = x + row->maxx + dx; + minx = nvg__minf(minx, rminx); + maxx = nvg__maxf(maxx, rmaxx); + // Vertical bounds. + miny = nvg__minf(miny, y + rminy); + maxy = nvg__maxf(maxy, y + rmaxy); + + y += lineh * state->lineHeight; + } + string = rows[nrows-1].next; + } + + state->textAlign = oldAlign; + + if (bounds != NULL) { + bounds[0] = minx; + bounds[1] = miny; + bounds[2] = maxx; + bounds[3] = maxy; + } +} + +void nvgTextMetrics(NVGcontext* ctx, float* ascender, float* descender, float* lineh) +{ + NVGstate* state = nvg__getState(ctx); + float scale = nvg__getFontScale(state) * ctx->devicePxRatio; + float invscale = 1.0f / scale; + + if (state->fontId == FONS_INVALID) return; + + fonsSetSize(ctx->fs, state->fontSize*scale); + fonsSetSpacing(ctx->fs, state->letterSpacing*scale); + fonsSetBlur(ctx->fs, state->fontBlur*scale); + fonsSetAlign(ctx->fs, state->textAlign); + fonsSetFont(ctx->fs, state->fontId); + + fonsVertMetrics(ctx->fs, ascender, descender, lineh); + if (ascender != NULL) + *ascender *= invscale; + if (descender != NULL) + *descender *= invscale; + if (lineh != NULL) + *lineh *= invscale; +} +// vim: ft=c nu noet ts=4 diff --git a/phonelibs/nanovg/nanovg.h b/phonelibs/nanovg/nanovg.h new file mode 100644 index 00000000000000..bb0d3417a286ce --- /dev/null +++ b/phonelibs/nanovg/nanovg.h @@ -0,0 +1,681 @@ +// +// Copyright (c) 2013 Mikko Mononen memon@inside.org +// +// 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 NANOVG_H +#define NANOVG_H + +#ifdef __cplusplus +extern "C" { +#endif + +#define NVG_PI 3.14159265358979323846264338327f + +#ifdef _MSC_VER +#pragma warning(push) +#pragma warning(disable: 4201) // nonstandard extension used : nameless struct/union +#endif + +typedef struct NVGcontext NVGcontext; + +struct NVGcolor { + union { + float rgba[4]; + struct { + float r,g,b,a; + }; + }; +}; +typedef struct NVGcolor NVGcolor; + +struct NVGpaint { + float xform[6]; + float extent[2]; + float radius; + float feather; + NVGcolor innerColor; + NVGcolor outerColor; + int image; +}; +typedef struct NVGpaint NVGpaint; + +enum NVGwinding { + NVG_CCW = 1, // Winding for solid shapes + NVG_CW = 2, // Winding for holes +}; + +enum NVGsolidity { + NVG_SOLID = 1, // CCW + NVG_HOLE = 2, // CW +}; + +enum NVGlineCap { + NVG_BUTT, + NVG_ROUND, + NVG_SQUARE, + NVG_BEVEL, + NVG_MITER, +}; + +enum NVGalign { + // Horizontal align + NVG_ALIGN_LEFT = 1<<0, // Default, align text horizontally to left. + NVG_ALIGN_CENTER = 1<<1, // Align text horizontally to center. + NVG_ALIGN_RIGHT = 1<<2, // Align text horizontally to right. + // Vertical align + NVG_ALIGN_TOP = 1<<3, // Align text vertically to top. + NVG_ALIGN_MIDDLE = 1<<4, // Align text vertically to middle. + NVG_ALIGN_BOTTOM = 1<<5, // Align text vertically to bottom. + NVG_ALIGN_BASELINE = 1<<6, // Default, align text vertically to baseline. +}; + +enum NVGblendFactor { + NVG_ZERO = 1<<0, + NVG_ONE = 1<<1, + NVG_SRC_COLOR = 1<<2, + NVG_ONE_MINUS_SRC_COLOR = 1<<3, + NVG_DST_COLOR = 1<<4, + NVG_ONE_MINUS_DST_COLOR = 1<<5, + NVG_SRC_ALPHA = 1<<6, + NVG_ONE_MINUS_SRC_ALPHA = 1<<7, + NVG_DST_ALPHA = 1<<8, + NVG_ONE_MINUS_DST_ALPHA = 1<<9, + NVG_SRC_ALPHA_SATURATE = 1<<10, +}; + +enum NVGcompositeOperation { + NVG_SOURCE_OVER, + NVG_SOURCE_IN, + NVG_SOURCE_OUT, + NVG_ATOP, + NVG_DESTINATION_OVER, + NVG_DESTINATION_IN, + NVG_DESTINATION_OUT, + NVG_DESTINATION_ATOP, + NVG_LIGHTER, + NVG_COPY, + NVG_XOR, +}; + +struct NVGcompositeOperationState { + int srcRGB; + int dstRGB; + int srcAlpha; + int dstAlpha; +}; +typedef struct NVGcompositeOperationState NVGcompositeOperationState; + +struct NVGglyphPosition { + const char* str; // Position of the glyph in the input string. + float x; // The x-coordinate of the logical glyph position. + float minx, maxx; // The bounds of the glyph shape. +}; +typedef struct NVGglyphPosition NVGglyphPosition; + +struct NVGtextRow { + const char* start; // Pointer to the input text where the row starts. + const char* end; // Pointer to the input text where the row ends (one past the last character). + const char* next; // Pointer to the beginning of the next row. + float width; // Logical width of the row. + float minx, maxx; // Actual bounds of the row. Logical with and bounds can differ because of kerning and some parts over extending. +}; +typedef struct NVGtextRow NVGtextRow; + +enum NVGimageFlags { + NVG_IMAGE_GENERATE_MIPMAPS = 1<<0, // Generate mipmaps during creation of the image. + NVG_IMAGE_REPEATX = 1<<1, // Repeat image in X direction. + NVG_IMAGE_REPEATY = 1<<2, // Repeat image in Y direction. + NVG_IMAGE_FLIPY = 1<<3, // Flips (inverses) image in Y direction when rendered. + NVG_IMAGE_PREMULTIPLIED = 1<<4, // Image data has premultiplied alpha. +}; + +// Begin drawing a new frame +// Calls to nanovg drawing API should be wrapped in nvgBeginFrame() & nvgEndFrame() +// nvgBeginFrame() defines the size of the window to render to in relation currently +// set viewport (i.e. glViewport on GL backends). Device pixel ration allows to +// control the rendering on Hi-DPI devices. +// For example, GLFW returns two dimension for an opened window: window size and +// frame buffer size. In that case you would set windowWidth/Height to the window size +// devicePixelRatio to: frameBufferWidth / windowWidth. +void nvgBeginFrame(NVGcontext* ctx, int windowWidth, int windowHeight, float devicePixelRatio); + +// Cancels drawing the current frame. +void nvgCancelFrame(NVGcontext* ctx); + +// Ends drawing flushing remaining render state. +void nvgEndFrame(NVGcontext* ctx); + +// +// Composite operation +// +// The composite operations in NanoVG are modeled after HTML Canvas API, and +// the blend func is based on OpenGL (see corresponding manuals for more info). +// The colors in the blending state have premultiplied alpha. + +// Sets the composite operation. The op parameter should be one of NVGcompositeOperation. +void nvgGlobalCompositeOperation(NVGcontext* ctx, int op); + +// Sets the composite operation with custom pixel arithmetic. The parameters should be one of NVGblendFactor. +void nvgGlobalCompositeBlendFunc(NVGcontext* ctx, int sfactor, int dfactor); + +// Sets the composite operation with custom pixel arithmetic for RGB and alpha components separately. The parameters should be one of NVGblendFactor. +void nvgGlobalCompositeBlendFuncSeparate(NVGcontext* ctx, int srcRGB, int dstRGB, int srcAlpha, int dstAlpha); + +// +// Color utils +// +// Colors in NanoVG are stored as unsigned ints in ABGR format. + +// Returns a color value from red, green, blue values. Alpha will be set to 255 (1.0f). +NVGcolor nvgRGB(unsigned char r, unsigned char g, unsigned char b); + +// Returns a color value from red, green, blue values. Alpha will be set to 1.0f. +NVGcolor nvgRGBf(float r, float g, float b); + + +// Returns a color value from red, green, blue and alpha values. +NVGcolor nvgRGBA(unsigned char r, unsigned char g, unsigned char b, unsigned char a); + +// Returns a color value from red, green, blue and alpha values. +NVGcolor nvgRGBAf(float r, float g, float b, float a); + + +// Linearly interpolates from color c0 to c1, and returns resulting color value. +NVGcolor nvgLerpRGBA(NVGcolor c0, NVGcolor c1, float u); + +// Sets transparency of a color value. +NVGcolor nvgTransRGBA(NVGcolor c0, unsigned char a); + +// Sets transparency of a color value. +NVGcolor nvgTransRGBAf(NVGcolor c0, float a); + +// Returns color value specified by hue, saturation and lightness. +// HSL values are all in range [0..1], alpha will be set to 255. +NVGcolor nvgHSL(float h, float s, float l); + +// Returns color value specified by hue, saturation and lightness and alpha. +// HSL values are all in range [0..1], alpha in range [0..255] +NVGcolor nvgHSLA(float h, float s, float l, unsigned char a); + +// +// State Handling +// +// NanoVG contains state which represents how paths will be rendered. +// The state contains transform, fill and stroke styles, text and font styles, +// and scissor clipping. + +// Pushes and saves the current render state into a state stack. +// A matching nvgRestore() must be used to restore the state. +void nvgSave(NVGcontext* ctx); + +// Pops and restores current render state. +void nvgRestore(NVGcontext* ctx); + +// Resets current render state to default values. Does not affect the render state stack. +void nvgReset(NVGcontext* ctx); + +// +// Render styles +// +// Fill and stroke render style can be either a solid color or a paint which is a gradient or a pattern. +// Solid color is simply defined as a color value, different kinds of paints can be created +// using nvgLinearGradient(), nvgBoxGradient(), nvgRadialGradient() and nvgImagePattern(). +// +// Current render style can be saved and restored using nvgSave() and nvgRestore(). + +// Sets current stroke style to a solid color. +void nvgStrokeColor(NVGcontext* ctx, NVGcolor color); + +// Sets current stroke style to a paint, which can be a one of the gradients or a pattern. +void nvgStrokePaint(NVGcontext* ctx, NVGpaint paint); + +// Sets current fill style to a solid color. +void nvgFillColor(NVGcontext* ctx, NVGcolor color); + +// Sets current fill style to a paint, which can be a one of the gradients or a pattern. +void nvgFillPaint(NVGcontext* ctx, NVGpaint paint); + +// Sets the miter limit of the stroke style. +// Miter limit controls when a sharp corner is beveled. +void nvgMiterLimit(NVGcontext* ctx, float limit); + +// Sets the stroke width of the stroke style. +void nvgStrokeWidth(NVGcontext* ctx, float size); + +// Sets how the end of the line (cap) is drawn, +// Can be one of: NVG_BUTT (default), NVG_ROUND, NVG_SQUARE. +void nvgLineCap(NVGcontext* ctx, int cap); + +// Sets how sharp path corners are drawn. +// Can be one of NVG_MITER (default), NVG_ROUND, NVG_BEVEL. +void nvgLineJoin(NVGcontext* ctx, int join); + +// Sets the transparency applied to all rendered shapes. +// Already transparent paths will get proportionally more transparent as well. +void nvgGlobalAlpha(NVGcontext* ctx, float alpha); + +// +// Transforms +// +// The paths, gradients, patterns and scissor region are transformed by an transformation +// matrix at the time when they are passed to the API. +// The current transformation matrix is a affine matrix: +// [sx kx tx] +// [ky sy ty] +// [ 0 0 1] +// Where: sx,sy define scaling, kx,ky skewing, and tx,ty translation. +// The last row is assumed to be 0,0,1 and is not stored. +// +// Apart from nvgResetTransform(), each transformation function first creates +// specific transformation matrix and pre-multiplies the current transformation by it. +// +// Current coordinate system (transformation) can be saved and restored using nvgSave() and nvgRestore(). + +// Resets current transform to a identity matrix. +void nvgResetTransform(NVGcontext* ctx); + +// Premultiplies current coordinate system by specified matrix. +// The parameters are interpreted as matrix as follows: +// [a c e] +// [b d f] +// [0 0 1] +void nvgTransform(NVGcontext* ctx, float a, float b, float c, float d, float e, float f); + +// Translates current coordinate system. +void nvgTranslate(NVGcontext* ctx, float x, float y); + +// Rotates current coordinate system. Angle is specified in radians. +void nvgRotate(NVGcontext* ctx, float angle); + +// Skews the current coordinate system along X axis. Angle is specified in radians. +void nvgSkewX(NVGcontext* ctx, float angle); + +// Skews the current coordinate system along Y axis. Angle is specified in radians. +void nvgSkewY(NVGcontext* ctx, float angle); + +// Scales the current coordinate system. +void nvgScale(NVGcontext* ctx, float x, float y); + +// Stores the top part (a-f) of the current transformation matrix in to the specified buffer. +// [a c e] +// [b d f] +// [0 0 1] +// There should be space for 6 floats in the return buffer for the values a-f. +void nvgCurrentTransform(NVGcontext* ctx, float* xform); + + +// The following functions can be used to make calculations on 2x3 transformation matrices. +// A 2x3 matrix is represented as float[6]. + +// Sets the transform to identity matrix. +void nvgTransformIdentity(float* dst); + +// Sets the transform to translation matrix matrix. +void nvgTransformTranslate(float* dst, float tx, float ty); + +// Sets the transform to scale matrix. +void nvgTransformScale(float* dst, float sx, float sy); + +// Sets the transform to rotate matrix. Angle is specified in radians. +void nvgTransformRotate(float* dst, float a); + +// Sets the transform to skew-x matrix. Angle is specified in radians. +void nvgTransformSkewX(float* dst, float a); + +// Sets the transform to skew-y matrix. Angle is specified in radians. +void nvgTransformSkewY(float* dst, float a); + +// Sets the transform to the result of multiplication of two transforms, of A = A*B. +void nvgTransformMultiply(float* dst, const float* src); + +// Sets the transform to the result of multiplication of two transforms, of A = B*A. +void nvgTransformPremultiply(float* dst, const float* src); + +// Sets the destination to inverse of specified transform. +// Returns 1 if the inverse could be calculated, else 0. +int nvgTransformInverse(float* dst, const float* src); + +// Transform a point by given transform. +void nvgTransformPoint(float* dstx, float* dsty, const float* xform, float srcx, float srcy); + +// Converts degrees to radians and vice versa. +float nvgDegToRad(float deg); +float nvgRadToDeg(float rad); + +// +// Images +// +// NanoVG allows you to load jpg, png, psd, tga, pic and gif files to be used for rendering. +// In addition you can upload your own image. The image loading is provided by stb_image. +// The parameter imageFlags is combination of flags defined in NVGimageFlags. + +// Creates image by loading it from the disk from specified file name. +// Returns handle to the image. +int nvgCreateImage(NVGcontext* ctx, const char* filename, int imageFlags); + +// Creates image by loading it from the specified chunk of memory. +// Returns handle to the image. +int nvgCreateImageMem(NVGcontext* ctx, int imageFlags, unsigned char* data, int ndata); + +// Creates image from specified image data. +// Returns handle to the image. +int nvgCreateImageRGBA(NVGcontext* ctx, int w, int h, int imageFlags, const unsigned char* data); + +// Updates image data specified by image handle. +void nvgUpdateImage(NVGcontext* ctx, int image, const unsigned char* data); + +// Returns the dimensions of a created image. +void nvgImageSize(NVGcontext* ctx, int image, int* w, int* h); + +// Deletes created image. +void nvgDeleteImage(NVGcontext* ctx, int image); + +// +// Paints +// +// NanoVG supports four types of paints: linear gradient, box gradient, radial gradient and image pattern. +// These can be used as paints for strokes and fills. + +// Creates and returns a linear gradient. Parameters (sx,sy)-(ex,ey) specify the start and end coordinates +// of the linear gradient, icol specifies the start color and ocol the end color. +// The gradient is transformed by the current transform when it is passed to nvgFillPaint() or nvgStrokePaint(). +NVGpaint nvgLinearGradient(NVGcontext* ctx, float sx, float sy, float ex, float ey, + NVGcolor icol, NVGcolor ocol); + +// Creates and returns a box gradient. Box gradient is a feathered rounded rectangle, it is useful for rendering +// drop shadows or highlights for boxes. Parameters (x,y) define the top-left corner of the rectangle, +// (w,h) define the size of the rectangle, r defines the corner radius, and f feather. Feather defines how blurry +// the border of the rectangle is. Parameter icol specifies the inner color and ocol the outer color of the gradient. +// The gradient is transformed by the current transform when it is passed to nvgFillPaint() or nvgStrokePaint(). +NVGpaint nvgBoxGradient(NVGcontext* ctx, float x, float y, float w, float h, + float r, float f, NVGcolor icol, NVGcolor ocol); + +// Creates and returns a radial gradient. Parameters (cx,cy) specify the center, inr and outr specify +// the inner and outer radius of the gradient, icol specifies the start color and ocol the end color. +// The gradient is transformed by the current transform when it is passed to nvgFillPaint() or nvgStrokePaint(). +NVGpaint nvgRadialGradient(NVGcontext* ctx, float cx, float cy, float inr, float outr, + NVGcolor icol, NVGcolor ocol); + +// Creates and returns an image patter. Parameters (ox,oy) specify the left-top location of the image pattern, +// (ex,ey) the size of one image, angle rotation around the top-left corner, image is handle to the image to render. +// The gradient is transformed by the current transform when it is passed to nvgFillPaint() or nvgStrokePaint(). +NVGpaint nvgImagePattern(NVGcontext* ctx, float ox, float oy, float ex, float ey, + float angle, int image, float alpha); + +// +// Scissoring +// +// Scissoring allows you to clip the rendering into a rectangle. This is useful for various +// user interface cases like rendering a text edit or a timeline. + +// Sets the current scissor rectangle. +// The scissor rectangle is transformed by the current transform. +void nvgScissor(NVGcontext* ctx, float x, float y, float w, float h); + +// Intersects current scissor rectangle with the specified rectangle. +// The scissor rectangle is transformed by the current transform. +// Note: in case the rotation of previous scissor rect differs from +// the current one, the intersection will be done between the specified +// rectangle and the previous scissor rectangle transformed in the current +// transform space. The resulting shape is always rectangle. +void nvgIntersectScissor(NVGcontext* ctx, float x, float y, float w, float h); + +// Reset and disables scissoring. +void nvgResetScissor(NVGcontext* ctx); + +// +// Paths +// +// Drawing a new shape starts with nvgBeginPath(), it clears all the currently defined paths. +// Then you define one or more paths and sub-paths which describe the shape. The are functions +// to draw common shapes like rectangles and circles, and lower level step-by-step functions, +// which allow to define a path curve by curve. +// +// NanoVG uses even-odd fill rule to draw the shapes. Solid shapes should have counter clockwise +// winding and holes should have counter clockwise order. To specify winding of a path you can +// call nvgPathWinding(). This is useful especially for the common shapes, which are drawn CCW. +// +// Finally you can fill the path using current fill style by calling nvgFill(), and stroke it +// with current stroke style by calling nvgStroke(). +// +// The curve segments and sub-paths are transformed by the current transform. + +// Clears the current path and sub-paths. +void nvgBeginPath(NVGcontext* ctx); + +// Starts new sub-path with specified point as first point. +void nvgMoveTo(NVGcontext* ctx, float x, float y); + +// Adds line segment from the last point in the path to the specified point. +void nvgLineTo(NVGcontext* ctx, float x, float y); + +// Adds cubic bezier segment from last point in the path via two control points to the specified point. +void nvgBezierTo(NVGcontext* ctx, float c1x, float c1y, float c2x, float c2y, float x, float y); + +// Adds quadratic bezier segment from last point in the path via a control point to the specified point. +void nvgQuadTo(NVGcontext* ctx, float cx, float cy, float x, float y); + +// Adds an arc segment at the corner defined by the last path point, and two specified points. +void nvgArcTo(NVGcontext* ctx, float x1, float y1, float x2, float y2, float radius); + +// Closes current sub-path with a line segment. +void nvgClosePath(NVGcontext* ctx); + +// Sets the current sub-path winding, see NVGwinding and NVGsolidity. +void nvgPathWinding(NVGcontext* ctx, int dir); + +// Creates new circle arc shaped sub-path. The arc center is at cx,cy, the arc radius is r, +// and the arc is drawn from angle a0 to a1, and swept in direction dir (NVG_CCW, or NVG_CW). +// Angles are specified in radians. +void nvgArc(NVGcontext* ctx, float cx, float cy, float r, float a0, float a1, int dir); + +// Creates new rectangle shaped sub-path. +void nvgRect(NVGcontext* ctx, float x, float y, float w, float h); + +// Creates new rounded rectangle shaped sub-path. +void nvgRoundedRect(NVGcontext* ctx, float x, float y, float w, float h, float r); + +// Creates new rounded rectangle shaped sub-path with varying radii for each corner. +void nvgRoundedRectVarying(NVGcontext* ctx, float x, float y, float w, float h, float radTopLeft, float radTopRight, float radBottomRight, float radBottomLeft); + +// Creates new ellipse shaped sub-path. +void nvgEllipse(NVGcontext* ctx, float cx, float cy, float rx, float ry); + +// Creates new circle shaped sub-path. +void nvgCircle(NVGcontext* ctx, float cx, float cy, float r); + +// Fills the current path with current fill style. +void nvgFill(NVGcontext* ctx); + +// Fills the current path with current stroke style. +void nvgStroke(NVGcontext* ctx); + + +// +// Text +// +// NanoVG allows you to load .ttf files and use the font to render text. +// +// The appearance of the text can be defined by setting the current text style +// and by specifying the fill color. Common text and font settings such as +// font size, letter spacing and text align are supported. Font blur allows you +// to create simple text effects such as drop shadows. +// +// At render time the font face can be set based on the font handles or name. +// +// Font measure functions return values in local space, the calculations are +// carried in the same resolution as the final rendering. This is done because +// the text glyph positions are snapped to the nearest pixels sharp rendering. +// +// The local space means that values are not rotated or scale as per the current +// transformation. For example if you set font size to 12, which would mean that +// line height is 16, then regardless of the current scaling and rotation, the +// returned line height is always 16. Some measures may vary because of the scaling +// since aforementioned pixel snapping. +// +// While this may sound a little odd, the setup allows you to always render the +// same way regardless of scaling. I.e. following works regardless of scaling: +// +// const char* txt = "Text me up."; +// nvgTextBounds(vg, x,y, txt, NULL, bounds); +// nvgBeginPath(vg); +// nvgRoundedRect(vg, bounds[0],bounds[1], bounds[2]-bounds[0], bounds[3]-bounds[1]); +// nvgFill(vg); +// +// Note: currently only solid color fill is supported for text. + +// Creates font by loading it from the disk from specified file name. +// Returns handle to the font. +int nvgCreateFont(NVGcontext* ctx, const char* name, const char* filename); + +// Creates font by loading it from the specified memory chunk. +// Returns handle to the font. +int nvgCreateFontMem(NVGcontext* ctx, const char* name, unsigned char* data, int ndata, int freeData); + +// Finds a loaded font of specified name, and returns handle to it, or -1 if the font is not found. +int nvgFindFont(NVGcontext* ctx, const char* name); + +// Adds a fallback font by handle. +int nvgAddFallbackFontId(NVGcontext* ctx, int baseFont, int fallbackFont); + +// Adds a fallback font by name. +int nvgAddFallbackFont(NVGcontext* ctx, const char* baseFont, const char* fallbackFont); + +// Sets the font size of current text style. +void nvgFontSize(NVGcontext* ctx, float size); + +// Sets the blur of current text style. +void nvgFontBlur(NVGcontext* ctx, float blur); + +// Sets the letter spacing of current text style. +void nvgTextLetterSpacing(NVGcontext* ctx, float spacing); + +// Sets the proportional line height of current text style. The line height is specified as multiple of font size. +void nvgTextLineHeight(NVGcontext* ctx, float lineHeight); + +// Sets the text align of current text style, see NVGalign for options. +void nvgTextAlign(NVGcontext* ctx, int align); + +// Sets the font face based on specified id of current text style. +void nvgFontFaceId(NVGcontext* ctx, int font); + +// Sets the font face based on specified name of current text style. +void nvgFontFace(NVGcontext* ctx, const char* font); + +// Draws text string at specified location. If end is specified only the sub-string up to the end is drawn. +float nvgText(NVGcontext* ctx, float x, float y, const char* string, const char* end); + +// Draws multi-line text string at specified location wrapped at the specified width. If end is specified only the sub-string up to the end is drawn. +// White space is stripped at the beginning of the rows, the text is split at word boundaries or when new-line characters are encountered. +// Words longer than the max width are slit at nearest character (i.e. no hyphenation). +void nvgTextBox(NVGcontext* ctx, float x, float y, float breakRowWidth, const char* string, const char* end); + +// Measures the specified text string. Parameter bounds should be a pointer to float[4], +// if the bounding box of the text should be returned. The bounds value are [xmin,ymin, xmax,ymax] +// Returns the horizontal advance of the measured text (i.e. where the next character should drawn). +// Measured values are returned in local coordinate space. +float nvgTextBounds(NVGcontext* ctx, float x, float y, const char* string, const char* end, float* bounds); + +// Measures the specified multi-text string. Parameter bounds should be a pointer to float[4], +// if the bounding box of the text should be returned. The bounds value are [xmin,ymin, xmax,ymax] +// Measured values are returned in local coordinate space. +void nvgTextBoxBounds(NVGcontext* ctx, float x, float y, float breakRowWidth, const char* string, const char* end, float* bounds); + +// Calculates the glyph x positions of the specified text. If end is specified only the sub-string will be used. +// Measured values are returned in local coordinate space. +int nvgTextGlyphPositions(NVGcontext* ctx, float x, float y, const char* string, const char* end, NVGglyphPosition* positions, int maxPositions); + +// Returns the vertical metrics based on the current text style. +// Measured values are returned in local coordinate space. +void nvgTextMetrics(NVGcontext* ctx, float* ascender, float* descender, float* lineh); + +// Breaks the specified text into lines. If end is specified only the sub-string will be used. +// White space is stripped at the beginning of the rows, the text is split at word boundaries or when new-line characters are encountered. +// Words longer than the max width are slit at nearest character (i.e. no hyphenation). +int nvgTextBreakLines(NVGcontext* ctx, const char* string, const char* end, float breakRowWidth, NVGtextRow* rows, int maxRows); + +// +// Internal Render API +// +enum NVGtexture { + NVG_TEXTURE_ALPHA = 0x01, + NVG_TEXTURE_RGBA = 0x02, +}; + +struct NVGscissor { + float xform[6]; + float extent[2]; +}; +typedef struct NVGscissor NVGscissor; + +struct NVGvertex { + float x,y,u,v; +}; +typedef struct NVGvertex NVGvertex; + +struct NVGpath { + int first; + int count; + unsigned char closed; + int nbevel; + NVGvertex* fill; + int nfill; + NVGvertex* stroke; + int nstroke; + int winding; + int convex; +}; +typedef struct NVGpath NVGpath; + +struct NVGparams { + void* userPtr; + int edgeAntiAlias; + int (*renderCreate)(void* uptr); + int (*renderCreateTexture)(void* uptr, int type, int w, int h, int imageFlags, const unsigned char* data); + int (*renderDeleteTexture)(void* uptr, int image); + int (*renderUpdateTexture)(void* uptr, int image, int x, int y, int w, int h, const unsigned char* data); + int (*renderGetTextureSize)(void* uptr, int image, int* w, int* h); + void (*renderViewport)(void* uptr, int width, int height, float devicePixelRatio); + void (*renderCancel)(void* uptr); + void (*renderFlush)(void* uptr, NVGcompositeOperationState compositeOperation); + void (*renderFill)(void* uptr, NVGpaint* paint, NVGscissor* scissor, float fringe, const float* bounds, const NVGpath* paths, int npaths); + void (*renderStroke)(void* uptr, NVGpaint* paint, NVGscissor* scissor, float fringe, float strokeWidth, const NVGpath* paths, int npaths); + void (*renderTriangles)(void* uptr, NVGpaint* paint, NVGscissor* scissor, const NVGvertex* verts, int nverts); + void (*renderDelete)(void* uptr); +}; +typedef struct NVGparams NVGparams; + +// Constructor and destructor, called by the render back-end. +NVGcontext* nvgCreateInternal(NVGparams* params); +void nvgDeleteInternal(NVGcontext* ctx); + +NVGparams* nvgInternalParams(NVGcontext* ctx); + +// Debug function to dump cached path data. +void nvgDebugDumpPathCache(NVGcontext* ctx); + +#ifdef _MSC_VER +#pragma warning(pop) +#endif + +#define NVG_NOTUSED(v) for (;;) { (void)(1 ? (void)0 : ( (void)(v) ) ); break; } + +#ifdef __cplusplus +} +#endif + +#endif // NANOVG_H diff --git a/phonelibs/nanovg/nanovg_gl.h b/phonelibs/nanovg/nanovg_gl.h new file mode 100644 index 00000000000000..c050067321993d --- /dev/null +++ b/phonelibs/nanovg/nanovg_gl.h @@ -0,0 +1,1592 @@ +// +// Copyright (c) 2009-2013 Mikko Mononen memon@inside.org +// +// 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 NANOVG_GL_H +#define NANOVG_GL_H + +#ifdef __cplusplus +extern "C" { +#endif + +// Create flags + +enum NVGcreateFlags { + // Flag indicating if geometry based anti-aliasing is used (may not be needed when using MSAA). + NVG_ANTIALIAS = 1<<0, + // Flag indicating if strokes should be drawn using stencil buffer. The rendering will be a little + // slower, but path overlaps (i.e. self-intersecting or sharp turns) will be drawn just once. + NVG_STENCIL_STROKES = 1<<1, + // Flag indicating that additional debug checks are done. + NVG_DEBUG = 1<<2, +}; + +#if defined NANOVG_GL2_IMPLEMENTATION +# define NANOVG_GL2 1 +# define NANOVG_GL_IMPLEMENTATION 1 +#elif defined NANOVG_GL3_IMPLEMENTATION +# define NANOVG_GL3 1 +# define NANOVG_GL_IMPLEMENTATION 1 +# define NANOVG_GL_USE_UNIFORMBUFFER 1 +#elif defined NANOVG_GLES2_IMPLEMENTATION +# define NANOVG_GLES2 1 +# define NANOVG_GL_IMPLEMENTATION 1 +#elif defined NANOVG_GLES3_IMPLEMENTATION +# define NANOVG_GLES3 1 +# define NANOVG_GL_IMPLEMENTATION 1 +#endif + +#define NANOVG_GL_USE_STATE_FILTER (1) + +// Creates NanoVG contexts for different OpenGL (ES) versions. +// Flags should be combination of the create flags above. + +#if defined NANOVG_GL2 + +NVGcontext* nvgCreateGL2(int flags); +void nvgDeleteGL2(NVGcontext* ctx); + +int nvglCreateImageFromHandleGL2(NVGcontext* ctx, GLuint textureId, int w, int h, int flags); +GLuint nvglImageHandleGL2(NVGcontext* ctx, int image); + +#endif + +#if defined NANOVG_GL3 + +NVGcontext* nvgCreateGL3(int flags); +void nvgDeleteGL3(NVGcontext* ctx); + +int nvglCreateImageFromHandleGL3(NVGcontext* ctx, GLuint textureId, int w, int h, int flags); +GLuint nvglImageHandleGL3(NVGcontext* ctx, int image); + +#endif + +#if defined NANOVG_GLES2 + +NVGcontext* nvgCreateGLES2(int flags); +void nvgDeleteGLES2(NVGcontext* ctx); + +int nvglCreateImageFromHandleGLES2(NVGcontext* ctx, GLuint textureId, int w, int h, int flags); +GLuint nvglImageHandleGLES2(NVGcontext* ctx, int image); + +#endif + +#if defined NANOVG_GLES3 + +NVGcontext* nvgCreateGLES3(int flags); +void nvgDeleteGLES3(NVGcontext* ctx); + +int nvglCreateImageFromHandleGLES3(NVGcontext* ctx, GLuint textureId, int w, int h, int flags); +GLuint nvglImageHandleGLES3(NVGcontext* ctx, int image); + +#endif + +// These are additional flags on top of NVGimageFlags. +enum NVGimageFlagsGL { + NVG_IMAGE_NODELETE = 1<<16, // Do not delete GL texture handle. +}; + +#ifdef __cplusplus +} +#endif + +#endif /* NANOVG_GL_H */ + +#ifdef NANOVG_GL_IMPLEMENTATION + +#include +#include +#include +#include +#include "nanovg.h" + +enum GLNVGuniformLoc { + GLNVG_LOC_VIEWSIZE, + GLNVG_LOC_TEX, + GLNVG_LOC_FRAG, + GLNVG_MAX_LOCS +}; + +enum GLNVGshaderType { + NSVG_SHADER_FILLGRAD, + NSVG_SHADER_FILLIMG, + NSVG_SHADER_SIMPLE, + NSVG_SHADER_IMG +}; + +#if NANOVG_GL_USE_UNIFORMBUFFER +enum GLNVGuniformBindings { + GLNVG_FRAG_BINDING = 0, +}; +#endif + +struct GLNVGshader { + GLuint prog; + GLuint frag; + GLuint vert; + GLint loc[GLNVG_MAX_LOCS]; +}; +typedef struct GLNVGshader GLNVGshader; + +struct GLNVGtexture { + int id; + GLuint tex; + int width, height; + int type; + int flags; +}; +typedef struct GLNVGtexture GLNVGtexture; + +enum GLNVGcallType { + GLNVG_NONE = 0, + GLNVG_FILL, + GLNVG_CONVEXFILL, + GLNVG_STROKE, + GLNVG_TRIANGLES, +}; + +struct GLNVGcall { + int type; + int image; + int pathOffset; + int pathCount; + int triangleOffset; + int triangleCount; + int uniformOffset; +}; +typedef struct GLNVGcall GLNVGcall; + +struct GLNVGpath { + int fillOffset; + int fillCount; + int strokeOffset; + int strokeCount; +}; +typedef struct GLNVGpath GLNVGpath; + +struct GLNVGfragUniforms { + #if NANOVG_GL_USE_UNIFORMBUFFER + float scissorMat[12]; // matrices are actually 3 vec4s + float paintMat[12]; + struct NVGcolor innerCol; + struct NVGcolor outerCol; + float scissorExt[2]; + float scissorScale[2]; + float extent[2]; + float radius; + float feather; + float strokeMult; + float strokeThr; + int texType; + int type; + #else + // note: after modifying layout or size of uniform array, + // don't forget to also update the fragment shader source! + #define NANOVG_GL_UNIFORMARRAY_SIZE 11 + union { + struct { + float scissorMat[12]; // matrices are actually 3 vec4s + float paintMat[12]; + struct NVGcolor innerCol; + struct NVGcolor outerCol; + float scissorExt[2]; + float scissorScale[2]; + float extent[2]; + float radius; + float feather; + float strokeMult; + float strokeThr; + float texType; + float type; + }; + float uniformArray[NANOVG_GL_UNIFORMARRAY_SIZE][4]; + }; + #endif +}; +typedef struct GLNVGfragUniforms GLNVGfragUniforms; + +struct GLNVGcontext { + GLNVGshader shader; + GLNVGtexture* textures; + float view[2]; + int ntextures; + int ctextures; + int textureId; + GLuint vertBuf; +#if defined NANOVG_GL3 + GLuint vertArr; +#endif +#if NANOVG_GL_USE_UNIFORMBUFFER + GLuint fragBuf; +#endif + int fragSize; + int flags; + + // Per frame buffers + GLNVGcall* calls; + int ccalls; + int ncalls; + GLNVGpath* paths; + int cpaths; + int npaths; + struct NVGvertex* verts; + int cverts; + int nverts; + unsigned char* uniforms; + int cuniforms; + int nuniforms; + + // cached state + #if NANOVG_GL_USE_STATE_FILTER + GLuint boundTexture; + GLuint stencilMask; + GLenum stencilFunc; + GLint stencilFuncRef; + GLuint stencilFuncMask; + #endif +}; +typedef struct GLNVGcontext GLNVGcontext; + +static int glnvg__maxi(int a, int b) { return a > b ? a : b; } + +#ifdef NANOVG_GLES2 +static unsigned int glnvg__nearestPow2(unsigned int num) +{ + unsigned n = num > 0 ? num - 1 : 0; + n |= n >> 1; + n |= n >> 2; + n |= n >> 4; + n |= n >> 8; + n |= n >> 16; + n++; + return n; +} +#endif + +static void glnvg__bindTexture(GLNVGcontext* gl, GLuint tex) +{ +#if NANOVG_GL_USE_STATE_FILTER + if (gl->boundTexture != tex) { + gl->boundTexture = tex; + glBindTexture(GL_TEXTURE_2D, tex); + } +#else + glBindTexture(GL_TEXTURE_2D, tex); +#endif +} + +static void glnvg__stencilMask(GLNVGcontext* gl, GLuint mask) +{ +#if NANOVG_GL_USE_STATE_FILTER + if (gl->stencilMask != mask) { + gl->stencilMask = mask; + glStencilMask(mask); + } +#else + glStencilMask(mask); +#endif +} + +static void glnvg__stencilFunc(GLNVGcontext* gl, GLenum func, GLint ref, GLuint mask) +{ +#if NANOVG_GL_USE_STATE_FILTER + if ((gl->stencilFunc != func) || + (gl->stencilFuncRef != ref) || + (gl->stencilFuncMask != mask)) { + + gl->stencilFunc = func; + gl->stencilFuncRef = ref; + gl->stencilFuncMask = mask; + glStencilFunc(func, ref, mask); + } +#else + glStencilFunc(func, ref, mask); +#endif +} + +static GLNVGtexture* glnvg__allocTexture(GLNVGcontext* gl) +{ + GLNVGtexture* tex = NULL; + int i; + + for (i = 0; i < gl->ntextures; i++) { + if (gl->textures[i].id == 0) { + tex = &gl->textures[i]; + break; + } + } + if (tex == NULL) { + if (gl->ntextures+1 > gl->ctextures) { + GLNVGtexture* textures; + int ctextures = glnvg__maxi(gl->ntextures+1, 4) + gl->ctextures/2; // 1.5x Overallocate + textures = (GLNVGtexture*)realloc(gl->textures, sizeof(GLNVGtexture)*ctextures); + if (textures == NULL) return NULL; + gl->textures = textures; + gl->ctextures = ctextures; + } + tex = &gl->textures[gl->ntextures++]; + } + + memset(tex, 0, sizeof(*tex)); + tex->id = ++gl->textureId; + + return tex; +} + +static GLNVGtexture* glnvg__findTexture(GLNVGcontext* gl, int id) +{ + int i; + for (i = 0; i < gl->ntextures; i++) + if (gl->textures[i].id == id) + return &gl->textures[i]; + return NULL; +} + +static int glnvg__deleteTexture(GLNVGcontext* gl, int id) +{ + int i; + for (i = 0; i < gl->ntextures; i++) { + if (gl->textures[i].id == id) { + if (gl->textures[i].tex != 0 && (gl->textures[i].flags & NVG_IMAGE_NODELETE) == 0) + glDeleteTextures(1, &gl->textures[i].tex); + memset(&gl->textures[i], 0, sizeof(gl->textures[i])); + return 1; + } + } + return 0; +} + +static void glnvg__dumpShaderError(GLuint shader, const char* name, const char* type) +{ + GLchar str[512+1]; + GLsizei len = 0; + glGetShaderInfoLog(shader, 512, &len, str); + if (len > 512) len = 512; + str[len] = '\0'; + printf("Shader %s/%s error:\n%s\n", name, type, str); +} + +static void glnvg__dumpProgramError(GLuint prog, const char* name) +{ + GLchar str[512+1]; + GLsizei len = 0; + glGetProgramInfoLog(prog, 512, &len, str); + if (len > 512) len = 512; + str[len] = '\0'; + printf("Program %s error:\n%s\n", name, str); +} + +static void glnvg__checkError(GLNVGcontext* gl, const char* str) +{ + GLenum err; + if ((gl->flags & NVG_DEBUG) == 0) return; + err = glGetError(); + if (err != GL_NO_ERROR) { + printf("Error %08x after %s\n", err, str); + return; + } +} + +static int glnvg__createShader(GLNVGshader* shader, const char* name, const char* header, const char* opts, const char* vshader, const char* fshader) +{ + GLint status; + GLuint prog, vert, frag; + const char* str[3]; + str[0] = header; + str[1] = opts != NULL ? opts : ""; + + memset(shader, 0, sizeof(*shader)); + + prog = glCreateProgram(); + vert = glCreateShader(GL_VERTEX_SHADER); + frag = glCreateShader(GL_FRAGMENT_SHADER); + str[2] = vshader; + glShaderSource(vert, 3, str, 0); + str[2] = fshader; + glShaderSource(frag, 3, str, 0); + + glCompileShader(vert); + glGetShaderiv(vert, GL_COMPILE_STATUS, &status); + if (status != GL_TRUE) { + glnvg__dumpShaderError(vert, name, "vert"); + return 0; + } + + glCompileShader(frag); + glGetShaderiv(frag, GL_COMPILE_STATUS, &status); + if (status != GL_TRUE) { + glnvg__dumpShaderError(frag, name, "frag"); + return 0; + } + + glAttachShader(prog, vert); + glAttachShader(prog, frag); + + glBindAttribLocation(prog, 0, "vertex"); + glBindAttribLocation(prog, 1, "tcoord"); + + glLinkProgram(prog); + glGetProgramiv(prog, GL_LINK_STATUS, &status); + if (status != GL_TRUE) { + glnvg__dumpProgramError(prog, name); + return 0; + } + + shader->prog = prog; + shader->vert = vert; + shader->frag = frag; + + return 1; +} + +static void glnvg__deleteShader(GLNVGshader* shader) +{ + if (shader->prog != 0) + glDeleteProgram(shader->prog); + if (shader->vert != 0) + glDeleteShader(shader->vert); + if (shader->frag != 0) + glDeleteShader(shader->frag); +} + +static void glnvg__getUniforms(GLNVGshader* shader) +{ + shader->loc[GLNVG_LOC_VIEWSIZE] = glGetUniformLocation(shader->prog, "viewSize"); + shader->loc[GLNVG_LOC_TEX] = glGetUniformLocation(shader->prog, "tex"); + +#if NANOVG_GL_USE_UNIFORMBUFFER + shader->loc[GLNVG_LOC_FRAG] = glGetUniformBlockIndex(shader->prog, "frag"); +#else + shader->loc[GLNVG_LOC_FRAG] = glGetUniformLocation(shader->prog, "frag"); +#endif +} + +static int glnvg__renderCreate(void* uptr) +{ + GLNVGcontext* gl = (GLNVGcontext*)uptr; + int align = 4; + + // TODO: mediump float may not be enough for GLES2 in iOS. + // see the following discussion: https://github.com/memononen/nanovg/issues/46 + static const char* shaderHeader = +#if defined NANOVG_GL2 + "#define NANOVG_GL2 1\n" +#elif defined NANOVG_GL3 + "#version 150 core\n" + "#define NANOVG_GL3 1\n" +#elif defined NANOVG_GLES2 + "#version 100\n" + "#define NANOVG_GL2 1\n" +#elif defined NANOVG_GLES3 + "#version 300 es\n" + "#define NANOVG_GL3 1\n" +#endif + +#if NANOVG_GL_USE_UNIFORMBUFFER + "#define USE_UNIFORMBUFFER 1\n" +#else + "#define UNIFORMARRAY_SIZE 11\n" +#endif + "\n"; + + static const char* fillVertShader = + "#ifdef NANOVG_GL3\n" + " uniform vec2 viewSize;\n" + " in vec2 vertex;\n" + " in vec2 tcoord;\n" + " out vec2 ftcoord;\n" + " out vec2 fpos;\n" + "#else\n" + " uniform vec2 viewSize;\n" + " attribute vec2 vertex;\n" + " attribute vec2 tcoord;\n" + " varying vec2 ftcoord;\n" + " varying vec2 fpos;\n" + "#endif\n" + "void main(void) {\n" + " ftcoord = tcoord;\n" + " fpos = vertex;\n" + " gl_Position = vec4(2.0*vertex.x/viewSize.x - 1.0, 1.0 - 2.0*vertex.y/viewSize.y, 0, 1);\n" + "}\n"; + + static const char* fillFragShader = + "#ifdef GL_ES\n" + "#if defined(GL_FRAGMENT_PRECISION_HIGH) || defined(NANOVG_GL3)\n" + " precision highp float;\n" + "#else\n" + " precision mediump float;\n" + "#endif\n" + "#endif\n" + "#ifdef NANOVG_GL3\n" + "#ifdef USE_UNIFORMBUFFER\n" + " layout(std140) uniform frag {\n" + " mat3 scissorMat;\n" + " mat3 paintMat;\n" + " vec4 innerCol;\n" + " vec4 outerCol;\n" + " vec2 scissorExt;\n" + " vec2 scissorScale;\n" + " vec2 extent;\n" + " float radius;\n" + " float feather;\n" + " float strokeMult;\n" + " float strokeThr;\n" + " int texType;\n" + " int type;\n" + " };\n" + "#else\n" // NANOVG_GL3 && !USE_UNIFORMBUFFER + " uniform vec4 frag[UNIFORMARRAY_SIZE];\n" + "#endif\n" + " uniform sampler2D tex;\n" + " in vec2 ftcoord;\n" + " in vec2 fpos;\n" + " out vec4 outColor;\n" + "#else\n" // !NANOVG_GL3 + " uniform vec4 frag[UNIFORMARRAY_SIZE];\n" + " uniform sampler2D tex;\n" + " varying vec2 ftcoord;\n" + " varying vec2 fpos;\n" + "#endif\n" + "#ifndef USE_UNIFORMBUFFER\n" + " #define scissorMat mat3(frag[0].xyz, frag[1].xyz, frag[2].xyz)\n" + " #define paintMat mat3(frag[3].xyz, frag[4].xyz, frag[5].xyz)\n" + " #define innerCol frag[6]\n" + " #define outerCol frag[7]\n" + " #define scissorExt frag[8].xy\n" + " #define scissorScale frag[8].zw\n" + " #define extent frag[9].xy\n" + " #define radius frag[9].z\n" + " #define feather frag[9].w\n" + " #define strokeMult frag[10].x\n" + " #define strokeThr frag[10].y\n" + " #define texType int(frag[10].z)\n" + " #define type int(frag[10].w)\n" + "#endif\n" + "\n" + "float sdroundrect(vec2 pt, vec2 ext, float rad) {\n" + " vec2 ext2 = ext - vec2(rad,rad);\n" + " vec2 d = abs(pt) - ext2;\n" + " return min(max(d.x,d.y),0.0) + length(max(d,0.0)) - rad;\n" + "}\n" + "\n" + "// Scissoring\n" + "float scissorMask(vec2 p) {\n" + " vec2 sc = (abs((scissorMat * vec3(p,1.0)).xy) - scissorExt);\n" + " sc = vec2(0.5,0.5) - sc * scissorScale;\n" + " return clamp(sc.x,0.0,1.0) * clamp(sc.y,0.0,1.0);\n" + "}\n" + "#ifdef EDGE_AA\n" + "// Stroke - from [0..1] to clipped pyramid, where the slope is 1px.\n" + "float strokeMask() {\n" + " return min(1.0, (1.0-abs(ftcoord.x*2.0-1.0))*strokeMult) * min(1.0, ftcoord.y);\n" + "}\n" + "#endif\n" + "\n" + "void main(void) {\n" + " vec4 result;\n" + " float scissor = scissorMask(fpos);\n" + "#ifdef EDGE_AA\n" + " float strokeAlpha = strokeMask();\n" + "#else\n" + " float strokeAlpha = 1.0;\n" + "#endif\n" + " if (type == 0) { // Gradient\n" + " // Calculate gradient color using box gradient\n" + " vec2 pt = (paintMat * vec3(fpos,1.0)).xy;\n" + " float d = clamp((sdroundrect(pt, extent, radius) + feather*0.5) / feather, 0.0, 1.0);\n" + " vec4 color = mix(innerCol,outerCol,d);\n" + " // Combine alpha\n" + " color *= strokeAlpha * scissor;\n" + " result = color;\n" + " } else if (type == 1) { // Image\n" + " // Calculate color fron texture\n" + " vec2 pt = (paintMat * vec3(fpos,1.0)).xy / extent;\n" + "#ifdef NANOVG_GL3\n" + " vec4 color = texture(tex, pt);\n" + "#else\n" + " vec4 color = texture2D(tex, pt);\n" + "#endif\n" + " if (texType == 1) color = vec4(color.xyz*color.w,color.w);" + " if (texType == 2) color = vec4(color.x);" + " // Apply color tint and alpha.\n" + " color *= innerCol;\n" + " // Combine alpha\n" + " color *= strokeAlpha * scissor;\n" + " result = color;\n" + " } else if (type == 2) { // Stencil fill\n" + " result = vec4(1,1,1,1);\n" + " } else if (type == 3) { // Textured tris\n" + "#ifdef NANOVG_GL3\n" + " vec4 color = texture(tex, ftcoord);\n" + "#else\n" + " vec4 color = texture2D(tex, ftcoord);\n" + "#endif\n" + " if (texType == 1) color = vec4(color.xyz*color.w,color.w);" + " if (texType == 2) color = vec4(color.x);" + " color *= scissor;\n" + " result = color * innerCol;\n" + " }\n" + "#ifdef EDGE_AA\n" + " if (strokeAlpha < strokeThr) discard;\n" + "#endif\n" + "#ifdef NANOVG_GL3\n" + " outColor = result;\n" + "#else\n" + " gl_FragColor = result;\n" + "#endif\n" + "}\n"; + + glnvg__checkError(gl, "init"); + + if (gl->flags & NVG_ANTIALIAS) { + if (glnvg__createShader(&gl->shader, "shader", shaderHeader, "#define EDGE_AA 1\n", fillVertShader, fillFragShader) == 0) + return 0; + } else { + if (glnvg__createShader(&gl->shader, "shader", shaderHeader, NULL, fillVertShader, fillFragShader) == 0) + return 0; + } + + glnvg__checkError(gl, "uniform locations"); + glnvg__getUniforms(&gl->shader); + + // Create dynamic vertex array +#if defined NANOVG_GL3 + glGenVertexArrays(1, &gl->vertArr); +#endif + glGenBuffers(1, &gl->vertBuf); + +#if NANOVG_GL_USE_UNIFORMBUFFER + // Create UBOs + glUniformBlockBinding(gl->shader.prog, gl->shader.loc[GLNVG_LOC_FRAG], GLNVG_FRAG_BINDING); + glGenBuffers(1, &gl->fragBuf); + glGetIntegerv(GL_UNIFORM_BUFFER_OFFSET_ALIGNMENT, &align); +#endif + gl->fragSize = sizeof(GLNVGfragUniforms) + align - sizeof(GLNVGfragUniforms) % align; + + glnvg__checkError(gl, "create done"); + + glFinish(); + + return 1; +} + +static int glnvg__renderCreateTexture(void* uptr, int type, int w, int h, int imageFlags, const unsigned char* data) +{ + GLNVGcontext* gl = (GLNVGcontext*)uptr; + GLNVGtexture* tex = glnvg__allocTexture(gl); + + if (tex == NULL) return 0; + +#ifdef NANOVG_GLES2 + // Check for non-power of 2. + if (glnvg__nearestPow2(w) != (unsigned int)w || glnvg__nearestPow2(h) != (unsigned int)h) { + // No repeat + if ((imageFlags & NVG_IMAGE_REPEATX) != 0 || (imageFlags & NVG_IMAGE_REPEATY) != 0) { + printf("Repeat X/Y is not supported for non power-of-two textures (%d x %d)\n", w, h); + imageFlags &= ~(NVG_IMAGE_REPEATX | NVG_IMAGE_REPEATY); + } + // No mips. + if (imageFlags & NVG_IMAGE_GENERATE_MIPMAPS) { + printf("Mip-maps is not support for non power-of-two textures (%d x %d)\n", w, h); + imageFlags &= ~NVG_IMAGE_GENERATE_MIPMAPS; + } + } +#endif + + glGenTextures(1, &tex->tex); + tex->width = w; + tex->height = h; + tex->type = type; + tex->flags = imageFlags; + glnvg__bindTexture(gl, tex->tex); + + glPixelStorei(GL_UNPACK_ALIGNMENT,1); +#ifndef NANOVG_GLES2 + glPixelStorei(GL_UNPACK_ROW_LENGTH, tex->width); + glPixelStorei(GL_UNPACK_SKIP_PIXELS, 0); + glPixelStorei(GL_UNPACK_SKIP_ROWS, 0); +#endif + +#if defined (NANOVG_GL2) + // GL 1.4 and later has support for generating mipmaps using a tex parameter. + if (imageFlags & NVG_IMAGE_GENERATE_MIPMAPS) { + glTexParameteri(GL_TEXTURE_2D, GL_GENERATE_MIPMAP, GL_TRUE); + } +#endif + + if (type == NVG_TEXTURE_RGBA) + glTexImage2D(GL_TEXTURE_2D, 0, GL_RGBA, w, h, 0, GL_RGBA, GL_UNSIGNED_BYTE, data); + else +#if defined(NANOVG_GLES2) + glTexImage2D(GL_TEXTURE_2D, 0, GL_LUMINANCE, w, h, 0, GL_LUMINANCE, GL_UNSIGNED_BYTE, data); +#elif defined(NANOVG_GLES3) + glTexImage2D(GL_TEXTURE_2D, 0, GL_R8, w, h, 0, GL_RED, GL_UNSIGNED_BYTE, data); +#else + glTexImage2D(GL_TEXTURE_2D, 0, GL_RED, w, h, 0, GL_RED, GL_UNSIGNED_BYTE, data); +#endif + + if (imageFlags & NVG_IMAGE_GENERATE_MIPMAPS) { + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_LINEAR_MIPMAP_LINEAR); + } else { + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_LINEAR); + } + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_LINEAR); + + if (imageFlags & NVG_IMAGE_REPEATX) + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_WRAP_S, GL_REPEAT); + else + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_WRAP_S, GL_CLAMP_TO_EDGE); + + if (imageFlags & NVG_IMAGE_REPEATY) + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_WRAP_T, GL_REPEAT); + else + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_WRAP_T, GL_CLAMP_TO_EDGE); + + glPixelStorei(GL_UNPACK_ALIGNMENT, 4); +#ifndef NANOVG_GLES2 + glPixelStorei(GL_UNPACK_ROW_LENGTH, 0); + glPixelStorei(GL_UNPACK_SKIP_PIXELS, 0); + glPixelStorei(GL_UNPACK_SKIP_ROWS, 0); +#endif + + // The new way to build mipmaps on GLES and GL3 +#if !defined(NANOVG_GL2) + if (imageFlags & NVG_IMAGE_GENERATE_MIPMAPS) { + glGenerateMipmap(GL_TEXTURE_2D); + } +#endif + + glnvg__checkError(gl, "create tex"); + glnvg__bindTexture(gl, 0); + + return tex->id; +} + + +static int glnvg__renderDeleteTexture(void* uptr, int image) +{ + GLNVGcontext* gl = (GLNVGcontext*)uptr; + return glnvg__deleteTexture(gl, image); +} + +static int glnvg__renderUpdateTexture(void* uptr, int image, int x, int y, int w, int h, const unsigned char* data) +{ + GLNVGcontext* gl = (GLNVGcontext*)uptr; + GLNVGtexture* tex = glnvg__findTexture(gl, image); + + if (tex == NULL) return 0; + glnvg__bindTexture(gl, tex->tex); + + glPixelStorei(GL_UNPACK_ALIGNMENT,1); + +#ifndef NANOVG_GLES2 + glPixelStorei(GL_UNPACK_ROW_LENGTH, tex->width); + glPixelStorei(GL_UNPACK_SKIP_PIXELS, x); + glPixelStorei(GL_UNPACK_SKIP_ROWS, y); +#else + // No support for all of skip, need to update a whole row at a time. + if (tex->type == NVG_TEXTURE_RGBA) + data += y*tex->width*4; + else + data += y*tex->width; + x = 0; + w = tex->width; +#endif + + if (tex->type == NVG_TEXTURE_RGBA) + glTexSubImage2D(GL_TEXTURE_2D, 0, x,y, w,h, GL_RGBA, GL_UNSIGNED_BYTE, data); + else +#ifdef NANOVG_GLES2 + glTexSubImage2D(GL_TEXTURE_2D, 0, x,y, w,h, GL_LUMINANCE, GL_UNSIGNED_BYTE, data); +#else + glTexSubImage2D(GL_TEXTURE_2D, 0, x,y, w,h, GL_RED, GL_UNSIGNED_BYTE, data); +#endif + + glPixelStorei(GL_UNPACK_ALIGNMENT, 4); +#ifndef NANOVG_GLES2 + glPixelStorei(GL_UNPACK_ROW_LENGTH, 0); + glPixelStorei(GL_UNPACK_SKIP_PIXELS, 0); + glPixelStorei(GL_UNPACK_SKIP_ROWS, 0); +#endif + + glnvg__bindTexture(gl, 0); + + return 1; +} + +static int glnvg__renderGetTextureSize(void* uptr, int image, int* w, int* h) +{ + GLNVGcontext* gl = (GLNVGcontext*)uptr; + GLNVGtexture* tex = glnvg__findTexture(gl, image); + if (tex == NULL) return 0; + *w = tex->width; + *h = tex->height; + return 1; +} + +static void glnvg__xformToMat3x4(float* m3, float* t) +{ + m3[0] = t[0]; + m3[1] = t[1]; + m3[2] = 0.0f; + m3[3] = 0.0f; + m3[4] = t[2]; + m3[5] = t[3]; + m3[6] = 0.0f; + m3[7] = 0.0f; + m3[8] = t[4]; + m3[9] = t[5]; + m3[10] = 1.0f; + m3[11] = 0.0f; +} + +static NVGcolor glnvg__premulColor(NVGcolor c) +{ + c.r *= c.a; + c.g *= c.a; + c.b *= c.a; + return c; +} + +static int glnvg__convertPaint(GLNVGcontext* gl, GLNVGfragUniforms* frag, NVGpaint* paint, + NVGscissor* scissor, float width, float fringe, float strokeThr) +{ + GLNVGtexture* tex = NULL; + float invxform[6]; + + memset(frag, 0, sizeof(*frag)); + + frag->innerCol = glnvg__premulColor(paint->innerColor); + frag->outerCol = glnvg__premulColor(paint->outerColor); + + if (scissor->extent[0] < -0.5f || scissor->extent[1] < -0.5f) { + memset(frag->scissorMat, 0, sizeof(frag->scissorMat)); + frag->scissorExt[0] = 1.0f; + frag->scissorExt[1] = 1.0f; + frag->scissorScale[0] = 1.0f; + frag->scissorScale[1] = 1.0f; + } else { + nvgTransformInverse(invxform, scissor->xform); + glnvg__xformToMat3x4(frag->scissorMat, invxform); + frag->scissorExt[0] = scissor->extent[0]; + frag->scissorExt[1] = scissor->extent[1]; + frag->scissorScale[0] = sqrtf(scissor->xform[0]*scissor->xform[0] + scissor->xform[2]*scissor->xform[2]) / fringe; + frag->scissorScale[1] = sqrtf(scissor->xform[1]*scissor->xform[1] + scissor->xform[3]*scissor->xform[3]) / fringe; + } + + memcpy(frag->extent, paint->extent, sizeof(frag->extent)); + frag->strokeMult = (width*0.5f + fringe*0.5f) / fringe; + frag->strokeThr = strokeThr; + + if (paint->image != 0) { + tex = glnvg__findTexture(gl, paint->image); + if (tex == NULL) return 0; + if ((tex->flags & NVG_IMAGE_FLIPY) != 0) { + float m1[6], m2[6]; + nvgTransformTranslate(m1, 0.0f, frag->extent[1] * 0.5f); + nvgTransformMultiply(m1, paint->xform); + nvgTransformScale(m2, 1.0f, -1.0f); + nvgTransformMultiply(m2, m1); + nvgTransformTranslate(m1, 0.0f, -frag->extent[1] * 0.5f); + nvgTransformMultiply(m1, m2); + nvgTransformInverse(invxform, m1); + } else { + nvgTransformInverse(invxform, paint->xform); + } + frag->type = NSVG_SHADER_FILLIMG; + + if (tex->type == NVG_TEXTURE_RGBA) + frag->texType = (tex->flags & NVG_IMAGE_PREMULTIPLIED) ? 0 : 1; + else + frag->texType = 2; +// printf("frag->texType = %d\n", frag->texType); + } else { + frag->type = NSVG_SHADER_FILLGRAD; + frag->radius = paint->radius; + frag->feather = paint->feather; + nvgTransformInverse(invxform, paint->xform); + } + + glnvg__xformToMat3x4(frag->paintMat, invxform); + + return 1; +} + +static GLNVGfragUniforms* nvg__fragUniformPtr(GLNVGcontext* gl, int i); + +static void glnvg__setUniforms(GLNVGcontext* gl, int uniformOffset, int image) +{ +#if NANOVG_GL_USE_UNIFORMBUFFER + glBindBufferRange(GL_UNIFORM_BUFFER, GLNVG_FRAG_BINDING, gl->fragBuf, uniformOffset, sizeof(GLNVGfragUniforms)); +#else + GLNVGfragUniforms* frag = nvg__fragUniformPtr(gl, uniformOffset); + glUniform4fv(gl->shader.loc[GLNVG_LOC_FRAG], NANOVG_GL_UNIFORMARRAY_SIZE, &(frag->uniformArray[0][0])); +#endif + + if (image != 0) { + GLNVGtexture* tex = glnvg__findTexture(gl, image); + glnvg__bindTexture(gl, tex != NULL ? tex->tex : 0); + glnvg__checkError(gl, "tex paint tex"); + } else { + glnvg__bindTexture(gl, 0); + } +} + +static void glnvg__renderViewport(void* uptr, int width, int height, float devicePixelRatio) +{ + GLNVGcontext* gl = (GLNVGcontext*)uptr; + gl->view[0] = (float)width; + gl->view[1] = (float)height; +} + +static void glnvg__fill(GLNVGcontext* gl, GLNVGcall* call) +{ + GLNVGpath* paths = &gl->paths[call->pathOffset]; + int i, npaths = call->pathCount; + + // Draw shapes + glEnable(GL_STENCIL_TEST); + glnvg__stencilMask(gl, 0xff); + glnvg__stencilFunc(gl, GL_ALWAYS, 0, 0xff); + glColorMask(GL_FALSE, GL_FALSE, GL_FALSE, GL_FALSE); + + // set bindpoint for solid loc + glnvg__setUniforms(gl, call->uniformOffset, 0); + glnvg__checkError(gl, "fill simple"); + + glStencilOpSeparate(GL_FRONT, GL_KEEP, GL_KEEP, GL_INCR_WRAP); + glStencilOpSeparate(GL_BACK, GL_KEEP, GL_KEEP, GL_DECR_WRAP); + glDisable(GL_CULL_FACE); + for (i = 0; i < npaths; i++) + glDrawArrays(GL_TRIANGLE_FAN, paths[i].fillOffset, paths[i].fillCount); + glEnable(GL_CULL_FACE); + + // Draw anti-aliased pixels + glColorMask(GL_TRUE, GL_TRUE, GL_TRUE, GL_TRUE); + + glnvg__setUniforms(gl, call->uniformOffset + gl->fragSize, call->image); + glnvg__checkError(gl, "fill fill"); + + if (gl->flags & NVG_ANTIALIAS) { + glnvg__stencilFunc(gl, GL_EQUAL, 0x00, 0xff); + glStencilOp(GL_KEEP, GL_KEEP, GL_KEEP); + // Draw fringes + for (i = 0; i < npaths; i++) + glDrawArrays(GL_TRIANGLE_STRIP, paths[i].strokeOffset, paths[i].strokeCount); + } + + // Draw fill + glnvg__stencilFunc(gl, GL_NOTEQUAL, 0x0, 0xff); + glStencilOp(GL_ZERO, GL_ZERO, GL_ZERO); + glDrawArrays(GL_TRIANGLES, call->triangleOffset, call->triangleCount); + + glDisable(GL_STENCIL_TEST); +} + +static void glnvg__convexFill(GLNVGcontext* gl, GLNVGcall* call) +{ + GLNVGpath* paths = &gl->paths[call->pathOffset]; + int i, npaths = call->pathCount; + + glnvg__setUniforms(gl, call->uniformOffset, call->image); + glnvg__checkError(gl, "convex fill"); + + for (i = 0; i < npaths; i++) + glDrawArrays(GL_TRIANGLE_FAN, paths[i].fillOffset, paths[i].fillCount); + if (gl->flags & NVG_ANTIALIAS) { + // Draw fringes + for (i = 0; i < npaths; i++) + glDrawArrays(GL_TRIANGLE_STRIP, paths[i].strokeOffset, paths[i].strokeCount); + } +} + +static void glnvg__stroke(GLNVGcontext* gl, GLNVGcall* call) +{ + GLNVGpath* paths = &gl->paths[call->pathOffset]; + int npaths = call->pathCount, i; + + if (gl->flags & NVG_STENCIL_STROKES) { + + glEnable(GL_STENCIL_TEST); + glnvg__stencilMask(gl, 0xff); + + // Fill the stroke base without overlap + glnvg__stencilFunc(gl, GL_EQUAL, 0x0, 0xff); + glStencilOp(GL_KEEP, GL_KEEP, GL_INCR); + glnvg__setUniforms(gl, call->uniformOffset + gl->fragSize, call->image); + glnvg__checkError(gl, "stroke fill 0"); + for (i = 0; i < npaths; i++) + glDrawArrays(GL_TRIANGLE_STRIP, paths[i].strokeOffset, paths[i].strokeCount); + + // Draw anti-aliased pixels. + glnvg__setUniforms(gl, call->uniformOffset, call->image); + glnvg__stencilFunc(gl, GL_EQUAL, 0x00, 0xff); + glStencilOp(GL_KEEP, GL_KEEP, GL_KEEP); + for (i = 0; i < npaths; i++) + glDrawArrays(GL_TRIANGLE_STRIP, paths[i].strokeOffset, paths[i].strokeCount); + + // Clear stencil buffer. + glColorMask(GL_FALSE, GL_FALSE, GL_FALSE, GL_FALSE); + glnvg__stencilFunc(gl, GL_ALWAYS, 0x0, 0xff); + glStencilOp(GL_ZERO, GL_ZERO, GL_ZERO); + glnvg__checkError(gl, "stroke fill 1"); + for (i = 0; i < npaths; i++) + glDrawArrays(GL_TRIANGLE_STRIP, paths[i].strokeOffset, paths[i].strokeCount); + glColorMask(GL_TRUE, GL_TRUE, GL_TRUE, GL_TRUE); + + glDisable(GL_STENCIL_TEST); + +// glnvg__convertPaint(gl, nvg__fragUniformPtr(gl, call->uniformOffset + gl->fragSize), paint, scissor, strokeWidth, fringe, 1.0f - 0.5f/255.0f); + + } else { + glnvg__setUniforms(gl, call->uniformOffset, call->image); + glnvg__checkError(gl, "stroke fill"); + // Draw Strokes + for (i = 0; i < npaths; i++) + glDrawArrays(GL_TRIANGLE_STRIP, paths[i].strokeOffset, paths[i].strokeCount); + } +} + +static void glnvg__triangles(GLNVGcontext* gl, GLNVGcall* call) +{ + glnvg__setUniforms(gl, call->uniformOffset, call->image); + glnvg__checkError(gl, "triangles fill"); + + glDrawArrays(GL_TRIANGLES, call->triangleOffset, call->triangleCount); +} + +static void glnvg__renderCancel(void* uptr) { + GLNVGcontext* gl = (GLNVGcontext*)uptr; + gl->nverts = 0; + gl->npaths = 0; + gl->ncalls = 0; + gl->nuniforms = 0; +} + +static GLenum glnvg_convertBlendFuncFactor(int factor) +{ + if (factor == NVG_ZERO) + return GL_ZERO; + if (factor == NVG_ONE) + return GL_ONE; + if (factor == NVG_SRC_COLOR) + return GL_SRC_COLOR; + if (factor == NVG_ONE_MINUS_SRC_COLOR) + return GL_ONE_MINUS_SRC_COLOR; + if (factor == NVG_DST_COLOR) + return GL_DST_COLOR; + if (factor == NVG_ONE_MINUS_DST_COLOR) + return GL_ONE_MINUS_DST_COLOR; + if (factor == NVG_SRC_ALPHA) + return GL_SRC_ALPHA; + if (factor == NVG_ONE_MINUS_SRC_ALPHA) + return GL_ONE_MINUS_SRC_ALPHA; + if (factor == NVG_DST_ALPHA) + return GL_DST_ALPHA; + if (factor == NVG_ONE_MINUS_DST_ALPHA) + return GL_ONE_MINUS_DST_ALPHA; + if (factor == NVG_SRC_ALPHA_SATURATE) + return GL_SRC_ALPHA_SATURATE; + return GL_INVALID_ENUM; +} + +static void glnvg__blendCompositeOperation(NVGcompositeOperationState op) +{ + GLenum srcRGB = glnvg_convertBlendFuncFactor(op.srcRGB); + GLenum dstRGB = glnvg_convertBlendFuncFactor(op.dstRGB); + GLenum srcAlpha = glnvg_convertBlendFuncFactor(op.srcAlpha); + GLenum dstAlpha = glnvg_convertBlendFuncFactor(op.dstAlpha); + if (srcRGB == GL_INVALID_ENUM || dstRGB == GL_INVALID_ENUM || srcAlpha == GL_INVALID_ENUM || dstAlpha == GL_INVALID_ENUM) + glBlendFunc(GL_ONE, GL_ONE_MINUS_SRC_ALPHA); + else + glBlendFuncSeparate(srcRGB, dstRGB, srcAlpha, dstAlpha); +} + +static void glnvg__renderFlush(void* uptr, NVGcompositeOperationState compositeOperation) +{ + GLNVGcontext* gl = (GLNVGcontext*)uptr; + int i; + + if (gl->ncalls > 0) { + + // Setup require GL state. + glUseProgram(gl->shader.prog); + + glnvg__blendCompositeOperation(compositeOperation); + glEnable(GL_CULL_FACE); + glCullFace(GL_BACK); + glFrontFace(GL_CCW); + glEnable(GL_BLEND); + glDisable(GL_DEPTH_TEST); + glDisable(GL_SCISSOR_TEST); + glColorMask(GL_TRUE, GL_TRUE, GL_TRUE, GL_TRUE); + glStencilMask(0xffffffff); + glStencilOp(GL_KEEP, GL_KEEP, GL_KEEP); + glStencilFunc(GL_ALWAYS, 0, 0xffffffff); + glActiveTexture(GL_TEXTURE0); + glBindTexture(GL_TEXTURE_2D, 0); + #if NANOVG_GL_USE_STATE_FILTER + gl->boundTexture = 0; + gl->stencilMask = 0xffffffff; + gl->stencilFunc = GL_ALWAYS; + gl->stencilFuncRef = 0; + gl->stencilFuncMask = 0xffffffff; + #endif + +#if NANOVG_GL_USE_UNIFORMBUFFER + // Upload ubo for frag shaders + glBindBuffer(GL_UNIFORM_BUFFER, gl->fragBuf); + glBufferData(GL_UNIFORM_BUFFER, gl->nuniforms * gl->fragSize, gl->uniforms, GL_STREAM_DRAW); +#endif + + // Upload vertex data +#if defined NANOVG_GL3 + glBindVertexArray(gl->vertArr); +#endif + glBindBuffer(GL_ARRAY_BUFFER, gl->vertBuf); + glBufferData(GL_ARRAY_BUFFER, gl->nverts * sizeof(NVGvertex), gl->verts, GL_STREAM_DRAW); + glEnableVertexAttribArray(0); + glEnableVertexAttribArray(1); + glVertexAttribPointer(0, 2, GL_FLOAT, GL_FALSE, sizeof(NVGvertex), (const GLvoid*)(size_t)0); + glVertexAttribPointer(1, 2, GL_FLOAT, GL_FALSE, sizeof(NVGvertex), (const GLvoid*)(0 + 2*sizeof(float))); + + // Set view and texture just once per frame. + glUniform1i(gl->shader.loc[GLNVG_LOC_TEX], 0); + glUniform2fv(gl->shader.loc[GLNVG_LOC_VIEWSIZE], 1, gl->view); + +#if NANOVG_GL_USE_UNIFORMBUFFER + glBindBuffer(GL_UNIFORM_BUFFER, gl->fragBuf); +#endif + + for (i = 0; i < gl->ncalls; i++) { + GLNVGcall* call = &gl->calls[i]; + if (call->type == GLNVG_FILL) + glnvg__fill(gl, call); + else if (call->type == GLNVG_CONVEXFILL) + glnvg__convexFill(gl, call); + else if (call->type == GLNVG_STROKE) + glnvg__stroke(gl, call); + else if (call->type == GLNVG_TRIANGLES) + glnvg__triangles(gl, call); + } + + glDisableVertexAttribArray(0); + glDisableVertexAttribArray(1); +#if defined NANOVG_GL3 + glBindVertexArray(0); +#endif + glDisable(GL_CULL_FACE); + glBindBuffer(GL_ARRAY_BUFFER, 0); + glUseProgram(0); + glnvg__bindTexture(gl, 0); + } + + // Reset calls + gl->nverts = 0; + gl->npaths = 0; + gl->ncalls = 0; + gl->nuniforms = 0; +} + +static int glnvg__maxVertCount(const NVGpath* paths, int npaths) +{ + int i, count = 0; + for (i = 0; i < npaths; i++) { + count += paths[i].nfill; + count += paths[i].nstroke; + } + return count; +} + +static GLNVGcall* glnvg__allocCall(GLNVGcontext* gl) +{ + GLNVGcall* ret = NULL; + if (gl->ncalls+1 > gl->ccalls) { + GLNVGcall* calls; + int ccalls = glnvg__maxi(gl->ncalls+1, 128) + gl->ccalls/2; // 1.5x Overallocate + calls = (GLNVGcall*)realloc(gl->calls, sizeof(GLNVGcall) * ccalls); + if (calls == NULL) return NULL; + gl->calls = calls; + gl->ccalls = ccalls; + } + ret = &gl->calls[gl->ncalls++]; + memset(ret, 0, sizeof(GLNVGcall)); + return ret; +} + +static int glnvg__allocPaths(GLNVGcontext* gl, int n) +{ + int ret = 0; + if (gl->npaths+n > gl->cpaths) { + GLNVGpath* paths; + int cpaths = glnvg__maxi(gl->npaths + n, 128) + gl->cpaths/2; // 1.5x Overallocate + paths = (GLNVGpath*)realloc(gl->paths, sizeof(GLNVGpath) * cpaths); + if (paths == NULL) return -1; + gl->paths = paths; + gl->cpaths = cpaths; + } + ret = gl->npaths; + gl->npaths += n; + return ret; +} + +static int glnvg__allocVerts(GLNVGcontext* gl, int n) +{ + int ret = 0; + if (gl->nverts+n > gl->cverts) { + NVGvertex* verts; + int cverts = glnvg__maxi(gl->nverts + n, 4096) + gl->cverts/2; // 1.5x Overallocate + verts = (NVGvertex*)realloc(gl->verts, sizeof(NVGvertex) * cverts); + if (verts == NULL) return -1; + gl->verts = verts; + gl->cverts = cverts; + } + ret = gl->nverts; + gl->nverts += n; + return ret; +} + +static int glnvg__allocFragUniforms(GLNVGcontext* gl, int n) +{ + int ret = 0, structSize = gl->fragSize; + if (gl->nuniforms+n > gl->cuniforms) { + unsigned char* uniforms; + int cuniforms = glnvg__maxi(gl->nuniforms+n, 128) + gl->cuniforms/2; // 1.5x Overallocate + uniforms = (unsigned char*)realloc(gl->uniforms, structSize * cuniforms); + if (uniforms == NULL) return -1; + gl->uniforms = uniforms; + gl->cuniforms = cuniforms; + } + ret = gl->nuniforms * structSize; + gl->nuniforms += n; + return ret; +} + +static GLNVGfragUniforms* nvg__fragUniformPtr(GLNVGcontext* gl, int i) +{ + return (GLNVGfragUniforms*)&gl->uniforms[i]; +} + +static void glnvg__vset(NVGvertex* vtx, float x, float y, float u, float v) +{ + vtx->x = x; + vtx->y = y; + vtx->u = u; + vtx->v = v; +} + +static void glnvg__renderFill(void* uptr, NVGpaint* paint, NVGscissor* scissor, float fringe, + const float* bounds, const NVGpath* paths, int npaths) +{ + GLNVGcontext* gl = (GLNVGcontext*)uptr; + GLNVGcall* call = glnvg__allocCall(gl); + NVGvertex* quad; + GLNVGfragUniforms* frag; + int i, maxverts, offset; + + if (call == NULL) return; + + call->type = GLNVG_FILL; + call->pathOffset = glnvg__allocPaths(gl, npaths); + if (call->pathOffset == -1) goto error; + call->pathCount = npaths; + call->image = paint->image; + + if (npaths == 1 && paths[0].convex) + call->type = GLNVG_CONVEXFILL; + + // Allocate vertices for all the paths. + maxverts = glnvg__maxVertCount(paths, npaths) + 6; + offset = glnvg__allocVerts(gl, maxverts); + if (offset == -1) goto error; + + for (i = 0; i < npaths; i++) { + GLNVGpath* copy = &gl->paths[call->pathOffset + i]; + const NVGpath* path = &paths[i]; + memset(copy, 0, sizeof(GLNVGpath)); + if (path->nfill > 0) { + copy->fillOffset = offset; + copy->fillCount = path->nfill; + memcpy(&gl->verts[offset], path->fill, sizeof(NVGvertex) * path->nfill); + offset += path->nfill; + } + if (path->nstroke > 0) { + copy->strokeOffset = offset; + copy->strokeCount = path->nstroke; + memcpy(&gl->verts[offset], path->stroke, sizeof(NVGvertex) * path->nstroke); + offset += path->nstroke; + } + } + + // Quad + call->triangleOffset = offset; + call->triangleCount = 6; + quad = &gl->verts[call->triangleOffset]; + glnvg__vset(&quad[0], bounds[0], bounds[3], 0.5f, 1.0f); + glnvg__vset(&quad[1], bounds[2], bounds[3], 0.5f, 1.0f); + glnvg__vset(&quad[2], bounds[2], bounds[1], 0.5f, 1.0f); + + glnvg__vset(&quad[3], bounds[0], bounds[3], 0.5f, 1.0f); + glnvg__vset(&quad[4], bounds[2], bounds[1], 0.5f, 1.0f); + glnvg__vset(&quad[5], bounds[0], bounds[1], 0.5f, 1.0f); + + // Setup uniforms for draw calls + if (call->type == GLNVG_FILL) { + call->uniformOffset = glnvg__allocFragUniforms(gl, 2); + if (call->uniformOffset == -1) goto error; + // Simple shader for stencil + frag = nvg__fragUniformPtr(gl, call->uniformOffset); + memset(frag, 0, sizeof(*frag)); + frag->strokeThr = -1.0f; + frag->type = NSVG_SHADER_SIMPLE; + // Fill shader + glnvg__convertPaint(gl, nvg__fragUniformPtr(gl, call->uniformOffset + gl->fragSize), paint, scissor, fringe, fringe, -1.0f); + } else { + call->uniformOffset = glnvg__allocFragUniforms(gl, 1); + if (call->uniformOffset == -1) goto error; + // Fill shader + glnvg__convertPaint(gl, nvg__fragUniformPtr(gl, call->uniformOffset), paint, scissor, fringe, fringe, -1.0f); + } + + return; + +error: + // We get here if call alloc was ok, but something else is not. + // Roll back the last call to prevent drawing it. + if (gl->ncalls > 0) gl->ncalls--; +} + +static void glnvg__renderStroke(void* uptr, NVGpaint* paint, NVGscissor* scissor, float fringe, + float strokeWidth, const NVGpath* paths, int npaths) +{ + GLNVGcontext* gl = (GLNVGcontext*)uptr; + GLNVGcall* call = glnvg__allocCall(gl); + int i, maxverts, offset; + + if (call == NULL) return; + + call->type = GLNVG_STROKE; + call->pathOffset = glnvg__allocPaths(gl, npaths); + if (call->pathOffset == -1) goto error; + call->pathCount = npaths; + call->image = paint->image; + + // Allocate vertices for all the paths. + maxverts = glnvg__maxVertCount(paths, npaths); + offset = glnvg__allocVerts(gl, maxverts); + if (offset == -1) goto error; + + for (i = 0; i < npaths; i++) { + GLNVGpath* copy = &gl->paths[call->pathOffset + i]; + const NVGpath* path = &paths[i]; + memset(copy, 0, sizeof(GLNVGpath)); + if (path->nstroke) { + copy->strokeOffset = offset; + copy->strokeCount = path->nstroke; + memcpy(&gl->verts[offset], path->stroke, sizeof(NVGvertex) * path->nstroke); + offset += path->nstroke; + } + } + + if (gl->flags & NVG_STENCIL_STROKES) { + // Fill shader + call->uniformOffset = glnvg__allocFragUniforms(gl, 2); + if (call->uniformOffset == -1) goto error; + + glnvg__convertPaint(gl, nvg__fragUniformPtr(gl, call->uniformOffset), paint, scissor, strokeWidth, fringe, -1.0f); + glnvg__convertPaint(gl, nvg__fragUniformPtr(gl, call->uniformOffset + gl->fragSize), paint, scissor, strokeWidth, fringe, 1.0f - 0.5f/255.0f); + + } else { + // Fill shader + call->uniformOffset = glnvg__allocFragUniforms(gl, 1); + if (call->uniformOffset == -1) goto error; + glnvg__convertPaint(gl, nvg__fragUniformPtr(gl, call->uniformOffset), paint, scissor, strokeWidth, fringe, -1.0f); + } + + return; + +error: + // We get here if call alloc was ok, but something else is not. + // Roll back the last call to prevent drawing it. + if (gl->ncalls > 0) gl->ncalls--; +} + +static void glnvg__renderTriangles(void* uptr, NVGpaint* paint, NVGscissor* scissor, + const NVGvertex* verts, int nverts) +{ + GLNVGcontext* gl = (GLNVGcontext*)uptr; + GLNVGcall* call = glnvg__allocCall(gl); + GLNVGfragUniforms* frag; + + if (call == NULL) return; + + call->type = GLNVG_TRIANGLES; + call->image = paint->image; + + // Allocate vertices for all the paths. + call->triangleOffset = glnvg__allocVerts(gl, nverts); + if (call->triangleOffset == -1) goto error; + call->triangleCount = nverts; + + memcpy(&gl->verts[call->triangleOffset], verts, sizeof(NVGvertex) * nverts); + + // Fill shader + call->uniformOffset = glnvg__allocFragUniforms(gl, 1); + if (call->uniformOffset == -1) goto error; + frag = nvg__fragUniformPtr(gl, call->uniformOffset); + glnvg__convertPaint(gl, frag, paint, scissor, 1.0f, 1.0f, -1.0f); + frag->type = NSVG_SHADER_IMG; + + return; + +error: + // We get here if call alloc was ok, but something else is not. + // Roll back the last call to prevent drawing it. + if (gl->ncalls > 0) gl->ncalls--; +} + +static void glnvg__renderDelete(void* uptr) +{ + GLNVGcontext* gl = (GLNVGcontext*)uptr; + int i; + if (gl == NULL) return; + + glnvg__deleteShader(&gl->shader); + +#if NANOVG_GL3 +#if NANOVG_GL_USE_UNIFORMBUFFER + if (gl->fragBuf != 0) + glDeleteBuffers(1, &gl->fragBuf); +#endif + if (gl->vertArr != 0) + glDeleteVertexArrays(1, &gl->vertArr); +#endif + if (gl->vertBuf != 0) + glDeleteBuffers(1, &gl->vertBuf); + + for (i = 0; i < gl->ntextures; i++) { + if (gl->textures[i].tex != 0 && (gl->textures[i].flags & NVG_IMAGE_NODELETE) == 0) + glDeleteTextures(1, &gl->textures[i].tex); + } + free(gl->textures); + + free(gl->paths); + free(gl->verts); + free(gl->uniforms); + free(gl->calls); + + free(gl); +} + + +#if defined NANOVG_GL2 +NVGcontext* nvgCreateGL2(int flags) +#elif defined NANOVG_GL3 +NVGcontext* nvgCreateGL3(int flags) +#elif defined NANOVG_GLES2 +NVGcontext* nvgCreateGLES2(int flags) +#elif defined NANOVG_GLES3 +NVGcontext* nvgCreateGLES3(int flags) +#endif +{ + NVGparams params; + NVGcontext* ctx = NULL; + GLNVGcontext* gl = (GLNVGcontext*)malloc(sizeof(GLNVGcontext)); + if (gl == NULL) goto error; + memset(gl, 0, sizeof(GLNVGcontext)); + + memset(¶ms, 0, sizeof(params)); + params.renderCreate = glnvg__renderCreate; + params.renderCreateTexture = glnvg__renderCreateTexture; + params.renderDeleteTexture = glnvg__renderDeleteTexture; + params.renderUpdateTexture = glnvg__renderUpdateTexture; + params.renderGetTextureSize = glnvg__renderGetTextureSize; + params.renderViewport = glnvg__renderViewport; + params.renderCancel = glnvg__renderCancel; + params.renderFlush = glnvg__renderFlush; + params.renderFill = glnvg__renderFill; + params.renderStroke = glnvg__renderStroke; + params.renderTriangles = glnvg__renderTriangles; + params.renderDelete = glnvg__renderDelete; + params.userPtr = gl; + params.edgeAntiAlias = flags & NVG_ANTIALIAS ? 1 : 0; + + gl->flags = flags; + + ctx = nvgCreateInternal(¶ms); + if (ctx == NULL) goto error; + + return ctx; + +error: + // 'gl' is freed by nvgDeleteInternal. + if (ctx != NULL) nvgDeleteInternal(ctx); + return NULL; +} + +#if defined NANOVG_GL2 +void nvgDeleteGL2(NVGcontext* ctx) +#elif defined NANOVG_GL3 +void nvgDeleteGL3(NVGcontext* ctx) +#elif defined NANOVG_GLES2 +void nvgDeleteGLES2(NVGcontext* ctx) +#elif defined NANOVG_GLES3 +void nvgDeleteGLES3(NVGcontext* ctx) +#endif +{ + nvgDeleteInternal(ctx); +} + +#if defined NANOVG_GL2 +int nvglCreateImageFromHandleGL2(NVGcontext* ctx, GLuint textureId, int w, int h, int imageFlags) +#elif defined NANOVG_GL3 +int nvglCreateImageFromHandleGL3(NVGcontext* ctx, GLuint textureId, int w, int h, int imageFlags) +#elif defined NANOVG_GLES2 +int nvglCreateImageFromHandleGLES2(NVGcontext* ctx, GLuint textureId, int w, int h, int imageFlags) +#elif defined NANOVG_GLES3 +int nvglCreateImageFromHandleGLES3(NVGcontext* ctx, GLuint textureId, int w, int h, int imageFlags) +#endif +{ + GLNVGcontext* gl = (GLNVGcontext*)nvgInternalParams(ctx)->userPtr; + GLNVGtexture* tex = glnvg__allocTexture(gl); + + if (tex == NULL) return 0; + + tex->type = NVG_TEXTURE_RGBA; + tex->tex = textureId; + tex->flags = imageFlags; + tex->width = w; + tex->height = h; + + return tex->id; +} + +#if defined NANOVG_GL2 +GLuint nvglImageHandleGL2(NVGcontext* ctx, int image) +#elif defined NANOVG_GL3 +GLuint nvglImageHandleGL3(NVGcontext* ctx, int image) +#elif defined NANOVG_GLES2 +GLuint nvglImageHandleGLES2(NVGcontext* ctx, int image) +#elif defined NANOVG_GLES3 +GLuint nvglImageHandleGLES3(NVGcontext* ctx, int image) +#endif +{ + GLNVGcontext* gl = (GLNVGcontext*)nvgInternalParams(ctx)->userPtr; + GLNVGtexture* tex = glnvg__findTexture(gl, image); + return tex->tex; +} + +#endif /* NANOVG_GL_IMPLEMENTATION */ diff --git a/phonelibs/nanovg/nanovg_gl_utils.h b/phonelibs/nanovg/nanovg_gl_utils.h new file mode 100644 index 00000000000000..1323e90c64cf90 --- /dev/null +++ b/phonelibs/nanovg/nanovg_gl_utils.h @@ -0,0 +1,143 @@ +// +// Copyright (c) 2009-2013 Mikko Mononen memon@inside.org +// +// 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 NANOVG_GL_UTILS_H +#define NANOVG_GL_UTILS_H + +struct NVGLUframebuffer { + NVGcontext* ctx; + GLuint fbo; + GLuint rbo; + GLuint texture; + int image; +}; +typedef struct NVGLUframebuffer NVGLUframebuffer; + +// Helper function to create GL frame buffer to render to. +void nvgluBindFramebuffer(NVGLUframebuffer* fb); +NVGLUframebuffer* nvgluCreateFramebuffer(NVGcontext* ctx, int w, int h, int imageFlags); +void nvgluDeleteFramebuffer(NVGLUframebuffer* fb); + +#endif // NANOVG_GL_UTILS_H + +#ifdef NANOVG_GL_IMPLEMENTATION + +#if defined(NANOVG_GL3) || defined(NANOVG_GLES2) || defined(NANOVG_GLES3) +// FBO is core in OpenGL 3>. +# define NANOVG_FBO_VALID 1 +#elif defined(NANOVG_GL2) +// On OS X including glext defines FBO on GL2 too. +# ifdef __APPLE__ +# include +# define NANOVG_FBO_VALID 1 +# endif +#endif + +static GLint defaultFBO = -1; + +NVGLUframebuffer* nvgluCreateFramebuffer(NVGcontext* ctx, int w, int h, int imageFlags) +{ +#ifdef NANOVG_FBO_VALID + GLint defaultFBO; + GLint defaultRBO; + NVGLUframebuffer* fb = NULL; + + glGetIntegerv(GL_FRAMEBUFFER_BINDING, &defaultFBO); + glGetIntegerv(GL_RENDERBUFFER_BINDING, &defaultRBO); + + fb = (NVGLUframebuffer*)malloc(sizeof(NVGLUframebuffer)); + if (fb == NULL) goto error; + memset(fb, 0, sizeof(NVGLUframebuffer)); + + fb->image = nvgCreateImageRGBA(ctx, w, h, imageFlags | NVG_IMAGE_FLIPY | NVG_IMAGE_PREMULTIPLIED, NULL); + +#if defined NANOVG_GL2 + fb->texture = nvglImageHandleGL2(ctx, fb->image); +#elif defined NANOVG_GL3 + fb->texture = nvglImageHandleGL3(ctx, fb->image); +#elif defined NANOVG_GLES2 + fb->texture = nvglImageHandleGLES2(ctx, fb->image); +#elif defined NANOVG_GLES3 + fb->texture = nvglImageHandleGLES3(ctx, fb->image); +#endif + + fb->ctx = ctx; + + // frame buffer object + glGenFramebuffers(1, &fb->fbo); + glBindFramebuffer(GL_FRAMEBUFFER, fb->fbo); + + // render buffer object + glGenRenderbuffers(1, &fb->rbo); + glBindRenderbuffer(GL_RENDERBUFFER, fb->rbo); + glRenderbufferStorage(GL_RENDERBUFFER, GL_STENCIL_INDEX8, w, h); + + // combine all + glFramebufferTexture2D(GL_FRAMEBUFFER, GL_COLOR_ATTACHMENT0, GL_TEXTURE_2D, fb->texture, 0); + glFramebufferRenderbuffer(GL_FRAMEBUFFER, GL_STENCIL_ATTACHMENT, GL_RENDERBUFFER, fb->rbo); + + if (glCheckFramebufferStatus(GL_FRAMEBUFFER) != GL_FRAMEBUFFER_COMPLETE) goto error; + + glBindFramebuffer(GL_FRAMEBUFFER, defaultFBO); + glBindRenderbuffer(GL_RENDERBUFFER, defaultRBO); + return fb; +error: + glBindFramebuffer(GL_FRAMEBUFFER, defaultFBO); + glBindRenderbuffer(GL_RENDERBUFFER, defaultRBO); + nvgluDeleteFramebuffer(fb); + return NULL; +#else + NVG_NOTUSED(ctx); + NVG_NOTUSED(w); + NVG_NOTUSED(h); + NVG_NOTUSED(imageFlags); + return NULL; +#endif +} + +void nvgluBindFramebuffer(NVGLUframebuffer* fb) +{ +#ifdef NANOVG_FBO_VALID + if (defaultFBO == -1) glGetIntegerv(GL_FRAMEBUFFER_BINDING, &defaultFBO); + glBindFramebuffer(GL_FRAMEBUFFER, fb != NULL ? fb->fbo : defaultFBO); +#else + NVG_NOTUSED(fb); +#endif +} + +void nvgluDeleteFramebuffer(NVGLUframebuffer* fb) +{ +#ifdef NANOVG_FBO_VALID + if (fb == NULL) return; + if (fb->fbo != 0) + glDeleteFramebuffers(1, &fb->fbo); + if (fb->rbo != 0) + glDeleteRenderbuffers(1, &fb->rbo); + if (fb->image >= 0) + nvgDeleteImage(fb->ctx, fb->image); + fb->ctx = NULL; + fb->fbo = 0; + fb->rbo = 0; + fb->texture = 0; + fb->image = -1; + free(fb); +#else + NVG_NOTUSED(fb); +#endif +} + +#endif // NANOVG_GL_IMPLEMENTATION diff --git a/phonelibs/nanovg/stb_image.h b/phonelibs/nanovg/stb_image.h new file mode 100644 index 00000000000000..e06f7a1d73b1e3 --- /dev/null +++ b/phonelibs/nanovg/stb_image.h @@ -0,0 +1,6614 @@ +/* stb_image - v2.10 - public domain image loader - http://nothings.org/stb_image.h + no warranty implied; use at your own risk + + Do this: + #define STB_IMAGE_IMPLEMENTATION + before you include this file in *one* C or C++ file to create the implementation. + + // i.e. it should look like this: + #include ... + #include ... + #include ... + #define STB_IMAGE_IMPLEMENTATION + #include "stb_image.h" + + You can #define STBI_ASSERT(x) before the #include to avoid using assert.h. + And #define STBI_MALLOC, STBI_REALLOC, and STBI_FREE to avoid using malloc,realloc,free + + + QUICK NOTES: + Primarily of interest to game developers and other people who can + avoid problematic images and only need the trivial interface + + JPEG baseline & progressive (12 bpc/arithmetic not supported, same as stock IJG lib) + PNG 1/2/4/8-bit-per-channel (16 bpc not supported) + + TGA (not sure what subset, if a subset) + BMP non-1bpp, non-RLE + PSD (composited view only, no extra channels, 8/16 bit-per-channel) + + GIF (*comp always reports as 4-channel) + HDR (radiance rgbE format) + PIC (Softimage PIC) + PNM (PPM and PGM binary only) + + Animated GIF still needs a proper API, but here's one way to do it: + http://gist.github.com/urraka/685d9a6340b26b830d49 + + - decode from memory or through FILE (define STBI_NO_STDIO to remove code) + - decode from arbitrary I/O callbacks + - SIMD acceleration on x86/x64 (SSE2) and ARM (NEON) + + Full documentation under "DOCUMENTATION" below. + + + Revision 2.00 release notes: + + - Progressive JPEG is now supported. + + - PPM and PGM binary formats are now supported, thanks to Ken Miller. + + - x86 platforms now make use of SSE2 SIMD instructions for + JPEG decoding, and ARM platforms can use NEON SIMD if requested. + This work was done by Fabian "ryg" Giesen. SSE2 is used by + default, but NEON must be enabled explicitly; see docs. + + With other JPEG optimizations included in this version, we see + 2x speedup on a JPEG on an x86 machine, and a 1.5x speedup + on a JPEG on an ARM machine, relative to previous versions of this + library. The same results will not obtain for all JPGs and for all + x86/ARM machines. (Note that progressive JPEGs are significantly + slower to decode than regular JPEGs.) This doesn't mean that this + is the fastest JPEG decoder in the land; rather, it brings it + closer to parity with standard libraries. If you want the fastest + decode, look elsewhere. (See "Philosophy" section of docs below.) + + See final bullet items below for more info on SIMD. + + - Added STBI_MALLOC, STBI_REALLOC, and STBI_FREE macros for replacing + the memory allocator. Unlike other STBI libraries, these macros don't + support a context parameter, so if you need to pass a context in to + the allocator, you'll have to store it in a global or a thread-local + variable. + + - Split existing STBI_NO_HDR flag into two flags, STBI_NO_HDR and + STBI_NO_LINEAR. + STBI_NO_HDR: suppress implementation of .hdr reader format + STBI_NO_LINEAR: suppress high-dynamic-range light-linear float API + + - You can suppress implementation of any of the decoders to reduce + your code footprint by #defining one or more of the following + symbols before creating the implementation. + + STBI_NO_JPEG + STBI_NO_PNG + STBI_NO_BMP + STBI_NO_PSD + STBI_NO_TGA + STBI_NO_GIF + STBI_NO_HDR + STBI_NO_PIC + STBI_NO_PNM (.ppm and .pgm) + + - You can request *only* certain decoders and suppress all other ones + (this will be more forward-compatible, as addition of new decoders + doesn't require you to disable them explicitly): + + STBI_ONLY_JPEG + STBI_ONLY_PNG + STBI_ONLY_BMP + STBI_ONLY_PSD + STBI_ONLY_TGA + STBI_ONLY_GIF + STBI_ONLY_HDR + STBI_ONLY_PIC + STBI_ONLY_PNM (.ppm and .pgm) + + Note that you can define multiples of these, and you will get all + of them ("only x" and "only y" is interpreted to mean "only x&y"). + + - If you use STBI_NO_PNG (or _ONLY_ without PNG), and you still + want the zlib decoder to be available, #define STBI_SUPPORT_ZLIB + + - Compilation of all SIMD code can be suppressed with + #define STBI_NO_SIMD + It should not be necessary to disable SIMD unless you have issues + compiling (e.g. using an x86 compiler which doesn't support SSE + intrinsics or that doesn't support the method used to detect + SSE2 support at run-time), and even those can be reported as + bugs so I can refine the built-in compile-time checking to be + smarter. + + - The old STBI_SIMD system which allowed installing a user-defined + IDCT etc. has been removed. If you need this, don't upgrade. My + assumption is that almost nobody was doing this, and those who + were will find the built-in SIMD more satisfactory anyway. + + - RGB values computed for JPEG images are slightly different from + previous versions of stb_image. (This is due to using less + integer precision in SIMD.) The C code has been adjusted so + that the same RGB values will be computed regardless of whether + SIMD support is available, so your app should always produce + consistent results. But these results are slightly different from + previous versions. (Specifically, about 3% of available YCbCr values + will compute different RGB results from pre-1.49 versions by +-1; + most of the deviating values are one smaller in the G channel.) + + - If you must produce consistent results with previous versions of + stb_image, #define STBI_JPEG_OLD and you will get the same results + you used to; however, you will not get the SIMD speedups for + the YCbCr-to-RGB conversion step (although you should still see + significant JPEG speedup from the other changes). + + Please note that STBI_JPEG_OLD is a temporary feature; it will be + removed in future versions of the library. It is only intended for + near-term back-compatibility use. + + + Latest revision history: + 2.10 (2016-01-22) avoid warning introduced in 2.09 + 2.09 (2016-01-16) 16-bit TGA; comments in PNM files; STBI_REALLOC_SIZED + 2.08 (2015-09-13) fix to 2.07 cleanup, reading RGB PSD as RGBA + 2.07 (2015-09-13) partial animated GIF support + limited 16-bit PSD support + minor bugs, code cleanup, and compiler warnings + 2.06 (2015-04-19) fix bug where PSD returns wrong '*comp' value + 2.05 (2015-04-19) fix bug in progressive JPEG handling, fix warning + 2.04 (2015-04-15) try to re-enable SIMD on MinGW 64-bit + 2.03 (2015-04-12) additional corruption checking + stbi_set_flip_vertically_on_load + fix NEON support; fix mingw support + 2.02 (2015-01-19) fix incorrect assert, fix warning + 2.01 (2015-01-17) fix various warnings + 2.00b (2014-12-25) fix STBI_MALLOC in progressive JPEG + 2.00 (2014-12-25) optimize JPEG, including x86 SSE2 & ARM NEON SIMD + progressive JPEG + PGM/PPM support + STBI_MALLOC,STBI_REALLOC,STBI_FREE + STBI_NO_*, STBI_ONLY_* + GIF bugfix + 1.48 (2014-12-14) fix incorrectly-named assert() + 1.47 (2014-12-14) 1/2/4-bit PNG support (both grayscale and paletted) + optimize PNG + fix bug in interlaced PNG with user-specified channel count + + See end of file for full revision history. + + + ============================ Contributors ========================= + + Image formats Extensions, features + Sean Barrett (jpeg, png, bmp) Jetro Lauha (stbi_info) + Nicolas Schulz (hdr, psd) Martin "SpartanJ" Golini (stbi_info) + Jonathan Dummer (tga) James "moose2000" Brown (iPhone PNG) + Jean-Marc Lienher (gif) Ben "Disch" Wenger (io callbacks) + Tom Seddon (pic) Omar Cornut (1/2/4-bit PNG) + Thatcher Ulrich (psd) Nicolas Guillemot (vertical flip) + Ken Miller (pgm, ppm) Richard Mitton (16-bit PSD) + urraka@github (animated gif) Junggon Kim (PNM comments) + Daniel Gibson (16-bit TGA) + + Optimizations & bugfixes + Fabian "ryg" Giesen + Arseny Kapoulkine + + Bug & warning fixes + Marc LeBlanc David Woo Guillaume George Martins Mozeiko + Christpher Lloyd Martin Golini Jerry Jansson Joseph Thomson + Dave Moore Roy Eltham Hayaki Saito Phil Jordan + Won Chun Luke Graham Johan Duparc Nathan Reed + the Horde3D community Thomas Ruf Ronny Chevalier Nick Verigakis + Janez Zemva John Bartholomew Michal Cichon svdijk@github + Jonathan Blow Ken Hamada Tero Hanninen Baldur Karlsson + Laurent Gomila Cort Stratton Sergio Gonzalez romigrou@github + Aruelien Pocheville Thibault Reuille Cass Everitt + Ryamond Barbiero Paul Du Bois Engin Manap + Blazej Dariusz Roszkowski + Michaelangel007@github + + +LICENSE + +This software is in the public domain. Where that dedication is not +recognized, you are granted a perpetual, irrevocable license to copy, +distribute, and modify this file as you see fit. + +*/ + +#ifndef STBI_INCLUDE_STB_IMAGE_H +#define STBI_INCLUDE_STB_IMAGE_H + +// DOCUMENTATION +// +// Limitations: +// - no 16-bit-per-channel PNG +// - no 12-bit-per-channel JPEG +// - no JPEGs with arithmetic coding +// - no 1-bit BMP +// - GIF always returns *comp=4 +// +// Basic usage (see HDR discussion below for HDR usage): +// int x,y,n; +// unsigned char *data = stbi_load(filename, &x, &y, &n, 0); +// // ... process data if not NULL ... +// // ... x = width, y = height, n = # 8-bit components per pixel ... +// // ... replace '0' with '1'..'4' to force that many components per pixel +// // ... but 'n' will always be the number that it would have been if you said 0 +// stbi_image_free(data) +// +// Standard parameters: +// int *x -- outputs image width in pixels +// int *y -- outputs image height in pixels +// int *comp -- outputs # of image components in image file +// int req_comp -- if non-zero, # of image components requested in result +// +// The return value from an image loader is an 'unsigned char *' which points +// to the pixel data, or NULL on an allocation failure or if the image is +// corrupt or invalid. The pixel data consists of *y scanlines of *x pixels, +// with each pixel consisting of N interleaved 8-bit components; the first +// pixel pointed to is top-left-most in the image. There is no padding between +// image scanlines or between pixels, regardless of format. The number of +// components N is 'req_comp' if req_comp is non-zero, or *comp otherwise. +// If req_comp is non-zero, *comp has the number of components that _would_ +// have been output otherwise. E.g. if you set req_comp to 4, you will always +// get RGBA output, but you can check *comp to see if it's trivially opaque +// because e.g. there were only 3 channels in the source image. +// +// An output image with N components has the following components interleaved +// in this order in each pixel: +// +// N=#comp components +// 1 grey +// 2 grey, alpha +// 3 red, green, blue +// 4 red, green, blue, alpha +// +// If image loading fails for any reason, the return value will be NULL, +// and *x, *y, *comp will be unchanged. The function stbi_failure_reason() +// can be queried for an extremely brief, end-user unfriendly explanation +// of why the load failed. Define STBI_NO_FAILURE_STRINGS to avoid +// compiling these strings at all, and STBI_FAILURE_USERMSG to get slightly +// more user-friendly ones. +// +// Paletted PNG, BMP, GIF, and PIC images are automatically depalettized. +// +// =========================================================================== +// +// Philosophy +// +// stb libraries are designed with the following priorities: +// +// 1. easy to use +// 2. easy to maintain +// 3. good performance +// +// Sometimes I let "good performance" creep up in priority over "easy to maintain", +// and for best performance I may provide less-easy-to-use APIs that give higher +// performance, in addition to the easy to use ones. Nevertheless, it's important +// to keep in mind that from the standpoint of you, a client of this library, +// all you care about is #1 and #3, and stb libraries do not emphasize #3 above all. +// +// Some secondary priorities arise directly from the first two, some of which +// make more explicit reasons why performance can't be emphasized. +// +// - Portable ("ease of use") +// - Small footprint ("easy to maintain") +// - No dependencies ("ease of use") +// +// =========================================================================== +// +// I/O callbacks +// +// I/O callbacks allow you to read from arbitrary sources, like packaged +// files or some other source. Data read from callbacks are processed +// through a small internal buffer (currently 128 bytes) to try to reduce +// overhead. +// +// The three functions you must define are "read" (reads some bytes of data), +// "skip" (skips some bytes of data), "eof" (reports if the stream is at the end). +// +// =========================================================================== +// +// SIMD support +// +// The JPEG decoder will try to automatically use SIMD kernels on x86 when +// supported by the compiler. For ARM Neon support, you must explicitly +// request it. +// +// (The old do-it-yourself SIMD API is no longer supported in the current +// code.) +// +// On x86, SSE2 will automatically be used when available based on a run-time +// test; if not, the generic C versions are used as a fall-back. On ARM targets, +// the typical path is to have separate builds for NEON and non-NEON devices +// (at least this is true for iOS and Android). Therefore, the NEON support is +// toggled by a build flag: define STBI_NEON to get NEON loops. +// +// The output of the JPEG decoder is slightly different from versions where +// SIMD support was introduced (that is, for versions before 1.49). The +// difference is only +-1 in the 8-bit RGB channels, and only on a small +// fraction of pixels. You can force the pre-1.49 behavior by defining +// STBI_JPEG_OLD, but this will disable some of the SIMD decoding path +// and hence cost some performance. +// +// If for some reason you do not want to use any of SIMD code, or if +// you have issues compiling it, you can disable it entirely by +// defining STBI_NO_SIMD. +// +// =========================================================================== +// +// HDR image support (disable by defining STBI_NO_HDR) +// +// stb_image now supports loading HDR images in general, and currently +// the Radiance .HDR file format, although the support is provided +// generically. You can still load any file through the existing interface; +// if you attempt to load an HDR file, it will be automatically remapped to +// LDR, assuming gamma 2.2 and an arbitrary scale factor defaulting to 1; +// both of these constants can be reconfigured through this interface: +// +// stbi_hdr_to_ldr_gamma(2.2f); +// stbi_hdr_to_ldr_scale(1.0f); +// +// (note, do not use _inverse_ constants; stbi_image will invert them +// appropriately). +// +// Additionally, there is a new, parallel interface for loading files as +// (linear) floats to preserve the full dynamic range: +// +// float *data = stbi_loadf(filename, &x, &y, &n, 0); +// +// If you load LDR images through this interface, those images will +// be promoted to floating point values, run through the inverse of +// constants corresponding to the above: +// +// stbi_ldr_to_hdr_scale(1.0f); +// stbi_ldr_to_hdr_gamma(2.2f); +// +// Finally, given a filename (or an open file or memory block--see header +// file for details) containing image data, you can query for the "most +// appropriate" interface to use (that is, whether the image is HDR or +// not), using: +// +// stbi_is_hdr(char *filename); +// +// =========================================================================== +// +// iPhone PNG support: +// +// By default we convert iphone-formatted PNGs back to RGB, even though +// they are internally encoded differently. You can disable this conversion +// by by calling stbi_convert_iphone_png_to_rgb(0), in which case +// you will always just get the native iphone "format" through (which +// is BGR stored in RGB). +// +// Call stbi_set_unpremultiply_on_load(1) as well to force a divide per +// pixel to remove any premultiplied alpha *only* if the image file explicitly +// says there's premultiplied data (currently only happens in iPhone images, +// and only if iPhone convert-to-rgb processing is on). +// + + +#ifndef STBI_NO_STDIO +#include +#endif // STBI_NO_STDIO + +#define STBI_VERSION 1 + +enum +{ + STBI_default = 0, // only used for req_comp + + STBI_grey = 1, + STBI_grey_alpha = 2, + STBI_rgb = 3, + STBI_rgb_alpha = 4 +}; + +typedef unsigned char stbi_uc; + +#ifdef __cplusplus +extern "C" { +#endif + +#ifdef STB_IMAGE_STATIC +#define STBIDEF static +#else +#define STBIDEF extern +#endif + +////////////////////////////////////////////////////////////////////////////// +// +// PRIMARY API - works on images of any type +// + +// +// load image by filename, open file, or memory buffer +// + +typedef struct +{ + int (*read) (void *user,char *data,int size); // fill 'data' with 'size' bytes. return number of bytes actually read + void (*skip) (void *user,int n); // skip the next 'n' bytes, or 'unget' the last -n bytes if negative + int (*eof) (void *user); // returns nonzero if we are at end of file/data +} stbi_io_callbacks; + +STBIDEF stbi_uc *stbi_load (char const *filename, int *x, int *y, int *comp, int req_comp); +STBIDEF stbi_uc *stbi_load_from_memory (stbi_uc const *buffer, int len , int *x, int *y, int *comp, int req_comp); +STBIDEF stbi_uc *stbi_load_from_callbacks(stbi_io_callbacks const *clbk , void *user, int *x, int *y, int *comp, int req_comp); + +#ifndef STBI_NO_STDIO +STBIDEF stbi_uc *stbi_load_from_file (FILE *f, int *x, int *y, int *comp, int req_comp); +// for stbi_load_from_file, file pointer is left pointing immediately after image +#endif + +#ifndef STBI_NO_LINEAR + STBIDEF float *stbi_loadf (char const *filename, int *x, int *y, int *comp, int req_comp); + STBIDEF float *stbi_loadf_from_memory (stbi_uc const *buffer, int len, int *x, int *y, int *comp, int req_comp); + STBIDEF float *stbi_loadf_from_callbacks (stbi_io_callbacks const *clbk, void *user, int *x, int *y, int *comp, int req_comp); + + #ifndef STBI_NO_STDIO + STBIDEF float *stbi_loadf_from_file (FILE *f, int *x, int *y, int *comp, int req_comp); + #endif +#endif + +#ifndef STBI_NO_HDR + STBIDEF void stbi_hdr_to_ldr_gamma(float gamma); + STBIDEF void stbi_hdr_to_ldr_scale(float scale); +#endif // STBI_NO_HDR + +#ifndef STBI_NO_LINEAR + STBIDEF void stbi_ldr_to_hdr_gamma(float gamma); + STBIDEF void stbi_ldr_to_hdr_scale(float scale); +#endif // STBI_NO_LINEAR + +// stbi_is_hdr is always defined, but always returns false if STBI_NO_HDR +STBIDEF int stbi_is_hdr_from_callbacks(stbi_io_callbacks const *clbk, void *user); +STBIDEF int stbi_is_hdr_from_memory(stbi_uc const *buffer, int len); +#ifndef STBI_NO_STDIO +STBIDEF int stbi_is_hdr (char const *filename); +STBIDEF int stbi_is_hdr_from_file(FILE *f); +#endif // STBI_NO_STDIO + + +// get a VERY brief reason for failure +// NOT THREADSAFE +STBIDEF const char *stbi_failure_reason (void); + +// free the loaded image -- this is just free() +STBIDEF void stbi_image_free (void *retval_from_stbi_load); + +// get image dimensions & components without fully decoding +STBIDEF int stbi_info_from_memory(stbi_uc const *buffer, int len, int *x, int *y, int *comp); +STBIDEF int stbi_info_from_callbacks(stbi_io_callbacks const *clbk, void *user, int *x, int *y, int *comp); + +#ifndef STBI_NO_STDIO +STBIDEF int stbi_info (char const *filename, int *x, int *y, int *comp); +STBIDEF int stbi_info_from_file (FILE *f, int *x, int *y, int *comp); + +#endif + + + +// for image formats that explicitly notate that they have premultiplied alpha, +// we just return the colors as stored in the file. set this flag to force +// unpremultiplication. results are undefined if the unpremultiply overflow. +STBIDEF void stbi_set_unpremultiply_on_load(int flag_true_if_should_unpremultiply); + +// indicate whether we should process iphone images back to canonical format, +// or just pass them through "as-is" +STBIDEF void stbi_convert_iphone_png_to_rgb(int flag_true_if_should_convert); + +// flip the image vertically, so the first pixel in the output array is the bottom left +STBIDEF void stbi_set_flip_vertically_on_load(int flag_true_if_should_flip); + +// ZLIB client - used by PNG, available for other purposes + +STBIDEF char *stbi_zlib_decode_malloc_guesssize(const char *buffer, int len, int initial_size, int *outlen); +STBIDEF char *stbi_zlib_decode_malloc_guesssize_headerflag(const char *buffer, int len, int initial_size, int *outlen, int parse_header); +STBIDEF char *stbi_zlib_decode_malloc(const char *buffer, int len, int *outlen); +STBIDEF int stbi_zlib_decode_buffer(char *obuffer, int olen, const char *ibuffer, int ilen); + +STBIDEF char *stbi_zlib_decode_noheader_malloc(const char *buffer, int len, int *outlen); +STBIDEF int stbi_zlib_decode_noheader_buffer(char *obuffer, int olen, const char *ibuffer, int ilen); + + +#ifdef __cplusplus +} +#endif + +// +// +//// end header file ///////////////////////////////////////////////////// +#endif // STBI_INCLUDE_STB_IMAGE_H + +#ifdef STB_IMAGE_IMPLEMENTATION + +#if defined(STBI_ONLY_JPEG) || defined(STBI_ONLY_PNG) || defined(STBI_ONLY_BMP) \ + || defined(STBI_ONLY_TGA) || defined(STBI_ONLY_GIF) || defined(STBI_ONLY_PSD) \ + || defined(STBI_ONLY_HDR) || defined(STBI_ONLY_PIC) || defined(STBI_ONLY_PNM) \ + || defined(STBI_ONLY_ZLIB) + #ifndef STBI_ONLY_JPEG + #define STBI_NO_JPEG + #endif + #ifndef STBI_ONLY_PNG + #define STBI_NO_PNG + #endif + #ifndef STBI_ONLY_BMP + #define STBI_NO_BMP + #endif + #ifndef STBI_ONLY_PSD + #define STBI_NO_PSD + #endif + #ifndef STBI_ONLY_TGA + #define STBI_NO_TGA + #endif + #ifndef STBI_ONLY_GIF + #define STBI_NO_GIF + #endif + #ifndef STBI_ONLY_HDR + #define STBI_NO_HDR + #endif + #ifndef STBI_ONLY_PIC + #define STBI_NO_PIC + #endif + #ifndef STBI_ONLY_PNM + #define STBI_NO_PNM + #endif +#endif + +#if defined(STBI_NO_PNG) && !defined(STBI_SUPPORT_ZLIB) && !defined(STBI_NO_ZLIB) +#define STBI_NO_ZLIB +#endif + + +#include +#include // ptrdiff_t on osx +#include +#include + +#if !defined(STBI_NO_LINEAR) || !defined(STBI_NO_HDR) +#include // ldexp +#endif + +#ifndef STBI_NO_STDIO +#include +#endif + +#ifndef STBI_ASSERT +#include +#define STBI_ASSERT(x) assert(x) +#endif + + +#ifndef _MSC_VER + #ifdef __cplusplus + #define stbi_inline inline + #else + #define stbi_inline + #endif +#else + #define stbi_inline __forceinline +#endif + + +#ifdef _MSC_VER +typedef unsigned short stbi__uint16; +typedef signed short stbi__int16; +typedef unsigned int stbi__uint32; +typedef signed int stbi__int32; +#else +#include +typedef uint16_t stbi__uint16; +typedef int16_t stbi__int16; +typedef uint32_t stbi__uint32; +typedef int32_t stbi__int32; +#endif + +// should produce compiler error if size is wrong +typedef unsigned char validate_uint32[sizeof(stbi__uint32)==4 ? 1 : -1]; + +#ifdef _MSC_VER +#define STBI_NOTUSED(v) (void)(v) +#else +#define STBI_NOTUSED(v) (void)sizeof(v) +#endif + +#ifdef _MSC_VER +#define STBI_HAS_LROTL +#endif + +#ifdef STBI_HAS_LROTL + #define stbi_lrot(x,y) _lrotl(x,y) +#else + #define stbi_lrot(x,y) (((x) << (y)) | ((x) >> (32 - (y)))) +#endif + +#if defined(STBI_MALLOC) && defined(STBI_FREE) && (defined(STBI_REALLOC) || defined(STBI_REALLOC_SIZED)) +// ok +#elif !defined(STBI_MALLOC) && !defined(STBI_FREE) && !defined(STBI_REALLOC) && !defined(STBI_REALLOC_SIZED) +// ok +#else +#error "Must define all or none of STBI_MALLOC, STBI_FREE, and STBI_REALLOC (or STBI_REALLOC_SIZED)." +#endif + +#ifndef STBI_MALLOC +#define STBI_MALLOC(sz) malloc(sz) +#define STBI_REALLOC(p,newsz) realloc(p,newsz) +#define STBI_FREE(p) free(p) +#endif + +#ifndef STBI_REALLOC_SIZED +#define STBI_REALLOC_SIZED(p,oldsz,newsz) STBI_REALLOC(p,newsz) +#endif + +// x86/x64 detection +#if defined(__x86_64__) || defined(_M_X64) +#define STBI__X64_TARGET +#elif defined(__i386) || defined(_M_IX86) +#define STBI__X86_TARGET +#endif + +#if defined(__GNUC__) && (defined(STBI__X86_TARGET) || defined(STBI__X64_TARGET)) && !defined(__SSE2__) && !defined(STBI_NO_SIMD) +// NOTE: not clear do we actually need this for the 64-bit path? +// gcc doesn't support sse2 intrinsics unless you compile with -msse2, +// (but compiling with -msse2 allows the compiler to use SSE2 everywhere; +// this is just broken and gcc are jerks for not fixing it properly +// http://www.virtualdub.org/blog/pivot/entry.php?id=363 ) +#define STBI_NO_SIMD +#endif + +#if defined(__MINGW32__) && defined(STBI__X86_TARGET) && !defined(STBI_MINGW_ENABLE_SSE2) && !defined(STBI_NO_SIMD) +// Note that __MINGW32__ doesn't actually mean 32-bit, so we have to avoid STBI__X64_TARGET +// +// 32-bit MinGW wants ESP to be 16-byte aligned, but this is not in the +// Windows ABI and VC++ as well as Windows DLLs don't maintain that invariant. +// As a result, enabling SSE2 on 32-bit MinGW is dangerous when not +// simultaneously enabling "-mstackrealign". +// +// See https://github.com/nothings/stb/issues/81 for more information. +// +// So default to no SSE2 on 32-bit MinGW. If you've read this far and added +// -mstackrealign to your build settings, feel free to #define STBI_MINGW_ENABLE_SSE2. +#define STBI_NO_SIMD +#endif + +#if !defined(STBI_NO_SIMD) && defined(STBI__X86_TARGET) +#define STBI_SSE2 +#include + +#ifdef _MSC_VER + +#if _MSC_VER >= 1400 // not VC6 +#include // __cpuid +static int stbi__cpuid3(void) +{ + int info[4]; + __cpuid(info,1); + return info[3]; +} +#else +static int stbi__cpuid3(void) +{ + int res; + __asm { + mov eax,1 + cpuid + mov res,edx + } + return res; +} +#endif + +#define STBI_SIMD_ALIGN(type, name) __declspec(align(16)) type name + +static int stbi__sse2_available() +{ + int info3 = stbi__cpuid3(); + return ((info3 >> 26) & 1) != 0; +} +#else // assume GCC-style if not VC++ +#define STBI_SIMD_ALIGN(type, name) type name __attribute__((aligned(16))) + +static int stbi__sse2_available() +{ +#if defined(__GNUC__) && (__GNUC__ * 100 + __GNUC_MINOR__) >= 408 // GCC 4.8 or later + // GCC 4.8+ has a nice way to do this + return __builtin_cpu_supports("sse2"); +#else + // portable way to do this, preferably without using GCC inline ASM? + // just bail for now. + return 0; +#endif +} +#endif +#endif + +// ARM NEON +#if defined(STBI_NO_SIMD) && defined(STBI_NEON) +#undef STBI_NEON +#endif + +#ifdef STBI_NEON +#include +// assume GCC or Clang on ARM targets +#define STBI_SIMD_ALIGN(type, name) type name __attribute__((aligned(16))) +#endif + +#ifndef STBI_SIMD_ALIGN +#define STBI_SIMD_ALIGN(type, name) type name +#endif + +/////////////////////////////////////////////// +// +// stbi__context struct and start_xxx functions + +// stbi__context structure is our basic context used by all images, so it +// contains all the IO context, plus some basic image information +typedef struct +{ + stbi__uint32 img_x, img_y; + int img_n, img_out_n; + + stbi_io_callbacks io; + void *io_user_data; + + int read_from_callbacks; + int buflen; + stbi_uc buffer_start[128]; + + stbi_uc *img_buffer, *img_buffer_end; + stbi_uc *img_buffer_original, *img_buffer_original_end; +} stbi__context; + + +static void stbi__refill_buffer(stbi__context *s); + +// initialize a memory-decode context +static void stbi__start_mem(stbi__context *s, stbi_uc const *buffer, int len) +{ + s->io.read = NULL; + s->read_from_callbacks = 0; + s->img_buffer = s->img_buffer_original = (stbi_uc *) buffer; + s->img_buffer_end = s->img_buffer_original_end = (stbi_uc *) buffer+len; +} + +// initialize a callback-based context +static void stbi__start_callbacks(stbi__context *s, stbi_io_callbacks *c, void *user) +{ + s->io = *c; + s->io_user_data = user; + s->buflen = sizeof(s->buffer_start); + s->read_from_callbacks = 1; + s->img_buffer_original = s->buffer_start; + stbi__refill_buffer(s); + s->img_buffer_original_end = s->img_buffer_end; +} + +#ifndef STBI_NO_STDIO + +static int stbi__stdio_read(void *user, char *data, int size) +{ + return (int) fread(data,1,size,(FILE*) user); +} + +static void stbi__stdio_skip(void *user, int n) +{ + fseek((FILE*) user, n, SEEK_CUR); +} + +static int stbi__stdio_eof(void *user) +{ + return feof((FILE*) user); +} + +static stbi_io_callbacks stbi__stdio_callbacks = +{ + stbi__stdio_read, + stbi__stdio_skip, + stbi__stdio_eof, +}; + +static void stbi__start_file(stbi__context *s, FILE *f) +{ + stbi__start_callbacks(s, &stbi__stdio_callbacks, (void *) f); +} + +//static void stop_file(stbi__context *s) { } + +#endif // !STBI_NO_STDIO + +static void stbi__rewind(stbi__context *s) +{ + // conceptually rewind SHOULD rewind to the beginning of the stream, + // but we just rewind to the beginning of the initial buffer, because + // we only use it after doing 'test', which only ever looks at at most 92 bytes + s->img_buffer = s->img_buffer_original; + s->img_buffer_end = s->img_buffer_original_end; +} + +#ifndef STBI_NO_JPEG +static int stbi__jpeg_test(stbi__context *s); +static stbi_uc *stbi__jpeg_load(stbi__context *s, int *x, int *y, int *comp, int req_comp); +static int stbi__jpeg_info(stbi__context *s, int *x, int *y, int *comp); +#endif + +#ifndef STBI_NO_PNG +static int stbi__png_test(stbi__context *s); +static stbi_uc *stbi__png_load(stbi__context *s, int *x, int *y, int *comp, int req_comp); +static int stbi__png_info(stbi__context *s, int *x, int *y, int *comp); +#endif + +#ifndef STBI_NO_BMP +static int stbi__bmp_test(stbi__context *s); +static stbi_uc *stbi__bmp_load(stbi__context *s, int *x, int *y, int *comp, int req_comp); +static int stbi__bmp_info(stbi__context *s, int *x, int *y, int *comp); +#endif + +#ifndef STBI_NO_TGA +static int stbi__tga_test(stbi__context *s); +static stbi_uc *stbi__tga_load(stbi__context *s, int *x, int *y, int *comp, int req_comp); +static int stbi__tga_info(stbi__context *s, int *x, int *y, int *comp); +#endif + +#ifndef STBI_NO_PSD +static int stbi__psd_test(stbi__context *s); +static stbi_uc *stbi__psd_load(stbi__context *s, int *x, int *y, int *comp, int req_comp); +static int stbi__psd_info(stbi__context *s, int *x, int *y, int *comp); +#endif + +#ifndef STBI_NO_HDR +static int stbi__hdr_test(stbi__context *s); +static float *stbi__hdr_load(stbi__context *s, int *x, int *y, int *comp, int req_comp); +static int stbi__hdr_info(stbi__context *s, int *x, int *y, int *comp); +#endif + +#ifndef STBI_NO_PIC +static int stbi__pic_test(stbi__context *s); +static stbi_uc *stbi__pic_load(stbi__context *s, int *x, int *y, int *comp, int req_comp); +static int stbi__pic_info(stbi__context *s, int *x, int *y, int *comp); +#endif + +#ifndef STBI_NO_GIF +static int stbi__gif_test(stbi__context *s); +static stbi_uc *stbi__gif_load(stbi__context *s, int *x, int *y, int *comp, int req_comp); +static int stbi__gif_info(stbi__context *s, int *x, int *y, int *comp); +#endif + +#ifndef STBI_NO_PNM +static int stbi__pnm_test(stbi__context *s); +static stbi_uc *stbi__pnm_load(stbi__context *s, int *x, int *y, int *comp, int req_comp); +static int stbi__pnm_info(stbi__context *s, int *x, int *y, int *comp); +#endif + +// this is not threadsafe +static const char *stbi__g_failure_reason; + +STBIDEF const char *stbi_failure_reason(void) +{ + return stbi__g_failure_reason; +} + +static int stbi__err(const char *str) +{ + stbi__g_failure_reason = str; + return 0; +} + +static void *stbi__malloc(size_t size) +{ + return STBI_MALLOC(size); +} + +// stbi__err - error +// stbi__errpf - error returning pointer to float +// stbi__errpuc - error returning pointer to unsigned char + +#ifdef STBI_NO_FAILURE_STRINGS + #define stbi__err(x,y) 0 +#elif defined(STBI_FAILURE_USERMSG) + #define stbi__err(x,y) stbi__err(y) +#else + #define stbi__err(x,y) stbi__err(x) +#endif + +#define stbi__errpf(x,y) ((float *)(size_t) (stbi__err(x,y)?NULL:NULL)) +#define stbi__errpuc(x,y) ((unsigned char *)(size_t) (stbi__err(x,y)?NULL:NULL)) + +STBIDEF void stbi_image_free(void *retval_from_stbi_load) +{ + STBI_FREE(retval_from_stbi_load); +} + +#ifndef STBI_NO_LINEAR +static float *stbi__ldr_to_hdr(stbi_uc *data, int x, int y, int comp); +#endif + +#ifndef STBI_NO_HDR +static stbi_uc *stbi__hdr_to_ldr(float *data, int x, int y, int comp); +#endif + +static int stbi__vertically_flip_on_load = 0; + +STBIDEF void stbi_set_flip_vertically_on_load(int flag_true_if_should_flip) +{ + stbi__vertically_flip_on_load = flag_true_if_should_flip; +} + +static unsigned char *stbi__load_main(stbi__context *s, int *x, int *y, int *comp, int req_comp) +{ + #ifndef STBI_NO_JPEG + if (stbi__jpeg_test(s)) return stbi__jpeg_load(s,x,y,comp,req_comp); + #endif + #ifndef STBI_NO_PNG + if (stbi__png_test(s)) return stbi__png_load(s,x,y,comp,req_comp); + #endif + #ifndef STBI_NO_BMP + if (stbi__bmp_test(s)) return stbi__bmp_load(s,x,y,comp,req_comp); + #endif + #ifndef STBI_NO_GIF + if (stbi__gif_test(s)) return stbi__gif_load(s,x,y,comp,req_comp); + #endif + #ifndef STBI_NO_PSD + if (stbi__psd_test(s)) return stbi__psd_load(s,x,y,comp,req_comp); + #endif + #ifndef STBI_NO_PIC + if (stbi__pic_test(s)) return stbi__pic_load(s,x,y,comp,req_comp); + #endif + #ifndef STBI_NO_PNM + if (stbi__pnm_test(s)) return stbi__pnm_load(s,x,y,comp,req_comp); + #endif + + #ifndef STBI_NO_HDR + if (stbi__hdr_test(s)) { + float *hdr = stbi__hdr_load(s, x,y,comp,req_comp); + return stbi__hdr_to_ldr(hdr, *x, *y, req_comp ? req_comp : *comp); + } + #endif + + #ifndef STBI_NO_TGA + // test tga last because it's a crappy test! + if (stbi__tga_test(s)) + return stbi__tga_load(s,x,y,comp,req_comp); + #endif + + return stbi__errpuc("unknown image type", "Image not of any known type, or corrupt"); +} + +static unsigned char *stbi__load_flip(stbi__context *s, int *x, int *y, int *comp, int req_comp) +{ + unsigned char *result = stbi__load_main(s, x, y, comp, req_comp); + + if (stbi__vertically_flip_on_load && result != NULL) { + int w = *x, h = *y; + int depth = req_comp ? req_comp : *comp; + int row,col,z; + stbi_uc temp; + + // @OPTIMIZE: use a bigger temp buffer and memcpy multiple pixels at once + for (row = 0; row < (h>>1); row++) { + for (col = 0; col < w; col++) { + for (z = 0; z < depth; z++) { + temp = result[(row * w + col) * depth + z]; + result[(row * w + col) * depth + z] = result[((h - row - 1) * w + col) * depth + z]; + result[((h - row - 1) * w + col) * depth + z] = temp; + } + } + } + } + + return result; +} + +#ifndef STBI_NO_HDR +static void stbi__float_postprocess(float *result, int *x, int *y, int *comp, int req_comp) +{ + if (stbi__vertically_flip_on_load && result != NULL) { + int w = *x, h = *y; + int depth = req_comp ? req_comp : *comp; + int row,col,z; + float temp; + + // @OPTIMIZE: use a bigger temp buffer and memcpy multiple pixels at once + for (row = 0; row < (h>>1); row++) { + for (col = 0; col < w; col++) { + for (z = 0; z < depth; z++) { + temp = result[(row * w + col) * depth + z]; + result[(row * w + col) * depth + z] = result[((h - row - 1) * w + col) * depth + z]; + result[((h - row - 1) * w + col) * depth + z] = temp; + } + } + } + } +} +#endif + +#ifndef STBI_NO_STDIO + +static FILE *stbi__fopen(char const *filename, char const *mode) +{ + FILE *f; +#if defined(_MSC_VER) && _MSC_VER >= 1400 + if (0 != fopen_s(&f, filename, mode)) + f=0; +#else + f = fopen(filename, mode); +#endif + return f; +} + + +STBIDEF stbi_uc *stbi_load(char const *filename, int *x, int *y, int *comp, int req_comp) +{ + FILE *f = stbi__fopen(filename, "rb"); + unsigned char *result; + if (!f) return stbi__errpuc("can't fopen", "Unable to open file"); + result = stbi_load_from_file(f,x,y,comp,req_comp); + fclose(f); + return result; +} + +STBIDEF stbi_uc *stbi_load_from_file(FILE *f, int *x, int *y, int *comp, int req_comp) +{ + unsigned char *result; + stbi__context s; + stbi__start_file(&s,f); + result = stbi__load_flip(&s,x,y,comp,req_comp); + if (result) { + // need to 'unget' all the characters in the IO buffer + fseek(f, - (int) (s.img_buffer_end - s.img_buffer), SEEK_CUR); + } + return result; +} +#endif //!STBI_NO_STDIO + +STBIDEF stbi_uc *stbi_load_from_memory(stbi_uc const *buffer, int len, int *x, int *y, int *comp, int req_comp) +{ + stbi__context s; + stbi__start_mem(&s,buffer,len); + return stbi__load_flip(&s,x,y,comp,req_comp); +} + +STBIDEF stbi_uc *stbi_load_from_callbacks(stbi_io_callbacks const *clbk, void *user, int *x, int *y, int *comp, int req_comp) +{ + stbi__context s; + stbi__start_callbacks(&s, (stbi_io_callbacks *) clbk, user); + return stbi__load_flip(&s,x,y,comp,req_comp); +} + +#ifndef STBI_NO_LINEAR +static float *stbi__loadf_main(stbi__context *s, int *x, int *y, int *comp, int req_comp) +{ + unsigned char *data; + #ifndef STBI_NO_HDR + if (stbi__hdr_test(s)) { + float *hdr_data = stbi__hdr_load(s,x,y,comp,req_comp); + if (hdr_data) + stbi__float_postprocess(hdr_data,x,y,comp,req_comp); + return hdr_data; + } + #endif + data = stbi__load_flip(s, x, y, comp, req_comp); + if (data) + return stbi__ldr_to_hdr(data, *x, *y, req_comp ? req_comp : *comp); + return stbi__errpf("unknown image type", "Image not of any known type, or corrupt"); +} + +STBIDEF float *stbi_loadf_from_memory(stbi_uc const *buffer, int len, int *x, int *y, int *comp, int req_comp) +{ + stbi__context s; + stbi__start_mem(&s,buffer,len); + return stbi__loadf_main(&s,x,y,comp,req_comp); +} + +STBIDEF float *stbi_loadf_from_callbacks(stbi_io_callbacks const *clbk, void *user, int *x, int *y, int *comp, int req_comp) +{ + stbi__context s; + stbi__start_callbacks(&s, (stbi_io_callbacks *) clbk, user); + return stbi__loadf_main(&s,x,y,comp,req_comp); +} + +#ifndef STBI_NO_STDIO +STBIDEF float *stbi_loadf(char const *filename, int *x, int *y, int *comp, int req_comp) +{ + float *result; + FILE *f = stbi__fopen(filename, "rb"); + if (!f) return stbi__errpf("can't fopen", "Unable to open file"); + result = stbi_loadf_from_file(f,x,y,comp,req_comp); + fclose(f); + return result; +} + +STBIDEF float *stbi_loadf_from_file(FILE *f, int *x, int *y, int *comp, int req_comp) +{ + stbi__context s; + stbi__start_file(&s,f); + return stbi__loadf_main(&s,x,y,comp,req_comp); +} +#endif // !STBI_NO_STDIO + +#endif // !STBI_NO_LINEAR + +// these is-hdr-or-not is defined independent of whether STBI_NO_LINEAR is +// defined, for API simplicity; if STBI_NO_LINEAR is defined, it always +// reports false! + +STBIDEF int stbi_is_hdr_from_memory(stbi_uc const *buffer, int len) +{ + #ifndef STBI_NO_HDR + stbi__context s; + stbi__start_mem(&s,buffer,len); + return stbi__hdr_test(&s); + #else + STBI_NOTUSED(buffer); + STBI_NOTUSED(len); + return 0; + #endif +} + +#ifndef STBI_NO_STDIO +STBIDEF int stbi_is_hdr (char const *filename) +{ + FILE *f = stbi__fopen(filename, "rb"); + int result=0; + if (f) { + result = stbi_is_hdr_from_file(f); + fclose(f); + } + return result; +} + +STBIDEF int stbi_is_hdr_from_file(FILE *f) +{ + #ifndef STBI_NO_HDR + stbi__context s; + stbi__start_file(&s,f); + return stbi__hdr_test(&s); + #else + STBI_NOTUSED(f); + return 0; + #endif +} +#endif // !STBI_NO_STDIO + +STBIDEF int stbi_is_hdr_from_callbacks(stbi_io_callbacks const *clbk, void *user) +{ + #ifndef STBI_NO_HDR + stbi__context s; + stbi__start_callbacks(&s, (stbi_io_callbacks *) clbk, user); + return stbi__hdr_test(&s); + #else + STBI_NOTUSED(clbk); + STBI_NOTUSED(user); + return 0; + #endif +} + +#ifndef STBI_NO_LINEAR +static float stbi__l2h_gamma=2.2f, stbi__l2h_scale=1.0f; + +STBIDEF void stbi_ldr_to_hdr_gamma(float gamma) { stbi__l2h_gamma = gamma; } +STBIDEF void stbi_ldr_to_hdr_scale(float scale) { stbi__l2h_scale = scale; } +#endif + +static float stbi__h2l_gamma_i=1.0f/2.2f, stbi__h2l_scale_i=1.0f; + +STBIDEF void stbi_hdr_to_ldr_gamma(float gamma) { stbi__h2l_gamma_i = 1/gamma; } +STBIDEF void stbi_hdr_to_ldr_scale(float scale) { stbi__h2l_scale_i = 1/scale; } + + +////////////////////////////////////////////////////////////////////////////// +// +// Common code used by all image loaders +// + +enum +{ + STBI__SCAN_load=0, + STBI__SCAN_type, + STBI__SCAN_header +}; + +static void stbi__refill_buffer(stbi__context *s) +{ + int n = (s->io.read)(s->io_user_data,(char*)s->buffer_start,s->buflen); + if (n == 0) { + // at end of file, treat same as if from memory, but need to handle case + // where s->img_buffer isn't pointing to safe memory, e.g. 0-byte file + s->read_from_callbacks = 0; + s->img_buffer = s->buffer_start; + s->img_buffer_end = s->buffer_start+1; + *s->img_buffer = 0; + } else { + s->img_buffer = s->buffer_start; + s->img_buffer_end = s->buffer_start + n; + } +} + +stbi_inline static stbi_uc stbi__get8(stbi__context *s) +{ + if (s->img_buffer < s->img_buffer_end) + return *s->img_buffer++; + if (s->read_from_callbacks) { + stbi__refill_buffer(s); + return *s->img_buffer++; + } + return 0; +} + +stbi_inline static int stbi__at_eof(stbi__context *s) +{ + if (s->io.read) { + if (!(s->io.eof)(s->io_user_data)) return 0; + // if feof() is true, check if buffer = end + // special case: we've only got the special 0 character at the end + if (s->read_from_callbacks == 0) return 1; + } + + return s->img_buffer >= s->img_buffer_end; +} + +static void stbi__skip(stbi__context *s, int n) +{ + if (n < 0) { + s->img_buffer = s->img_buffer_end; + return; + } + if (s->io.read) { + int blen = (int) (s->img_buffer_end - s->img_buffer); + if (blen < n) { + s->img_buffer = s->img_buffer_end; + (s->io.skip)(s->io_user_data, n - blen); + return; + } + } + s->img_buffer += n; +} + +static int stbi__getn(stbi__context *s, stbi_uc *buffer, int n) +{ + if (s->io.read) { + int blen = (int) (s->img_buffer_end - s->img_buffer); + if (blen < n) { + int res, count; + + memcpy(buffer, s->img_buffer, blen); + + count = (s->io.read)(s->io_user_data, (char*) buffer + blen, n - blen); + res = (count == (n-blen)); + s->img_buffer = s->img_buffer_end; + return res; + } + } + + if (s->img_buffer+n <= s->img_buffer_end) { + memcpy(buffer, s->img_buffer, n); + s->img_buffer += n; + return 1; + } else + return 0; +} + +static int stbi__get16be(stbi__context *s) +{ + int z = stbi__get8(s); + return (z << 8) + stbi__get8(s); +} + +static stbi__uint32 stbi__get32be(stbi__context *s) +{ + stbi__uint32 z = stbi__get16be(s); + return (z << 16) + stbi__get16be(s); +} + +#if defined(STBI_NO_BMP) && defined(STBI_NO_TGA) && defined(STBI_NO_GIF) +// nothing +#else +static int stbi__get16le(stbi__context *s) +{ + int z = stbi__get8(s); + return z + (stbi__get8(s) << 8); +} +#endif + +#ifndef STBI_NO_BMP +static stbi__uint32 stbi__get32le(stbi__context *s) +{ + stbi__uint32 z = stbi__get16le(s); + return z + (stbi__get16le(s) << 16); +} +#endif + +#define STBI__BYTECAST(x) ((stbi_uc) ((x) & 255)) // truncate int to byte without warnings + + +////////////////////////////////////////////////////////////////////////////// +// +// generic converter from built-in img_n to req_comp +// individual types do this automatically as much as possible (e.g. jpeg +// does all cases internally since it needs to colorspace convert anyway, +// and it never has alpha, so very few cases ). png can automatically +// interleave an alpha=255 channel, but falls back to this for other cases +// +// assume data buffer is malloced, so malloc a new one and free that one +// only failure mode is malloc failing + +static stbi_uc stbi__compute_y(int r, int g, int b) +{ + return (stbi_uc) (((r*77) + (g*150) + (29*b)) >> 8); +} + +static unsigned char *stbi__convert_format(unsigned char *data, int img_n, int req_comp, unsigned int x, unsigned int y) +{ + int i,j; + unsigned char *good; + + if (req_comp == img_n) return data; + STBI_ASSERT(req_comp >= 1 && req_comp <= 4); + + good = (unsigned char *) stbi__malloc(req_comp * x * y); + if (good == NULL) { + STBI_FREE(data); + return stbi__errpuc("outofmem", "Out of memory"); + } + + for (j=0; j < (int) y; ++j) { + unsigned char *src = data + j * x * img_n ; + unsigned char *dest = good + j * x * req_comp; + + #define COMBO(a,b) ((a)*8+(b)) + #define CASE(a,b) case COMBO(a,b): for(i=x-1; i >= 0; --i, src += a, dest += b) + // convert source image with img_n components to one with req_comp components; + // avoid switch per pixel, so use switch per scanline and massive macros + switch (COMBO(img_n, req_comp)) { + CASE(1,2) dest[0]=src[0], dest[1]=255; break; + CASE(1,3) dest[0]=dest[1]=dest[2]=src[0]; break; + CASE(1,4) dest[0]=dest[1]=dest[2]=src[0], dest[3]=255; break; + CASE(2,1) dest[0]=src[0]; break; + CASE(2,3) dest[0]=dest[1]=dest[2]=src[0]; break; + CASE(2,4) dest[0]=dest[1]=dest[2]=src[0], dest[3]=src[1]; break; + CASE(3,4) dest[0]=src[0],dest[1]=src[1],dest[2]=src[2],dest[3]=255; break; + CASE(3,1) dest[0]=stbi__compute_y(src[0],src[1],src[2]); break; + CASE(3,2) dest[0]=stbi__compute_y(src[0],src[1],src[2]), dest[1] = 255; break; + CASE(4,1) dest[0]=stbi__compute_y(src[0],src[1],src[2]); break; + CASE(4,2) dest[0]=stbi__compute_y(src[0],src[1],src[2]), dest[1] = src[3]; break; + CASE(4,3) dest[0]=src[0],dest[1]=src[1],dest[2]=src[2]; break; + default: STBI_ASSERT(0); + } + #undef CASE + } + + STBI_FREE(data); + return good; +} + +#ifndef STBI_NO_LINEAR +static float *stbi__ldr_to_hdr(stbi_uc *data, int x, int y, int comp) +{ + int i,k,n; + float *output = (float *) stbi__malloc(x * y * comp * sizeof(float)); + if (output == NULL) { STBI_FREE(data); return stbi__errpf("outofmem", "Out of memory"); } + // compute number of non-alpha components + if (comp & 1) n = comp; else n = comp-1; + for (i=0; i < x*y; ++i) { + for (k=0; k < n; ++k) { + output[i*comp + k] = (float) (pow(data[i*comp+k]/255.0f, stbi__l2h_gamma) * stbi__l2h_scale); + } + if (k < comp) output[i*comp + k] = data[i*comp+k]/255.0f; + } + STBI_FREE(data); + return output; +} +#endif + +#ifndef STBI_NO_HDR +#define stbi__float2int(x) ((int) (x)) +static stbi_uc *stbi__hdr_to_ldr(float *data, int x, int y, int comp) +{ + int i,k,n; + stbi_uc *output = (stbi_uc *) stbi__malloc(x * y * comp); + if (output == NULL) { STBI_FREE(data); return stbi__errpuc("outofmem", "Out of memory"); } + // compute number of non-alpha components + if (comp & 1) n = comp; else n = comp-1; + for (i=0; i < x*y; ++i) { + for (k=0; k < n; ++k) { + float z = (float) pow(data[i*comp+k]*stbi__h2l_scale_i, stbi__h2l_gamma_i) * 255 + 0.5f; + if (z < 0) z = 0; + if (z > 255) z = 255; + output[i*comp + k] = (stbi_uc) stbi__float2int(z); + } + if (k < comp) { + float z = data[i*comp+k] * 255 + 0.5f; + if (z < 0) z = 0; + if (z > 255) z = 255; + output[i*comp + k] = (stbi_uc) stbi__float2int(z); + } + } + STBI_FREE(data); + return output; +} +#endif + +////////////////////////////////////////////////////////////////////////////// +// +// "baseline" JPEG/JFIF decoder +// +// simple implementation +// - doesn't support delayed output of y-dimension +// - simple interface (only one output format: 8-bit interleaved RGB) +// - doesn't try to recover corrupt jpegs +// - doesn't allow partial loading, loading multiple at once +// - still fast on x86 (copying globals into locals doesn't help x86) +// - allocates lots of intermediate memory (full size of all components) +// - non-interleaved case requires this anyway +// - allows good upsampling (see next) +// high-quality +// - upsampled channels are bilinearly interpolated, even across blocks +// - quality integer IDCT derived from IJG's 'slow' +// performance +// - fast huffman; reasonable integer IDCT +// - some SIMD kernels for common paths on targets with SSE2/NEON +// - uses a lot of intermediate memory, could cache poorly + +#ifndef STBI_NO_JPEG + +// huffman decoding acceleration +#define FAST_BITS 9 // larger handles more cases; smaller stomps less cache + +typedef struct +{ + stbi_uc fast[1 << FAST_BITS]; + // weirdly, repacking this into AoS is a 10% speed loss, instead of a win + stbi__uint16 code[256]; + stbi_uc values[256]; + stbi_uc size[257]; + unsigned int maxcode[18]; + int delta[17]; // old 'firstsymbol' - old 'firstcode' +} stbi__huffman; + +typedef struct +{ + stbi__context *s; + stbi__huffman huff_dc[4]; + stbi__huffman huff_ac[4]; + stbi_uc dequant[4][64]; + stbi__int16 fast_ac[4][1 << FAST_BITS]; + +// sizes for components, interleaved MCUs + int img_h_max, img_v_max; + int img_mcu_x, img_mcu_y; + int img_mcu_w, img_mcu_h; + +// definition of jpeg image component + struct + { + int id; + int h,v; + int tq; + int hd,ha; + int dc_pred; + + int x,y,w2,h2; + stbi_uc *data; + void *raw_data, *raw_coeff; + stbi_uc *linebuf; + short *coeff; // progressive only + int coeff_w, coeff_h; // number of 8x8 coefficient blocks + } img_comp[4]; + + stbi__uint32 code_buffer; // jpeg entropy-coded buffer + int code_bits; // number of valid bits + unsigned char marker; // marker seen while filling entropy buffer + int nomore; // flag if we saw a marker so must stop + + int progressive; + int spec_start; + int spec_end; + int succ_high; + int succ_low; + int eob_run; + + int scan_n, order[4]; + int restart_interval, todo; + +// kernels + void (*idct_block_kernel)(stbi_uc *out, int out_stride, short data[64]); + void (*YCbCr_to_RGB_kernel)(stbi_uc *out, const stbi_uc *y, const stbi_uc *pcb, const stbi_uc *pcr, int count, int step); + stbi_uc *(*resample_row_hv_2_kernel)(stbi_uc *out, stbi_uc *in_near, stbi_uc *in_far, int w, int hs); +} stbi__jpeg; + +static int stbi__build_huffman(stbi__huffman *h, int *count) +{ + int i,j,k=0,code; + // build size list for each symbol (from JPEG spec) + for (i=0; i < 16; ++i) + for (j=0; j < count[i]; ++j) + h->size[k++] = (stbi_uc) (i+1); + h->size[k] = 0; + + // compute actual symbols (from jpeg spec) + code = 0; + k = 0; + for(j=1; j <= 16; ++j) { + // compute delta to add to code to compute symbol id + h->delta[j] = k - code; + if (h->size[k] == j) { + while (h->size[k] == j) + h->code[k++] = (stbi__uint16) (code++); + if (code-1 >= (1 << j)) return stbi__err("bad code lengths","Corrupt JPEG"); + } + // compute largest code + 1 for this size, preshifted as needed later + h->maxcode[j] = code << (16-j); + code <<= 1; + } + h->maxcode[j] = 0xffffffff; + + // build non-spec acceleration table; 255 is flag for not-accelerated + memset(h->fast, 255, 1 << FAST_BITS); + for (i=0; i < k; ++i) { + int s = h->size[i]; + if (s <= FAST_BITS) { + int c = h->code[i] << (FAST_BITS-s); + int m = 1 << (FAST_BITS-s); + for (j=0; j < m; ++j) { + h->fast[c+j] = (stbi_uc) i; + } + } + } + return 1; +} + +// build a table that decodes both magnitude and value of small ACs in +// one go. +static void stbi__build_fast_ac(stbi__int16 *fast_ac, stbi__huffman *h) +{ + int i; + for (i=0; i < (1 << FAST_BITS); ++i) { + stbi_uc fast = h->fast[i]; + fast_ac[i] = 0; + if (fast < 255) { + int rs = h->values[fast]; + int run = (rs >> 4) & 15; + int magbits = rs & 15; + int len = h->size[fast]; + + if (magbits && len + magbits <= FAST_BITS) { + // magnitude code followed by receive_extend code + int k = ((i << len) & ((1 << FAST_BITS) - 1)) >> (FAST_BITS - magbits); + int m = 1 << (magbits - 1); + if (k < m) k += (-1 << magbits) + 1; + // if the result is small enough, we can fit it in fast_ac table + if (k >= -128 && k <= 127) + fast_ac[i] = (stbi__int16) ((k << 8) + (run << 4) + (len + magbits)); + } + } + } +} + +static void stbi__grow_buffer_unsafe(stbi__jpeg *j) +{ + do { + int b = j->nomore ? 0 : stbi__get8(j->s); + if (b == 0xff) { + int c = stbi__get8(j->s); + if (c != 0) { + j->marker = (unsigned char) c; + j->nomore = 1; + return; + } + } + j->code_buffer |= b << (24 - j->code_bits); + j->code_bits += 8; + } while (j->code_bits <= 24); +} + +// (1 << n) - 1 +static stbi__uint32 stbi__bmask[17]={0,1,3,7,15,31,63,127,255,511,1023,2047,4095,8191,16383,32767,65535}; + +// decode a jpeg huffman value from the bitstream +stbi_inline static int stbi__jpeg_huff_decode(stbi__jpeg *j, stbi__huffman *h) +{ + unsigned int temp; + int c,k; + + if (j->code_bits < 16) stbi__grow_buffer_unsafe(j); + + // look at the top FAST_BITS and determine what symbol ID it is, + // if the code is <= FAST_BITS + c = (j->code_buffer >> (32 - FAST_BITS)) & ((1 << FAST_BITS)-1); + k = h->fast[c]; + if (k < 255) { + int s = h->size[k]; + if (s > j->code_bits) + return -1; + j->code_buffer <<= s; + j->code_bits -= s; + return h->values[k]; + } + + // naive test is to shift the code_buffer down so k bits are + // valid, then test against maxcode. To speed this up, we've + // preshifted maxcode left so that it has (16-k) 0s at the + // end; in other words, regardless of the number of bits, it + // wants to be compared against something shifted to have 16; + // that way we don't need to shift inside the loop. + temp = j->code_buffer >> 16; + for (k=FAST_BITS+1 ; ; ++k) + if (temp < h->maxcode[k]) + break; + if (k == 17) { + // error! code not found + j->code_bits -= 16; + return -1; + } + + if (k > j->code_bits) + return -1; + + // convert the huffman code to the symbol id + c = ((j->code_buffer >> (32 - k)) & stbi__bmask[k]) + h->delta[k]; + STBI_ASSERT((((j->code_buffer) >> (32 - h->size[c])) & stbi__bmask[h->size[c]]) == h->code[c]); + + // convert the id to a symbol + j->code_bits -= k; + j->code_buffer <<= k; + return h->values[c]; +} + +// bias[n] = (-1<code_bits < n) stbi__grow_buffer_unsafe(j); + + sgn = (stbi__int32)j->code_buffer >> 31; // sign bit is always in MSB + k = stbi_lrot(j->code_buffer, n); + STBI_ASSERT(n >= 0 && n < (int) (sizeof(stbi__bmask)/sizeof(*stbi__bmask))); + j->code_buffer = k & ~stbi__bmask[n]; + k &= stbi__bmask[n]; + j->code_bits -= n; + return k + (stbi__jbias[n] & ~sgn); +} + +// get some unsigned bits +stbi_inline static int stbi__jpeg_get_bits(stbi__jpeg *j, int n) +{ + unsigned int k; + if (j->code_bits < n) stbi__grow_buffer_unsafe(j); + k = stbi_lrot(j->code_buffer, n); + j->code_buffer = k & ~stbi__bmask[n]; + k &= stbi__bmask[n]; + j->code_bits -= n; + return k; +} + +stbi_inline static int stbi__jpeg_get_bit(stbi__jpeg *j) +{ + unsigned int k; + if (j->code_bits < 1) stbi__grow_buffer_unsafe(j); + k = j->code_buffer; + j->code_buffer <<= 1; + --j->code_bits; + return k & 0x80000000; +} + +// given a value that's at position X in the zigzag stream, +// where does it appear in the 8x8 matrix coded as row-major? +static stbi_uc stbi__jpeg_dezigzag[64+15] = +{ + 0, 1, 8, 16, 9, 2, 3, 10, + 17, 24, 32, 25, 18, 11, 4, 5, + 12, 19, 26, 33, 40, 48, 41, 34, + 27, 20, 13, 6, 7, 14, 21, 28, + 35, 42, 49, 56, 57, 50, 43, 36, + 29, 22, 15, 23, 30, 37, 44, 51, + 58, 59, 52, 45, 38, 31, 39, 46, + 53, 60, 61, 54, 47, 55, 62, 63, + // let corrupt input sample past end + 63, 63, 63, 63, 63, 63, 63, 63, + 63, 63, 63, 63, 63, 63, 63 +}; + +// decode one 64-entry block-- +static int stbi__jpeg_decode_block(stbi__jpeg *j, short data[64], stbi__huffman *hdc, stbi__huffman *hac, stbi__int16 *fac, int b, stbi_uc *dequant) +{ + int diff,dc,k; + int t; + + if (j->code_bits < 16) stbi__grow_buffer_unsafe(j); + t = stbi__jpeg_huff_decode(j, hdc); + if (t < 0) return stbi__err("bad huffman code","Corrupt JPEG"); + + // 0 all the ac values now so we can do it 32-bits at a time + memset(data,0,64*sizeof(data[0])); + + diff = t ? stbi__extend_receive(j, t) : 0; + dc = j->img_comp[b].dc_pred + diff; + j->img_comp[b].dc_pred = dc; + data[0] = (short) (dc * dequant[0]); + + // decode AC components, see JPEG spec + k = 1; + do { + unsigned int zig; + int c,r,s; + if (j->code_bits < 16) stbi__grow_buffer_unsafe(j); + c = (j->code_buffer >> (32 - FAST_BITS)) & ((1 << FAST_BITS)-1); + r = fac[c]; + if (r) { // fast-AC path + k += (r >> 4) & 15; // run + s = r & 15; // combined length + j->code_buffer <<= s; + j->code_bits -= s; + // decode into unzigzag'd location + zig = stbi__jpeg_dezigzag[k++]; + data[zig] = (short) ((r >> 8) * dequant[zig]); + } else { + int rs = stbi__jpeg_huff_decode(j, hac); + if (rs < 0) return stbi__err("bad huffman code","Corrupt JPEG"); + s = rs & 15; + r = rs >> 4; + if (s == 0) { + if (rs != 0xf0) break; // end block + k += 16; + } else { + k += r; + // decode into unzigzag'd location + zig = stbi__jpeg_dezigzag[k++]; + data[zig] = (short) (stbi__extend_receive(j,s) * dequant[zig]); + } + } + } while (k < 64); + return 1; +} + +static int stbi__jpeg_decode_block_prog_dc(stbi__jpeg *j, short data[64], stbi__huffman *hdc, int b) +{ + int diff,dc; + int t; + if (j->spec_end != 0) return stbi__err("can't merge dc and ac", "Corrupt JPEG"); + + if (j->code_bits < 16) stbi__grow_buffer_unsafe(j); + + if (j->succ_high == 0) { + // first scan for DC coefficient, must be first + memset(data,0,64*sizeof(data[0])); // 0 all the ac values now + t = stbi__jpeg_huff_decode(j, hdc); + diff = t ? stbi__extend_receive(j, t) : 0; + + dc = j->img_comp[b].dc_pred + diff; + j->img_comp[b].dc_pred = dc; + data[0] = (short) (dc << j->succ_low); + } else { + // refinement scan for DC coefficient + if (stbi__jpeg_get_bit(j)) + data[0] += (short) (1 << j->succ_low); + } + return 1; +} + +// @OPTIMIZE: store non-zigzagged during the decode passes, +// and only de-zigzag when dequantizing +static int stbi__jpeg_decode_block_prog_ac(stbi__jpeg *j, short data[64], stbi__huffman *hac, stbi__int16 *fac) +{ + int k; + if (j->spec_start == 0) return stbi__err("can't merge dc and ac", "Corrupt JPEG"); + + if (j->succ_high == 0) { + int shift = j->succ_low; + + if (j->eob_run) { + --j->eob_run; + return 1; + } + + k = j->spec_start; + do { + unsigned int zig; + int c,r,s; + if (j->code_bits < 16) stbi__grow_buffer_unsafe(j); + c = (j->code_buffer >> (32 - FAST_BITS)) & ((1 << FAST_BITS)-1); + r = fac[c]; + if (r) { // fast-AC path + k += (r >> 4) & 15; // run + s = r & 15; // combined length + j->code_buffer <<= s; + j->code_bits -= s; + zig = stbi__jpeg_dezigzag[k++]; + data[zig] = (short) ((r >> 8) << shift); + } else { + int rs = stbi__jpeg_huff_decode(j, hac); + if (rs < 0) return stbi__err("bad huffman code","Corrupt JPEG"); + s = rs & 15; + r = rs >> 4; + if (s == 0) { + if (r < 15) { + j->eob_run = (1 << r); + if (r) + j->eob_run += stbi__jpeg_get_bits(j, r); + --j->eob_run; + break; + } + k += 16; + } else { + k += r; + zig = stbi__jpeg_dezigzag[k++]; + data[zig] = (short) (stbi__extend_receive(j,s) << shift); + } + } + } while (k <= j->spec_end); + } else { + // refinement scan for these AC coefficients + + short bit = (short) (1 << j->succ_low); + + if (j->eob_run) { + --j->eob_run; + for (k = j->spec_start; k <= j->spec_end; ++k) { + short *p = &data[stbi__jpeg_dezigzag[k]]; + if (*p != 0) + if (stbi__jpeg_get_bit(j)) + if ((*p & bit)==0) { + if (*p > 0) + *p += bit; + else + *p -= bit; + } + } + } else { + k = j->spec_start; + do { + int r,s; + int rs = stbi__jpeg_huff_decode(j, hac); // @OPTIMIZE see if we can use the fast path here, advance-by-r is so slow, eh + if (rs < 0) return stbi__err("bad huffman code","Corrupt JPEG"); + s = rs & 15; + r = rs >> 4; + if (s == 0) { + if (r < 15) { + j->eob_run = (1 << r) - 1; + if (r) + j->eob_run += stbi__jpeg_get_bits(j, r); + r = 64; // force end of block + } else { + // r=15 s=0 should write 16 0s, so we just do + // a run of 15 0s and then write s (which is 0), + // so we don't have to do anything special here + } + } else { + if (s != 1) return stbi__err("bad huffman code", "Corrupt JPEG"); + // sign bit + if (stbi__jpeg_get_bit(j)) + s = bit; + else + s = -bit; + } + + // advance by r + while (k <= j->spec_end) { + short *p = &data[stbi__jpeg_dezigzag[k++]]; + if (*p != 0) { + if (stbi__jpeg_get_bit(j)) + if ((*p & bit)==0) { + if (*p > 0) + *p += bit; + else + *p -= bit; + } + } else { + if (r == 0) { + *p = (short) s; + break; + } + --r; + } + } + } while (k <= j->spec_end); + } + } + return 1; +} + +// take a -128..127 value and stbi__clamp it and convert to 0..255 +stbi_inline static stbi_uc stbi__clamp(int x) +{ + // trick to use a single test to catch both cases + if ((unsigned int) x > 255) { + if (x < 0) return 0; + if (x > 255) return 255; + } + return (stbi_uc) x; +} + +#define stbi__f2f(x) ((int) (((x) * 4096 + 0.5))) +#define stbi__fsh(x) ((x) << 12) + +// derived from jidctint -- DCT_ISLOW +#define STBI__IDCT_1D(s0,s1,s2,s3,s4,s5,s6,s7) \ + int t0,t1,t2,t3,p1,p2,p3,p4,p5,x0,x1,x2,x3; \ + p2 = s2; \ + p3 = s6; \ + p1 = (p2+p3) * stbi__f2f(0.5411961f); \ + t2 = p1 + p3*stbi__f2f(-1.847759065f); \ + t3 = p1 + p2*stbi__f2f( 0.765366865f); \ + p2 = s0; \ + p3 = s4; \ + t0 = stbi__fsh(p2+p3); \ + t1 = stbi__fsh(p2-p3); \ + x0 = t0+t3; \ + x3 = t0-t3; \ + x1 = t1+t2; \ + x2 = t1-t2; \ + t0 = s7; \ + t1 = s5; \ + t2 = s3; \ + t3 = s1; \ + p3 = t0+t2; \ + p4 = t1+t3; \ + p1 = t0+t3; \ + p2 = t1+t2; \ + p5 = (p3+p4)*stbi__f2f( 1.175875602f); \ + t0 = t0*stbi__f2f( 0.298631336f); \ + t1 = t1*stbi__f2f( 2.053119869f); \ + t2 = t2*stbi__f2f( 3.072711026f); \ + t3 = t3*stbi__f2f( 1.501321110f); \ + p1 = p5 + p1*stbi__f2f(-0.899976223f); \ + p2 = p5 + p2*stbi__f2f(-2.562915447f); \ + p3 = p3*stbi__f2f(-1.961570560f); \ + p4 = p4*stbi__f2f(-0.390180644f); \ + t3 += p1+p4; \ + t2 += p2+p3; \ + t1 += p2+p4; \ + t0 += p1+p3; + +static void stbi__idct_block(stbi_uc *out, int out_stride, short data[64]) +{ + int i,val[64],*v=val; + stbi_uc *o; + short *d = data; + + // columns + for (i=0; i < 8; ++i,++d, ++v) { + // if all zeroes, shortcut -- this avoids dequantizing 0s and IDCTing + if (d[ 8]==0 && d[16]==0 && d[24]==0 && d[32]==0 + && d[40]==0 && d[48]==0 && d[56]==0) { + // no shortcut 0 seconds + // (1|2|3|4|5|6|7)==0 0 seconds + // all separate -0.047 seconds + // 1 && 2|3 && 4|5 && 6|7: -0.047 seconds + int dcterm = d[0] << 2; + v[0] = v[8] = v[16] = v[24] = v[32] = v[40] = v[48] = v[56] = dcterm; + } else { + STBI__IDCT_1D(d[ 0],d[ 8],d[16],d[24],d[32],d[40],d[48],d[56]) + // constants scaled things up by 1<<12; let's bring them back + // down, but keep 2 extra bits of precision + x0 += 512; x1 += 512; x2 += 512; x3 += 512; + v[ 0] = (x0+t3) >> 10; + v[56] = (x0-t3) >> 10; + v[ 8] = (x1+t2) >> 10; + v[48] = (x1-t2) >> 10; + v[16] = (x2+t1) >> 10; + v[40] = (x2-t1) >> 10; + v[24] = (x3+t0) >> 10; + v[32] = (x3-t0) >> 10; + } + } + + for (i=0, v=val, o=out; i < 8; ++i,v+=8,o+=out_stride) { + // no fast case since the first 1D IDCT spread components out + STBI__IDCT_1D(v[0],v[1],v[2],v[3],v[4],v[5],v[6],v[7]) + // constants scaled things up by 1<<12, plus we had 1<<2 from first + // loop, plus horizontal and vertical each scale by sqrt(8) so together + // we've got an extra 1<<3, so 1<<17 total we need to remove. + // so we want to round that, which means adding 0.5 * 1<<17, + // aka 65536. Also, we'll end up with -128 to 127 that we want + // to encode as 0..255 by adding 128, so we'll add that before the shift + x0 += 65536 + (128<<17); + x1 += 65536 + (128<<17); + x2 += 65536 + (128<<17); + x3 += 65536 + (128<<17); + // tried computing the shifts into temps, or'ing the temps to see + // if any were out of range, but that was slower + o[0] = stbi__clamp((x0+t3) >> 17); + o[7] = stbi__clamp((x0-t3) >> 17); + o[1] = stbi__clamp((x1+t2) >> 17); + o[6] = stbi__clamp((x1-t2) >> 17); + o[2] = stbi__clamp((x2+t1) >> 17); + o[5] = stbi__clamp((x2-t1) >> 17); + o[3] = stbi__clamp((x3+t0) >> 17); + o[4] = stbi__clamp((x3-t0) >> 17); + } +} + +#ifdef STBI_SSE2 +// sse2 integer IDCT. not the fastest possible implementation but it +// produces bit-identical results to the generic C version so it's +// fully "transparent". +static void stbi__idct_simd(stbi_uc *out, int out_stride, short data[64]) +{ + // This is constructed to match our regular (generic) integer IDCT exactly. + __m128i row0, row1, row2, row3, row4, row5, row6, row7; + __m128i tmp; + + // dot product constant: even elems=x, odd elems=y + #define dct_const(x,y) _mm_setr_epi16((x),(y),(x),(y),(x),(y),(x),(y)) + + // out(0) = c0[even]*x + c0[odd]*y (c0, x, y 16-bit, out 32-bit) + // out(1) = c1[even]*x + c1[odd]*y + #define dct_rot(out0,out1, x,y,c0,c1) \ + __m128i c0##lo = _mm_unpacklo_epi16((x),(y)); \ + __m128i c0##hi = _mm_unpackhi_epi16((x),(y)); \ + __m128i out0##_l = _mm_madd_epi16(c0##lo, c0); \ + __m128i out0##_h = _mm_madd_epi16(c0##hi, c0); \ + __m128i out1##_l = _mm_madd_epi16(c0##lo, c1); \ + __m128i out1##_h = _mm_madd_epi16(c0##hi, c1) + + // out = in << 12 (in 16-bit, out 32-bit) + #define dct_widen(out, in) \ + __m128i out##_l = _mm_srai_epi32(_mm_unpacklo_epi16(_mm_setzero_si128(), (in)), 4); \ + __m128i out##_h = _mm_srai_epi32(_mm_unpackhi_epi16(_mm_setzero_si128(), (in)), 4) + + // wide add + #define dct_wadd(out, a, b) \ + __m128i out##_l = _mm_add_epi32(a##_l, b##_l); \ + __m128i out##_h = _mm_add_epi32(a##_h, b##_h) + + // wide sub + #define dct_wsub(out, a, b) \ + __m128i out##_l = _mm_sub_epi32(a##_l, b##_l); \ + __m128i out##_h = _mm_sub_epi32(a##_h, b##_h) + + // butterfly a/b, add bias, then shift by "s" and pack + #define dct_bfly32o(out0, out1, a,b,bias,s) \ + { \ + __m128i abiased_l = _mm_add_epi32(a##_l, bias); \ + __m128i abiased_h = _mm_add_epi32(a##_h, bias); \ + dct_wadd(sum, abiased, b); \ + dct_wsub(dif, abiased, b); \ + out0 = _mm_packs_epi32(_mm_srai_epi32(sum_l, s), _mm_srai_epi32(sum_h, s)); \ + out1 = _mm_packs_epi32(_mm_srai_epi32(dif_l, s), _mm_srai_epi32(dif_h, s)); \ + } + + // 8-bit interleave step (for transposes) + #define dct_interleave8(a, b) \ + tmp = a; \ + a = _mm_unpacklo_epi8(a, b); \ + b = _mm_unpackhi_epi8(tmp, b) + + // 16-bit interleave step (for transposes) + #define dct_interleave16(a, b) \ + tmp = a; \ + a = _mm_unpacklo_epi16(a, b); \ + b = _mm_unpackhi_epi16(tmp, b) + + #define dct_pass(bias,shift) \ + { \ + /* even part */ \ + dct_rot(t2e,t3e, row2,row6, rot0_0,rot0_1); \ + __m128i sum04 = _mm_add_epi16(row0, row4); \ + __m128i dif04 = _mm_sub_epi16(row0, row4); \ + dct_widen(t0e, sum04); \ + dct_widen(t1e, dif04); \ + dct_wadd(x0, t0e, t3e); \ + dct_wsub(x3, t0e, t3e); \ + dct_wadd(x1, t1e, t2e); \ + dct_wsub(x2, t1e, t2e); \ + /* odd part */ \ + dct_rot(y0o,y2o, row7,row3, rot2_0,rot2_1); \ + dct_rot(y1o,y3o, row5,row1, rot3_0,rot3_1); \ + __m128i sum17 = _mm_add_epi16(row1, row7); \ + __m128i sum35 = _mm_add_epi16(row3, row5); \ + dct_rot(y4o,y5o, sum17,sum35, rot1_0,rot1_1); \ + dct_wadd(x4, y0o, y4o); \ + dct_wadd(x5, y1o, y5o); \ + dct_wadd(x6, y2o, y5o); \ + dct_wadd(x7, y3o, y4o); \ + dct_bfly32o(row0,row7, x0,x7,bias,shift); \ + dct_bfly32o(row1,row6, x1,x6,bias,shift); \ + dct_bfly32o(row2,row5, x2,x5,bias,shift); \ + dct_bfly32o(row3,row4, x3,x4,bias,shift); \ + } + + __m128i rot0_0 = dct_const(stbi__f2f(0.5411961f), stbi__f2f(0.5411961f) + stbi__f2f(-1.847759065f)); + __m128i rot0_1 = dct_const(stbi__f2f(0.5411961f) + stbi__f2f( 0.765366865f), stbi__f2f(0.5411961f)); + __m128i rot1_0 = dct_const(stbi__f2f(1.175875602f) + stbi__f2f(-0.899976223f), stbi__f2f(1.175875602f)); + __m128i rot1_1 = dct_const(stbi__f2f(1.175875602f), stbi__f2f(1.175875602f) + stbi__f2f(-2.562915447f)); + __m128i rot2_0 = dct_const(stbi__f2f(-1.961570560f) + stbi__f2f( 0.298631336f), stbi__f2f(-1.961570560f)); + __m128i rot2_1 = dct_const(stbi__f2f(-1.961570560f), stbi__f2f(-1.961570560f) + stbi__f2f( 3.072711026f)); + __m128i rot3_0 = dct_const(stbi__f2f(-0.390180644f) + stbi__f2f( 2.053119869f), stbi__f2f(-0.390180644f)); + __m128i rot3_1 = dct_const(stbi__f2f(-0.390180644f), stbi__f2f(-0.390180644f) + stbi__f2f( 1.501321110f)); + + // rounding biases in column/row passes, see stbi__idct_block for explanation. + __m128i bias_0 = _mm_set1_epi32(512); + __m128i bias_1 = _mm_set1_epi32(65536 + (128<<17)); + + // load + row0 = _mm_load_si128((const __m128i *) (data + 0*8)); + row1 = _mm_load_si128((const __m128i *) (data + 1*8)); + row2 = _mm_load_si128((const __m128i *) (data + 2*8)); + row3 = _mm_load_si128((const __m128i *) (data + 3*8)); + row4 = _mm_load_si128((const __m128i *) (data + 4*8)); + row5 = _mm_load_si128((const __m128i *) (data + 5*8)); + row6 = _mm_load_si128((const __m128i *) (data + 6*8)); + row7 = _mm_load_si128((const __m128i *) (data + 7*8)); + + // column pass + dct_pass(bias_0, 10); + + { + // 16bit 8x8 transpose pass 1 + dct_interleave16(row0, row4); + dct_interleave16(row1, row5); + dct_interleave16(row2, row6); + dct_interleave16(row3, row7); + + // transpose pass 2 + dct_interleave16(row0, row2); + dct_interleave16(row1, row3); + dct_interleave16(row4, row6); + dct_interleave16(row5, row7); + + // transpose pass 3 + dct_interleave16(row0, row1); + dct_interleave16(row2, row3); + dct_interleave16(row4, row5); + dct_interleave16(row6, row7); + } + + // row pass + dct_pass(bias_1, 17); + + { + // pack + __m128i p0 = _mm_packus_epi16(row0, row1); // a0a1a2a3...a7b0b1b2b3...b7 + __m128i p1 = _mm_packus_epi16(row2, row3); + __m128i p2 = _mm_packus_epi16(row4, row5); + __m128i p3 = _mm_packus_epi16(row6, row7); + + // 8bit 8x8 transpose pass 1 + dct_interleave8(p0, p2); // a0e0a1e1... + dct_interleave8(p1, p3); // c0g0c1g1... + + // transpose pass 2 + dct_interleave8(p0, p1); // a0c0e0g0... + dct_interleave8(p2, p3); // b0d0f0h0... + + // transpose pass 3 + dct_interleave8(p0, p2); // a0b0c0d0... + dct_interleave8(p1, p3); // a4b4c4d4... + + // store + _mm_storel_epi64((__m128i *) out, p0); out += out_stride; + _mm_storel_epi64((__m128i *) out, _mm_shuffle_epi32(p0, 0x4e)); out += out_stride; + _mm_storel_epi64((__m128i *) out, p2); out += out_stride; + _mm_storel_epi64((__m128i *) out, _mm_shuffle_epi32(p2, 0x4e)); out += out_stride; + _mm_storel_epi64((__m128i *) out, p1); out += out_stride; + _mm_storel_epi64((__m128i *) out, _mm_shuffle_epi32(p1, 0x4e)); out += out_stride; + _mm_storel_epi64((__m128i *) out, p3); out += out_stride; + _mm_storel_epi64((__m128i *) out, _mm_shuffle_epi32(p3, 0x4e)); + } + +#undef dct_const +#undef dct_rot +#undef dct_widen +#undef dct_wadd +#undef dct_wsub +#undef dct_bfly32o +#undef dct_interleave8 +#undef dct_interleave16 +#undef dct_pass +} + +#endif // STBI_SSE2 + +#ifdef STBI_NEON + +// NEON integer IDCT. should produce bit-identical +// results to the generic C version. +static void stbi__idct_simd(stbi_uc *out, int out_stride, short data[64]) +{ + int16x8_t row0, row1, row2, row3, row4, row5, row6, row7; + + int16x4_t rot0_0 = vdup_n_s16(stbi__f2f(0.5411961f)); + int16x4_t rot0_1 = vdup_n_s16(stbi__f2f(-1.847759065f)); + int16x4_t rot0_2 = vdup_n_s16(stbi__f2f( 0.765366865f)); + int16x4_t rot1_0 = vdup_n_s16(stbi__f2f( 1.175875602f)); + int16x4_t rot1_1 = vdup_n_s16(stbi__f2f(-0.899976223f)); + int16x4_t rot1_2 = vdup_n_s16(stbi__f2f(-2.562915447f)); + int16x4_t rot2_0 = vdup_n_s16(stbi__f2f(-1.961570560f)); + int16x4_t rot2_1 = vdup_n_s16(stbi__f2f(-0.390180644f)); + int16x4_t rot3_0 = vdup_n_s16(stbi__f2f( 0.298631336f)); + int16x4_t rot3_1 = vdup_n_s16(stbi__f2f( 2.053119869f)); + int16x4_t rot3_2 = vdup_n_s16(stbi__f2f( 3.072711026f)); + int16x4_t rot3_3 = vdup_n_s16(stbi__f2f( 1.501321110f)); + +#define dct_long_mul(out, inq, coeff) \ + int32x4_t out##_l = vmull_s16(vget_low_s16(inq), coeff); \ + int32x4_t out##_h = vmull_s16(vget_high_s16(inq), coeff) + +#define dct_long_mac(out, acc, inq, coeff) \ + int32x4_t out##_l = vmlal_s16(acc##_l, vget_low_s16(inq), coeff); \ + int32x4_t out##_h = vmlal_s16(acc##_h, vget_high_s16(inq), coeff) + +#define dct_widen(out, inq) \ + int32x4_t out##_l = vshll_n_s16(vget_low_s16(inq), 12); \ + int32x4_t out##_h = vshll_n_s16(vget_high_s16(inq), 12) + +// wide add +#define dct_wadd(out, a, b) \ + int32x4_t out##_l = vaddq_s32(a##_l, b##_l); \ + int32x4_t out##_h = vaddq_s32(a##_h, b##_h) + +// wide sub +#define dct_wsub(out, a, b) \ + int32x4_t out##_l = vsubq_s32(a##_l, b##_l); \ + int32x4_t out##_h = vsubq_s32(a##_h, b##_h) + +// butterfly a/b, then shift using "shiftop" by "s" and pack +#define dct_bfly32o(out0,out1, a,b,shiftop,s) \ + { \ + dct_wadd(sum, a, b); \ + dct_wsub(dif, a, b); \ + out0 = vcombine_s16(shiftop(sum_l, s), shiftop(sum_h, s)); \ + out1 = vcombine_s16(shiftop(dif_l, s), shiftop(dif_h, s)); \ + } + +#define dct_pass(shiftop, shift) \ + { \ + /* even part */ \ + int16x8_t sum26 = vaddq_s16(row2, row6); \ + dct_long_mul(p1e, sum26, rot0_0); \ + dct_long_mac(t2e, p1e, row6, rot0_1); \ + dct_long_mac(t3e, p1e, row2, rot0_2); \ + int16x8_t sum04 = vaddq_s16(row0, row4); \ + int16x8_t dif04 = vsubq_s16(row0, row4); \ + dct_widen(t0e, sum04); \ + dct_widen(t1e, dif04); \ + dct_wadd(x0, t0e, t3e); \ + dct_wsub(x3, t0e, t3e); \ + dct_wadd(x1, t1e, t2e); \ + dct_wsub(x2, t1e, t2e); \ + /* odd part */ \ + int16x8_t sum15 = vaddq_s16(row1, row5); \ + int16x8_t sum17 = vaddq_s16(row1, row7); \ + int16x8_t sum35 = vaddq_s16(row3, row5); \ + int16x8_t sum37 = vaddq_s16(row3, row7); \ + int16x8_t sumodd = vaddq_s16(sum17, sum35); \ + dct_long_mul(p5o, sumodd, rot1_0); \ + dct_long_mac(p1o, p5o, sum17, rot1_1); \ + dct_long_mac(p2o, p5o, sum35, rot1_2); \ + dct_long_mul(p3o, sum37, rot2_0); \ + dct_long_mul(p4o, sum15, rot2_1); \ + dct_wadd(sump13o, p1o, p3o); \ + dct_wadd(sump24o, p2o, p4o); \ + dct_wadd(sump23o, p2o, p3o); \ + dct_wadd(sump14o, p1o, p4o); \ + dct_long_mac(x4, sump13o, row7, rot3_0); \ + dct_long_mac(x5, sump24o, row5, rot3_1); \ + dct_long_mac(x6, sump23o, row3, rot3_2); \ + dct_long_mac(x7, sump14o, row1, rot3_3); \ + dct_bfly32o(row0,row7, x0,x7,shiftop,shift); \ + dct_bfly32o(row1,row6, x1,x6,shiftop,shift); \ + dct_bfly32o(row2,row5, x2,x5,shiftop,shift); \ + dct_bfly32o(row3,row4, x3,x4,shiftop,shift); \ + } + + // load + row0 = vld1q_s16(data + 0*8); + row1 = vld1q_s16(data + 1*8); + row2 = vld1q_s16(data + 2*8); + row3 = vld1q_s16(data + 3*8); + row4 = vld1q_s16(data + 4*8); + row5 = vld1q_s16(data + 5*8); + row6 = vld1q_s16(data + 6*8); + row7 = vld1q_s16(data + 7*8); + + // add DC bias + row0 = vaddq_s16(row0, vsetq_lane_s16(1024, vdupq_n_s16(0), 0)); + + // column pass + dct_pass(vrshrn_n_s32, 10); + + // 16bit 8x8 transpose + { +// these three map to a single VTRN.16, VTRN.32, and VSWP, respectively. +// whether compilers actually get this is another story, sadly. +#define dct_trn16(x, y) { int16x8x2_t t = vtrnq_s16(x, y); x = t.val[0]; y = t.val[1]; } +#define dct_trn32(x, y) { int32x4x2_t t = vtrnq_s32(vreinterpretq_s32_s16(x), vreinterpretq_s32_s16(y)); x = vreinterpretq_s16_s32(t.val[0]); y = vreinterpretq_s16_s32(t.val[1]); } +#define dct_trn64(x, y) { int16x8_t x0 = x; int16x8_t y0 = y; x = vcombine_s16(vget_low_s16(x0), vget_low_s16(y0)); y = vcombine_s16(vget_high_s16(x0), vget_high_s16(y0)); } + + // pass 1 + dct_trn16(row0, row1); // a0b0a2b2a4b4a6b6 + dct_trn16(row2, row3); + dct_trn16(row4, row5); + dct_trn16(row6, row7); + + // pass 2 + dct_trn32(row0, row2); // a0b0c0d0a4b4c4d4 + dct_trn32(row1, row3); + dct_trn32(row4, row6); + dct_trn32(row5, row7); + + // pass 3 + dct_trn64(row0, row4); // a0b0c0d0e0f0g0h0 + dct_trn64(row1, row5); + dct_trn64(row2, row6); + dct_trn64(row3, row7); + +#undef dct_trn16 +#undef dct_trn32 +#undef dct_trn64 + } + + // row pass + // vrshrn_n_s32 only supports shifts up to 16, we need + // 17. so do a non-rounding shift of 16 first then follow + // up with a rounding shift by 1. + dct_pass(vshrn_n_s32, 16); + + { + // pack and round + uint8x8_t p0 = vqrshrun_n_s16(row0, 1); + uint8x8_t p1 = vqrshrun_n_s16(row1, 1); + uint8x8_t p2 = vqrshrun_n_s16(row2, 1); + uint8x8_t p3 = vqrshrun_n_s16(row3, 1); + uint8x8_t p4 = vqrshrun_n_s16(row4, 1); + uint8x8_t p5 = vqrshrun_n_s16(row5, 1); + uint8x8_t p6 = vqrshrun_n_s16(row6, 1); + uint8x8_t p7 = vqrshrun_n_s16(row7, 1); + + // again, these can translate into one instruction, but often don't. +#define dct_trn8_8(x, y) { uint8x8x2_t t = vtrn_u8(x, y); x = t.val[0]; y = t.val[1]; } +#define dct_trn8_16(x, y) { uint16x4x2_t t = vtrn_u16(vreinterpret_u16_u8(x), vreinterpret_u16_u8(y)); x = vreinterpret_u8_u16(t.val[0]); y = vreinterpret_u8_u16(t.val[1]); } +#define dct_trn8_32(x, y) { uint32x2x2_t t = vtrn_u32(vreinterpret_u32_u8(x), vreinterpret_u32_u8(y)); x = vreinterpret_u8_u32(t.val[0]); y = vreinterpret_u8_u32(t.val[1]); } + + // sadly can't use interleaved stores here since we only write + // 8 bytes to each scan line! + + // 8x8 8-bit transpose pass 1 + dct_trn8_8(p0, p1); + dct_trn8_8(p2, p3); + dct_trn8_8(p4, p5); + dct_trn8_8(p6, p7); + + // pass 2 + dct_trn8_16(p0, p2); + dct_trn8_16(p1, p3); + dct_trn8_16(p4, p6); + dct_trn8_16(p5, p7); + + // pass 3 + dct_trn8_32(p0, p4); + dct_trn8_32(p1, p5); + dct_trn8_32(p2, p6); + dct_trn8_32(p3, p7); + + // store + vst1_u8(out, p0); out += out_stride; + vst1_u8(out, p1); out += out_stride; + vst1_u8(out, p2); out += out_stride; + vst1_u8(out, p3); out += out_stride; + vst1_u8(out, p4); out += out_stride; + vst1_u8(out, p5); out += out_stride; + vst1_u8(out, p6); out += out_stride; + vst1_u8(out, p7); + +#undef dct_trn8_8 +#undef dct_trn8_16 +#undef dct_trn8_32 + } + +#undef dct_long_mul +#undef dct_long_mac +#undef dct_widen +#undef dct_wadd +#undef dct_wsub +#undef dct_bfly32o +#undef dct_pass +} + +#endif // STBI_NEON + +#define STBI__MARKER_none 0xff +// if there's a pending marker from the entropy stream, return that +// otherwise, fetch from the stream and get a marker. if there's no +// marker, return 0xff, which is never a valid marker value +static stbi_uc stbi__get_marker(stbi__jpeg *j) +{ + stbi_uc x; + if (j->marker != STBI__MARKER_none) { x = j->marker; j->marker = STBI__MARKER_none; return x; } + x = stbi__get8(j->s); + if (x != 0xff) return STBI__MARKER_none; + while (x == 0xff) + x = stbi__get8(j->s); + return x; +} + +// in each scan, we'll have scan_n components, and the order +// of the components is specified by order[] +#define STBI__RESTART(x) ((x) >= 0xd0 && (x) <= 0xd7) + +// after a restart interval, stbi__jpeg_reset the entropy decoder and +// the dc prediction +static void stbi__jpeg_reset(stbi__jpeg *j) +{ + j->code_bits = 0; + j->code_buffer = 0; + j->nomore = 0; + j->img_comp[0].dc_pred = j->img_comp[1].dc_pred = j->img_comp[2].dc_pred = 0; + j->marker = STBI__MARKER_none; + j->todo = j->restart_interval ? j->restart_interval : 0x7fffffff; + j->eob_run = 0; + // no more than 1<<31 MCUs if no restart_interal? that's plenty safe, + // since we don't even allow 1<<30 pixels +} + +static int stbi__parse_entropy_coded_data(stbi__jpeg *z) +{ + stbi__jpeg_reset(z); + if (!z->progressive) { + if (z->scan_n == 1) { + int i,j; + STBI_SIMD_ALIGN(short, data[64]); + int n = z->order[0]; + // non-interleaved data, we just need to process one block at a time, + // in trivial scanline order + // number of blocks to do just depends on how many actual "pixels" this + // component has, independent of interleaved MCU blocking and such + int w = (z->img_comp[n].x+7) >> 3; + int h = (z->img_comp[n].y+7) >> 3; + for (j=0; j < h; ++j) { + for (i=0; i < w; ++i) { + int ha = z->img_comp[n].ha; + if (!stbi__jpeg_decode_block(z, data, z->huff_dc+z->img_comp[n].hd, z->huff_ac+ha, z->fast_ac[ha], n, z->dequant[z->img_comp[n].tq])) return 0; + z->idct_block_kernel(z->img_comp[n].data+z->img_comp[n].w2*j*8+i*8, z->img_comp[n].w2, data); + // every data block is an MCU, so countdown the restart interval + if (--z->todo <= 0) { + if (z->code_bits < 24) stbi__grow_buffer_unsafe(z); + // if it's NOT a restart, then just bail, so we get corrupt data + // rather than no data + if (!STBI__RESTART(z->marker)) return 1; + stbi__jpeg_reset(z); + } + } + } + return 1; + } else { // interleaved + int i,j,k,x,y; + STBI_SIMD_ALIGN(short, data[64]); + for (j=0; j < z->img_mcu_y; ++j) { + for (i=0; i < z->img_mcu_x; ++i) { + // scan an interleaved mcu... process scan_n components in order + for (k=0; k < z->scan_n; ++k) { + int n = z->order[k]; + // scan out an mcu's worth of this component; that's just determined + // by the basic H and V specified for the component + for (y=0; y < z->img_comp[n].v; ++y) { + for (x=0; x < z->img_comp[n].h; ++x) { + int x2 = (i*z->img_comp[n].h + x)*8; + int y2 = (j*z->img_comp[n].v + y)*8; + int ha = z->img_comp[n].ha; + if (!stbi__jpeg_decode_block(z, data, z->huff_dc+z->img_comp[n].hd, z->huff_ac+ha, z->fast_ac[ha], n, z->dequant[z->img_comp[n].tq])) return 0; + z->idct_block_kernel(z->img_comp[n].data+z->img_comp[n].w2*y2+x2, z->img_comp[n].w2, data); + } + } + } + // after all interleaved components, that's an interleaved MCU, + // so now count down the restart interval + if (--z->todo <= 0) { + if (z->code_bits < 24) stbi__grow_buffer_unsafe(z); + if (!STBI__RESTART(z->marker)) return 1; + stbi__jpeg_reset(z); + } + } + } + return 1; + } + } else { + if (z->scan_n == 1) { + int i,j; + int n = z->order[0]; + // non-interleaved data, we just need to process one block at a time, + // in trivial scanline order + // number of blocks to do just depends on how many actual "pixels" this + // component has, independent of interleaved MCU blocking and such + int w = (z->img_comp[n].x+7) >> 3; + int h = (z->img_comp[n].y+7) >> 3; + for (j=0; j < h; ++j) { + for (i=0; i < w; ++i) { + short *data = z->img_comp[n].coeff + 64 * (i + j * z->img_comp[n].coeff_w); + if (z->spec_start == 0) { + if (!stbi__jpeg_decode_block_prog_dc(z, data, &z->huff_dc[z->img_comp[n].hd], n)) + return 0; + } else { + int ha = z->img_comp[n].ha; + if (!stbi__jpeg_decode_block_prog_ac(z, data, &z->huff_ac[ha], z->fast_ac[ha])) + return 0; + } + // every data block is an MCU, so countdown the restart interval + if (--z->todo <= 0) { + if (z->code_bits < 24) stbi__grow_buffer_unsafe(z); + if (!STBI__RESTART(z->marker)) return 1; + stbi__jpeg_reset(z); + } + } + } + return 1; + } else { // interleaved + int i,j,k,x,y; + for (j=0; j < z->img_mcu_y; ++j) { + for (i=0; i < z->img_mcu_x; ++i) { + // scan an interleaved mcu... process scan_n components in order + for (k=0; k < z->scan_n; ++k) { + int n = z->order[k]; + // scan out an mcu's worth of this component; that's just determined + // by the basic H and V specified for the component + for (y=0; y < z->img_comp[n].v; ++y) { + for (x=0; x < z->img_comp[n].h; ++x) { + int x2 = (i*z->img_comp[n].h + x); + int y2 = (j*z->img_comp[n].v + y); + short *data = z->img_comp[n].coeff + 64 * (x2 + y2 * z->img_comp[n].coeff_w); + if (!stbi__jpeg_decode_block_prog_dc(z, data, &z->huff_dc[z->img_comp[n].hd], n)) + return 0; + } + } + } + // after all interleaved components, that's an interleaved MCU, + // so now count down the restart interval + if (--z->todo <= 0) { + if (z->code_bits < 24) stbi__grow_buffer_unsafe(z); + if (!STBI__RESTART(z->marker)) return 1; + stbi__jpeg_reset(z); + } + } + } + return 1; + } + } +} + +static void stbi__jpeg_dequantize(short *data, stbi_uc *dequant) +{ + int i; + for (i=0; i < 64; ++i) + data[i] *= dequant[i]; +} + +static void stbi__jpeg_finish(stbi__jpeg *z) +{ + if (z->progressive) { + // dequantize and idct the data + int i,j,n; + for (n=0; n < z->s->img_n; ++n) { + int w = (z->img_comp[n].x+7) >> 3; + int h = (z->img_comp[n].y+7) >> 3; + for (j=0; j < h; ++j) { + for (i=0; i < w; ++i) { + short *data = z->img_comp[n].coeff + 64 * (i + j * z->img_comp[n].coeff_w); + stbi__jpeg_dequantize(data, z->dequant[z->img_comp[n].tq]); + z->idct_block_kernel(z->img_comp[n].data+z->img_comp[n].w2*j*8+i*8, z->img_comp[n].w2, data); + } + } + } + } +} + +static int stbi__process_marker(stbi__jpeg *z, int m) +{ + int L; + switch (m) { + case STBI__MARKER_none: // no marker found + return stbi__err("expected marker","Corrupt JPEG"); + + case 0xDD: // DRI - specify restart interval + if (stbi__get16be(z->s) != 4) return stbi__err("bad DRI len","Corrupt JPEG"); + z->restart_interval = stbi__get16be(z->s); + return 1; + + case 0xDB: // DQT - define quantization table + L = stbi__get16be(z->s)-2; + while (L > 0) { + int q = stbi__get8(z->s); + int p = q >> 4; + int t = q & 15,i; + if (p != 0) return stbi__err("bad DQT type","Corrupt JPEG"); + if (t > 3) return stbi__err("bad DQT table","Corrupt JPEG"); + for (i=0; i < 64; ++i) + z->dequant[t][stbi__jpeg_dezigzag[i]] = stbi__get8(z->s); + L -= 65; + } + return L==0; + + case 0xC4: // DHT - define huffman table + L = stbi__get16be(z->s)-2; + while (L > 0) { + stbi_uc *v; + int sizes[16],i,n=0; + int q = stbi__get8(z->s); + int tc = q >> 4; + int th = q & 15; + if (tc > 1 || th > 3) return stbi__err("bad DHT header","Corrupt JPEG"); + for (i=0; i < 16; ++i) { + sizes[i] = stbi__get8(z->s); + n += sizes[i]; + } + L -= 17; + if (tc == 0) { + if (!stbi__build_huffman(z->huff_dc+th, sizes)) return 0; + v = z->huff_dc[th].values; + } else { + if (!stbi__build_huffman(z->huff_ac+th, sizes)) return 0; + v = z->huff_ac[th].values; + } + for (i=0; i < n; ++i) + v[i] = stbi__get8(z->s); + if (tc != 0) + stbi__build_fast_ac(z->fast_ac[th], z->huff_ac + th); + L -= n; + } + return L==0; + } + // check for comment block or APP blocks + if ((m >= 0xE0 && m <= 0xEF) || m == 0xFE) { + stbi__skip(z->s, stbi__get16be(z->s)-2); + return 1; + } + return 0; +} + +// after we see SOS +static int stbi__process_scan_header(stbi__jpeg *z) +{ + int i; + int Ls = stbi__get16be(z->s); + z->scan_n = stbi__get8(z->s); + if (z->scan_n < 1 || z->scan_n > 4 || z->scan_n > (int) z->s->img_n) return stbi__err("bad SOS component count","Corrupt JPEG"); + if (Ls != 6+2*z->scan_n) return stbi__err("bad SOS len","Corrupt JPEG"); + for (i=0; i < z->scan_n; ++i) { + int id = stbi__get8(z->s), which; + int q = stbi__get8(z->s); + for (which = 0; which < z->s->img_n; ++which) + if (z->img_comp[which].id == id) + break; + if (which == z->s->img_n) return 0; // no match + z->img_comp[which].hd = q >> 4; if (z->img_comp[which].hd > 3) return stbi__err("bad DC huff","Corrupt JPEG"); + z->img_comp[which].ha = q & 15; if (z->img_comp[which].ha > 3) return stbi__err("bad AC huff","Corrupt JPEG"); + z->order[i] = which; + } + + { + int aa; + z->spec_start = stbi__get8(z->s); + z->spec_end = stbi__get8(z->s); // should be 63, but might be 0 + aa = stbi__get8(z->s); + z->succ_high = (aa >> 4); + z->succ_low = (aa & 15); + if (z->progressive) { + if (z->spec_start > 63 || z->spec_end > 63 || z->spec_start > z->spec_end || z->succ_high > 13 || z->succ_low > 13) + return stbi__err("bad SOS", "Corrupt JPEG"); + } else { + if (z->spec_start != 0) return stbi__err("bad SOS","Corrupt JPEG"); + if (z->succ_high != 0 || z->succ_low != 0) return stbi__err("bad SOS","Corrupt JPEG"); + z->spec_end = 63; + } + } + + return 1; +} + +static int stbi__process_frame_header(stbi__jpeg *z, int scan) +{ + stbi__context *s = z->s; + int Lf,p,i,q, h_max=1,v_max=1,c; + Lf = stbi__get16be(s); if (Lf < 11) return stbi__err("bad SOF len","Corrupt JPEG"); // JPEG + p = stbi__get8(s); if (p != 8) return stbi__err("only 8-bit","JPEG format not supported: 8-bit only"); // JPEG baseline + s->img_y = stbi__get16be(s); if (s->img_y == 0) return stbi__err("no header height", "JPEG format not supported: delayed height"); // Legal, but we don't handle it--but neither does IJG + s->img_x = stbi__get16be(s); if (s->img_x == 0) return stbi__err("0 width","Corrupt JPEG"); // JPEG requires + c = stbi__get8(s); + if (c != 3 && c != 1) return stbi__err("bad component count","Corrupt JPEG"); // JFIF requires + s->img_n = c; + for (i=0; i < c; ++i) { + z->img_comp[i].data = NULL; + z->img_comp[i].linebuf = NULL; + } + + if (Lf != 8+3*s->img_n) return stbi__err("bad SOF len","Corrupt JPEG"); + + for (i=0; i < s->img_n; ++i) { + z->img_comp[i].id = stbi__get8(s); + if (z->img_comp[i].id != i+1) // JFIF requires + if (z->img_comp[i].id != i) // some version of jpegtran outputs non-JFIF-compliant files! + return stbi__err("bad component ID","Corrupt JPEG"); + q = stbi__get8(s); + z->img_comp[i].h = (q >> 4); if (!z->img_comp[i].h || z->img_comp[i].h > 4) return stbi__err("bad H","Corrupt JPEG"); + z->img_comp[i].v = q & 15; if (!z->img_comp[i].v || z->img_comp[i].v > 4) return stbi__err("bad V","Corrupt JPEG"); + z->img_comp[i].tq = stbi__get8(s); if (z->img_comp[i].tq > 3) return stbi__err("bad TQ","Corrupt JPEG"); + } + + if (scan != STBI__SCAN_load) return 1; + + if ((1 << 30) / s->img_x / s->img_n < s->img_y) return stbi__err("too large", "Image too large to decode"); + + for (i=0; i < s->img_n; ++i) { + if (z->img_comp[i].h > h_max) h_max = z->img_comp[i].h; + if (z->img_comp[i].v > v_max) v_max = z->img_comp[i].v; + } + + // compute interleaved mcu info + z->img_h_max = h_max; + z->img_v_max = v_max; + z->img_mcu_w = h_max * 8; + z->img_mcu_h = v_max * 8; + z->img_mcu_x = (s->img_x + z->img_mcu_w-1) / z->img_mcu_w; + z->img_mcu_y = (s->img_y + z->img_mcu_h-1) / z->img_mcu_h; + + for (i=0; i < s->img_n; ++i) { + // number of effective pixels (e.g. for non-interleaved MCU) + z->img_comp[i].x = (s->img_x * z->img_comp[i].h + h_max-1) / h_max; + z->img_comp[i].y = (s->img_y * z->img_comp[i].v + v_max-1) / v_max; + // to simplify generation, we'll allocate enough memory to decode + // the bogus oversized data from using interleaved MCUs and their + // big blocks (e.g. a 16x16 iMCU on an image of width 33); we won't + // discard the extra data until colorspace conversion + z->img_comp[i].w2 = z->img_mcu_x * z->img_comp[i].h * 8; + z->img_comp[i].h2 = z->img_mcu_y * z->img_comp[i].v * 8; + z->img_comp[i].raw_data = stbi__malloc(z->img_comp[i].w2 * z->img_comp[i].h2+15); + + if (z->img_comp[i].raw_data == NULL) { + for(--i; i >= 0; --i) { + STBI_FREE(z->img_comp[i].raw_data); + z->img_comp[i].raw_data = NULL; + } + return stbi__err("outofmem", "Out of memory"); + } + // align blocks for idct using mmx/sse + z->img_comp[i].data = (stbi_uc*) (((size_t) z->img_comp[i].raw_data + 15) & ~15); + z->img_comp[i].linebuf = NULL; + if (z->progressive) { + z->img_comp[i].coeff_w = (z->img_comp[i].w2 + 7) >> 3; + z->img_comp[i].coeff_h = (z->img_comp[i].h2 + 7) >> 3; + z->img_comp[i].raw_coeff = STBI_MALLOC(z->img_comp[i].coeff_w * z->img_comp[i].coeff_h * 64 * sizeof(short) + 15); + z->img_comp[i].coeff = (short*) (((size_t) z->img_comp[i].raw_coeff + 15) & ~15); + } else { + z->img_comp[i].coeff = 0; + z->img_comp[i].raw_coeff = 0; + } + } + + return 1; +} + +// use comparisons since in some cases we handle more than one case (e.g. SOF) +#define stbi__DNL(x) ((x) == 0xdc) +#define stbi__SOI(x) ((x) == 0xd8) +#define stbi__EOI(x) ((x) == 0xd9) +#define stbi__SOF(x) ((x) == 0xc0 || (x) == 0xc1 || (x) == 0xc2) +#define stbi__SOS(x) ((x) == 0xda) + +#define stbi__SOF_progressive(x) ((x) == 0xc2) + +static int stbi__decode_jpeg_header(stbi__jpeg *z, int scan) +{ + int m; + z->marker = STBI__MARKER_none; // initialize cached marker to empty + m = stbi__get_marker(z); + if (!stbi__SOI(m)) return stbi__err("no SOI","Corrupt JPEG"); + if (scan == STBI__SCAN_type) return 1; + m = stbi__get_marker(z); + while (!stbi__SOF(m)) { + if (!stbi__process_marker(z,m)) return 0; + m = stbi__get_marker(z); + while (m == STBI__MARKER_none) { + // some files have extra padding after their blocks, so ok, we'll scan + if (stbi__at_eof(z->s)) return stbi__err("no SOF", "Corrupt JPEG"); + m = stbi__get_marker(z); + } + } + z->progressive = stbi__SOF_progressive(m); + if (!stbi__process_frame_header(z, scan)) return 0; + return 1; +} + +// decode image to YCbCr format +static int stbi__decode_jpeg_image(stbi__jpeg *j) +{ + int m; + for (m = 0; m < 4; m++) { + j->img_comp[m].raw_data = NULL; + j->img_comp[m].raw_coeff = NULL; + } + j->restart_interval = 0; + if (!stbi__decode_jpeg_header(j, STBI__SCAN_load)) return 0; + m = stbi__get_marker(j); + while (!stbi__EOI(m)) { + if (stbi__SOS(m)) { + if (!stbi__process_scan_header(j)) return 0; + if (!stbi__parse_entropy_coded_data(j)) return 0; + if (j->marker == STBI__MARKER_none ) { + // handle 0s at the end of image data from IP Kamera 9060 + while (!stbi__at_eof(j->s)) { + int x = stbi__get8(j->s); + if (x == 255) { + j->marker = stbi__get8(j->s); + break; + } else if (x != 0) { + return stbi__err("junk before marker", "Corrupt JPEG"); + } + } + // if we reach eof without hitting a marker, stbi__get_marker() below will fail and we'll eventually return 0 + } + } else { + if (!stbi__process_marker(j, m)) return 0; + } + m = stbi__get_marker(j); + } + if (j->progressive) + stbi__jpeg_finish(j); + return 1; +} + +// static jfif-centered resampling (across block boundaries) + +typedef stbi_uc *(*resample_row_func)(stbi_uc *out, stbi_uc *in0, stbi_uc *in1, + int w, int hs); + +#define stbi__div4(x) ((stbi_uc) ((x) >> 2)) + +static stbi_uc *resample_row_1(stbi_uc *out, stbi_uc *in_near, stbi_uc *in_far, int w, int hs) +{ + STBI_NOTUSED(out); + STBI_NOTUSED(in_far); + STBI_NOTUSED(w); + STBI_NOTUSED(hs); + return in_near; +} + +static stbi_uc* stbi__resample_row_v_2(stbi_uc *out, stbi_uc *in_near, stbi_uc *in_far, int w, int hs) +{ + // need to generate two samples vertically for every one in input + int i; + STBI_NOTUSED(hs); + for (i=0; i < w; ++i) + out[i] = stbi__div4(3*in_near[i] + in_far[i] + 2); + return out; +} + +static stbi_uc* stbi__resample_row_h_2(stbi_uc *out, stbi_uc *in_near, stbi_uc *in_far, int w, int hs) +{ + // need to generate two samples horizontally for every one in input + int i; + stbi_uc *input = in_near; + + if (w == 1) { + // if only one sample, can't do any interpolation + out[0] = out[1] = input[0]; + return out; + } + + out[0] = input[0]; + out[1] = stbi__div4(input[0]*3 + input[1] + 2); + for (i=1; i < w-1; ++i) { + int n = 3*input[i]+2; + out[i*2+0] = stbi__div4(n+input[i-1]); + out[i*2+1] = stbi__div4(n+input[i+1]); + } + out[i*2+0] = stbi__div4(input[w-2]*3 + input[w-1] + 2); + out[i*2+1] = input[w-1]; + + STBI_NOTUSED(in_far); + STBI_NOTUSED(hs); + + return out; +} + +#define stbi__div16(x) ((stbi_uc) ((x) >> 4)) + +static stbi_uc *stbi__resample_row_hv_2(stbi_uc *out, stbi_uc *in_near, stbi_uc *in_far, int w, int hs) +{ + // need to generate 2x2 samples for every one in input + int i,t0,t1; + if (w == 1) { + out[0] = out[1] = stbi__div4(3*in_near[0] + in_far[0] + 2); + return out; + } + + t1 = 3*in_near[0] + in_far[0]; + out[0] = stbi__div4(t1+2); + for (i=1; i < w; ++i) { + t0 = t1; + t1 = 3*in_near[i]+in_far[i]; + out[i*2-1] = stbi__div16(3*t0 + t1 + 8); + out[i*2 ] = stbi__div16(3*t1 + t0 + 8); + } + out[w*2-1] = stbi__div4(t1+2); + + STBI_NOTUSED(hs); + + return out; +} + +#if defined(STBI_SSE2) || defined(STBI_NEON) +static stbi_uc *stbi__resample_row_hv_2_simd(stbi_uc *out, stbi_uc *in_near, stbi_uc *in_far, int w, int hs) +{ + // need to generate 2x2 samples for every one in input + int i=0,t0,t1; + + if (w == 1) { + out[0] = out[1] = stbi__div4(3*in_near[0] + in_far[0] + 2); + return out; + } + + t1 = 3*in_near[0] + in_far[0]; + // process groups of 8 pixels for as long as we can. + // note we can't handle the last pixel in a row in this loop + // because we need to handle the filter boundary conditions. + for (; i < ((w-1) & ~7); i += 8) { +#if defined(STBI_SSE2) + // load and perform the vertical filtering pass + // this uses 3*x + y = 4*x + (y - x) + __m128i zero = _mm_setzero_si128(); + __m128i farb = _mm_loadl_epi64((__m128i *) (in_far + i)); + __m128i nearb = _mm_loadl_epi64((__m128i *) (in_near + i)); + __m128i farw = _mm_unpacklo_epi8(farb, zero); + __m128i nearw = _mm_unpacklo_epi8(nearb, zero); + __m128i diff = _mm_sub_epi16(farw, nearw); + __m128i nears = _mm_slli_epi16(nearw, 2); + __m128i curr = _mm_add_epi16(nears, diff); // current row + + // horizontal filter works the same based on shifted vers of current + // row. "prev" is current row shifted right by 1 pixel; we need to + // insert the previous pixel value (from t1). + // "next" is current row shifted left by 1 pixel, with first pixel + // of next block of 8 pixels added in. + __m128i prv0 = _mm_slli_si128(curr, 2); + __m128i nxt0 = _mm_srli_si128(curr, 2); + __m128i prev = _mm_insert_epi16(prv0, t1, 0); + __m128i next = _mm_insert_epi16(nxt0, 3*in_near[i+8] + in_far[i+8], 7); + + // horizontal filter, polyphase implementation since it's convenient: + // even pixels = 3*cur + prev = cur*4 + (prev - cur) + // odd pixels = 3*cur + next = cur*4 + (next - cur) + // note the shared term. + __m128i bias = _mm_set1_epi16(8); + __m128i curs = _mm_slli_epi16(curr, 2); + __m128i prvd = _mm_sub_epi16(prev, curr); + __m128i nxtd = _mm_sub_epi16(next, curr); + __m128i curb = _mm_add_epi16(curs, bias); + __m128i even = _mm_add_epi16(prvd, curb); + __m128i odd = _mm_add_epi16(nxtd, curb); + + // interleave even and odd pixels, then undo scaling. + __m128i int0 = _mm_unpacklo_epi16(even, odd); + __m128i int1 = _mm_unpackhi_epi16(even, odd); + __m128i de0 = _mm_srli_epi16(int0, 4); + __m128i de1 = _mm_srli_epi16(int1, 4); + + // pack and write output + __m128i outv = _mm_packus_epi16(de0, de1); + _mm_storeu_si128((__m128i *) (out + i*2), outv); +#elif defined(STBI_NEON) + // load and perform the vertical filtering pass + // this uses 3*x + y = 4*x + (y - x) + uint8x8_t farb = vld1_u8(in_far + i); + uint8x8_t nearb = vld1_u8(in_near + i); + int16x8_t diff = vreinterpretq_s16_u16(vsubl_u8(farb, nearb)); + int16x8_t nears = vreinterpretq_s16_u16(vshll_n_u8(nearb, 2)); + int16x8_t curr = vaddq_s16(nears, diff); // current row + + // horizontal filter works the same based on shifted vers of current + // row. "prev" is current row shifted right by 1 pixel; we need to + // insert the previous pixel value (from t1). + // "next" is current row shifted left by 1 pixel, with first pixel + // of next block of 8 pixels added in. + int16x8_t prv0 = vextq_s16(curr, curr, 7); + int16x8_t nxt0 = vextq_s16(curr, curr, 1); + int16x8_t prev = vsetq_lane_s16(t1, prv0, 0); + int16x8_t next = vsetq_lane_s16(3*in_near[i+8] + in_far[i+8], nxt0, 7); + + // horizontal filter, polyphase implementation since it's convenient: + // even pixels = 3*cur + prev = cur*4 + (prev - cur) + // odd pixels = 3*cur + next = cur*4 + (next - cur) + // note the shared term. + int16x8_t curs = vshlq_n_s16(curr, 2); + int16x8_t prvd = vsubq_s16(prev, curr); + int16x8_t nxtd = vsubq_s16(next, curr); + int16x8_t even = vaddq_s16(curs, prvd); + int16x8_t odd = vaddq_s16(curs, nxtd); + + // undo scaling and round, then store with even/odd phases interleaved + uint8x8x2_t o; + o.val[0] = vqrshrun_n_s16(even, 4); + o.val[1] = vqrshrun_n_s16(odd, 4); + vst2_u8(out + i*2, o); +#endif + + // "previous" value for next iter + t1 = 3*in_near[i+7] + in_far[i+7]; + } + + t0 = t1; + t1 = 3*in_near[i] + in_far[i]; + out[i*2] = stbi__div16(3*t1 + t0 + 8); + + for (++i; i < w; ++i) { + t0 = t1; + t1 = 3*in_near[i]+in_far[i]; + out[i*2-1] = stbi__div16(3*t0 + t1 + 8); + out[i*2 ] = stbi__div16(3*t1 + t0 + 8); + } + out[w*2-1] = stbi__div4(t1+2); + + STBI_NOTUSED(hs); + + return out; +} +#endif + +static stbi_uc *stbi__resample_row_generic(stbi_uc *out, stbi_uc *in_near, stbi_uc *in_far, int w, int hs) +{ + // resample with nearest-neighbor + int i,j; + STBI_NOTUSED(in_far); + for (i=0; i < w; ++i) + for (j=0; j < hs; ++j) + out[i*hs+j] = in_near[i]; + return out; +} + +#ifdef STBI_JPEG_OLD +// this is the same YCbCr-to-RGB calculation that stb_image has used +// historically before the algorithm changes in 1.49 +#define float2fixed(x) ((int) ((x) * 65536 + 0.5)) +static void stbi__YCbCr_to_RGB_row(stbi_uc *out, const stbi_uc *y, const stbi_uc *pcb, const stbi_uc *pcr, int count, int step) +{ + int i; + for (i=0; i < count; ++i) { + int y_fixed = (y[i] << 16) + 32768; // rounding + int r,g,b; + int cr = pcr[i] - 128; + int cb = pcb[i] - 128; + r = y_fixed + cr*float2fixed(1.40200f); + g = y_fixed - cr*float2fixed(0.71414f) - cb*float2fixed(0.34414f); + b = y_fixed + cb*float2fixed(1.77200f); + r >>= 16; + g >>= 16; + b >>= 16; + if ((unsigned) r > 255) { if (r < 0) r = 0; else r = 255; } + if ((unsigned) g > 255) { if (g < 0) g = 0; else g = 255; } + if ((unsigned) b > 255) { if (b < 0) b = 0; else b = 255; } + out[0] = (stbi_uc)r; + out[1] = (stbi_uc)g; + out[2] = (stbi_uc)b; + out[3] = 255; + out += step; + } +} +#else +// this is a reduced-precision calculation of YCbCr-to-RGB introduced +// to make sure the code produces the same results in both SIMD and scalar +#define float2fixed(x) (((int) ((x) * 4096.0f + 0.5f)) << 8) +static void stbi__YCbCr_to_RGB_row(stbi_uc *out, const stbi_uc *y, const stbi_uc *pcb, const stbi_uc *pcr, int count, int step) +{ + int i; + for (i=0; i < count; ++i) { + int y_fixed = (y[i] << 20) + (1<<19); // rounding + int r,g,b; + int cr = pcr[i] - 128; + int cb = pcb[i] - 128; + r = y_fixed + cr* float2fixed(1.40200f); + g = y_fixed + (cr*-float2fixed(0.71414f)) + ((cb*-float2fixed(0.34414f)) & 0xffff0000); + b = y_fixed + cb* float2fixed(1.77200f); + r >>= 20; + g >>= 20; + b >>= 20; + if ((unsigned) r > 255) { if (r < 0) r = 0; else r = 255; } + if ((unsigned) g > 255) { if (g < 0) g = 0; else g = 255; } + if ((unsigned) b > 255) { if (b < 0) b = 0; else b = 255; } + out[0] = (stbi_uc)r; + out[1] = (stbi_uc)g; + out[2] = (stbi_uc)b; + out[3] = 255; + out += step; + } +} +#endif + +#if defined(STBI_SSE2) || defined(STBI_NEON) +static void stbi__YCbCr_to_RGB_simd(stbi_uc *out, stbi_uc const *y, stbi_uc const *pcb, stbi_uc const *pcr, int count, int step) +{ + int i = 0; + +#ifdef STBI_SSE2 + // step == 3 is pretty ugly on the final interleave, and i'm not convinced + // it's useful in practice (you wouldn't use it for textures, for example). + // so just accelerate step == 4 case. + if (step == 4) { + // this is a fairly straightforward implementation and not super-optimized. + __m128i signflip = _mm_set1_epi8(-0x80); + __m128i cr_const0 = _mm_set1_epi16( (short) ( 1.40200f*4096.0f+0.5f)); + __m128i cr_const1 = _mm_set1_epi16( - (short) ( 0.71414f*4096.0f+0.5f)); + __m128i cb_const0 = _mm_set1_epi16( - (short) ( 0.34414f*4096.0f+0.5f)); + __m128i cb_const1 = _mm_set1_epi16( (short) ( 1.77200f*4096.0f+0.5f)); + __m128i y_bias = _mm_set1_epi8((char) (unsigned char) 128); + __m128i xw = _mm_set1_epi16(255); // alpha channel + + for (; i+7 < count; i += 8) { + // load + __m128i y_bytes = _mm_loadl_epi64((__m128i *) (y+i)); + __m128i cr_bytes = _mm_loadl_epi64((__m128i *) (pcr+i)); + __m128i cb_bytes = _mm_loadl_epi64((__m128i *) (pcb+i)); + __m128i cr_biased = _mm_xor_si128(cr_bytes, signflip); // -128 + __m128i cb_biased = _mm_xor_si128(cb_bytes, signflip); // -128 + + // unpack to short (and left-shift cr, cb by 8) + __m128i yw = _mm_unpacklo_epi8(y_bias, y_bytes); + __m128i crw = _mm_unpacklo_epi8(_mm_setzero_si128(), cr_biased); + __m128i cbw = _mm_unpacklo_epi8(_mm_setzero_si128(), cb_biased); + + // color transform + __m128i yws = _mm_srli_epi16(yw, 4); + __m128i cr0 = _mm_mulhi_epi16(cr_const0, crw); + __m128i cb0 = _mm_mulhi_epi16(cb_const0, cbw); + __m128i cb1 = _mm_mulhi_epi16(cbw, cb_const1); + __m128i cr1 = _mm_mulhi_epi16(crw, cr_const1); + __m128i rws = _mm_add_epi16(cr0, yws); + __m128i gwt = _mm_add_epi16(cb0, yws); + __m128i bws = _mm_add_epi16(yws, cb1); + __m128i gws = _mm_add_epi16(gwt, cr1); + + // descale + __m128i rw = _mm_srai_epi16(rws, 4); + __m128i bw = _mm_srai_epi16(bws, 4); + __m128i gw = _mm_srai_epi16(gws, 4); + + // back to byte, set up for transpose + __m128i brb = _mm_packus_epi16(rw, bw); + __m128i gxb = _mm_packus_epi16(gw, xw); + + // transpose to interleave channels + __m128i t0 = _mm_unpacklo_epi8(brb, gxb); + __m128i t1 = _mm_unpackhi_epi8(brb, gxb); + __m128i o0 = _mm_unpacklo_epi16(t0, t1); + __m128i o1 = _mm_unpackhi_epi16(t0, t1); + + // store + _mm_storeu_si128((__m128i *) (out + 0), o0); + _mm_storeu_si128((__m128i *) (out + 16), o1); + out += 32; + } + } +#endif + +#ifdef STBI_NEON + // in this version, step=3 support would be easy to add. but is there demand? + if (step == 4) { + // this is a fairly straightforward implementation and not super-optimized. + uint8x8_t signflip = vdup_n_u8(0x80); + int16x8_t cr_const0 = vdupq_n_s16( (short) ( 1.40200f*4096.0f+0.5f)); + int16x8_t cr_const1 = vdupq_n_s16( - (short) ( 0.71414f*4096.0f+0.5f)); + int16x8_t cb_const0 = vdupq_n_s16( - (short) ( 0.34414f*4096.0f+0.5f)); + int16x8_t cb_const1 = vdupq_n_s16( (short) ( 1.77200f*4096.0f+0.5f)); + + for (; i+7 < count; i += 8) { + // load + uint8x8_t y_bytes = vld1_u8(y + i); + uint8x8_t cr_bytes = vld1_u8(pcr + i); + uint8x8_t cb_bytes = vld1_u8(pcb + i); + int8x8_t cr_biased = vreinterpret_s8_u8(vsub_u8(cr_bytes, signflip)); + int8x8_t cb_biased = vreinterpret_s8_u8(vsub_u8(cb_bytes, signflip)); + + // expand to s16 + int16x8_t yws = vreinterpretq_s16_u16(vshll_n_u8(y_bytes, 4)); + int16x8_t crw = vshll_n_s8(cr_biased, 7); + int16x8_t cbw = vshll_n_s8(cb_biased, 7); + + // color transform + int16x8_t cr0 = vqdmulhq_s16(crw, cr_const0); + int16x8_t cb0 = vqdmulhq_s16(cbw, cb_const0); + int16x8_t cr1 = vqdmulhq_s16(crw, cr_const1); + int16x8_t cb1 = vqdmulhq_s16(cbw, cb_const1); + int16x8_t rws = vaddq_s16(yws, cr0); + int16x8_t gws = vaddq_s16(vaddq_s16(yws, cb0), cr1); + int16x8_t bws = vaddq_s16(yws, cb1); + + // undo scaling, round, convert to byte + uint8x8x4_t o; + o.val[0] = vqrshrun_n_s16(rws, 4); + o.val[1] = vqrshrun_n_s16(gws, 4); + o.val[2] = vqrshrun_n_s16(bws, 4); + o.val[3] = vdup_n_u8(255); + + // store, interleaving r/g/b/a + vst4_u8(out, o); + out += 8*4; + } + } +#endif + + for (; i < count; ++i) { + int y_fixed = (y[i] << 20) + (1<<19); // rounding + int r,g,b; + int cr = pcr[i] - 128; + int cb = pcb[i] - 128; + r = y_fixed + cr* float2fixed(1.40200f); + g = y_fixed + cr*-float2fixed(0.71414f) + ((cb*-float2fixed(0.34414f)) & 0xffff0000); + b = y_fixed + cb* float2fixed(1.77200f); + r >>= 20; + g >>= 20; + b >>= 20; + if ((unsigned) r > 255) { if (r < 0) r = 0; else r = 255; } + if ((unsigned) g > 255) { if (g < 0) g = 0; else g = 255; } + if ((unsigned) b > 255) { if (b < 0) b = 0; else b = 255; } + out[0] = (stbi_uc)r; + out[1] = (stbi_uc)g; + out[2] = (stbi_uc)b; + out[3] = 255; + out += step; + } +} +#endif + +// set up the kernels +static void stbi__setup_jpeg(stbi__jpeg *j) +{ + j->idct_block_kernel = stbi__idct_block; + j->YCbCr_to_RGB_kernel = stbi__YCbCr_to_RGB_row; + j->resample_row_hv_2_kernel = stbi__resample_row_hv_2; + +#ifdef STBI_SSE2 + if (stbi__sse2_available()) { + j->idct_block_kernel = stbi__idct_simd; + #ifndef STBI_JPEG_OLD + j->YCbCr_to_RGB_kernel = stbi__YCbCr_to_RGB_simd; + #endif + j->resample_row_hv_2_kernel = stbi__resample_row_hv_2_simd; + } +#endif + +#ifdef STBI_NEON + j->idct_block_kernel = stbi__idct_simd; + #ifndef STBI_JPEG_OLD + j->YCbCr_to_RGB_kernel = stbi__YCbCr_to_RGB_simd; + #endif + j->resample_row_hv_2_kernel = stbi__resample_row_hv_2_simd; +#endif +} + +// clean up the temporary component buffers +static void stbi__cleanup_jpeg(stbi__jpeg *j) +{ + int i; + for (i=0; i < j->s->img_n; ++i) { + if (j->img_comp[i].raw_data) { + STBI_FREE(j->img_comp[i].raw_data); + j->img_comp[i].raw_data = NULL; + j->img_comp[i].data = NULL; + } + if (j->img_comp[i].raw_coeff) { + STBI_FREE(j->img_comp[i].raw_coeff); + j->img_comp[i].raw_coeff = 0; + j->img_comp[i].coeff = 0; + } + if (j->img_comp[i].linebuf) { + STBI_FREE(j->img_comp[i].linebuf); + j->img_comp[i].linebuf = NULL; + } + } +} + +typedef struct +{ + resample_row_func resample; + stbi_uc *line0,*line1; + int hs,vs; // expansion factor in each axis + int w_lores; // horizontal pixels pre-expansion + int ystep; // how far through vertical expansion we are + int ypos; // which pre-expansion row we're on +} stbi__resample; + +static stbi_uc *load_jpeg_image(stbi__jpeg *z, int *out_x, int *out_y, int *comp, int req_comp) +{ + int n, decode_n; + z->s->img_n = 0; // make stbi__cleanup_jpeg safe + + // validate req_comp + if (req_comp < 0 || req_comp > 4) return stbi__errpuc("bad req_comp", "Internal error"); + + // load a jpeg image from whichever source, but leave in YCbCr format + if (!stbi__decode_jpeg_image(z)) { stbi__cleanup_jpeg(z); return NULL; } + + // determine actual number of components to generate + n = req_comp ? req_comp : z->s->img_n; + + if (z->s->img_n == 3 && n < 3) + decode_n = 1; + else + decode_n = z->s->img_n; + + // resample and color-convert + { + int k; + unsigned int i,j; + stbi_uc *output; + stbi_uc *coutput[4]; + + stbi__resample res_comp[4]; + + for (k=0; k < decode_n; ++k) { + stbi__resample *r = &res_comp[k]; + + // allocate line buffer big enough for upsampling off the edges + // with upsample factor of 4 + z->img_comp[k].linebuf = (stbi_uc *) stbi__malloc(z->s->img_x + 3); + if (!z->img_comp[k].linebuf) { stbi__cleanup_jpeg(z); return stbi__errpuc("outofmem", "Out of memory"); } + + r->hs = z->img_h_max / z->img_comp[k].h; + r->vs = z->img_v_max / z->img_comp[k].v; + r->ystep = r->vs >> 1; + r->w_lores = (z->s->img_x + r->hs-1) / r->hs; + r->ypos = 0; + r->line0 = r->line1 = z->img_comp[k].data; + + if (r->hs == 1 && r->vs == 1) r->resample = resample_row_1; + else if (r->hs == 1 && r->vs == 2) r->resample = stbi__resample_row_v_2; + else if (r->hs == 2 && r->vs == 1) r->resample = stbi__resample_row_h_2; + else if (r->hs == 2 && r->vs == 2) r->resample = z->resample_row_hv_2_kernel; + else r->resample = stbi__resample_row_generic; + } + + // can't error after this so, this is safe + output = (stbi_uc *) stbi__malloc(n * z->s->img_x * z->s->img_y + 1); + if (!output) { stbi__cleanup_jpeg(z); return stbi__errpuc("outofmem", "Out of memory"); } + + // now go ahead and resample + for (j=0; j < z->s->img_y; ++j) { + stbi_uc *out = output + n * z->s->img_x * j; + for (k=0; k < decode_n; ++k) { + stbi__resample *r = &res_comp[k]; + int y_bot = r->ystep >= (r->vs >> 1); + coutput[k] = r->resample(z->img_comp[k].linebuf, + y_bot ? r->line1 : r->line0, + y_bot ? r->line0 : r->line1, + r->w_lores, r->hs); + if (++r->ystep >= r->vs) { + r->ystep = 0; + r->line0 = r->line1; + if (++r->ypos < z->img_comp[k].y) + r->line1 += z->img_comp[k].w2; + } + } + if (n >= 3) { + stbi_uc *y = coutput[0]; + if (z->s->img_n == 3) { + z->YCbCr_to_RGB_kernel(out, y, coutput[1], coutput[2], z->s->img_x, n); + } else + for (i=0; i < z->s->img_x; ++i) { + out[0] = out[1] = out[2] = y[i]; + out[3] = 255; // not used if n==3 + out += n; + } + } else { + stbi_uc *y = coutput[0]; + if (n == 1) + for (i=0; i < z->s->img_x; ++i) out[i] = y[i]; + else + for (i=0; i < z->s->img_x; ++i) *out++ = y[i], *out++ = 255; + } + } + stbi__cleanup_jpeg(z); + *out_x = z->s->img_x; + *out_y = z->s->img_y; + if (comp) *comp = z->s->img_n; // report original components, not output + return output; + } +} + +static unsigned char *stbi__jpeg_load(stbi__context *s, int *x, int *y, int *comp, int req_comp) +{ + stbi__jpeg j; + j.s = s; + stbi__setup_jpeg(&j); + return load_jpeg_image(&j, x,y,comp,req_comp); +} + +static int stbi__jpeg_test(stbi__context *s) +{ + int r; + stbi__jpeg j; + j.s = s; + stbi__setup_jpeg(&j); + r = stbi__decode_jpeg_header(&j, STBI__SCAN_type); + stbi__rewind(s); + return r; +} + +static int stbi__jpeg_info_raw(stbi__jpeg *j, int *x, int *y, int *comp) +{ + if (!stbi__decode_jpeg_header(j, STBI__SCAN_header)) { + stbi__rewind( j->s ); + return 0; + } + if (x) *x = j->s->img_x; + if (y) *y = j->s->img_y; + if (comp) *comp = j->s->img_n; + return 1; +} + +static int stbi__jpeg_info(stbi__context *s, int *x, int *y, int *comp) +{ + stbi__jpeg j; + j.s = s; + return stbi__jpeg_info_raw(&j, x, y, comp); +} +#endif + +// public domain zlib decode v0.2 Sean Barrett 2006-11-18 +// simple implementation +// - all input must be provided in an upfront buffer +// - all output is written to a single output buffer (can malloc/realloc) +// performance +// - fast huffman + +#ifndef STBI_NO_ZLIB + +// fast-way is faster to check than jpeg huffman, but slow way is slower +#define STBI__ZFAST_BITS 9 // accelerate all cases in default tables +#define STBI__ZFAST_MASK ((1 << STBI__ZFAST_BITS) - 1) + +// zlib-style huffman encoding +// (jpegs packs from left, zlib from right, so can't share code) +typedef struct +{ + stbi__uint16 fast[1 << STBI__ZFAST_BITS]; + stbi__uint16 firstcode[16]; + int maxcode[17]; + stbi__uint16 firstsymbol[16]; + stbi_uc size[288]; + stbi__uint16 value[288]; +} stbi__zhuffman; + +stbi_inline static int stbi__bitreverse16(int n) +{ + n = ((n & 0xAAAA) >> 1) | ((n & 0x5555) << 1); + n = ((n & 0xCCCC) >> 2) | ((n & 0x3333) << 2); + n = ((n & 0xF0F0) >> 4) | ((n & 0x0F0F) << 4); + n = ((n & 0xFF00) >> 8) | ((n & 0x00FF) << 8); + return n; +} + +stbi_inline static int stbi__bit_reverse(int v, int bits) +{ + STBI_ASSERT(bits <= 16); + // to bit reverse n bits, reverse 16 and shift + // e.g. 11 bits, bit reverse and shift away 5 + return stbi__bitreverse16(v) >> (16-bits); +} + +static int stbi__zbuild_huffman(stbi__zhuffman *z, stbi_uc *sizelist, int num) +{ + int i,k=0; + int code, next_code[16], sizes[17]; + + // DEFLATE spec for generating codes + memset(sizes, 0, sizeof(sizes)); + memset(z->fast, 0, sizeof(z->fast)); + for (i=0; i < num; ++i) + ++sizes[sizelist[i]]; + sizes[0] = 0; + for (i=1; i < 16; ++i) + if (sizes[i] > (1 << i)) + return stbi__err("bad sizes", "Corrupt PNG"); + code = 0; + for (i=1; i < 16; ++i) { + next_code[i] = code; + z->firstcode[i] = (stbi__uint16) code; + z->firstsymbol[i] = (stbi__uint16) k; + code = (code + sizes[i]); + if (sizes[i]) + if (code-1 >= (1 << i)) return stbi__err("bad codelengths","Corrupt PNG"); + z->maxcode[i] = code << (16-i); // preshift for inner loop + code <<= 1; + k += sizes[i]; + } + z->maxcode[16] = 0x10000; // sentinel + for (i=0; i < num; ++i) { + int s = sizelist[i]; + if (s) { + int c = next_code[s] - z->firstcode[s] + z->firstsymbol[s]; + stbi__uint16 fastv = (stbi__uint16) ((s << 9) | i); + z->size [c] = (stbi_uc ) s; + z->value[c] = (stbi__uint16) i; + if (s <= STBI__ZFAST_BITS) { + int j = stbi__bit_reverse(next_code[s],s); + while (j < (1 << STBI__ZFAST_BITS)) { + z->fast[j] = fastv; + j += (1 << s); + } + } + ++next_code[s]; + } + } + return 1; +} + +// zlib-from-memory implementation for PNG reading +// because PNG allows splitting the zlib stream arbitrarily, +// and it's annoying structurally to have PNG call ZLIB call PNG, +// we require PNG read all the IDATs and combine them into a single +// memory buffer + +typedef struct +{ + stbi_uc *zbuffer, *zbuffer_end; + int num_bits; + stbi__uint32 code_buffer; + + char *zout; + char *zout_start; + char *zout_end; + int z_expandable; + + stbi__zhuffman z_length, z_distance; +} stbi__zbuf; + +stbi_inline static stbi_uc stbi__zget8(stbi__zbuf *z) +{ + if (z->zbuffer >= z->zbuffer_end) return 0; + return *z->zbuffer++; +} + +static void stbi__fill_bits(stbi__zbuf *z) +{ + do { + STBI_ASSERT(z->code_buffer < (1U << z->num_bits)); + z->code_buffer |= (unsigned int) stbi__zget8(z) << z->num_bits; + z->num_bits += 8; + } while (z->num_bits <= 24); +} + +stbi_inline static unsigned int stbi__zreceive(stbi__zbuf *z, int n) +{ + unsigned int k; + if (z->num_bits < n) stbi__fill_bits(z); + k = z->code_buffer & ((1 << n) - 1); + z->code_buffer >>= n; + z->num_bits -= n; + return k; +} + +static int stbi__zhuffman_decode_slowpath(stbi__zbuf *a, stbi__zhuffman *z) +{ + int b,s,k; + // not resolved by fast table, so compute it the slow way + // use jpeg approach, which requires MSbits at top + k = stbi__bit_reverse(a->code_buffer, 16); + for (s=STBI__ZFAST_BITS+1; ; ++s) + if (k < z->maxcode[s]) + break; + if (s == 16) return -1; // invalid code! + // code size is s, so: + b = (k >> (16-s)) - z->firstcode[s] + z->firstsymbol[s]; + STBI_ASSERT(z->size[b] == s); + a->code_buffer >>= s; + a->num_bits -= s; + return z->value[b]; +} + +stbi_inline static int stbi__zhuffman_decode(stbi__zbuf *a, stbi__zhuffman *z) +{ + int b,s; + if (a->num_bits < 16) stbi__fill_bits(a); + b = z->fast[a->code_buffer & STBI__ZFAST_MASK]; + if (b) { + s = b >> 9; + a->code_buffer >>= s; + a->num_bits -= s; + return b & 511; + } + return stbi__zhuffman_decode_slowpath(a, z); +} + +static int stbi__zexpand(stbi__zbuf *z, char *zout, int n) // need to make room for n bytes +{ + char *q; + int cur, limit, old_limit; + z->zout = zout; + if (!z->z_expandable) return stbi__err("output buffer limit","Corrupt PNG"); + cur = (int) (z->zout - z->zout_start); + limit = old_limit = (int) (z->zout_end - z->zout_start); + while (cur + n > limit) + limit *= 2; + q = (char *) STBI_REALLOC_SIZED(z->zout_start, old_limit, limit); + STBI_NOTUSED(old_limit); + if (q == NULL) return stbi__err("outofmem", "Out of memory"); + z->zout_start = q; + z->zout = q + cur; + z->zout_end = q + limit; + return 1; +} + +static int stbi__zlength_base[31] = { + 3,4,5,6,7,8,9,10,11,13, + 15,17,19,23,27,31,35,43,51,59, + 67,83,99,115,131,163,195,227,258,0,0 }; + +static int stbi__zlength_extra[31]= +{ 0,0,0,0,0,0,0,0,1,1,1,1,2,2,2,2,3,3,3,3,4,4,4,4,5,5,5,5,0,0,0 }; + +static int stbi__zdist_base[32] = { 1,2,3,4,5,7,9,13,17,25,33,49,65,97,129,193, +257,385,513,769,1025,1537,2049,3073,4097,6145,8193,12289,16385,24577,0,0}; + +static int stbi__zdist_extra[32] = +{ 0,0,0,0,1,1,2,2,3,3,4,4,5,5,6,6,7,7,8,8,9,9,10,10,11,11,12,12,13,13}; + +static int stbi__parse_huffman_block(stbi__zbuf *a) +{ + char *zout = a->zout; + for(;;) { + int z = stbi__zhuffman_decode(a, &a->z_length); + if (z < 256) { + if (z < 0) return stbi__err("bad huffman code","Corrupt PNG"); // error in huffman codes + if (zout >= a->zout_end) { + if (!stbi__zexpand(a, zout, 1)) return 0; + zout = a->zout; + } + *zout++ = (char) z; + } else { + stbi_uc *p; + int len,dist; + if (z == 256) { + a->zout = zout; + return 1; + } + z -= 257; + len = stbi__zlength_base[z]; + if (stbi__zlength_extra[z]) len += stbi__zreceive(a, stbi__zlength_extra[z]); + z = stbi__zhuffman_decode(a, &a->z_distance); + if (z < 0) return stbi__err("bad huffman code","Corrupt PNG"); + dist = stbi__zdist_base[z]; + if (stbi__zdist_extra[z]) dist += stbi__zreceive(a, stbi__zdist_extra[z]); + if (zout - a->zout_start < dist) return stbi__err("bad dist","Corrupt PNG"); + if (zout + len > a->zout_end) { + if (!stbi__zexpand(a, zout, len)) return 0; + zout = a->zout; + } + p = (stbi_uc *) (zout - dist); + if (dist == 1) { // run of one byte; common in images. + stbi_uc v = *p; + if (len) { do *zout++ = v; while (--len); } + } else { + if (len) { do *zout++ = *p++; while (--len); } + } + } + } +} + +static int stbi__compute_huffman_codes(stbi__zbuf *a) +{ + static stbi_uc length_dezigzag[19] = { 16,17,18,0,8,7,9,6,10,5,11,4,12,3,13,2,14,1,15 }; + stbi__zhuffman z_codelength; + stbi_uc lencodes[286+32+137];//padding for maximum single op + stbi_uc codelength_sizes[19]; + int i,n; + + int hlit = stbi__zreceive(a,5) + 257; + int hdist = stbi__zreceive(a,5) + 1; + int hclen = stbi__zreceive(a,4) + 4; + + memset(codelength_sizes, 0, sizeof(codelength_sizes)); + for (i=0; i < hclen; ++i) { + int s = stbi__zreceive(a,3); + codelength_sizes[length_dezigzag[i]] = (stbi_uc) s; + } + if (!stbi__zbuild_huffman(&z_codelength, codelength_sizes, 19)) return 0; + + n = 0; + while (n < hlit + hdist) { + int c = stbi__zhuffman_decode(a, &z_codelength); + if (c < 0 || c >= 19) return stbi__err("bad codelengths", "Corrupt PNG"); + if (c < 16) + lencodes[n++] = (stbi_uc) c; + else if (c == 16) { + c = stbi__zreceive(a,2)+3; + memset(lencodes+n, lencodes[n-1], c); + n += c; + } else if (c == 17) { + c = stbi__zreceive(a,3)+3; + memset(lencodes+n, 0, c); + n += c; + } else { + STBI_ASSERT(c == 18); + c = stbi__zreceive(a,7)+11; + memset(lencodes+n, 0, c); + n += c; + } + } + if (n != hlit+hdist) return stbi__err("bad codelengths","Corrupt PNG"); + if (!stbi__zbuild_huffman(&a->z_length, lencodes, hlit)) return 0; + if (!stbi__zbuild_huffman(&a->z_distance, lencodes+hlit, hdist)) return 0; + return 1; +} + +static int stbi__parse_uncomperssed_block(stbi__zbuf *a) +{ + stbi_uc header[4]; + int len,nlen,k; + if (a->num_bits & 7) + stbi__zreceive(a, a->num_bits & 7); // discard + // drain the bit-packed data into header + k = 0; + while (a->num_bits > 0) { + header[k++] = (stbi_uc) (a->code_buffer & 255); // suppress MSVC run-time check + a->code_buffer >>= 8; + a->num_bits -= 8; + } + STBI_ASSERT(a->num_bits == 0); + // now fill header the normal way + while (k < 4) + header[k++] = stbi__zget8(a); + len = header[1] * 256 + header[0]; + nlen = header[3] * 256 + header[2]; + if (nlen != (len ^ 0xffff)) return stbi__err("zlib corrupt","Corrupt PNG"); + if (a->zbuffer + len > a->zbuffer_end) return stbi__err("read past buffer","Corrupt PNG"); + if (a->zout + len > a->zout_end) + if (!stbi__zexpand(a, a->zout, len)) return 0; + memcpy(a->zout, a->zbuffer, len); + a->zbuffer += len; + a->zout += len; + return 1; +} + +static int stbi__parse_zlib_header(stbi__zbuf *a) +{ + int cmf = stbi__zget8(a); + int cm = cmf & 15; + /* int cinfo = cmf >> 4; */ + int flg = stbi__zget8(a); + if ((cmf*256+flg) % 31 != 0) return stbi__err("bad zlib header","Corrupt PNG"); // zlib spec + if (flg & 32) return stbi__err("no preset dict","Corrupt PNG"); // preset dictionary not allowed in png + if (cm != 8) return stbi__err("bad compression","Corrupt PNG"); // DEFLATE required for png + // window = 1 << (8 + cinfo)... but who cares, we fully buffer output + return 1; +} + +// @TODO: should statically initialize these for optimal thread safety +static stbi_uc stbi__zdefault_length[288], stbi__zdefault_distance[32]; +static void stbi__init_zdefaults(void) +{ + int i; // use <= to match clearly with spec + for (i=0; i <= 143; ++i) stbi__zdefault_length[i] = 8; + for ( ; i <= 255; ++i) stbi__zdefault_length[i] = 9; + for ( ; i <= 279; ++i) stbi__zdefault_length[i] = 7; + for ( ; i <= 287; ++i) stbi__zdefault_length[i] = 8; + + for (i=0; i <= 31; ++i) stbi__zdefault_distance[i] = 5; +} + +static int stbi__parse_zlib(stbi__zbuf *a, int parse_header) +{ + int final, type; + if (parse_header) + if (!stbi__parse_zlib_header(a)) return 0; + a->num_bits = 0; + a->code_buffer = 0; + do { + final = stbi__zreceive(a,1); + type = stbi__zreceive(a,2); + if (type == 0) { + if (!stbi__parse_uncomperssed_block(a)) return 0; + } else if (type == 3) { + return 0; + } else { + if (type == 1) { + // use fixed code lengths + if (!stbi__zdefault_distance[31]) stbi__init_zdefaults(); + if (!stbi__zbuild_huffman(&a->z_length , stbi__zdefault_length , 288)) return 0; + if (!stbi__zbuild_huffman(&a->z_distance, stbi__zdefault_distance, 32)) return 0; + } else { + if (!stbi__compute_huffman_codes(a)) return 0; + } + if (!stbi__parse_huffman_block(a)) return 0; + } + } while (!final); + return 1; +} + +static int stbi__do_zlib(stbi__zbuf *a, char *obuf, int olen, int exp, int parse_header) +{ + a->zout_start = obuf; + a->zout = obuf; + a->zout_end = obuf + olen; + a->z_expandable = exp; + + return stbi__parse_zlib(a, parse_header); +} + +STBIDEF char *stbi_zlib_decode_malloc_guesssize(const char *buffer, int len, int initial_size, int *outlen) +{ + stbi__zbuf a; + char *p = (char *) stbi__malloc(initial_size); + if (p == NULL) return NULL; + a.zbuffer = (stbi_uc *) buffer; + a.zbuffer_end = (stbi_uc *) buffer + len; + if (stbi__do_zlib(&a, p, initial_size, 1, 1)) { + if (outlen) *outlen = (int) (a.zout - a.zout_start); + return a.zout_start; + } else { + STBI_FREE(a.zout_start); + return NULL; + } +} + +STBIDEF char *stbi_zlib_decode_malloc(char const *buffer, int len, int *outlen) +{ + return stbi_zlib_decode_malloc_guesssize(buffer, len, 16384, outlen); +} + +STBIDEF char *stbi_zlib_decode_malloc_guesssize_headerflag(const char *buffer, int len, int initial_size, int *outlen, int parse_header) +{ + stbi__zbuf a; + char *p = (char *) stbi__malloc(initial_size); + if (p == NULL) return NULL; + a.zbuffer = (stbi_uc *) buffer; + a.zbuffer_end = (stbi_uc *) buffer + len; + if (stbi__do_zlib(&a, p, initial_size, 1, parse_header)) { + if (outlen) *outlen = (int) (a.zout - a.zout_start); + return a.zout_start; + } else { + STBI_FREE(a.zout_start); + return NULL; + } +} + +STBIDEF int stbi_zlib_decode_buffer(char *obuffer, int olen, char const *ibuffer, int ilen) +{ + stbi__zbuf a; + a.zbuffer = (stbi_uc *) ibuffer; + a.zbuffer_end = (stbi_uc *) ibuffer + ilen; + if (stbi__do_zlib(&a, obuffer, olen, 0, 1)) + return (int) (a.zout - a.zout_start); + else + return -1; +} + +STBIDEF char *stbi_zlib_decode_noheader_malloc(char const *buffer, int len, int *outlen) +{ + stbi__zbuf a; + char *p = (char *) stbi__malloc(16384); + if (p == NULL) return NULL; + a.zbuffer = (stbi_uc *) buffer; + a.zbuffer_end = (stbi_uc *) buffer+len; + if (stbi__do_zlib(&a, p, 16384, 1, 0)) { + if (outlen) *outlen = (int) (a.zout - a.zout_start); + return a.zout_start; + } else { + STBI_FREE(a.zout_start); + return NULL; + } +} + +STBIDEF int stbi_zlib_decode_noheader_buffer(char *obuffer, int olen, const char *ibuffer, int ilen) +{ + stbi__zbuf a; + a.zbuffer = (stbi_uc *) ibuffer; + a.zbuffer_end = (stbi_uc *) ibuffer + ilen; + if (stbi__do_zlib(&a, obuffer, olen, 0, 0)) + return (int) (a.zout - a.zout_start); + else + return -1; +} +#endif + +// public domain "baseline" PNG decoder v0.10 Sean Barrett 2006-11-18 +// simple implementation +// - only 8-bit samples +// - no CRC checking +// - allocates lots of intermediate memory +// - avoids problem of streaming data between subsystems +// - avoids explicit window management +// performance +// - uses stb_zlib, a PD zlib implementation with fast huffman decoding + +#ifndef STBI_NO_PNG +typedef struct +{ + stbi__uint32 length; + stbi__uint32 type; +} stbi__pngchunk; + +static stbi__pngchunk stbi__get_chunk_header(stbi__context *s) +{ + stbi__pngchunk c; + c.length = stbi__get32be(s); + c.type = stbi__get32be(s); + return c; +} + +static int stbi__check_png_header(stbi__context *s) +{ + static stbi_uc png_sig[8] = { 137,80,78,71,13,10,26,10 }; + int i; + for (i=0; i < 8; ++i) + if (stbi__get8(s) != png_sig[i]) return stbi__err("bad png sig","Not a PNG"); + return 1; +} + +typedef struct +{ + stbi__context *s; + stbi_uc *idata, *expanded, *out; +} stbi__png; + + +enum { + STBI__F_none=0, + STBI__F_sub=1, + STBI__F_up=2, + STBI__F_avg=3, + STBI__F_paeth=4, + // synthetic filters used for first scanline to avoid needing a dummy row of 0s + STBI__F_avg_first, + STBI__F_paeth_first +}; + +static stbi_uc first_row_filter[5] = +{ + STBI__F_none, + STBI__F_sub, + STBI__F_none, + STBI__F_avg_first, + STBI__F_paeth_first +}; + +static int stbi__paeth(int a, int b, int c) +{ + int p = a + b - c; + int pa = abs(p-a); + int pb = abs(p-b); + int pc = abs(p-c); + if (pa <= pb && pa <= pc) return a; + if (pb <= pc) return b; + return c; +} + +static stbi_uc stbi__depth_scale_table[9] = { 0, 0xff, 0x55, 0, 0x11, 0,0,0, 0x01 }; + +// create the png data from post-deflated data +static int stbi__create_png_image_raw(stbi__png *a, stbi_uc *raw, stbi__uint32 raw_len, int out_n, stbi__uint32 x, stbi__uint32 y, int depth, int color) +{ + stbi__context *s = a->s; + stbi__uint32 i,j,stride = x*out_n; + stbi__uint32 img_len, img_width_bytes; + int k; + int img_n = s->img_n; // copy it into a local for later + + STBI_ASSERT(out_n == s->img_n || out_n == s->img_n+1); + a->out = (stbi_uc *) stbi__malloc(x * y * out_n); // extra bytes to write off the end into + if (!a->out) return stbi__err("outofmem", "Out of memory"); + + img_width_bytes = (((img_n * x * depth) + 7) >> 3); + img_len = (img_width_bytes + 1) * y; + if (s->img_x == x && s->img_y == y) { + if (raw_len != img_len) return stbi__err("not enough pixels","Corrupt PNG"); + } else { // interlaced: + if (raw_len < img_len) return stbi__err("not enough pixels","Corrupt PNG"); + } + + for (j=0; j < y; ++j) { + stbi_uc *cur = a->out + stride*j; + stbi_uc *prior = cur - stride; + int filter = *raw++; + int filter_bytes = img_n; + int width = x; + if (filter > 4) + return stbi__err("invalid filter","Corrupt PNG"); + + if (depth < 8) { + STBI_ASSERT(img_width_bytes <= x); + cur += x*out_n - img_width_bytes; // store output to the rightmost img_len bytes, so we can decode in place + filter_bytes = 1; + width = img_width_bytes; + } + + // if first row, use special filter that doesn't sample previous row + if (j == 0) filter = first_row_filter[filter]; + + // handle first byte explicitly + for (k=0; k < filter_bytes; ++k) { + switch (filter) { + case STBI__F_none : cur[k] = raw[k]; break; + case STBI__F_sub : cur[k] = raw[k]; break; + case STBI__F_up : cur[k] = STBI__BYTECAST(raw[k] + prior[k]); break; + case STBI__F_avg : cur[k] = STBI__BYTECAST(raw[k] + (prior[k]>>1)); break; + case STBI__F_paeth : cur[k] = STBI__BYTECAST(raw[k] + stbi__paeth(0,prior[k],0)); break; + case STBI__F_avg_first : cur[k] = raw[k]; break; + case STBI__F_paeth_first: cur[k] = raw[k]; break; + } + } + + if (depth == 8) { + if (img_n != out_n) + cur[img_n] = 255; // first pixel + raw += img_n; + cur += out_n; + prior += out_n; + } else { + raw += 1; + cur += 1; + prior += 1; + } + + // this is a little gross, so that we don't switch per-pixel or per-component + if (depth < 8 || img_n == out_n) { + int nk = (width - 1)*img_n; + #define CASE(f) \ + case f: \ + for (k=0; k < nk; ++k) + switch (filter) { + // "none" filter turns into a memcpy here; make that explicit. + case STBI__F_none: memcpy(cur, raw, nk); break; + CASE(STBI__F_sub) cur[k] = STBI__BYTECAST(raw[k] + cur[k-filter_bytes]); break; + CASE(STBI__F_up) cur[k] = STBI__BYTECAST(raw[k] + prior[k]); break; + CASE(STBI__F_avg) cur[k] = STBI__BYTECAST(raw[k] + ((prior[k] + cur[k-filter_bytes])>>1)); break; + CASE(STBI__F_paeth) cur[k] = STBI__BYTECAST(raw[k] + stbi__paeth(cur[k-filter_bytes],prior[k],prior[k-filter_bytes])); break; + CASE(STBI__F_avg_first) cur[k] = STBI__BYTECAST(raw[k] + (cur[k-filter_bytes] >> 1)); break; + CASE(STBI__F_paeth_first) cur[k] = STBI__BYTECAST(raw[k] + stbi__paeth(cur[k-filter_bytes],0,0)); break; + } + #undef CASE + raw += nk; + } else { + STBI_ASSERT(img_n+1 == out_n); + #define CASE(f) \ + case f: \ + for (i=x-1; i >= 1; --i, cur[img_n]=255,raw+=img_n,cur+=out_n,prior+=out_n) \ + for (k=0; k < img_n; ++k) + switch (filter) { + CASE(STBI__F_none) cur[k] = raw[k]; break; + CASE(STBI__F_sub) cur[k] = STBI__BYTECAST(raw[k] + cur[k-out_n]); break; + CASE(STBI__F_up) cur[k] = STBI__BYTECAST(raw[k] + prior[k]); break; + CASE(STBI__F_avg) cur[k] = STBI__BYTECAST(raw[k] + ((prior[k] + cur[k-out_n])>>1)); break; + CASE(STBI__F_paeth) cur[k] = STBI__BYTECAST(raw[k] + stbi__paeth(cur[k-out_n],prior[k],prior[k-out_n])); break; + CASE(STBI__F_avg_first) cur[k] = STBI__BYTECAST(raw[k] + (cur[k-out_n] >> 1)); break; + CASE(STBI__F_paeth_first) cur[k] = STBI__BYTECAST(raw[k] + stbi__paeth(cur[k-out_n],0,0)); break; + } + #undef CASE + } + } + + // we make a separate pass to expand bits to pixels; for performance, + // this could run two scanlines behind the above code, so it won't + // intefere with filtering but will still be in the cache. + if (depth < 8) { + for (j=0; j < y; ++j) { + stbi_uc *cur = a->out + stride*j; + stbi_uc *in = a->out + stride*j + x*out_n - img_width_bytes; + // unpack 1/2/4-bit into a 8-bit buffer. allows us to keep the common 8-bit path optimal at minimal cost for 1/2/4-bit + // png guarante byte alignment, if width is not multiple of 8/4/2 we'll decode dummy trailing data that will be skipped in the later loop + stbi_uc scale = (color == 0) ? stbi__depth_scale_table[depth] : 1; // scale grayscale values to 0..255 range + + // note that the final byte might overshoot and write more data than desired. + // we can allocate enough data that this never writes out of memory, but it + // could also overwrite the next scanline. can it overwrite non-empty data + // on the next scanline? yes, consider 1-pixel-wide scanlines with 1-bit-per-pixel. + // so we need to explicitly clamp the final ones + + if (depth == 4) { + for (k=x*img_n; k >= 2; k-=2, ++in) { + *cur++ = scale * ((*in >> 4) ); + *cur++ = scale * ((*in ) & 0x0f); + } + if (k > 0) *cur++ = scale * ((*in >> 4) ); + } else if (depth == 2) { + for (k=x*img_n; k >= 4; k-=4, ++in) { + *cur++ = scale * ((*in >> 6) ); + *cur++ = scale * ((*in >> 4) & 0x03); + *cur++ = scale * ((*in >> 2) & 0x03); + *cur++ = scale * ((*in ) & 0x03); + } + if (k > 0) *cur++ = scale * ((*in >> 6) ); + if (k > 1) *cur++ = scale * ((*in >> 4) & 0x03); + if (k > 2) *cur++ = scale * ((*in >> 2) & 0x03); + } else if (depth == 1) { + for (k=x*img_n; k >= 8; k-=8, ++in) { + *cur++ = scale * ((*in >> 7) ); + *cur++ = scale * ((*in >> 6) & 0x01); + *cur++ = scale * ((*in >> 5) & 0x01); + *cur++ = scale * ((*in >> 4) & 0x01); + *cur++ = scale * ((*in >> 3) & 0x01); + *cur++ = scale * ((*in >> 2) & 0x01); + *cur++ = scale * ((*in >> 1) & 0x01); + *cur++ = scale * ((*in ) & 0x01); + } + if (k > 0) *cur++ = scale * ((*in >> 7) ); + if (k > 1) *cur++ = scale * ((*in >> 6) & 0x01); + if (k > 2) *cur++ = scale * ((*in >> 5) & 0x01); + if (k > 3) *cur++ = scale * ((*in >> 4) & 0x01); + if (k > 4) *cur++ = scale * ((*in >> 3) & 0x01); + if (k > 5) *cur++ = scale * ((*in >> 2) & 0x01); + if (k > 6) *cur++ = scale * ((*in >> 1) & 0x01); + } + if (img_n != out_n) { + int q; + // insert alpha = 255 + cur = a->out + stride*j; + if (img_n == 1) { + for (q=x-1; q >= 0; --q) { + cur[q*2+1] = 255; + cur[q*2+0] = cur[q]; + } + } else { + STBI_ASSERT(img_n == 3); + for (q=x-1; q >= 0; --q) { + cur[q*4+3] = 255; + cur[q*4+2] = cur[q*3+2]; + cur[q*4+1] = cur[q*3+1]; + cur[q*4+0] = cur[q*3+0]; + } + } + } + } + } + + return 1; +} + +static int stbi__create_png_image(stbi__png *a, stbi_uc *image_data, stbi__uint32 image_data_len, int out_n, int depth, int color, int interlaced) +{ + stbi_uc *final; + int p; + if (!interlaced) + return stbi__create_png_image_raw(a, image_data, image_data_len, out_n, a->s->img_x, a->s->img_y, depth, color); + + // de-interlacing + final = (stbi_uc *) stbi__malloc(a->s->img_x * a->s->img_y * out_n); + for (p=0; p < 7; ++p) { + int xorig[] = { 0,4,0,2,0,1,0 }; + int yorig[] = { 0,0,4,0,2,0,1 }; + int xspc[] = { 8,8,4,4,2,2,1 }; + int yspc[] = { 8,8,8,4,4,2,2 }; + int i,j,x,y; + // pass1_x[4] = 0, pass1_x[5] = 1, pass1_x[12] = 1 + x = (a->s->img_x - xorig[p] + xspc[p]-1) / xspc[p]; + y = (a->s->img_y - yorig[p] + yspc[p]-1) / yspc[p]; + if (x && y) { + stbi__uint32 img_len = ((((a->s->img_n * x * depth) + 7) >> 3) + 1) * y; + if (!stbi__create_png_image_raw(a, image_data, image_data_len, out_n, x, y, depth, color)) { + STBI_FREE(final); + return 0; + } + for (j=0; j < y; ++j) { + for (i=0; i < x; ++i) { + int out_y = j*yspc[p]+yorig[p]; + int out_x = i*xspc[p]+xorig[p]; + memcpy(final + out_y*a->s->img_x*out_n + out_x*out_n, + a->out + (j*x+i)*out_n, out_n); + } + } + STBI_FREE(a->out); + image_data += img_len; + image_data_len -= img_len; + } + } + a->out = final; + + return 1; +} + +static int stbi__compute_transparency(stbi__png *z, stbi_uc tc[3], int out_n) +{ + stbi__context *s = z->s; + stbi__uint32 i, pixel_count = s->img_x * s->img_y; + stbi_uc *p = z->out; + + // compute color-based transparency, assuming we've + // already got 255 as the alpha value in the output + STBI_ASSERT(out_n == 2 || out_n == 4); + + if (out_n == 2) { + for (i=0; i < pixel_count; ++i) { + p[1] = (p[0] == tc[0] ? 0 : 255); + p += 2; + } + } else { + for (i=0; i < pixel_count; ++i) { + if (p[0] == tc[0] && p[1] == tc[1] && p[2] == tc[2]) + p[3] = 0; + p += 4; + } + } + return 1; +} + +static int stbi__expand_png_palette(stbi__png *a, stbi_uc *palette, int len, int pal_img_n) +{ + stbi__uint32 i, pixel_count = a->s->img_x * a->s->img_y; + stbi_uc *p, *temp_out, *orig = a->out; + + p = (stbi_uc *) stbi__malloc(pixel_count * pal_img_n); + if (p == NULL) return stbi__err("outofmem", "Out of memory"); + + // between here and free(out) below, exitting would leak + temp_out = p; + + if (pal_img_n == 3) { + for (i=0; i < pixel_count; ++i) { + int n = orig[i]*4; + p[0] = palette[n ]; + p[1] = palette[n+1]; + p[2] = palette[n+2]; + p += 3; + } + } else { + for (i=0; i < pixel_count; ++i) { + int n = orig[i]*4; + p[0] = palette[n ]; + p[1] = palette[n+1]; + p[2] = palette[n+2]; + p[3] = palette[n+3]; + p += 4; + } + } + STBI_FREE(a->out); + a->out = temp_out; + + STBI_NOTUSED(len); + + return 1; +} + +static int stbi__unpremultiply_on_load = 0; +static int stbi__de_iphone_flag = 0; + +STBIDEF void stbi_set_unpremultiply_on_load(int flag_true_if_should_unpremultiply) +{ + stbi__unpremultiply_on_load = flag_true_if_should_unpremultiply; +} + +STBIDEF void stbi_convert_iphone_png_to_rgb(int flag_true_if_should_convert) +{ + stbi__de_iphone_flag = flag_true_if_should_convert; +} + +static void stbi__de_iphone(stbi__png *z) +{ + stbi__context *s = z->s; + stbi__uint32 i, pixel_count = s->img_x * s->img_y; + stbi_uc *p = z->out; + + if (s->img_out_n == 3) { // convert bgr to rgb + for (i=0; i < pixel_count; ++i) { + stbi_uc t = p[0]; + p[0] = p[2]; + p[2] = t; + p += 3; + } + } else { + STBI_ASSERT(s->img_out_n == 4); + if (stbi__unpremultiply_on_load) { + // convert bgr to rgb and unpremultiply + for (i=0; i < pixel_count; ++i) { + stbi_uc a = p[3]; + stbi_uc t = p[0]; + if (a) { + p[0] = p[2] * 255 / a; + p[1] = p[1] * 255 / a; + p[2] = t * 255 / a; + } else { + p[0] = p[2]; + p[2] = t; + } + p += 4; + } + } else { + // convert bgr to rgb + for (i=0; i < pixel_count; ++i) { + stbi_uc t = p[0]; + p[0] = p[2]; + p[2] = t; + p += 4; + } + } + } +} + +#define STBI__PNG_TYPE(a,b,c,d) (((a) << 24) + ((b) << 16) + ((c) << 8) + (d)) + +static int stbi__parse_png_file(stbi__png *z, int scan, int req_comp) +{ + stbi_uc palette[1024], pal_img_n=0; + stbi_uc has_trans=0, tc[3]; + stbi__uint32 ioff=0, idata_limit=0, i, pal_len=0; + int first=1,k,interlace=0, color=0, depth=0, is_iphone=0; + stbi__context *s = z->s; + + z->expanded = NULL; + z->idata = NULL; + z->out = NULL; + + if (!stbi__check_png_header(s)) return 0; + + if (scan == STBI__SCAN_type) return 1; + + for (;;) { + stbi__pngchunk c = stbi__get_chunk_header(s); + switch (c.type) { + case STBI__PNG_TYPE('C','g','B','I'): + is_iphone = 1; + stbi__skip(s, c.length); + break; + case STBI__PNG_TYPE('I','H','D','R'): { + int comp,filter; + if (!first) return stbi__err("multiple IHDR","Corrupt PNG"); + first = 0; + if (c.length != 13) return stbi__err("bad IHDR len","Corrupt PNG"); + s->img_x = stbi__get32be(s); if (s->img_x > (1 << 24)) return stbi__err("too large","Very large image (corrupt?)"); + s->img_y = stbi__get32be(s); if (s->img_y > (1 << 24)) return stbi__err("too large","Very large image (corrupt?)"); + depth = stbi__get8(s); if (depth != 1 && depth != 2 && depth != 4 && depth != 8) return stbi__err("1/2/4/8-bit only","PNG not supported: 1/2/4/8-bit only"); + color = stbi__get8(s); if (color > 6) return stbi__err("bad ctype","Corrupt PNG"); + if (color == 3) pal_img_n = 3; else if (color & 1) return stbi__err("bad ctype","Corrupt PNG"); + comp = stbi__get8(s); if (comp) return stbi__err("bad comp method","Corrupt PNG"); + filter= stbi__get8(s); if (filter) return stbi__err("bad filter method","Corrupt PNG"); + interlace = stbi__get8(s); if (interlace>1) return stbi__err("bad interlace method","Corrupt PNG"); + if (!s->img_x || !s->img_y) return stbi__err("0-pixel image","Corrupt PNG"); + if (!pal_img_n) { + s->img_n = (color & 2 ? 3 : 1) + (color & 4 ? 1 : 0); + if ((1 << 30) / s->img_x / s->img_n < s->img_y) return stbi__err("too large", "Image too large to decode"); + if (scan == STBI__SCAN_header) return 1; + } else { + // if paletted, then pal_n is our final components, and + // img_n is # components to decompress/filter. + s->img_n = 1; + if ((1 << 30) / s->img_x / 4 < s->img_y) return stbi__err("too large","Corrupt PNG"); + // if SCAN_header, have to scan to see if we have a tRNS + } + break; + } + + case STBI__PNG_TYPE('P','L','T','E'): { + if (first) return stbi__err("first not IHDR", "Corrupt PNG"); + if (c.length > 256*3) return stbi__err("invalid PLTE","Corrupt PNG"); + pal_len = c.length / 3; + if (pal_len * 3 != c.length) return stbi__err("invalid PLTE","Corrupt PNG"); + for (i=0; i < pal_len; ++i) { + palette[i*4+0] = stbi__get8(s); + palette[i*4+1] = stbi__get8(s); + palette[i*4+2] = stbi__get8(s); + palette[i*4+3] = 255; + } + break; + } + + case STBI__PNG_TYPE('t','R','N','S'): { + if (first) return stbi__err("first not IHDR", "Corrupt PNG"); + if (z->idata) return stbi__err("tRNS after IDAT","Corrupt PNG"); + if (pal_img_n) { + if (scan == STBI__SCAN_header) { s->img_n = 4; return 1; } + if (pal_len == 0) return stbi__err("tRNS before PLTE","Corrupt PNG"); + if (c.length > pal_len) return stbi__err("bad tRNS len","Corrupt PNG"); + pal_img_n = 4; + for (i=0; i < c.length; ++i) + palette[i*4+3] = stbi__get8(s); + } else { + if (!(s->img_n & 1)) return stbi__err("tRNS with alpha","Corrupt PNG"); + if (c.length != (stbi__uint32) s->img_n*2) return stbi__err("bad tRNS len","Corrupt PNG"); + has_trans = 1; + for (k=0; k < s->img_n; ++k) + tc[k] = (stbi_uc) (stbi__get16be(s) & 255) * stbi__depth_scale_table[depth]; // non 8-bit images will be larger + } + break; + } + + case STBI__PNG_TYPE('I','D','A','T'): { + if (first) return stbi__err("first not IHDR", "Corrupt PNG"); + if (pal_img_n && !pal_len) return stbi__err("no PLTE","Corrupt PNG"); + if (scan == STBI__SCAN_header) { s->img_n = pal_img_n; return 1; } + if ((int)(ioff + c.length) < (int)ioff) return 0; + if (ioff + c.length > idata_limit) { + stbi__uint32 idata_limit_old = idata_limit; + stbi_uc *p; + if (idata_limit == 0) idata_limit = c.length > 4096 ? c.length : 4096; + while (ioff + c.length > idata_limit) + idata_limit *= 2; + STBI_NOTUSED(idata_limit_old); + p = (stbi_uc *) STBI_REALLOC_SIZED(z->idata, idata_limit_old, idata_limit); if (p == NULL) return stbi__err("outofmem", "Out of memory"); + z->idata = p; + } + if (!stbi__getn(s, z->idata+ioff,c.length)) return stbi__err("outofdata","Corrupt PNG"); + ioff += c.length; + break; + } + + case STBI__PNG_TYPE('I','E','N','D'): { + stbi__uint32 raw_len, bpl; + if (first) return stbi__err("first not IHDR", "Corrupt PNG"); + if (scan != STBI__SCAN_load) return 1; + if (z->idata == NULL) return stbi__err("no IDAT","Corrupt PNG"); + // initial guess for decoded data size to avoid unnecessary reallocs + bpl = (s->img_x * depth + 7) / 8; // bytes per line, per component + raw_len = bpl * s->img_y * s->img_n /* pixels */ + s->img_y /* filter mode per row */; + z->expanded = (stbi_uc *) stbi_zlib_decode_malloc_guesssize_headerflag((char *) z->idata, ioff, raw_len, (int *) &raw_len, !is_iphone); + if (z->expanded == NULL) return 0; // zlib should set error + STBI_FREE(z->idata); z->idata = NULL; + if ((req_comp == s->img_n+1 && req_comp != 3 && !pal_img_n) || has_trans) + s->img_out_n = s->img_n+1; + else + s->img_out_n = s->img_n; + if (!stbi__create_png_image(z, z->expanded, raw_len, s->img_out_n, depth, color, interlace)) return 0; + if (has_trans) + if (!stbi__compute_transparency(z, tc, s->img_out_n)) return 0; + if (is_iphone && stbi__de_iphone_flag && s->img_out_n > 2) + stbi__de_iphone(z); + if (pal_img_n) { + // pal_img_n == 3 or 4 + s->img_n = pal_img_n; // record the actual colors we had + s->img_out_n = pal_img_n; + if (req_comp >= 3) s->img_out_n = req_comp; + if (!stbi__expand_png_palette(z, palette, pal_len, s->img_out_n)) + return 0; + } + STBI_FREE(z->expanded); z->expanded = NULL; + return 1; + } + + default: + // if critical, fail + if (first) return stbi__err("first not IHDR", "Corrupt PNG"); + if ((c.type & (1 << 29)) == 0) { + #ifndef STBI_NO_FAILURE_STRINGS + // not threadsafe + static char invalid_chunk[] = "XXXX PNG chunk not known"; + invalid_chunk[0] = STBI__BYTECAST(c.type >> 24); + invalid_chunk[1] = STBI__BYTECAST(c.type >> 16); + invalid_chunk[2] = STBI__BYTECAST(c.type >> 8); + invalid_chunk[3] = STBI__BYTECAST(c.type >> 0); + #endif + return stbi__err(invalid_chunk, "PNG not supported: unknown PNG chunk type"); + } + stbi__skip(s, c.length); + break; + } + // end of PNG chunk, read and skip CRC + stbi__get32be(s); + } +} + +static unsigned char *stbi__do_png(stbi__png *p, int *x, int *y, int *n, int req_comp) +{ + unsigned char *result=NULL; + if (req_comp < 0 || req_comp > 4) return stbi__errpuc("bad req_comp", "Internal error"); + if (stbi__parse_png_file(p, STBI__SCAN_load, req_comp)) { + result = p->out; + p->out = NULL; + if (req_comp && req_comp != p->s->img_out_n) { + result = stbi__convert_format(result, p->s->img_out_n, req_comp, p->s->img_x, p->s->img_y); + p->s->img_out_n = req_comp; + if (result == NULL) return result; + } + *x = p->s->img_x; + *y = p->s->img_y; + if (n) *n = p->s->img_out_n; + } + STBI_FREE(p->out); p->out = NULL; + STBI_FREE(p->expanded); p->expanded = NULL; + STBI_FREE(p->idata); p->idata = NULL; + + return result; +} + +static unsigned char *stbi__png_load(stbi__context *s, int *x, int *y, int *comp, int req_comp) +{ + stbi__png p; + p.s = s; + return stbi__do_png(&p, x,y,comp,req_comp); +} + +static int stbi__png_test(stbi__context *s) +{ + int r; + r = stbi__check_png_header(s); + stbi__rewind(s); + return r; +} + +static int stbi__png_info_raw(stbi__png *p, int *x, int *y, int *comp) +{ + if (!stbi__parse_png_file(p, STBI__SCAN_header, 0)) { + stbi__rewind( p->s ); + return 0; + } + if (x) *x = p->s->img_x; + if (y) *y = p->s->img_y; + if (comp) *comp = p->s->img_n; + return 1; +} + +static int stbi__png_info(stbi__context *s, int *x, int *y, int *comp) +{ + stbi__png p; + p.s = s; + return stbi__png_info_raw(&p, x, y, comp); +} +#endif + +// Microsoft/Windows BMP image + +#ifndef STBI_NO_BMP +static int stbi__bmp_test_raw(stbi__context *s) +{ + int r; + int sz; + if (stbi__get8(s) != 'B') return 0; + if (stbi__get8(s) != 'M') return 0; + stbi__get32le(s); // discard filesize + stbi__get16le(s); // discard reserved + stbi__get16le(s); // discard reserved + stbi__get32le(s); // discard data offset + sz = stbi__get32le(s); + r = (sz == 12 || sz == 40 || sz == 56 || sz == 108 || sz == 124); + return r; +} + +static int stbi__bmp_test(stbi__context *s) +{ + int r = stbi__bmp_test_raw(s); + stbi__rewind(s); + return r; +} + + +// returns 0..31 for the highest set bit +static int stbi__high_bit(unsigned int z) +{ + int n=0; + if (z == 0) return -1; + if (z >= 0x10000) n += 16, z >>= 16; + if (z >= 0x00100) n += 8, z >>= 8; + if (z >= 0x00010) n += 4, z >>= 4; + if (z >= 0x00004) n += 2, z >>= 2; + if (z >= 0x00002) n += 1, z >>= 1; + return n; +} + +static int stbi__bitcount(unsigned int a) +{ + a = (a & 0x55555555) + ((a >> 1) & 0x55555555); // max 2 + a = (a & 0x33333333) + ((a >> 2) & 0x33333333); // max 4 + a = (a + (a >> 4)) & 0x0f0f0f0f; // max 8 per 4, now 8 bits + a = (a + (a >> 8)); // max 16 per 8 bits + a = (a + (a >> 16)); // max 32 per 8 bits + return a & 0xff; +} + +static int stbi__shiftsigned(int v, int shift, int bits) +{ + int result; + int z=0; + + if (shift < 0) v <<= -shift; + else v >>= shift; + result = v; + + z = bits; + while (z < 8) { + result += v >> z; + z += bits; + } + return result; +} + +typedef struct +{ + int bpp, offset, hsz; + unsigned int mr,mg,mb,ma, all_a; +} stbi__bmp_data; + +static void *stbi__bmp_parse_header(stbi__context *s, stbi__bmp_data *info) +{ + int hsz; + if (stbi__get8(s) != 'B' || stbi__get8(s) != 'M') return stbi__errpuc("not BMP", "Corrupt BMP"); + stbi__get32le(s); // discard filesize + stbi__get16le(s); // discard reserved + stbi__get16le(s); // discard reserved + info->offset = stbi__get32le(s); + info->hsz = hsz = stbi__get32le(s); + + if (hsz != 12 && hsz != 40 && hsz != 56 && hsz != 108 && hsz != 124) return stbi__errpuc("unknown BMP", "BMP type not supported: unknown"); + if (hsz == 12) { + s->img_x = stbi__get16le(s); + s->img_y = stbi__get16le(s); + } else { + s->img_x = stbi__get32le(s); + s->img_y = stbi__get32le(s); + } + if (stbi__get16le(s) != 1) return stbi__errpuc("bad BMP", "bad BMP"); + info->bpp = stbi__get16le(s); + if (info->bpp == 1) return stbi__errpuc("monochrome", "BMP type not supported: 1-bit"); + if (hsz != 12) { + int compress = stbi__get32le(s); + if (compress == 1 || compress == 2) return stbi__errpuc("BMP RLE", "BMP type not supported: RLE"); + stbi__get32le(s); // discard sizeof + stbi__get32le(s); // discard hres + stbi__get32le(s); // discard vres + stbi__get32le(s); // discard colorsused + stbi__get32le(s); // discard max important + if (hsz == 40 || hsz == 56) { + if (hsz == 56) { + stbi__get32le(s); + stbi__get32le(s); + stbi__get32le(s); + stbi__get32le(s); + } + if (info->bpp == 16 || info->bpp == 32) { + info->mr = info->mg = info->mb = 0; + if (compress == 0) { + if (info->bpp == 32) { + info->mr = 0xffu << 16; + info->mg = 0xffu << 8; + info->mb = 0xffu << 0; + info->ma = 0xffu << 24; + info->all_a = 0; // if all_a is 0 at end, then we loaded alpha channel but it was all 0 + } else { + info->mr = 31u << 10; + info->mg = 31u << 5; + info->mb = 31u << 0; + } + } else if (compress == 3) { + info->mr = stbi__get32le(s); + info->mg = stbi__get32le(s); + info->mb = stbi__get32le(s); + // not documented, but generated by photoshop and handled by mspaint + if (info->mr == info->mg && info->mg == info->mb) { + // ?!?!? + return stbi__errpuc("bad BMP", "bad BMP"); + } + } else + return stbi__errpuc("bad BMP", "bad BMP"); + } + } else { + int i; + if (hsz != 108 && hsz != 124) + return stbi__errpuc("bad BMP", "bad BMP"); + info->mr = stbi__get32le(s); + info->mg = stbi__get32le(s); + info->mb = stbi__get32le(s); + info->ma = stbi__get32le(s); + stbi__get32le(s); // discard color space + for (i=0; i < 12; ++i) + stbi__get32le(s); // discard color space parameters + if (hsz == 124) { + stbi__get32le(s); // discard rendering intent + stbi__get32le(s); // discard offset of profile data + stbi__get32le(s); // discard size of profile data + stbi__get32le(s); // discard reserved + } + } + } + return (void *) 1; +} + + +static stbi_uc *stbi__bmp_load(stbi__context *s, int *x, int *y, int *comp, int req_comp) +{ + stbi_uc *out; + unsigned int mr=0,mg=0,mb=0,ma=0, all_a; + stbi_uc pal[256][4]; + int psize=0,i,j,width; + int flip_vertically, pad, target; + stbi__bmp_data info; + + info.all_a = 255; + if (stbi__bmp_parse_header(s, &info) == NULL) + return NULL; // error code already set + + flip_vertically = ((int) s->img_y) > 0; + s->img_y = abs((int) s->img_y); + + mr = info.mr; + mg = info.mg; + mb = info.mb; + ma = info.ma; + all_a = info.all_a; + + if (info.hsz == 12) { + if (info.bpp < 24) + psize = (info.offset - 14 - 24) / 3; + } else { + if (info.bpp < 16) + psize = (info.offset - 14 - info.hsz) >> 2; + } + + s->img_n = ma ? 4 : 3; + if (req_comp && req_comp >= 3) // we can directly decode 3 or 4 + target = req_comp; + else + target = s->img_n; // if they want monochrome, we'll post-convert + + out = (stbi_uc *) stbi__malloc(target * s->img_x * s->img_y); + if (!out) return stbi__errpuc("outofmem", "Out of memory"); + if (info.bpp < 16) { + int z=0; + if (psize == 0 || psize > 256) { STBI_FREE(out); return stbi__errpuc("invalid", "Corrupt BMP"); } + for (i=0; i < psize; ++i) { + pal[i][2] = stbi__get8(s); + pal[i][1] = stbi__get8(s); + pal[i][0] = stbi__get8(s); + if (info.hsz != 12) stbi__get8(s); + pal[i][3] = 255; + } + stbi__skip(s, info.offset - 14 - info.hsz - psize * (info.hsz == 12 ? 3 : 4)); + if (info.bpp == 4) width = (s->img_x + 1) >> 1; + else if (info.bpp == 8) width = s->img_x; + else { STBI_FREE(out); return stbi__errpuc("bad bpp", "Corrupt BMP"); } + pad = (-width)&3; + for (j=0; j < (int) s->img_y; ++j) { + for (i=0; i < (int) s->img_x; i += 2) { + int v=stbi__get8(s),v2=0; + if (info.bpp == 4) { + v2 = v & 15; + v >>= 4; + } + out[z++] = pal[v][0]; + out[z++] = pal[v][1]; + out[z++] = pal[v][2]; + if (target == 4) out[z++] = 255; + if (i+1 == (int) s->img_x) break; + v = (info.bpp == 8) ? stbi__get8(s) : v2; + out[z++] = pal[v][0]; + out[z++] = pal[v][1]; + out[z++] = pal[v][2]; + if (target == 4) out[z++] = 255; + } + stbi__skip(s, pad); + } + } else { + int rshift=0,gshift=0,bshift=0,ashift=0,rcount=0,gcount=0,bcount=0,acount=0; + int z = 0; + int easy=0; + stbi__skip(s, info.offset - 14 - info.hsz); + if (info.bpp == 24) width = 3 * s->img_x; + else if (info.bpp == 16) width = 2*s->img_x; + else /* bpp = 32 and pad = 0 */ width=0; + pad = (-width) & 3; + if (info.bpp == 24) { + easy = 1; + } else if (info.bpp == 32) { + if (mb == 0xff && mg == 0xff00 && mr == 0x00ff0000 && ma == 0xff000000) + easy = 2; + } + if (!easy) { + if (!mr || !mg || !mb) { STBI_FREE(out); return stbi__errpuc("bad masks", "Corrupt BMP"); } + // right shift amt to put high bit in position #7 + rshift = stbi__high_bit(mr)-7; rcount = stbi__bitcount(mr); + gshift = stbi__high_bit(mg)-7; gcount = stbi__bitcount(mg); + bshift = stbi__high_bit(mb)-7; bcount = stbi__bitcount(mb); + ashift = stbi__high_bit(ma)-7; acount = stbi__bitcount(ma); + } + for (j=0; j < (int) s->img_y; ++j) { + if (easy) { + for (i=0; i < (int) s->img_x; ++i) { + unsigned char a; + out[z+2] = stbi__get8(s); + out[z+1] = stbi__get8(s); + out[z+0] = stbi__get8(s); + z += 3; + a = (easy == 2 ? stbi__get8(s) : 255); + all_a |= a; + if (target == 4) out[z++] = a; + } + } else { + int bpp = info.bpp; + for (i=0; i < (int) s->img_x; ++i) { + stbi__uint32 v = (bpp == 16 ? (stbi__uint32) stbi__get16le(s) : stbi__get32le(s)); + int a; + out[z++] = STBI__BYTECAST(stbi__shiftsigned(v & mr, rshift, rcount)); + out[z++] = STBI__BYTECAST(stbi__shiftsigned(v & mg, gshift, gcount)); + out[z++] = STBI__BYTECAST(stbi__shiftsigned(v & mb, bshift, bcount)); + a = (ma ? stbi__shiftsigned(v & ma, ashift, acount) : 255); + all_a |= a; + if (target == 4) out[z++] = STBI__BYTECAST(a); + } + } + stbi__skip(s, pad); + } + } + + // if alpha channel is all 0s, replace with all 255s + if (target == 4 && all_a == 0) + for (i=4*s->img_x*s->img_y-1; i >= 0; i -= 4) + out[i] = 255; + + if (flip_vertically) { + stbi_uc t; + for (j=0; j < (int) s->img_y>>1; ++j) { + stbi_uc *p1 = out + j *s->img_x*target; + stbi_uc *p2 = out + (s->img_y-1-j)*s->img_x*target; + for (i=0; i < (int) s->img_x*target; ++i) { + t = p1[i], p1[i] = p2[i], p2[i] = t; + } + } + } + + if (req_comp && req_comp != target) { + out = stbi__convert_format(out, target, req_comp, s->img_x, s->img_y); + if (out == NULL) return out; // stbi__convert_format frees input on failure + } + + *x = s->img_x; + *y = s->img_y; + if (comp) *comp = s->img_n; + return out; +} +#endif + +// Targa Truevision - TGA +// by Jonathan Dummer +#ifndef STBI_NO_TGA +// returns STBI_rgb or whatever, 0 on error +static int stbi__tga_get_comp(int bits_per_pixel, int is_grey, int* is_rgb16) +{ + // only RGB or RGBA (incl. 16bit) or grey allowed + if(is_rgb16) *is_rgb16 = 0; + switch(bits_per_pixel) { + case 8: return STBI_grey; + case 16: if(is_grey) return STBI_grey_alpha; + // else: fall-through + case 15: if(is_rgb16) *is_rgb16 = 1; + return STBI_rgb; + case 24: // fall-through + case 32: return bits_per_pixel/8; + default: return 0; + } +} + +static int stbi__tga_info(stbi__context *s, int *x, int *y, int *comp) +{ + int tga_w, tga_h, tga_comp, tga_image_type, tga_bits_per_pixel, tga_colormap_bpp; + int sz, tga_colormap_type; + stbi__get8(s); // discard Offset + tga_colormap_type = stbi__get8(s); // colormap type + if( tga_colormap_type > 1 ) { + stbi__rewind(s); + return 0; // only RGB or indexed allowed + } + tga_image_type = stbi__get8(s); // image type + if ( tga_colormap_type == 1 ) { // colormapped (paletted) image + if (tga_image_type != 1 && tga_image_type != 9) { + stbi__rewind(s); + return 0; + } + stbi__skip(s,4); // skip index of first colormap entry and number of entries + sz = stbi__get8(s); // check bits per palette color entry + if ( (sz != 8) && (sz != 15) && (sz != 16) && (sz != 24) && (sz != 32) ) { + stbi__rewind(s); + return 0; + } + stbi__skip(s,4); // skip image x and y origin + tga_colormap_bpp = sz; + } else { // "normal" image w/o colormap - only RGB or grey allowed, +/- RLE + if ( (tga_image_type != 2) && (tga_image_type != 3) && (tga_image_type != 10) && (tga_image_type != 11) ) { + stbi__rewind(s); + return 0; // only RGB or grey allowed, +/- RLE + } + stbi__skip(s,9); // skip colormap specification and image x/y origin + tga_colormap_bpp = 0; + } + tga_w = stbi__get16le(s); + if( tga_w < 1 ) { + stbi__rewind(s); + return 0; // test width + } + tga_h = stbi__get16le(s); + if( tga_h < 1 ) { + stbi__rewind(s); + return 0; // test height + } + tga_bits_per_pixel = stbi__get8(s); // bits per pixel + stbi__get8(s); // ignore alpha bits + if (tga_colormap_bpp != 0) { + if((tga_bits_per_pixel != 8) && (tga_bits_per_pixel != 16)) { + // when using a colormap, tga_bits_per_pixel is the size of the indexes + // I don't think anything but 8 or 16bit indexes makes sense + stbi__rewind(s); + return 0; + } + tga_comp = stbi__tga_get_comp(tga_colormap_bpp, 0, NULL); + } else { + tga_comp = stbi__tga_get_comp(tga_bits_per_pixel, (tga_image_type == 3) || (tga_image_type == 11), NULL); + } + if(!tga_comp) { + stbi__rewind(s); + return 0; + } + if (x) *x = tga_w; + if (y) *y = tga_h; + if (comp) *comp = tga_comp; + return 1; // seems to have passed everything +} + +static int stbi__tga_test(stbi__context *s) +{ + int res = 0; + int sz, tga_color_type; + stbi__get8(s); // discard Offset + tga_color_type = stbi__get8(s); // color type + if ( tga_color_type > 1 ) goto errorEnd; // only RGB or indexed allowed + sz = stbi__get8(s); // image type + if ( tga_color_type == 1 ) { // colormapped (paletted) image + if (sz != 1 && sz != 9) goto errorEnd; // colortype 1 demands image type 1 or 9 + stbi__skip(s,4); // skip index of first colormap entry and number of entries + sz = stbi__get8(s); // check bits per palette color entry + if ( (sz != 8) && (sz != 15) && (sz != 16) && (sz != 24) && (sz != 32) ) goto errorEnd; + stbi__skip(s,4); // skip image x and y origin + } else { // "normal" image w/o colormap + if ( (sz != 2) && (sz != 3) && (sz != 10) && (sz != 11) ) goto errorEnd; // only RGB or grey allowed, +/- RLE + stbi__skip(s,9); // skip colormap specification and image x/y origin + } + if ( stbi__get16le(s) < 1 ) goto errorEnd; // test width + if ( stbi__get16le(s) < 1 ) goto errorEnd; // test height + sz = stbi__get8(s); // bits per pixel + if ( (tga_color_type == 1) && (sz != 8) && (sz != 16) ) goto errorEnd; // for colormapped images, bpp is size of an index + if ( (sz != 8) && (sz != 15) && (sz != 16) && (sz != 24) && (sz != 32) ) goto errorEnd; + + res = 1; // if we got this far, everything's good and we can return 1 instead of 0 + +errorEnd: + stbi__rewind(s); + return res; +} + +// read 16bit value and convert to 24bit RGB +void stbi__tga_read_rgb16(stbi__context *s, stbi_uc* out) +{ + stbi__uint16 px = stbi__get16le(s); + stbi__uint16 fiveBitMask = 31; + // we have 3 channels with 5bits each + int r = (px >> 10) & fiveBitMask; + int g = (px >> 5) & fiveBitMask; + int b = px & fiveBitMask; + // Note that this saves the data in RGB(A) order, so it doesn't need to be swapped later + out[0] = (r * 255)/31; + out[1] = (g * 255)/31; + out[2] = (b * 255)/31; + + // some people claim that the most significant bit might be used for alpha + // (possibly if an alpha-bit is set in the "image descriptor byte") + // but that only made 16bit test images completely translucent.. + // so let's treat all 15 and 16bit TGAs as RGB with no alpha. +} + +static stbi_uc *stbi__tga_load(stbi__context *s, int *x, int *y, int *comp, int req_comp) +{ + // read in the TGA header stuff + int tga_offset = stbi__get8(s); + int tga_indexed = stbi__get8(s); + int tga_image_type = stbi__get8(s); + int tga_is_RLE = 0; + int tga_palette_start = stbi__get16le(s); + int tga_palette_len = stbi__get16le(s); + int tga_palette_bits = stbi__get8(s); + int tga_x_origin = stbi__get16le(s); + int tga_y_origin = stbi__get16le(s); + int tga_width = stbi__get16le(s); + int tga_height = stbi__get16le(s); + int tga_bits_per_pixel = stbi__get8(s); + int tga_comp, tga_rgb16=0; + int tga_inverted = stbi__get8(s); + // int tga_alpha_bits = tga_inverted & 15; // the 4 lowest bits - unused (useless?) + // image data + unsigned char *tga_data; + unsigned char *tga_palette = NULL; + int i, j; + unsigned char raw_data[4]; + int RLE_count = 0; + int RLE_repeating = 0; + int read_next_pixel = 1; + + // do a tiny bit of precessing + if ( tga_image_type >= 8 ) + { + tga_image_type -= 8; + tga_is_RLE = 1; + } + tga_inverted = 1 - ((tga_inverted >> 5) & 1); + + // If I'm paletted, then I'll use the number of bits from the palette + if ( tga_indexed ) tga_comp = stbi__tga_get_comp(tga_palette_bits, 0, &tga_rgb16); + else tga_comp = stbi__tga_get_comp(tga_bits_per_pixel, (tga_image_type == 3), &tga_rgb16); + + if(!tga_comp) // shouldn't really happen, stbi__tga_test() should have ensured basic consistency + return stbi__errpuc("bad format", "Can't find out TGA pixelformat"); + + // tga info + *x = tga_width; + *y = tga_height; + if (comp) *comp = tga_comp; + + tga_data = (unsigned char*)stbi__malloc( (size_t)tga_width * tga_height * tga_comp ); + if (!tga_data) return stbi__errpuc("outofmem", "Out of memory"); + + // skip to the data's starting position (offset usually = 0) + stbi__skip(s, tga_offset ); + + if ( !tga_indexed && !tga_is_RLE && !tga_rgb16 ) { + for (i=0; i < tga_height; ++i) { + int row = tga_inverted ? tga_height -i - 1 : i; + stbi_uc *tga_row = tga_data + row*tga_width*tga_comp; + stbi__getn(s, tga_row, tga_width * tga_comp); + } + } else { + // do I need to load a palette? + if ( tga_indexed) + { + // any data to skip? (offset usually = 0) + stbi__skip(s, tga_palette_start ); + // load the palette + tga_palette = (unsigned char*)stbi__malloc( tga_palette_len * tga_comp ); + if (!tga_palette) { + STBI_FREE(tga_data); + return stbi__errpuc("outofmem", "Out of memory"); + } + if (tga_rgb16) { + stbi_uc *pal_entry = tga_palette; + STBI_ASSERT(tga_comp == STBI_rgb); + for (i=0; i < tga_palette_len; ++i) { + stbi__tga_read_rgb16(s, pal_entry); + pal_entry += tga_comp; + } + } else if (!stbi__getn(s, tga_palette, tga_palette_len * tga_comp)) { + STBI_FREE(tga_data); + STBI_FREE(tga_palette); + return stbi__errpuc("bad palette", "Corrupt TGA"); + } + } + // load the data + for (i=0; i < tga_width * tga_height; ++i) + { + // if I'm in RLE mode, do I need to get a RLE stbi__pngchunk? + if ( tga_is_RLE ) + { + if ( RLE_count == 0 ) + { + // yep, get the next byte as a RLE command + int RLE_cmd = stbi__get8(s); + RLE_count = 1 + (RLE_cmd & 127); + RLE_repeating = RLE_cmd >> 7; + read_next_pixel = 1; + } else if ( !RLE_repeating ) + { + read_next_pixel = 1; + } + } else + { + read_next_pixel = 1; + } + // OK, if I need to read a pixel, do it now + if ( read_next_pixel ) + { + // load however much data we did have + if ( tga_indexed ) + { + // read in index, then perform the lookup + int pal_idx = (tga_bits_per_pixel == 8) ? stbi__get8(s) : stbi__get16le(s); + if ( pal_idx >= tga_palette_len ) { + // invalid index + pal_idx = 0; + } + pal_idx *= tga_comp; + for (j = 0; j < tga_comp; ++j) { + raw_data[j] = tga_palette[pal_idx+j]; + } + } else if(tga_rgb16) { + STBI_ASSERT(tga_comp == STBI_rgb); + stbi__tga_read_rgb16(s, raw_data); + } else { + // read in the data raw + for (j = 0; j < tga_comp; ++j) { + raw_data[j] = stbi__get8(s); + } + } + // clear the reading flag for the next pixel + read_next_pixel = 0; + } // end of reading a pixel + + // copy data + for (j = 0; j < tga_comp; ++j) + tga_data[i*tga_comp+j] = raw_data[j]; + + // in case we're in RLE mode, keep counting down + --RLE_count; + } + // do I need to invert the image? + if ( tga_inverted ) + { + for (j = 0; j*2 < tga_height; ++j) + { + int index1 = j * tga_width * tga_comp; + int index2 = (tga_height - 1 - j) * tga_width * tga_comp; + for (i = tga_width * tga_comp; i > 0; --i) + { + unsigned char temp = tga_data[index1]; + tga_data[index1] = tga_data[index2]; + tga_data[index2] = temp; + ++index1; + ++index2; + } + } + } + // clear my palette, if I had one + if ( tga_palette != NULL ) + { + STBI_FREE( tga_palette ); + } + } + + // swap RGB - if the source data was RGB16, it already is in the right order + if (tga_comp >= 3 && !tga_rgb16) + { + unsigned char* tga_pixel = tga_data; + for (i=0; i < tga_width * tga_height; ++i) + { + unsigned char temp = tga_pixel[0]; + tga_pixel[0] = tga_pixel[2]; + tga_pixel[2] = temp; + tga_pixel += tga_comp; + } + } + + // convert to target component count + if (req_comp && req_comp != tga_comp) + tga_data = stbi__convert_format(tga_data, tga_comp, req_comp, tga_width, tga_height); + + // the things I do to get rid of an error message, and yet keep + // Microsoft's C compilers happy... [8^( + tga_palette_start = tga_palette_len = tga_palette_bits = + tga_x_origin = tga_y_origin = 0; + // OK, done + return tga_data; +} +#endif + +// ************************************************************************************************* +// Photoshop PSD loader -- PD by Thatcher Ulrich, integration by Nicolas Schulz, tweaked by STB + +#ifndef STBI_NO_PSD +static int stbi__psd_test(stbi__context *s) +{ + int r = (stbi__get32be(s) == 0x38425053); + stbi__rewind(s); + return r; +} + +static stbi_uc *stbi__psd_load(stbi__context *s, int *x, int *y, int *comp, int req_comp) +{ + int pixelCount; + int channelCount, compression; + int channel, i, count, len; + int bitdepth; + int w,h; + stbi_uc *out; + + // Check identifier + if (stbi__get32be(s) != 0x38425053) // "8BPS" + return stbi__errpuc("not PSD", "Corrupt PSD image"); + + // Check file type version. + if (stbi__get16be(s) != 1) + return stbi__errpuc("wrong version", "Unsupported version of PSD image"); + + // Skip 6 reserved bytes. + stbi__skip(s, 6 ); + + // Read the number of channels (R, G, B, A, etc). + channelCount = stbi__get16be(s); + if (channelCount < 0 || channelCount > 16) + return stbi__errpuc("wrong channel count", "Unsupported number of channels in PSD image"); + + // Read the rows and columns of the image. + h = stbi__get32be(s); + w = stbi__get32be(s); + + // Make sure the depth is 8 bits. + bitdepth = stbi__get16be(s); + if (bitdepth != 8 && bitdepth != 16) + return stbi__errpuc("unsupported bit depth", "PSD bit depth is not 8 or 16 bit"); + + // Make sure the color mode is RGB. + // Valid options are: + // 0: Bitmap + // 1: Grayscale + // 2: Indexed color + // 3: RGB color + // 4: CMYK color + // 7: Multichannel + // 8: Duotone + // 9: Lab color + if (stbi__get16be(s) != 3) + return stbi__errpuc("wrong color format", "PSD is not in RGB color format"); + + // Skip the Mode Data. (It's the palette for indexed color; other info for other modes.) + stbi__skip(s,stbi__get32be(s) ); + + // Skip the image resources. (resolution, pen tool paths, etc) + stbi__skip(s, stbi__get32be(s) ); + + // Skip the reserved data. + stbi__skip(s, stbi__get32be(s) ); + + // Find out if the data is compressed. + // Known values: + // 0: no compression + // 1: RLE compressed + compression = stbi__get16be(s); + if (compression > 1) + return stbi__errpuc("bad compression", "PSD has an unknown compression format"); + + // Create the destination image. + out = (stbi_uc *) stbi__malloc(4 * w*h); + if (!out) return stbi__errpuc("outofmem", "Out of memory"); + pixelCount = w*h; + + // Initialize the data to zero. + //memset( out, 0, pixelCount * 4 ); + + // Finally, the image data. + if (compression) { + // RLE as used by .PSD and .TIFF + // Loop until you get the number of unpacked bytes you are expecting: + // Read the next source byte into n. + // If n is between 0 and 127 inclusive, copy the next n+1 bytes literally. + // Else if n is between -127 and -1 inclusive, copy the next byte -n+1 times. + // Else if n is 128, noop. + // Endloop + + // The RLE-compressed data is preceeded by a 2-byte data count for each row in the data, + // which we're going to just skip. + stbi__skip(s, h * channelCount * 2 ); + + // Read the RLE data by channel. + for (channel = 0; channel < 4; channel++) { + stbi_uc *p; + + p = out+channel; + if (channel >= channelCount) { + // Fill this channel with default data. + for (i = 0; i < pixelCount; i++, p += 4) + *p = (channel == 3 ? 255 : 0); + } else { + // Read the RLE data. + count = 0; + while (count < pixelCount) { + len = stbi__get8(s); + if (len == 128) { + // No-op. + } else if (len < 128) { + // Copy next len+1 bytes literally. + len++; + count += len; + while (len) { + *p = stbi__get8(s); + p += 4; + len--; + } + } else if (len > 128) { + stbi_uc val; + // Next -len+1 bytes in the dest are replicated from next source byte. + // (Interpret len as a negative 8-bit int.) + len ^= 0x0FF; + len += 2; + val = stbi__get8(s); + count += len; + while (len) { + *p = val; + p += 4; + len--; + } + } + } + } + } + + } else { + // We're at the raw image data. It's each channel in order (Red, Green, Blue, Alpha, ...) + // where each channel consists of an 8-bit value for each pixel in the image. + + // Read the data by channel. + for (channel = 0; channel < 4; channel++) { + stbi_uc *p; + + p = out + channel; + if (channel >= channelCount) { + // Fill this channel with default data. + stbi_uc val = channel == 3 ? 255 : 0; + for (i = 0; i < pixelCount; i++, p += 4) + *p = val; + } else { + // Read the data. + if (bitdepth == 16) { + for (i = 0; i < pixelCount; i++, p += 4) + *p = (stbi_uc) (stbi__get16be(s) >> 8); + } else { + for (i = 0; i < pixelCount; i++, p += 4) + *p = stbi__get8(s); + } + } + } + } + + if (req_comp && req_comp != 4) { + out = stbi__convert_format(out, 4, req_comp, w, h); + if (out == NULL) return out; // stbi__convert_format frees input on failure + } + + if (comp) *comp = 4; + *y = h; + *x = w; + + return out; +} +#endif + +// ************************************************************************************************* +// Softimage PIC loader +// by Tom Seddon +// +// See http://softimage.wiki.softimage.com/index.php/INFO:_PIC_file_format +// See http://ozviz.wasp.uwa.edu.au/~pbourke/dataformats/softimagepic/ + +#ifndef STBI_NO_PIC +static int stbi__pic_is4(stbi__context *s,const char *str) +{ + int i; + for (i=0; i<4; ++i) + if (stbi__get8(s) != (stbi_uc)str[i]) + return 0; + + return 1; +} + +static int stbi__pic_test_core(stbi__context *s) +{ + int i; + + if (!stbi__pic_is4(s,"\x53\x80\xF6\x34")) + return 0; + + for(i=0;i<84;++i) + stbi__get8(s); + + if (!stbi__pic_is4(s,"PICT")) + return 0; + + return 1; +} + +typedef struct +{ + stbi_uc size,type,channel; +} stbi__pic_packet; + +static stbi_uc *stbi__readval(stbi__context *s, int channel, stbi_uc *dest) +{ + int mask=0x80, i; + + for (i=0; i<4; ++i, mask>>=1) { + if (channel & mask) { + if (stbi__at_eof(s)) return stbi__errpuc("bad file","PIC file too short"); + dest[i]=stbi__get8(s); + } + } + + return dest; +} + +static void stbi__copyval(int channel,stbi_uc *dest,const stbi_uc *src) +{ + int mask=0x80,i; + + for (i=0;i<4; ++i, mask>>=1) + if (channel&mask) + dest[i]=src[i]; +} + +static stbi_uc *stbi__pic_load_core(stbi__context *s,int width,int height,int *comp, stbi_uc *result) +{ + int act_comp=0,num_packets=0,y,chained; + stbi__pic_packet packets[10]; + + // this will (should...) cater for even some bizarre stuff like having data + // for the same channel in multiple packets. + do { + stbi__pic_packet *packet; + + if (num_packets==sizeof(packets)/sizeof(packets[0])) + return stbi__errpuc("bad format","too many packets"); + + packet = &packets[num_packets++]; + + chained = stbi__get8(s); + packet->size = stbi__get8(s); + packet->type = stbi__get8(s); + packet->channel = stbi__get8(s); + + act_comp |= packet->channel; + + if (stbi__at_eof(s)) return stbi__errpuc("bad file","file too short (reading packets)"); + if (packet->size != 8) return stbi__errpuc("bad format","packet isn't 8bpp"); + } while (chained); + + *comp = (act_comp & 0x10 ? 4 : 3); // has alpha channel? + + for(y=0; ytype) { + default: + return stbi__errpuc("bad format","packet has bad compression type"); + + case 0: {//uncompressed + int x; + + for(x=0;xchannel,dest)) + return 0; + break; + } + + case 1://Pure RLE + { + int left=width, i; + + while (left>0) { + stbi_uc count,value[4]; + + count=stbi__get8(s); + if (stbi__at_eof(s)) return stbi__errpuc("bad file","file too short (pure read count)"); + + if (count > left) + count = (stbi_uc) left; + + if (!stbi__readval(s,packet->channel,value)) return 0; + + for(i=0; ichannel,dest,value); + left -= count; + } + } + break; + + case 2: {//Mixed RLE + int left=width; + while (left>0) { + int count = stbi__get8(s), i; + if (stbi__at_eof(s)) return stbi__errpuc("bad file","file too short (mixed read count)"); + + if (count >= 128) { // Repeated + stbi_uc value[4]; + + if (count==128) + count = stbi__get16be(s); + else + count -= 127; + if (count > left) + return stbi__errpuc("bad file","scanline overrun"); + + if (!stbi__readval(s,packet->channel,value)) + return 0; + + for(i=0;ichannel,dest,value); + } else { // Raw + ++count; + if (count>left) return stbi__errpuc("bad file","scanline overrun"); + + for(i=0;ichannel,dest)) + return 0; + } + left-=count; + } + break; + } + } + } + } + + return result; +} + +static stbi_uc *stbi__pic_load(stbi__context *s,int *px,int *py,int *comp,int req_comp) +{ + stbi_uc *result; + int i, x,y; + + for (i=0; i<92; ++i) + stbi__get8(s); + + x = stbi__get16be(s); + y = stbi__get16be(s); + if (stbi__at_eof(s)) return stbi__errpuc("bad file","file too short (pic header)"); + if ((1 << 28) / x < y) return stbi__errpuc("too large", "Image too large to decode"); + + stbi__get32be(s); //skip `ratio' + stbi__get16be(s); //skip `fields' + stbi__get16be(s); //skip `pad' + + // intermediate buffer is RGBA + result = (stbi_uc *) stbi__malloc(x*y*4); + memset(result, 0xff, x*y*4); + + if (!stbi__pic_load_core(s,x,y,comp, result)) { + STBI_FREE(result); + result=0; + } + *px = x; + *py = y; + if (req_comp == 0) req_comp = *comp; + result=stbi__convert_format(result,4,req_comp,x,y); + + return result; +} + +static int stbi__pic_test(stbi__context *s) +{ + int r = stbi__pic_test_core(s); + stbi__rewind(s); + return r; +} +#endif + +// ************************************************************************************************* +// GIF loader -- public domain by Jean-Marc Lienher -- simplified/shrunk by stb + +#ifndef STBI_NO_GIF +typedef struct +{ + stbi__int16 prefix; + stbi_uc first; + stbi_uc suffix; +} stbi__gif_lzw; + +typedef struct +{ + int w,h; + stbi_uc *out, *old_out; // output buffer (always 4 components) + int flags, bgindex, ratio, transparent, eflags, delay; + stbi_uc pal[256][4]; + stbi_uc lpal[256][4]; + stbi__gif_lzw codes[4096]; + stbi_uc *color_table; + int parse, step; + int lflags; + int start_x, start_y; + int max_x, max_y; + int cur_x, cur_y; + int line_size; +} stbi__gif; + +static int stbi__gif_test_raw(stbi__context *s) +{ + int sz; + if (stbi__get8(s) != 'G' || stbi__get8(s) != 'I' || stbi__get8(s) != 'F' || stbi__get8(s) != '8') return 0; + sz = stbi__get8(s); + if (sz != '9' && sz != '7') return 0; + if (stbi__get8(s) != 'a') return 0; + return 1; +} + +static int stbi__gif_test(stbi__context *s) +{ + int r = stbi__gif_test_raw(s); + stbi__rewind(s); + return r; +} + +static void stbi__gif_parse_colortable(stbi__context *s, stbi_uc pal[256][4], int num_entries, int transp) +{ + int i; + for (i=0; i < num_entries; ++i) { + pal[i][2] = stbi__get8(s); + pal[i][1] = stbi__get8(s); + pal[i][0] = stbi__get8(s); + pal[i][3] = transp == i ? 0 : 255; + } +} + +static int stbi__gif_header(stbi__context *s, stbi__gif *g, int *comp, int is_info) +{ + stbi_uc version; + if (stbi__get8(s) != 'G' || stbi__get8(s) != 'I' || stbi__get8(s) != 'F' || stbi__get8(s) != '8') + return stbi__err("not GIF", "Corrupt GIF"); + + version = stbi__get8(s); + if (version != '7' && version != '9') return stbi__err("not GIF", "Corrupt GIF"); + if (stbi__get8(s) != 'a') return stbi__err("not GIF", "Corrupt GIF"); + + stbi__g_failure_reason = ""; + g->w = stbi__get16le(s); + g->h = stbi__get16le(s); + g->flags = stbi__get8(s); + g->bgindex = stbi__get8(s); + g->ratio = stbi__get8(s); + g->transparent = -1; + + if (comp != 0) *comp = 4; // can't actually tell whether it's 3 or 4 until we parse the comments + + if (is_info) return 1; + + if (g->flags & 0x80) + stbi__gif_parse_colortable(s,g->pal, 2 << (g->flags & 7), -1); + + return 1; +} + +static int stbi__gif_info_raw(stbi__context *s, int *x, int *y, int *comp) +{ + stbi__gif g; + if (!stbi__gif_header(s, &g, comp, 1)) { + stbi__rewind( s ); + return 0; + } + if (x) *x = g.w; + if (y) *y = g.h; + return 1; +} + +static void stbi__out_gif_code(stbi__gif *g, stbi__uint16 code) +{ + stbi_uc *p, *c; + + // recurse to decode the prefixes, since the linked-list is backwards, + // and working backwards through an interleaved image would be nasty + if (g->codes[code].prefix >= 0) + stbi__out_gif_code(g, g->codes[code].prefix); + + if (g->cur_y >= g->max_y) return; + + p = &g->out[g->cur_x + g->cur_y]; + c = &g->color_table[g->codes[code].suffix * 4]; + + if (c[3] >= 128) { + p[0] = c[2]; + p[1] = c[1]; + p[2] = c[0]; + p[3] = c[3]; + } + g->cur_x += 4; + + if (g->cur_x >= g->max_x) { + g->cur_x = g->start_x; + g->cur_y += g->step; + + while (g->cur_y >= g->max_y && g->parse > 0) { + g->step = (1 << g->parse) * g->line_size; + g->cur_y = g->start_y + (g->step >> 1); + --g->parse; + } + } +} + +static stbi_uc *stbi__process_gif_raster(stbi__context *s, stbi__gif *g) +{ + stbi_uc lzw_cs; + stbi__int32 len, init_code; + stbi__uint32 first; + stbi__int32 codesize, codemask, avail, oldcode, bits, valid_bits, clear; + stbi__gif_lzw *p; + + lzw_cs = stbi__get8(s); + if (lzw_cs > 12) return NULL; + clear = 1 << lzw_cs; + first = 1; + codesize = lzw_cs + 1; + codemask = (1 << codesize) - 1; + bits = 0; + valid_bits = 0; + for (init_code = 0; init_code < clear; init_code++) { + g->codes[init_code].prefix = -1; + g->codes[init_code].first = (stbi_uc) init_code; + g->codes[init_code].suffix = (stbi_uc) init_code; + } + + // support no starting clear code + avail = clear+2; + oldcode = -1; + + len = 0; + for(;;) { + if (valid_bits < codesize) { + if (len == 0) { + len = stbi__get8(s); // start new block + if (len == 0) + return g->out; + } + --len; + bits |= (stbi__int32) stbi__get8(s) << valid_bits; + valid_bits += 8; + } else { + stbi__int32 code = bits & codemask; + bits >>= codesize; + valid_bits -= codesize; + // @OPTIMIZE: is there some way we can accelerate the non-clear path? + if (code == clear) { // clear code + codesize = lzw_cs + 1; + codemask = (1 << codesize) - 1; + avail = clear + 2; + oldcode = -1; + first = 0; + } else if (code == clear + 1) { // end of stream code + stbi__skip(s, len); + while ((len = stbi__get8(s)) > 0) + stbi__skip(s,len); + return g->out; + } else if (code <= avail) { + if (first) return stbi__errpuc("no clear code", "Corrupt GIF"); + + if (oldcode >= 0) { + p = &g->codes[avail++]; + if (avail > 4096) return stbi__errpuc("too many codes", "Corrupt GIF"); + p->prefix = (stbi__int16) oldcode; + p->first = g->codes[oldcode].first; + p->suffix = (code == avail) ? p->first : g->codes[code].first; + } else if (code == avail) + return stbi__errpuc("illegal code in raster", "Corrupt GIF"); + + stbi__out_gif_code(g, (stbi__uint16) code); + + if ((avail & codemask) == 0 && avail <= 0x0FFF) { + codesize++; + codemask = (1 << codesize) - 1; + } + + oldcode = code; + } else { + return stbi__errpuc("illegal code in raster", "Corrupt GIF"); + } + } + } +} + +static void stbi__fill_gif_background(stbi__gif *g, int x0, int y0, int x1, int y1) +{ + int x, y; + stbi_uc *c = g->pal[g->bgindex]; + for (y = y0; y < y1; y += 4 * g->w) { + for (x = x0; x < x1; x += 4) { + stbi_uc *p = &g->out[y + x]; + p[0] = c[2]; + p[1] = c[1]; + p[2] = c[0]; + p[3] = 0; + } + } +} + +// this function is designed to support animated gifs, although stb_image doesn't support it +static stbi_uc *stbi__gif_load_next(stbi__context *s, stbi__gif *g, int *comp, int req_comp) +{ + int i; + stbi_uc *prev_out = 0; + + if (g->out == 0 && !stbi__gif_header(s, g, comp,0)) + return 0; // stbi__g_failure_reason set by stbi__gif_header + + prev_out = g->out; + g->out = (stbi_uc *) stbi__malloc(4 * g->w * g->h); + if (g->out == 0) return stbi__errpuc("outofmem", "Out of memory"); + + switch ((g->eflags & 0x1C) >> 2) { + case 0: // unspecified (also always used on 1st frame) + stbi__fill_gif_background(g, 0, 0, 4 * g->w, 4 * g->w * g->h); + break; + case 1: // do not dispose + if (prev_out) memcpy(g->out, prev_out, 4 * g->w * g->h); + g->old_out = prev_out; + break; + case 2: // dispose to background + if (prev_out) memcpy(g->out, prev_out, 4 * g->w * g->h); + stbi__fill_gif_background(g, g->start_x, g->start_y, g->max_x, g->max_y); + break; + case 3: // dispose to previous + if (g->old_out) { + for (i = g->start_y; i < g->max_y; i += 4 * g->w) + memcpy(&g->out[i + g->start_x], &g->old_out[i + g->start_x], g->max_x - g->start_x); + } + break; + } + + for (;;) { + switch (stbi__get8(s)) { + case 0x2C: /* Image Descriptor */ + { + int prev_trans = -1; + stbi__int32 x, y, w, h; + stbi_uc *o; + + x = stbi__get16le(s); + y = stbi__get16le(s); + w = stbi__get16le(s); + h = stbi__get16le(s); + if (((x + w) > (g->w)) || ((y + h) > (g->h))) + return stbi__errpuc("bad Image Descriptor", "Corrupt GIF"); + + g->line_size = g->w * 4; + g->start_x = x * 4; + g->start_y = y * g->line_size; + g->max_x = g->start_x + w * 4; + g->max_y = g->start_y + h * g->line_size; + g->cur_x = g->start_x; + g->cur_y = g->start_y; + + g->lflags = stbi__get8(s); + + if (g->lflags & 0x40) { + g->step = 8 * g->line_size; // first interlaced spacing + g->parse = 3; + } else { + g->step = g->line_size; + g->parse = 0; + } + + if (g->lflags & 0x80) { + stbi__gif_parse_colortable(s,g->lpal, 2 << (g->lflags & 7), g->eflags & 0x01 ? g->transparent : -1); + g->color_table = (stbi_uc *) g->lpal; + } else if (g->flags & 0x80) { + if (g->transparent >= 0 && (g->eflags & 0x01)) { + prev_trans = g->pal[g->transparent][3]; + g->pal[g->transparent][3] = 0; + } + g->color_table = (stbi_uc *) g->pal; + } else + return stbi__errpuc("missing color table", "Corrupt GIF"); + + o = stbi__process_gif_raster(s, g); + if (o == NULL) return NULL; + + if (prev_trans != -1) + g->pal[g->transparent][3] = (stbi_uc) prev_trans; + + return o; + } + + case 0x21: // Comment Extension. + { + int len; + if (stbi__get8(s) == 0xF9) { // Graphic Control Extension. + len = stbi__get8(s); + if (len == 4) { + g->eflags = stbi__get8(s); + g->delay = stbi__get16le(s); + g->transparent = stbi__get8(s); + } else { + stbi__skip(s, len); + break; + } + } + while ((len = stbi__get8(s)) != 0) + stbi__skip(s, len); + break; + } + + case 0x3B: // gif stream termination code + return (stbi_uc *) s; // using '1' causes warning on some compilers + + default: + return stbi__errpuc("unknown code", "Corrupt GIF"); + } + } + + STBI_NOTUSED(req_comp); +} + +static stbi_uc *stbi__gif_load(stbi__context *s, int *x, int *y, int *comp, int req_comp) +{ + stbi_uc *u = 0; + stbi__gif g; + memset(&g, 0, sizeof(g)); + + u = stbi__gif_load_next(s, &g, comp, req_comp); + if (u == (stbi_uc *) s) u = 0; // end of animated gif marker + if (u) { + *x = g.w; + *y = g.h; + if (req_comp && req_comp != 4) + u = stbi__convert_format(u, 4, req_comp, g.w, g.h); + } + else if (g.out) + STBI_FREE(g.out); + + return u; +} + +static int stbi__gif_info(stbi__context *s, int *x, int *y, int *comp) +{ + return stbi__gif_info_raw(s,x,y,comp); +} +#endif + +// ************************************************************************************************* +// Radiance RGBE HDR loader +// originally by Nicolas Schulz +#ifndef STBI_NO_HDR +static int stbi__hdr_test_core(stbi__context *s) +{ + const char *signature = "#?RADIANCE\n"; + int i; + for (i=0; signature[i]; ++i) + if (stbi__get8(s) != signature[i]) + return 0; + return 1; +} + +static int stbi__hdr_test(stbi__context* s) +{ + int r = stbi__hdr_test_core(s); + stbi__rewind(s); + return r; +} + +#define STBI__HDR_BUFLEN 1024 +static char *stbi__hdr_gettoken(stbi__context *z, char *buffer) +{ + int len=0; + char c = '\0'; + + c = (char) stbi__get8(z); + + while (!stbi__at_eof(z) && c != '\n') { + buffer[len++] = c; + if (len == STBI__HDR_BUFLEN-1) { + // flush to end of line + while (!stbi__at_eof(z) && stbi__get8(z) != '\n') + ; + break; + } + c = (char) stbi__get8(z); + } + + buffer[len] = 0; + return buffer; +} + +static void stbi__hdr_convert(float *output, stbi_uc *input, int req_comp) +{ + if ( input[3] != 0 ) { + float f1; + // Exponent + f1 = (float) ldexp(1.0f, input[3] - (int)(128 + 8)); + if (req_comp <= 2) + output[0] = (input[0] + input[1] + input[2]) * f1 / 3; + else { + output[0] = input[0] * f1; + output[1] = input[1] * f1; + output[2] = input[2] * f1; + } + if (req_comp == 2) output[1] = 1; + if (req_comp == 4) output[3] = 1; + } else { + switch (req_comp) { + case 4: output[3] = 1; /* fallthrough */ + case 3: output[0] = output[1] = output[2] = 0; + break; + case 2: output[1] = 1; /* fallthrough */ + case 1: output[0] = 0; + break; + } + } +} + +static float *stbi__hdr_load(stbi__context *s, int *x, int *y, int *comp, int req_comp) +{ + char buffer[STBI__HDR_BUFLEN]; + char *token; + int valid = 0; + int width, height; + stbi_uc *scanline; + float *hdr_data; + int len; + unsigned char count, value; + int i, j, k, c1,c2, z; + + + // Check identifier + if (strcmp(stbi__hdr_gettoken(s,buffer), "#?RADIANCE") != 0) + return stbi__errpf("not HDR", "Corrupt HDR image"); + + // Parse header + for(;;) { + token = stbi__hdr_gettoken(s,buffer); + if (token[0] == 0) break; + if (strcmp(token, "FORMAT=32-bit_rle_rgbe") == 0) valid = 1; + } + + if (!valid) return stbi__errpf("unsupported format", "Unsupported HDR format"); + + // Parse width and height + // can't use sscanf() if we're not using stdio! + token = stbi__hdr_gettoken(s,buffer); + if (strncmp(token, "-Y ", 3)) return stbi__errpf("unsupported data layout", "Unsupported HDR format"); + token += 3; + height = (int) strtol(token, &token, 10); + while (*token == ' ') ++token; + if (strncmp(token, "+X ", 3)) return stbi__errpf("unsupported data layout", "Unsupported HDR format"); + token += 3; + width = (int) strtol(token, NULL, 10); + + *x = width; + *y = height; + + if (comp) *comp = 3; + if (req_comp == 0) req_comp = 3; + + // Read data + hdr_data = (float *) stbi__malloc(height * width * req_comp * sizeof(float)); + + // Load image data + // image data is stored as some number of sca + if ( width < 8 || width >= 32768) { + // Read flat data + for (j=0; j < height; ++j) { + for (i=0; i < width; ++i) { + stbi_uc rgbe[4]; + main_decode_loop: + stbi__getn(s, rgbe, 4); + stbi__hdr_convert(hdr_data + j * width * req_comp + i * req_comp, rgbe, req_comp); + } + } + } else { + // Read RLE-encoded data + scanline = NULL; + + for (j = 0; j < height; ++j) { + c1 = stbi__get8(s); + c2 = stbi__get8(s); + len = stbi__get8(s); + if (c1 != 2 || c2 != 2 || (len & 0x80)) { + // not run-length encoded, so we have to actually use THIS data as a decoded + // pixel (note this can't be a valid pixel--one of RGB must be >= 128) + stbi_uc rgbe[4]; + rgbe[0] = (stbi_uc) c1; + rgbe[1] = (stbi_uc) c2; + rgbe[2] = (stbi_uc) len; + rgbe[3] = (stbi_uc) stbi__get8(s); + stbi__hdr_convert(hdr_data, rgbe, req_comp); + i = 1; + j = 0; + STBI_FREE(scanline); + goto main_decode_loop; // yes, this makes no sense + } + len <<= 8; + len |= stbi__get8(s); + if (len != width) { STBI_FREE(hdr_data); STBI_FREE(scanline); return stbi__errpf("invalid decoded scanline length", "corrupt HDR"); } + if (scanline == NULL) scanline = (stbi_uc *) stbi__malloc(width * 4); + + for (k = 0; k < 4; ++k) { + i = 0; + while (i < width) { + count = stbi__get8(s); + if (count > 128) { + // Run + value = stbi__get8(s); + count -= 128; + for (z = 0; z < count; ++z) + scanline[i++ * 4 + k] = value; + } else { + // Dump + for (z = 0; z < count; ++z) + scanline[i++ * 4 + k] = stbi__get8(s); + } + } + } + for (i=0; i < width; ++i) + stbi__hdr_convert(hdr_data+(j*width + i)*req_comp, scanline + i*4, req_comp); + } + STBI_FREE(scanline); + } + + return hdr_data; +} + +static int stbi__hdr_info(stbi__context *s, int *x, int *y, int *comp) +{ + char buffer[STBI__HDR_BUFLEN]; + char *token; + int valid = 0; + + if (stbi__hdr_test(s) == 0) { + stbi__rewind( s ); + return 0; + } + + for(;;) { + token = stbi__hdr_gettoken(s,buffer); + if (token[0] == 0) break; + if (strcmp(token, "FORMAT=32-bit_rle_rgbe") == 0) valid = 1; + } + + if (!valid) { + stbi__rewind( s ); + return 0; + } + token = stbi__hdr_gettoken(s,buffer); + if (strncmp(token, "-Y ", 3)) { + stbi__rewind( s ); + return 0; + } + token += 3; + *y = (int) strtol(token, &token, 10); + while (*token == ' ') ++token; + if (strncmp(token, "+X ", 3)) { + stbi__rewind( s ); + return 0; + } + token += 3; + *x = (int) strtol(token, NULL, 10); + *comp = 3; + return 1; +} +#endif // STBI_NO_HDR + +#ifndef STBI_NO_BMP +static int stbi__bmp_info(stbi__context *s, int *x, int *y, int *comp) +{ + void *p; + stbi__bmp_data info; + + info.all_a = 255; + p = stbi__bmp_parse_header(s, &info); + stbi__rewind( s ); + if (p == NULL) + return 0; + *x = s->img_x; + *y = s->img_y; + *comp = info.ma ? 4 : 3; + return 1; +} +#endif + +#ifndef STBI_NO_PSD +static int stbi__psd_info(stbi__context *s, int *x, int *y, int *comp) +{ + int channelCount; + if (stbi__get32be(s) != 0x38425053) { + stbi__rewind( s ); + return 0; + } + if (stbi__get16be(s) != 1) { + stbi__rewind( s ); + return 0; + } + stbi__skip(s, 6); + channelCount = stbi__get16be(s); + if (channelCount < 0 || channelCount > 16) { + stbi__rewind( s ); + return 0; + } + *y = stbi__get32be(s); + *x = stbi__get32be(s); + if (stbi__get16be(s) != 8) { + stbi__rewind( s ); + return 0; + } + if (stbi__get16be(s) != 3) { + stbi__rewind( s ); + return 0; + } + *comp = 4; + return 1; +} +#endif + +#ifndef STBI_NO_PIC +static int stbi__pic_info(stbi__context *s, int *x, int *y, int *comp) +{ + int act_comp=0,num_packets=0,chained; + stbi__pic_packet packets[10]; + + if (!stbi__pic_is4(s,"\x53\x80\xF6\x34")) { + stbi__rewind(s); + return 0; + } + + stbi__skip(s, 88); + + *x = stbi__get16be(s); + *y = stbi__get16be(s); + if (stbi__at_eof(s)) { + stbi__rewind( s); + return 0; + } + if ( (*x) != 0 && (1 << 28) / (*x) < (*y)) { + stbi__rewind( s ); + return 0; + } + + stbi__skip(s, 8); + + do { + stbi__pic_packet *packet; + + if (num_packets==sizeof(packets)/sizeof(packets[0])) + return 0; + + packet = &packets[num_packets++]; + chained = stbi__get8(s); + packet->size = stbi__get8(s); + packet->type = stbi__get8(s); + packet->channel = stbi__get8(s); + act_comp |= packet->channel; + + if (stbi__at_eof(s)) { + stbi__rewind( s ); + return 0; + } + if (packet->size != 8) { + stbi__rewind( s ); + return 0; + } + } while (chained); + + *comp = (act_comp & 0x10 ? 4 : 3); + + return 1; +} +#endif + +// ************************************************************************************************* +// Portable Gray Map and Portable Pixel Map loader +// by Ken Miller +// +// PGM: http://netpbm.sourceforge.net/doc/pgm.html +// PPM: http://netpbm.sourceforge.net/doc/ppm.html +// +// Known limitations: +// Does not support comments in the header section +// Does not support ASCII image data (formats P2 and P3) +// Does not support 16-bit-per-channel + +#ifndef STBI_NO_PNM + +static int stbi__pnm_test(stbi__context *s) +{ + char p, t; + p = (char) stbi__get8(s); + t = (char) stbi__get8(s); + if (p != 'P' || (t != '5' && t != '6')) { + stbi__rewind( s ); + return 0; + } + return 1; +} + +static stbi_uc *stbi__pnm_load(stbi__context *s, int *x, int *y, int *comp, int req_comp) +{ + stbi_uc *out; + if (!stbi__pnm_info(s, (int *)&s->img_x, (int *)&s->img_y, (int *)&s->img_n)) + return 0; + *x = s->img_x; + *y = s->img_y; + *comp = s->img_n; + + out = (stbi_uc *) stbi__malloc(s->img_n * s->img_x * s->img_y); + if (!out) return stbi__errpuc("outofmem", "Out of memory"); + stbi__getn(s, out, s->img_n * s->img_x * s->img_y); + + if (req_comp && req_comp != s->img_n) { + out = stbi__convert_format(out, s->img_n, req_comp, s->img_x, s->img_y); + if (out == NULL) return out; // stbi__convert_format frees input on failure + } + return out; +} + +static int stbi__pnm_isspace(char c) +{ + return c == ' ' || c == '\t' || c == '\n' || c == '\v' || c == '\f' || c == '\r'; +} + +static void stbi__pnm_skip_whitespace(stbi__context *s, char *c) +{ + for (;;) { + while (!stbi__at_eof(s) && stbi__pnm_isspace(*c)) + *c = (char) stbi__get8(s); + + if (stbi__at_eof(s) || *c != '#') + break; + + while (!stbi__at_eof(s) && *c != '\n' && *c != '\r' ) + *c = (char) stbi__get8(s); + } +} + +static int stbi__pnm_isdigit(char c) +{ + return c >= '0' && c <= '9'; +} + +static int stbi__pnm_getinteger(stbi__context *s, char *c) +{ + int value = 0; + + while (!stbi__at_eof(s) && stbi__pnm_isdigit(*c)) { + value = value*10 + (*c - '0'); + *c = (char) stbi__get8(s); + } + + return value; +} + +static int stbi__pnm_info(stbi__context *s, int *x, int *y, int *comp) +{ + int maxv; + char c, p, t; + + stbi__rewind( s ); + + // Get identifier + p = (char) stbi__get8(s); + t = (char) stbi__get8(s); + if (p != 'P' || (t != '5' && t != '6')) { + stbi__rewind( s ); + return 0; + } + + *comp = (t == '6') ? 3 : 1; // '5' is 1-component .pgm; '6' is 3-component .ppm + + c = (char) stbi__get8(s); + stbi__pnm_skip_whitespace(s, &c); + + *x = stbi__pnm_getinteger(s, &c); // read width + stbi__pnm_skip_whitespace(s, &c); + + *y = stbi__pnm_getinteger(s, &c); // read height + stbi__pnm_skip_whitespace(s, &c); + + maxv = stbi__pnm_getinteger(s, &c); // read max value + + if (maxv > 255) + return stbi__err("max value > 255", "PPM image not 8-bit"); + else + return 1; +} +#endif + +static int stbi__info_main(stbi__context *s, int *x, int *y, int *comp) +{ + #ifndef STBI_NO_JPEG + if (stbi__jpeg_info(s, x, y, comp)) return 1; + #endif + + #ifndef STBI_NO_PNG + if (stbi__png_info(s, x, y, comp)) return 1; + #endif + + #ifndef STBI_NO_GIF + if (stbi__gif_info(s, x, y, comp)) return 1; + #endif + + #ifndef STBI_NO_BMP + if (stbi__bmp_info(s, x, y, comp)) return 1; + #endif + + #ifndef STBI_NO_PSD + if (stbi__psd_info(s, x, y, comp)) return 1; + #endif + + #ifndef STBI_NO_PIC + if (stbi__pic_info(s, x, y, comp)) return 1; + #endif + + #ifndef STBI_NO_PNM + if (stbi__pnm_info(s, x, y, comp)) return 1; + #endif + + #ifndef STBI_NO_HDR + if (stbi__hdr_info(s, x, y, comp)) return 1; + #endif + + // test tga last because it's a crappy test! + #ifndef STBI_NO_TGA + if (stbi__tga_info(s, x, y, comp)) + return 1; + #endif + return stbi__err("unknown image type", "Image not of any known type, or corrupt"); +} + +#ifndef STBI_NO_STDIO +STBIDEF int stbi_info(char const *filename, int *x, int *y, int *comp) +{ + FILE *f = stbi__fopen(filename, "rb"); + int result; + if (!f) return stbi__err("can't fopen", "Unable to open file"); + result = stbi_info_from_file(f, x, y, comp); + fclose(f); + return result; +} + +STBIDEF int stbi_info_from_file(FILE *f, int *x, int *y, int *comp) +{ + int r; + stbi__context s; + long pos = ftell(f); + stbi__start_file(&s, f); + r = stbi__info_main(&s,x,y,comp); + fseek(f,pos,SEEK_SET); + return r; +} +#endif // !STBI_NO_STDIO + +STBIDEF int stbi_info_from_memory(stbi_uc const *buffer, int len, int *x, int *y, int *comp) +{ + stbi__context s; + stbi__start_mem(&s,buffer,len); + return stbi__info_main(&s,x,y,comp); +} + +STBIDEF int stbi_info_from_callbacks(stbi_io_callbacks const *c, void *user, int *x, int *y, int *comp) +{ + stbi__context s; + stbi__start_callbacks(&s, (stbi_io_callbacks *) c, user); + return stbi__info_main(&s,x,y,comp); +} + +#endif // STB_IMAGE_IMPLEMENTATION + +/* + revision history: + 2.10 (2016-01-22) avoid warning introduced in 2.09 by STBI_REALLOC_SIZED + 2.09 (2016-01-16) allow comments in PNM files + 16-bit-per-pixel TGA (not bit-per-component) + info() for TGA could break due to .hdr handling + info() for BMP to shares code instead of sloppy parse + can use STBI_REALLOC_SIZED if allocator doesn't support realloc + code cleanup + 2.08 (2015-09-13) fix to 2.07 cleanup, reading RGB PSD as RGBA + 2.07 (2015-09-13) fix compiler warnings + partial animated GIF support + limited 16-bpc PSD support + #ifdef unused functions + bug with < 92 byte PIC,PNM,HDR,TGA + 2.06 (2015-04-19) fix bug where PSD returns wrong '*comp' value + 2.05 (2015-04-19) fix bug in progressive JPEG handling, fix warning + 2.04 (2015-04-15) try to re-enable SIMD on MinGW 64-bit + 2.03 (2015-04-12) extra corruption checking (mmozeiko) + stbi_set_flip_vertically_on_load (nguillemot) + fix NEON support; fix mingw support + 2.02 (2015-01-19) fix incorrect assert, fix warning + 2.01 (2015-01-17) fix various warnings; suppress SIMD on gcc 32-bit without -msse2 + 2.00b (2014-12-25) fix STBI_MALLOC in progressive JPEG + 2.00 (2014-12-25) optimize JPG, including x86 SSE2 & NEON SIMD (ryg) + progressive JPEG (stb) + PGM/PPM support (Ken Miller) + STBI_MALLOC,STBI_REALLOC,STBI_FREE + GIF bugfix -- seemingly never worked + STBI_NO_*, STBI_ONLY_* + 1.48 (2014-12-14) fix incorrectly-named assert() + 1.47 (2014-12-14) 1/2/4-bit PNG support, both direct and paletted (Omar Cornut & stb) + optimize PNG (ryg) + fix bug in interlaced PNG with user-specified channel count (stb) + 1.46 (2014-08-26) + fix broken tRNS chunk (colorkey-style transparency) in non-paletted PNG + 1.45 (2014-08-16) + fix MSVC-ARM internal compiler error by wrapping malloc + 1.44 (2014-08-07) + various warning fixes from Ronny Chevalier + 1.43 (2014-07-15) + fix MSVC-only compiler problem in code changed in 1.42 + 1.42 (2014-07-09) + don't define _CRT_SECURE_NO_WARNINGS (affects user code) + fixes to stbi__cleanup_jpeg path + added STBI_ASSERT to avoid requiring assert.h + 1.41 (2014-06-25) + fix search&replace from 1.36 that messed up comments/error messages + 1.40 (2014-06-22) + fix gcc struct-initialization warning + 1.39 (2014-06-15) + fix to TGA optimization when req_comp != number of components in TGA; + fix to GIF loading because BMP wasn't rewinding (whoops, no GIFs in my test suite) + add support for BMP version 5 (more ignored fields) + 1.38 (2014-06-06) + suppress MSVC warnings on integer casts truncating values + fix accidental rename of 'skip' field of I/O + 1.37 (2014-06-04) + remove duplicate typedef + 1.36 (2014-06-03) + convert to header file single-file library + if de-iphone isn't set, load iphone images color-swapped instead of returning NULL + 1.35 (2014-05-27) + various warnings + fix broken STBI_SIMD path + fix bug where stbi_load_from_file no longer left file pointer in correct place + fix broken non-easy path for 32-bit BMP (possibly never used) + TGA optimization by Arseny Kapoulkine + 1.34 (unknown) + use STBI_NOTUSED in stbi__resample_row_generic(), fix one more leak in tga failure case + 1.33 (2011-07-14) + make stbi_is_hdr work in STBI_NO_HDR (as specified), minor compiler-friendly improvements + 1.32 (2011-07-13) + support for "info" function for all supported filetypes (SpartanJ) + 1.31 (2011-06-20) + a few more leak fixes, bug in PNG handling (SpartanJ) + 1.30 (2011-06-11) + added ability to load files via callbacks to accomidate custom input streams (Ben Wenger) + removed deprecated format-specific test/load functions + removed support for installable file formats (stbi_loader) -- would have been broken for IO callbacks anyway + error cases in bmp and tga give messages and don't leak (Raymond Barbiero, grisha) + fix inefficiency in decoding 32-bit BMP (David Woo) + 1.29 (2010-08-16) + various warning fixes from Aurelien Pocheville + 1.28 (2010-08-01) + fix bug in GIF palette transparency (SpartanJ) + 1.27 (2010-08-01) + cast-to-stbi_uc to fix warnings + 1.26 (2010-07-24) + fix bug in file buffering for PNG reported by SpartanJ + 1.25 (2010-07-17) + refix trans_data warning (Won Chun) + 1.24 (2010-07-12) + perf improvements reading from files on platforms with lock-heavy fgetc() + minor perf improvements for jpeg + deprecated type-specific functions so we'll get feedback if they're needed + attempt to fix trans_data warning (Won Chun) + 1.23 fixed bug in iPhone support + 1.22 (2010-07-10) + removed image *writing* support + stbi_info support from Jetro Lauha + GIF support from Jean-Marc Lienher + iPhone PNG-extensions from James Brown + warning-fixes from Nicolas Schulz and Janez Zemva (i.stbi__err. Janez (U+017D)emva) + 1.21 fix use of 'stbi_uc' in header (reported by jon blow) + 1.20 added support for Softimage PIC, by Tom Seddon + 1.19 bug in interlaced PNG corruption check (found by ryg) + 1.18 (2008-08-02) + fix a threading bug (local mutable static) + 1.17 support interlaced PNG + 1.16 major bugfix - stbi__convert_format converted one too many pixels + 1.15 initialize some fields for thread safety + 1.14 fix threadsafe conversion bug + header-file-only version (#define STBI_HEADER_FILE_ONLY before including) + 1.13 threadsafe + 1.12 const qualifiers in the API + 1.11 Support installable IDCT, colorspace conversion routines + 1.10 Fixes for 64-bit (don't use "unsigned long") + optimized upsampling by Fabian "ryg" Giesen + 1.09 Fix format-conversion for PSD code (bad global variables!) + 1.08 Thatcher Ulrich's PSD code integrated by Nicolas Schulz + 1.07 attempt to fix C++ warning/errors again + 1.06 attempt to fix C++ warning/errors again + 1.05 fix TGA loading to return correct *comp and use good luminance calc + 1.04 default float alpha is 1, not 255; use 'void *' for stbi_image_free + 1.03 bugfixes to STBI_NO_STDIO, STBI_NO_HDR + 1.02 support for (subset of) HDR files, float interface for preferred access to them + 1.01 fix bug: possible bug in handling right-side up bmps... not sure + fix bug: the stbi__bmp_load() and stbi__tga_load() functions didn't work at all + 1.00 interface to zlib that skips zlib header + 0.99 correct handling of alpha in palette + 0.98 TGA loader by lonesock; dynamically add loaders (untested) + 0.97 jpeg errors on too large a file; also catch another malloc failure + 0.96 fix detection of invalid v value - particleman@mollyrocket forum + 0.95 during header scan, seek to markers in case of padding + 0.94 STBI_NO_STDIO to disable stdio usage; rename all #defines the same + 0.93 handle jpegtran output; verbose errors + 0.92 read 4,8,16,24,32-bit BMP files of several formats + 0.91 output 24-bit Windows 3.0 BMP files + 0.90 fix a few more warnings; bump version number to approach 1.0 + 0.61 bugfixes due to Marc LeBlanc, Christopher Lloyd + 0.60 fix compiling as c++ + 0.59 fix warnings: merge Dave Moore's -Wall fixes + 0.58 fix bug: zlib uncompressed mode len/nlen was wrong endian + 0.57 fix bug: jpg last huffman symbol before marker was >9 bits but less than 16 available + 0.56 fix bug: zlib uncompressed mode len vs. nlen + 0.55 fix bug: restart_interval not initialized to 0 + 0.54 allow NULL for 'int *comp' + 0.53 fix bug in png 3->4; speedup png decoding + 0.52 png handles req_comp=3,4 directly; minor cleanup; jpeg comments + 0.51 obey req_comp requests, 1-component jpegs return as 1-component, + on 'test' only check type, not whether we support this variant + 0.50 (2006-11-19) + first released version +*/ diff --git a/phonelibs/nanovg/stb_truetype.h b/phonelibs/nanovg/stb_truetype.h new file mode 100644 index 00000000000000..bfb1841f6989ce --- /dev/null +++ b/phonelibs/nanovg/stb_truetype.h @@ -0,0 +1,3249 @@ +// stb_truetype.h - v1.09 - public domain +// authored from 2009-2015 by Sean Barrett / RAD Game Tools +// +// This library processes TrueType files: +// parse files +// extract glyph metrics +// extract glyph shapes +// render glyphs to one-channel bitmaps with antialiasing (box filter) +// +// Todo: +// non-MS cmaps +// crashproof on bad data +// hinting? (no longer patented) +// cleartype-style AA? +// optimize: use simple memory allocator for intermediates +// optimize: build edge-list directly from curves +// optimize: rasterize directly from curves? +// +// ADDITIONAL CONTRIBUTORS +// +// Mikko Mononen: compound shape support, more cmap formats +// Tor Andersson: kerning, subpixel rendering +// +// Bug/warning reports/fixes: +// "Zer" on mollyrocket (with fix) +// Cass Everitt +// stoiko (Haemimont Games) +// Brian Hook +// Walter van Niftrik +// David Gow +// David Given +// Ivan-Assen Ivanov +// Anthony Pesch +// Johan Duparc +// Hou Qiming +// Fabian "ryg" Giesen +// Martins Mozeiko +// Cap Petschulat +// Omar Cornut +// github:aloucks +// Peter LaValle +// Sergey Popov +// Giumo X. Clanjor +// Higor Euripedes +// Thomas Fields +// Derek Vinyard +// +// Misc other: +// Ryan Gordon +// +// VERSION HISTORY +// +// 1.09 (2016-01-16) warning fix; avoid crash on outofmem; use allocation userdata properly +// 1.08 (2015-09-13) document stbtt_Rasterize(); fixes for vertical & horizontal edges +// 1.07 (2015-08-01) allow PackFontRanges to accept arrays of sparse codepoints; +// variant PackFontRanges to pack and render in separate phases; +// fix stbtt_GetFontOFfsetForIndex (never worked for non-0 input?); +// fixed an assert() bug in the new rasterizer +// replace assert() with STBTT_assert() in new rasterizer +// 1.06 (2015-07-14) performance improvements (~35% faster on x86 and x64 on test machine) +// also more precise AA rasterizer, except if shapes overlap +// remove need for STBTT_sort +// 1.05 (2015-04-15) fix misplaced definitions for STBTT_STATIC +// 1.04 (2015-04-15) typo in example +// 1.03 (2015-04-12) STBTT_STATIC, fix memory leak in new packing, various fixes +// +// Full history can be found at the end of this file. +// +// LICENSE +// +// This software is in the public domain. Where that dedication is not +// recognized, you are granted a perpetual, irrevocable license to copy, +// distribute, and modify this file as you see fit. +// +// USAGE +// +// Include this file in whatever places neeed to refer to it. In ONE C/C++ +// file, write: +// #define STB_TRUETYPE_IMPLEMENTATION +// before the #include of this file. This expands out the actual +// implementation into that C/C++ file. +// +// To make the implementation private to the file that generates the implementation, +// #define STBTT_STATIC +// +// Simple 3D API (don't ship this, but it's fine for tools and quick start) +// stbtt_BakeFontBitmap() -- bake a font to a bitmap for use as texture +// stbtt_GetBakedQuad() -- compute quad to draw for a given char +// +// Improved 3D API (more shippable): +// #include "stb_rect_pack.h" -- optional, but you really want it +// stbtt_PackBegin() +// stbtt_PackSetOversample() -- for improved quality on small fonts +// stbtt_PackFontRanges() -- pack and renders +// stbtt_PackEnd() +// stbtt_GetPackedQuad() +// +// "Load" a font file from a memory buffer (you have to keep the buffer loaded) +// stbtt_InitFont() +// stbtt_GetFontOffsetForIndex() -- use for TTC font collections +// +// Render a unicode codepoint to a bitmap +// stbtt_GetCodepointBitmap() -- allocates and returns a bitmap +// stbtt_MakeCodepointBitmap() -- renders into bitmap you provide +// stbtt_GetCodepointBitmapBox() -- how big the bitmap must be +// +// Character advance/positioning +// stbtt_GetCodepointHMetrics() +// stbtt_GetFontVMetrics() +// stbtt_GetCodepointKernAdvance() +// +// Starting with version 1.06, the rasterizer was replaced with a new, +// faster and generally-more-precise rasterizer. The new rasterizer more +// accurately measures pixel coverage for anti-aliasing, except in the case +// where multiple shapes overlap, in which case it overestimates the AA pixel +// coverage. Thus, anti-aliasing of intersecting shapes may look wrong. If +// this turns out to be a problem, you can re-enable the old rasterizer with +// #define STBTT_RASTERIZER_VERSION 1 +// which will incur about a 15% speed hit. +// +// ADDITIONAL DOCUMENTATION +// +// Immediately after this block comment are a series of sample programs. +// +// After the sample programs is the "header file" section. This section +// includes documentation for each API function. +// +// Some important concepts to understand to use this library: +// +// Codepoint +// Characters are defined by unicode codepoints, e.g. 65 is +// uppercase A, 231 is lowercase c with a cedilla, 0x7e30 is +// the hiragana for "ma". +// +// Glyph +// A visual character shape (every codepoint is rendered as +// some glyph) +// +// Glyph index +// A font-specific integer ID representing a glyph +// +// Baseline +// Glyph shapes are defined relative to a baseline, which is the +// bottom of uppercase characters. Characters extend both above +// and below the baseline. +// +// Current Point +// As you draw text to the screen, you keep track of a "current point" +// which is the origin of each character. The current point's vertical +// position is the baseline. Even "baked fonts" use this model. +// +// Vertical Font Metrics +// The vertical qualities of the font, used to vertically position +// and space the characters. See docs for stbtt_GetFontVMetrics. +// +// Font Size in Pixels or Points +// The preferred interface for specifying font sizes in stb_truetype +// is to specify how tall the font's vertical extent should be in pixels. +// If that sounds good enough, skip the next paragraph. +// +// Most font APIs instead use "points", which are a common typographic +// measurement for describing font size, defined as 72 points per inch. +// stb_truetype provides a point API for compatibility. However, true +// "per inch" conventions don't make much sense on computer displays +// since they different monitors have different number of pixels per +// inch. For example, Windows traditionally uses a convention that +// there are 96 pixels per inch, thus making 'inch' measurements have +// nothing to do with inches, and thus effectively defining a point to +// be 1.333 pixels. Additionally, the TrueType font data provides +// an explicit scale factor to scale a given font's glyphs to points, +// but the author has observed that this scale factor is often wrong +// for non-commercial fonts, thus making fonts scaled in points +// according to the TrueType spec incoherently sized in practice. +// +// ADVANCED USAGE +// +// Quality: +// +// - Use the functions with Subpixel at the end to allow your characters +// to have subpixel positioning. Since the font is anti-aliased, not +// hinted, this is very import for quality. (This is not possible with +// baked fonts.) +// +// - Kerning is now supported, and if you're supporting subpixel rendering +// then kerning is worth using to give your text a polished look. +// +// Performance: +// +// - Convert Unicode codepoints to glyph indexes and operate on the glyphs; +// if you don't do this, stb_truetype is forced to do the conversion on +// every call. +// +// - There are a lot of memory allocations. We should modify it to take +// a temp buffer and allocate from the temp buffer (without freeing), +// should help performance a lot. +// +// NOTES +// +// The system uses the raw data found in the .ttf file without changing it +// and without building auxiliary data structures. This is a bit inefficient +// on little-endian systems (the data is big-endian), but assuming you're +// caching the bitmaps or glyph shapes this shouldn't be a big deal. +// +// It appears to be very hard to programmatically determine what font a +// given file is in a general way. I provide an API for this, but I don't +// recommend it. +// +// +// SOURCE STATISTICS (based on v0.6c, 2050 LOC) +// +// Documentation & header file 520 LOC \___ 660 LOC documentation +// Sample code 140 LOC / +// Truetype parsing 620 LOC ---- 620 LOC TrueType +// Software rasterization 240 LOC \ . +// Curve tesselation 120 LOC \__ 550 LOC Bitmap creation +// Bitmap management 100 LOC / +// Baked bitmap interface 70 LOC / +// Font name matching & access 150 LOC ---- 150 +// C runtime library abstraction 60 LOC ---- 60 +// +// +// PERFORMANCE MEASUREMENTS FOR 1.06: +// +// 32-bit 64-bit +// Previous release: 8.83 s 7.68 s +// Pool allocations: 7.72 s 6.34 s +// Inline sort : 6.54 s 5.65 s +// New rasterizer : 5.63 s 5.00 s + +////////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////////// +//// +//// SAMPLE PROGRAMS +//// +// +// Incomplete text-in-3d-api example, which draws quads properly aligned to be lossless +// +#if 0 +#define STB_TRUETYPE_IMPLEMENTATION // force following include to generate implementation +#include "stb_truetype.h" + +unsigned char ttf_buffer[1<<20]; +unsigned char temp_bitmap[512*512]; + +stbtt_bakedchar cdata[96]; // ASCII 32..126 is 95 glyphs +GLuint ftex; + +void my_stbtt_initfont(void) +{ + fread(ttf_buffer, 1, 1<<20, fopen("c:/windows/fonts/times.ttf", "rb")); + stbtt_BakeFontBitmap(ttf_buffer,0, 32.0, temp_bitmap,512,512, 32,96, cdata); // no guarantee this fits! + // can free ttf_buffer at this point + glGenTextures(1, &ftex); + glBindTexture(GL_TEXTURE_2D, ftex); + glTexImage2D(GL_TEXTURE_2D, 0, GL_ALPHA, 512,512, 0, GL_ALPHA, GL_UNSIGNED_BYTE, temp_bitmap); + // can free temp_bitmap at this point + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_LINEAR); +} + +void my_stbtt_print(float x, float y, char *text) +{ + // assume orthographic projection with units = screen pixels, origin at top left + glEnable(GL_TEXTURE_2D); + glBindTexture(GL_TEXTURE_2D, ftex); + glBegin(GL_QUADS); + while (*text) { + if (*text >= 32 && *text < 128) { + stbtt_aligned_quad q; + stbtt_GetBakedQuad(cdata, 512,512, *text-32, &x,&y,&q,1);//1=opengl & d3d10+,0=d3d9 + glTexCoord2f(q.s0,q.t1); glVertex2f(q.x0,q.y0); + glTexCoord2f(q.s1,q.t1); glVertex2f(q.x1,q.y0); + glTexCoord2f(q.s1,q.t0); glVertex2f(q.x1,q.y1); + glTexCoord2f(q.s0,q.t0); glVertex2f(q.x0,q.y1); + } + ++text; + } + glEnd(); +} +#endif +// +// +////////////////////////////////////////////////////////////////////////////// +// +// Complete program (this compiles): get a single bitmap, print as ASCII art +// +#if 0 +#include +#define STB_TRUETYPE_IMPLEMENTATION // force following include to generate implementation +#include "stb_truetype.h" + +char ttf_buffer[1<<25]; + +int main(int argc, char **argv) +{ + stbtt_fontinfo font; + unsigned char *bitmap; + int w,h,i,j,c = (argc > 1 ? atoi(argv[1]) : 'a'), s = (argc > 2 ? atoi(argv[2]) : 20); + + fread(ttf_buffer, 1, 1<<25, fopen(argc > 3 ? argv[3] : "c:/windows/fonts/arialbd.ttf", "rb")); + + stbtt_InitFont(&font, ttf_buffer, stbtt_GetFontOffsetForIndex(ttf_buffer,0)); + bitmap = stbtt_GetCodepointBitmap(&font, 0,stbtt_ScaleForPixelHeight(&font, s), c, &w, &h, 0,0); + + for (j=0; j < h; ++j) { + for (i=0; i < w; ++i) + putchar(" .:ioVM@"[bitmap[j*w+i]>>5]); + putchar('\n'); + } + return 0; +} +#endif +// +// Output: +// +// .ii. +// @@@@@@. +// V@Mio@@o +// :i. V@V +// :oM@@M +// :@@@MM@M +// @@o o@M +// :@@. M@M +// @@@o@@@@ +// :M@@V:@@. +// +////////////////////////////////////////////////////////////////////////////// +// +// Complete program: print "Hello World!" banner, with bugs +// +#if 0 +char buffer[24<<20]; +unsigned char screen[20][79]; + +int main(int arg, char **argv) +{ + stbtt_fontinfo font; + int i,j,ascent,baseline,ch=0; + float scale, xpos=2; // leave a little padding in case the character extends left + char *text = "Heljo World!"; // intentionally misspelled to show 'lj' brokenness + + fread(buffer, 1, 1000000, fopen("c:/windows/fonts/arialbd.ttf", "rb")); + stbtt_InitFont(&font, buffer, 0); + + scale = stbtt_ScaleForPixelHeight(&font, 15); + stbtt_GetFontVMetrics(&font, &ascent,0,0); + baseline = (int) (ascent*scale); + + while (text[ch]) { + int advance,lsb,x0,y0,x1,y1; + float x_shift = xpos - (float) floor(xpos); + stbtt_GetCodepointHMetrics(&font, text[ch], &advance, &lsb); + stbtt_GetCodepointBitmapBoxSubpixel(&font, text[ch], scale,scale,x_shift,0, &x0,&y0,&x1,&y1); + stbtt_MakeCodepointBitmapSubpixel(&font, &screen[baseline + y0][(int) xpos + x0], x1-x0,y1-y0, 79, scale,scale,x_shift,0, text[ch]); + // note that this stomps the old data, so where character boxes overlap (e.g. 'lj') it's wrong + // because this API is really for baking character bitmaps into textures. if you want to render + // a sequence of characters, you really need to render each bitmap to a temp buffer, then + // "alpha blend" that into the working buffer + xpos += (advance * scale); + if (text[ch+1]) + xpos += scale*stbtt_GetCodepointKernAdvance(&font, text[ch],text[ch+1]); + ++ch; + } + + for (j=0; j < 20; ++j) { + for (i=0; i < 78; ++i) + putchar(" .:ioVM@"[screen[j][i]>>5]); + putchar('\n'); + } + + return 0; +} +#endif + + +////////////////////////////////////////////////////////////////////////////// +////////////////////////////////////////////////////////////////////////////// +//// +//// INTEGRATION WITH YOUR CODEBASE +//// +//// The following sections allow you to supply alternate definitions +//// of C library functions used by stb_truetype. + +#ifdef STB_TRUETYPE_IMPLEMENTATION + // #define your own (u)stbtt_int8/16/32 before including to override this + #ifndef stbtt_uint8 + typedef unsigned char stbtt_uint8; + typedef signed char stbtt_int8; + typedef unsigned short stbtt_uint16; + typedef signed short stbtt_int16; + typedef unsigned int stbtt_uint32; + typedef signed int stbtt_int32; + #endif + + typedef char stbtt__check_size32[sizeof(stbtt_int32)==4 ? 1 : -1]; + typedef char stbtt__check_size16[sizeof(stbtt_int16)==2 ? 1 : -1]; + + // #define your own STBTT_ifloor/STBTT_iceil() to avoid math.h + #ifndef STBTT_ifloor + #include + #define STBTT_ifloor(x) ((int) floor(x)) + #define STBTT_iceil(x) ((int) ceil(x)) + #endif + + #ifndef STBTT_sqrt + #include + #define STBTT_sqrt(x) sqrt(x) + #endif + + // #define your own functions "STBTT_malloc" / "STBTT_free" to avoid malloc.h + #ifndef STBTT_malloc + #include + #define STBTT_malloc(x,u) ((void)(u),malloc(x)) + #define STBTT_free(x,u) ((void)(u),free(x)) + #endif + + #ifndef STBTT_assert + #include + #define STBTT_assert(x) assert(x) + #endif + + #ifndef STBTT_strlen + #include + #define STBTT_strlen(x) strlen(x) + #endif + + #ifndef STBTT_memcpy + #include + #define STBTT_memcpy memcpy + #define STBTT_memset memset + #endif +#endif + +/////////////////////////////////////////////////////////////////////////////// +/////////////////////////////////////////////////////////////////////////////// +//// +//// INTERFACE +//// +//// + +#ifndef __STB_INCLUDE_STB_TRUETYPE_H__ +#define __STB_INCLUDE_STB_TRUETYPE_H__ + +#ifdef STBTT_STATIC +#define STBTT_DEF static +#else +#define STBTT_DEF extern +#endif + +#ifdef __cplusplus +extern "C" { +#endif + +////////////////////////////////////////////////////////////////////////////// +// +// TEXTURE BAKING API +// +// If you use this API, you only have to call two functions ever. +// + +typedef struct +{ + unsigned short x0,y0,x1,y1; // coordinates of bbox in bitmap + float xoff,yoff,xadvance; +} stbtt_bakedchar; + +STBTT_DEF int stbtt_BakeFontBitmap(const unsigned char *data, int offset, // font location (use offset=0 for plain .ttf) + float pixel_height, // height of font in pixels + unsigned char *pixels, int pw, int ph, // bitmap to be filled in + int first_char, int num_chars, // characters to bake + stbtt_bakedchar *chardata); // you allocate this, it's num_chars long +// if return is positive, the first unused row of the bitmap +// if return is negative, returns the negative of the number of characters that fit +// if return is 0, no characters fit and no rows were used +// This uses a very crappy packing. + +typedef struct +{ + float x0,y0,s0,t0; // top-left + float x1,y1,s1,t1; // bottom-right +} stbtt_aligned_quad; + +STBTT_DEF void stbtt_GetBakedQuad(stbtt_bakedchar *chardata, int pw, int ph, // same data as above + int char_index, // character to display + float *xpos, float *ypos, // pointers to current position in screen pixel space + stbtt_aligned_quad *q, // output: quad to draw + int opengl_fillrule); // true if opengl fill rule; false if DX9 or earlier +// Call GetBakedQuad with char_index = 'character - first_char', and it +// creates the quad you need to draw and advances the current position. +// +// The coordinate system used assumes y increases downwards. +// +// Characters will extend both above and below the current position; +// see discussion of "BASELINE" above. +// +// It's inefficient; you might want to c&p it and optimize it. + + + +////////////////////////////////////////////////////////////////////////////// +// +// NEW TEXTURE BAKING API +// +// This provides options for packing multiple fonts into one atlas, not +// perfectly but better than nothing. + +typedef struct +{ + unsigned short x0,y0,x1,y1; // coordinates of bbox in bitmap + float xoff,yoff,xadvance; + float xoff2,yoff2; +} stbtt_packedchar; + +typedef struct stbtt_pack_context stbtt_pack_context; +typedef struct stbtt_fontinfo stbtt_fontinfo; +#ifndef STB_RECT_PACK_VERSION +typedef struct stbrp_rect stbrp_rect; +#endif + +STBTT_DEF int stbtt_PackBegin(stbtt_pack_context *spc, unsigned char *pixels, int width, int height, int stride_in_bytes, int padding, void *alloc_context); +// Initializes a packing context stored in the passed-in stbtt_pack_context. +// Future calls using this context will pack characters into the bitmap passed +// in here: a 1-channel bitmap that is weight x height. stride_in_bytes is +// the distance from one row to the next (or 0 to mean they are packed tightly +// together). "padding" is the amount of padding to leave between each +// character (normally you want '1' for bitmaps you'll use as textures with +// bilinear filtering). +// +// Returns 0 on failure, 1 on success. + +STBTT_DEF void stbtt_PackEnd (stbtt_pack_context *spc); +// Cleans up the packing context and frees all memory. + +#define STBTT_POINT_SIZE(x) (-(x)) + +STBTT_DEF int stbtt_PackFontRange(stbtt_pack_context *spc, unsigned char *fontdata, int font_index, float font_size, + int first_unicode_char_in_range, int num_chars_in_range, stbtt_packedchar *chardata_for_range); +// Creates character bitmaps from the font_index'th font found in fontdata (use +// font_index=0 if you don't know what that is). It creates num_chars_in_range +// bitmaps for characters with unicode values starting at first_unicode_char_in_range +// and increasing. Data for how to render them is stored in chardata_for_range; +// pass these to stbtt_GetPackedQuad to get back renderable quads. +// +// font_size is the full height of the character from ascender to descender, +// as computed by stbtt_ScaleForPixelHeight. To use a point size as computed +// by stbtt_ScaleForMappingEmToPixels, wrap the point size in STBTT_POINT_SIZE() +// and pass that result as 'font_size': +// ..., 20 , ... // font max minus min y is 20 pixels tall +// ..., STBTT_POINT_SIZE(20), ... // 'M' is 20 pixels tall + +typedef struct +{ + float font_size; + int first_unicode_codepoint_in_range; // if non-zero, then the chars are continuous, and this is the first codepoint + int *array_of_unicode_codepoints; // if non-zero, then this is an array of unicode codepoints + int num_chars; + stbtt_packedchar *chardata_for_range; // output + unsigned char h_oversample, v_oversample; // don't set these, they're used internally +} stbtt_pack_range; + +STBTT_DEF int stbtt_PackFontRanges(stbtt_pack_context *spc, unsigned char *fontdata, int font_index, stbtt_pack_range *ranges, int num_ranges); +// Creates character bitmaps from multiple ranges of characters stored in +// ranges. This will usually create a better-packed bitmap than multiple +// calls to stbtt_PackFontRange. Note that you can call this multiple +// times within a single PackBegin/PackEnd. + +STBTT_DEF void stbtt_PackSetOversampling(stbtt_pack_context *spc, unsigned int h_oversample, unsigned int v_oversample); +// Oversampling a font increases the quality by allowing higher-quality subpixel +// positioning, and is especially valuable at smaller text sizes. +// +// This function sets the amount of oversampling for all following calls to +// stbtt_PackFontRange(s) or stbtt_PackFontRangesGatherRects for a given +// pack context. The default (no oversampling) is achieved by h_oversample=1 +// and v_oversample=1. The total number of pixels required is +// h_oversample*v_oversample larger than the default; for example, 2x2 +// oversampling requires 4x the storage of 1x1. For best results, render +// oversampled textures with bilinear filtering. Look at the readme in +// stb/tests/oversample for information about oversampled fonts +// +// To use with PackFontRangesGather etc., you must set it before calls +// call to PackFontRangesGatherRects. + +STBTT_DEF void stbtt_GetPackedQuad(stbtt_packedchar *chardata, int pw, int ph, // same data as above + int char_index, // character to display + float *xpos, float *ypos, // pointers to current position in screen pixel space + stbtt_aligned_quad *q, // output: quad to draw + int align_to_integer); + +STBTT_DEF int stbtt_PackFontRangesGatherRects(stbtt_pack_context *spc, stbtt_fontinfo *info, stbtt_pack_range *ranges, int num_ranges, stbrp_rect *rects); +STBTT_DEF void stbtt_PackFontRangesPackRects(stbtt_pack_context *spc, stbrp_rect *rects, int num_rects); +STBTT_DEF int stbtt_PackFontRangesRenderIntoRects(stbtt_pack_context *spc, stbtt_fontinfo *info, stbtt_pack_range *ranges, int num_ranges, stbrp_rect *rects); +// Calling these functions in sequence is roughly equivalent to calling +// stbtt_PackFontRanges(). If you more control over the packing of multiple +// fonts, or if you want to pack custom data into a font texture, take a look +// at the source to of stbtt_PackFontRanges() and create a custom version +// using these functions, e.g. call GatherRects multiple times, +// building up a single array of rects, then call PackRects once, +// then call RenderIntoRects repeatedly. This may result in a +// better packing than calling PackFontRanges multiple times +// (or it may not). + +// this is an opaque structure that you shouldn't mess with which holds +// all the context needed from PackBegin to PackEnd. +struct stbtt_pack_context { + void *user_allocator_context; + void *pack_info; + int width; + int height; + int stride_in_bytes; + int padding; + unsigned int h_oversample, v_oversample; + unsigned char *pixels; + void *nodes; +}; + +////////////////////////////////////////////////////////////////////////////// +// +// FONT LOADING +// +// + +STBTT_DEF int stbtt_GetFontOffsetForIndex(const unsigned char *data, int index); +// Each .ttf/.ttc file may have more than one font. Each font has a sequential +// index number starting from 0. Call this function to get the font offset for +// a given index; it returns -1 if the index is out of range. A regular .ttf +// file will only define one font and it always be at offset 0, so it will +// return '0' for index 0, and -1 for all other indices. You can just skip +// this step if you know it's that kind of font. + + +// The following structure is defined publically so you can declare one on +// the stack or as a global or etc, but you should treat it as opaque. +typedef struct stbtt_fontinfo +{ + void * userdata; + unsigned char * data; // pointer to .ttf file + int fontstart; // offset of start of font + + int numGlyphs; // number of glyphs, needed for range checking + + int loca,head,glyf,hhea,hmtx,kern; // table locations as offset from start of .ttf + int index_map; // a cmap mapping for our chosen character encoding + int indexToLocFormat; // format needed to map from glyph index to glyph +} stbtt_fontinfo; + +STBTT_DEF int stbtt_InitFont(stbtt_fontinfo *info, const unsigned char *data, int offset); +// Given an offset into the file that defines a font, this function builds +// the necessary cached info for the rest of the system. You must allocate +// the stbtt_fontinfo yourself, and stbtt_InitFont will fill it out. You don't +// need to do anything special to free it, because the contents are pure +// value data with no additional data structures. Returns 0 on failure. + + +////////////////////////////////////////////////////////////////////////////// +// +// CHARACTER TO GLYPH-INDEX CONVERSIOn + +STBTT_DEF int stbtt_FindGlyphIndex(const stbtt_fontinfo *info, int unicode_codepoint); +// If you're going to perform multiple operations on the same character +// and you want a speed-up, call this function with the character you're +// going to process, then use glyph-based functions instead of the +// codepoint-based functions. + + +////////////////////////////////////////////////////////////////////////////// +// +// CHARACTER PROPERTIES +// + +STBTT_DEF float stbtt_ScaleForPixelHeight(const stbtt_fontinfo *info, float pixels); +// computes a scale factor to produce a font whose "height" is 'pixels' tall. +// Height is measured as the distance from the highest ascender to the lowest +// descender; in other words, it's equivalent to calling stbtt_GetFontVMetrics +// and computing: +// scale = pixels / (ascent - descent) +// so if you prefer to measure height by the ascent only, use a similar calculation. + +STBTT_DEF float stbtt_ScaleForMappingEmToPixels(const stbtt_fontinfo *info, float pixels); +// computes a scale factor to produce a font whose EM size is mapped to +// 'pixels' tall. This is probably what traditional APIs compute, but +// I'm not positive. + +STBTT_DEF void stbtt_GetFontVMetrics(const stbtt_fontinfo *info, int *ascent, int *descent, int *lineGap); +// ascent is the coordinate above the baseline the font extends; descent +// is the coordinate below the baseline the font extends (i.e. it is typically negative) +// lineGap is the spacing between one row's descent and the next row's ascent... +// so you should advance the vertical position by "*ascent - *descent + *lineGap" +// these are expressed in unscaled coordinates, so you must multiply by +// the scale factor for a given size + +STBTT_DEF void stbtt_GetFontBoundingBox(const stbtt_fontinfo *info, int *x0, int *y0, int *x1, int *y1); +// the bounding box around all possible characters + +STBTT_DEF void stbtt_GetCodepointHMetrics(const stbtt_fontinfo *info, int codepoint, int *advanceWidth, int *leftSideBearing); +// leftSideBearing is the offset from the current horizontal position to the left edge of the character +// advanceWidth is the offset from the current horizontal position to the next horizontal position +// these are expressed in unscaled coordinates + +STBTT_DEF int stbtt_GetCodepointKernAdvance(const stbtt_fontinfo *info, int ch1, int ch2); +// an additional amount to add to the 'advance' value between ch1 and ch2 + +STBTT_DEF int stbtt_GetCodepointBox(const stbtt_fontinfo *info, int codepoint, int *x0, int *y0, int *x1, int *y1); +// Gets the bounding box of the visible part of the glyph, in unscaled coordinates + +STBTT_DEF void stbtt_GetGlyphHMetrics(const stbtt_fontinfo *info, int glyph_index, int *advanceWidth, int *leftSideBearing); +STBTT_DEF int stbtt_GetGlyphKernAdvance(const stbtt_fontinfo *info, int glyph1, int glyph2); +STBTT_DEF int stbtt_GetGlyphBox(const stbtt_fontinfo *info, int glyph_index, int *x0, int *y0, int *x1, int *y1); +// as above, but takes one or more glyph indices for greater efficiency + + +////////////////////////////////////////////////////////////////////////////// +// +// GLYPH SHAPES (you probably don't need these, but they have to go before +// the bitmaps for C declaration-order reasons) +// + +#ifndef STBTT_vmove // you can predefine these to use different values (but why?) + enum { + STBTT_vmove=1, + STBTT_vline, + STBTT_vcurve + }; +#endif + +#ifndef stbtt_vertex // you can predefine this to use different values + // (we share this with other code at RAD) + #define stbtt_vertex_type short // can't use stbtt_int16 because that's not visible in the header file + typedef struct + { + stbtt_vertex_type x,y,cx,cy; + unsigned char type,padding; + } stbtt_vertex; +#endif + +STBTT_DEF int stbtt_IsGlyphEmpty(const stbtt_fontinfo *info, int glyph_index); +// returns non-zero if nothing is drawn for this glyph + +STBTT_DEF int stbtt_GetCodepointShape(const stbtt_fontinfo *info, int unicode_codepoint, stbtt_vertex **vertices); +STBTT_DEF int stbtt_GetGlyphShape(const stbtt_fontinfo *info, int glyph_index, stbtt_vertex **vertices); +// returns # of vertices and fills *vertices with the pointer to them +// these are expressed in "unscaled" coordinates +// +// The shape is a series of countours. Each one starts with +// a STBTT_moveto, then consists of a series of mixed +// STBTT_lineto and STBTT_curveto segments. A lineto +// draws a line from previous endpoint to its x,y; a curveto +// draws a quadratic bezier from previous endpoint to +// its x,y, using cx,cy as the bezier control point. + +STBTT_DEF void stbtt_FreeShape(const stbtt_fontinfo *info, stbtt_vertex *vertices); +// frees the data allocated above + +////////////////////////////////////////////////////////////////////////////// +// +// BITMAP RENDERING +// + +STBTT_DEF void stbtt_FreeBitmap(unsigned char *bitmap, void *userdata); +// frees the bitmap allocated below + +STBTT_DEF unsigned char *stbtt_GetCodepointBitmap(const stbtt_fontinfo *info, float scale_x, float scale_y, int codepoint, int *width, int *height, int *xoff, int *yoff); +// allocates a large-enough single-channel 8bpp bitmap and renders the +// specified character/glyph at the specified scale into it, with +// antialiasing. 0 is no coverage (transparent), 255 is fully covered (opaque). +// *width & *height are filled out with the width & height of the bitmap, +// which is stored left-to-right, top-to-bottom. +// +// xoff/yoff are the offset it pixel space from the glyph origin to the top-left of the bitmap + +STBTT_DEF unsigned char *stbtt_GetCodepointBitmapSubpixel(const stbtt_fontinfo *info, float scale_x, float scale_y, float shift_x, float shift_y, int codepoint, int *width, int *height, int *xoff, int *yoff); +// the same as stbtt_GetCodepoitnBitmap, but you can specify a subpixel +// shift for the character + +STBTT_DEF void stbtt_MakeCodepointBitmap(const stbtt_fontinfo *info, unsigned char *output, int out_w, int out_h, int out_stride, float scale_x, float scale_y, int codepoint); +// the same as stbtt_GetCodepointBitmap, but you pass in storage for the bitmap +// in the form of 'output', with row spacing of 'out_stride' bytes. the bitmap +// is clipped to out_w/out_h bytes. Call stbtt_GetCodepointBitmapBox to get the +// width and height and positioning info for it first. + +STBTT_DEF void stbtt_MakeCodepointBitmapSubpixel(const stbtt_fontinfo *info, unsigned char *output, int out_w, int out_h, int out_stride, float scale_x, float scale_y, float shift_x, float shift_y, int codepoint); +// same as stbtt_MakeCodepointBitmap, but you can specify a subpixel +// shift for the character + +STBTT_DEF void stbtt_GetCodepointBitmapBox(const stbtt_fontinfo *font, int codepoint, float scale_x, float scale_y, int *ix0, int *iy0, int *ix1, int *iy1); +// get the bbox of the bitmap centered around the glyph origin; so the +// bitmap width is ix1-ix0, height is iy1-iy0, and location to place +// the bitmap top left is (leftSideBearing*scale,iy0). +// (Note that the bitmap uses y-increases-down, but the shape uses +// y-increases-up, so CodepointBitmapBox and CodepointBox are inverted.) + +STBTT_DEF void stbtt_GetCodepointBitmapBoxSubpixel(const stbtt_fontinfo *font, int codepoint, float scale_x, float scale_y, float shift_x, float shift_y, int *ix0, int *iy0, int *ix1, int *iy1); +// same as stbtt_GetCodepointBitmapBox, but you can specify a subpixel +// shift for the character + +// the following functions are equivalent to the above functions, but operate +// on glyph indices instead of Unicode codepoints (for efficiency) +STBTT_DEF unsigned char *stbtt_GetGlyphBitmap(const stbtt_fontinfo *info, float scale_x, float scale_y, int glyph, int *width, int *height, int *xoff, int *yoff); +STBTT_DEF unsigned char *stbtt_GetGlyphBitmapSubpixel(const stbtt_fontinfo *info, float scale_x, float scale_y, float shift_x, float shift_y, int glyph, int *width, int *height, int *xoff, int *yoff); +STBTT_DEF void stbtt_MakeGlyphBitmap(const stbtt_fontinfo *info, unsigned char *output, int out_w, int out_h, int out_stride, float scale_x, float scale_y, int glyph); +STBTT_DEF void stbtt_MakeGlyphBitmapSubpixel(const stbtt_fontinfo *info, unsigned char *output, int out_w, int out_h, int out_stride, float scale_x, float scale_y, float shift_x, float shift_y, int glyph); +STBTT_DEF void stbtt_GetGlyphBitmapBox(const stbtt_fontinfo *font, int glyph, float scale_x, float scale_y, int *ix0, int *iy0, int *ix1, int *iy1); +STBTT_DEF void stbtt_GetGlyphBitmapBoxSubpixel(const stbtt_fontinfo *font, int glyph, float scale_x, float scale_y,float shift_x, float shift_y, int *ix0, int *iy0, int *ix1, int *iy1); + + +// @TODO: don't expose this structure +typedef struct +{ + int w,h,stride; + unsigned char *pixels; +} stbtt__bitmap; + +// rasterize a shape with quadratic beziers into a bitmap +STBTT_DEF void stbtt_Rasterize(stbtt__bitmap *result, // 1-channel bitmap to draw into + float flatness_in_pixels, // allowable error of curve in pixels + stbtt_vertex *vertices, // array of vertices defining shape + int num_verts, // number of vertices in above array + float scale_x, float scale_y, // scale applied to input vertices + float shift_x, float shift_y, // translation applied to input vertices + int x_off, int y_off, // another translation applied to input + int invert, // if non-zero, vertically flip shape + void *userdata); // context for to STBTT_MALLOC + +////////////////////////////////////////////////////////////////////////////// +// +// Finding the right font... +// +// You should really just solve this offline, keep your own tables +// of what font is what, and don't try to get it out of the .ttf file. +// That's because getting it out of the .ttf file is really hard, because +// the names in the file can appear in many possible encodings, in many +// possible languages, and e.g. if you need a case-insensitive comparison, +// the details of that depend on the encoding & language in a complex way +// (actually underspecified in truetype, but also gigantic). +// +// But you can use the provided functions in two possible ways: +// stbtt_FindMatchingFont() will use *case-sensitive* comparisons on +// unicode-encoded names to try to find the font you want; +// you can run this before calling stbtt_InitFont() +// +// stbtt_GetFontNameString() lets you get any of the various strings +// from the file yourself and do your own comparisons on them. +// You have to have called stbtt_InitFont() first. + + +STBTT_DEF int stbtt_FindMatchingFont(const unsigned char *fontdata, const char *name, int flags); +// returns the offset (not index) of the font that matches, or -1 if none +// if you use STBTT_MACSTYLE_DONTCARE, use a font name like "Arial Bold". +// if you use any other flag, use a font name like "Arial"; this checks +// the 'macStyle' header field; i don't know if fonts set this consistently +#define STBTT_MACSTYLE_DONTCARE 0 +#define STBTT_MACSTYLE_BOLD 1 +#define STBTT_MACSTYLE_ITALIC 2 +#define STBTT_MACSTYLE_UNDERSCORE 4 +#define STBTT_MACSTYLE_NONE 8 // <= not same as 0, this makes us check the bitfield is 0 + +STBTT_DEF int stbtt_CompareUTF8toUTF16_bigendian(const char *s1, int len1, const char *s2, int len2); +// returns 1/0 whether the first string interpreted as utf8 is identical to +// the second string interpreted as big-endian utf16... useful for strings from next func + +STBTT_DEF const char *stbtt_GetFontNameString(const stbtt_fontinfo *font, int *length, int platformID, int encodingID, int languageID, int nameID); +// returns the string (which may be big-endian double byte, e.g. for unicode) +// and puts the length in bytes in *length. +// +// some of the values for the IDs are below; for more see the truetype spec: +// http://developer.apple.com/textfonts/TTRefMan/RM06/Chap6name.html +// http://www.microsoft.com/typography/otspec/name.htm + +enum { // platformID + STBTT_PLATFORM_ID_UNICODE =0, + STBTT_PLATFORM_ID_MAC =1, + STBTT_PLATFORM_ID_ISO =2, + STBTT_PLATFORM_ID_MICROSOFT =3 +}; + +enum { // encodingID for STBTT_PLATFORM_ID_UNICODE + STBTT_UNICODE_EID_UNICODE_1_0 =0, + STBTT_UNICODE_EID_UNICODE_1_1 =1, + STBTT_UNICODE_EID_ISO_10646 =2, + STBTT_UNICODE_EID_UNICODE_2_0_BMP=3, + STBTT_UNICODE_EID_UNICODE_2_0_FULL=4 +}; + +enum { // encodingID for STBTT_PLATFORM_ID_MICROSOFT + STBTT_MS_EID_SYMBOL =0, + STBTT_MS_EID_UNICODE_BMP =1, + STBTT_MS_EID_SHIFTJIS =2, + STBTT_MS_EID_UNICODE_FULL =10 +}; + +enum { // encodingID for STBTT_PLATFORM_ID_MAC; same as Script Manager codes + STBTT_MAC_EID_ROMAN =0, STBTT_MAC_EID_ARABIC =4, + STBTT_MAC_EID_JAPANESE =1, STBTT_MAC_EID_HEBREW =5, + STBTT_MAC_EID_CHINESE_TRAD =2, STBTT_MAC_EID_GREEK =6, + STBTT_MAC_EID_KOREAN =3, STBTT_MAC_EID_RUSSIAN =7 +}; + +enum { // languageID for STBTT_PLATFORM_ID_MICROSOFT; same as LCID... + // problematic because there are e.g. 16 english LCIDs and 16 arabic LCIDs + STBTT_MS_LANG_ENGLISH =0x0409, STBTT_MS_LANG_ITALIAN =0x0410, + STBTT_MS_LANG_CHINESE =0x0804, STBTT_MS_LANG_JAPANESE =0x0411, + STBTT_MS_LANG_DUTCH =0x0413, STBTT_MS_LANG_KOREAN =0x0412, + STBTT_MS_LANG_FRENCH =0x040c, STBTT_MS_LANG_RUSSIAN =0x0419, + STBTT_MS_LANG_GERMAN =0x0407, STBTT_MS_LANG_SPANISH =0x0409, + STBTT_MS_LANG_HEBREW =0x040d, STBTT_MS_LANG_SWEDISH =0x041D +}; + +enum { // languageID for STBTT_PLATFORM_ID_MAC + STBTT_MAC_LANG_ENGLISH =0 , STBTT_MAC_LANG_JAPANESE =11, + STBTT_MAC_LANG_ARABIC =12, STBTT_MAC_LANG_KOREAN =23, + STBTT_MAC_LANG_DUTCH =4 , STBTT_MAC_LANG_RUSSIAN =32, + STBTT_MAC_LANG_FRENCH =1 , STBTT_MAC_LANG_SPANISH =6 , + STBTT_MAC_LANG_GERMAN =2 , STBTT_MAC_LANG_SWEDISH =5 , + STBTT_MAC_LANG_HEBREW =10, STBTT_MAC_LANG_CHINESE_SIMPLIFIED =33, + STBTT_MAC_LANG_ITALIAN =3 , STBTT_MAC_LANG_CHINESE_TRAD =19 +}; + +#ifdef __cplusplus +} +#endif + +#endif // __STB_INCLUDE_STB_TRUETYPE_H__ + +/////////////////////////////////////////////////////////////////////////////// +/////////////////////////////////////////////////////////////////////////////// +//// +//// IMPLEMENTATION +//// +//// + +#ifdef STB_TRUETYPE_IMPLEMENTATION + +#ifndef STBTT_MAX_OVERSAMPLE +#define STBTT_MAX_OVERSAMPLE 8 +#endif + +#if STBTT_MAX_OVERSAMPLE > 255 +#error "STBTT_MAX_OVERSAMPLE cannot be > 255" +#endif + +typedef int stbtt__test_oversample_pow2[(STBTT_MAX_OVERSAMPLE & (STBTT_MAX_OVERSAMPLE-1)) == 0 ? 1 : -1]; + +#ifndef STBTT_RASTERIZER_VERSION +#define STBTT_RASTERIZER_VERSION 2 +#endif + +////////////////////////////////////////////////////////////////////////// +// +// accessors to parse data from file +// + +// on platforms that don't allow misaligned reads, if we want to allow +// truetype fonts that aren't padded to alignment, define ALLOW_UNALIGNED_TRUETYPE + +#define ttBYTE(p) (* (stbtt_uint8 *) (p)) +#define ttCHAR(p) (* (stbtt_int8 *) (p)) +#define ttFixed(p) ttLONG(p) + +#if defined(STB_TRUETYPE_BIGENDIAN) && !defined(ALLOW_UNALIGNED_TRUETYPE) + + #define ttUSHORT(p) (* (stbtt_uint16 *) (p)) + #define ttSHORT(p) (* (stbtt_int16 *) (p)) + #define ttULONG(p) (* (stbtt_uint32 *) (p)) + #define ttLONG(p) (* (stbtt_int32 *) (p)) + +#else + + static stbtt_uint16 ttUSHORT(const stbtt_uint8 *p) { return p[0]*256 + p[1]; } + static stbtt_int16 ttSHORT(const stbtt_uint8 *p) { return p[0]*256 + p[1]; } + static stbtt_uint32 ttULONG(const stbtt_uint8 *p) { return (p[0]<<24) + (p[1]<<16) + (p[2]<<8) + p[3]; } + static stbtt_int32 ttLONG(const stbtt_uint8 *p) { return (p[0]<<24) + (p[1]<<16) + (p[2]<<8) + p[3]; } + +#endif + +#define stbtt_tag4(p,c0,c1,c2,c3) ((p)[0] == (c0) && (p)[1] == (c1) && (p)[2] == (c2) && (p)[3] == (c3)) +#define stbtt_tag(p,str) stbtt_tag4(p,str[0],str[1],str[2],str[3]) + +static int stbtt__isfont(const stbtt_uint8 *font) +{ + // check the version number + if (stbtt_tag4(font, '1',0,0,0)) return 1; // TrueType 1 + if (stbtt_tag(font, "typ1")) return 1; // TrueType with type 1 font -- we don't support this! + if (stbtt_tag(font, "OTTO")) return 1; // OpenType with CFF + if (stbtt_tag4(font, 0,1,0,0)) return 1; // OpenType 1.0 + return 0; +} + +// @OPTIMIZE: binary search +static stbtt_uint32 stbtt__find_table(stbtt_uint8 *data, stbtt_uint32 fontstart, const char *tag) +{ + stbtt_int32 num_tables = ttUSHORT(data+fontstart+4); + stbtt_uint32 tabledir = fontstart + 12; + stbtt_int32 i; + for (i=0; i < num_tables; ++i) { + stbtt_uint32 loc = tabledir + 16*i; + if (stbtt_tag(data+loc+0, tag)) + return ttULONG(data+loc+8); + } + return 0; +} + +STBTT_DEF int stbtt_GetFontOffsetForIndex(const unsigned char *font_collection, int index) +{ + // if it's just a font, there's only one valid index + if (stbtt__isfont(font_collection)) + return index == 0 ? 0 : -1; + + // check if it's a TTC + if (stbtt_tag(font_collection, "ttcf")) { + // version 1? + if (ttULONG(font_collection+4) == 0x00010000 || ttULONG(font_collection+4) == 0x00020000) { + stbtt_int32 n = ttLONG(font_collection+8); + if (index >= n) + return -1; + return ttULONG(font_collection+12+index*4); + } + } + return -1; +} + +STBTT_DEF int stbtt_InitFont(stbtt_fontinfo *info, const unsigned char *data2, int fontstart) +{ + stbtt_uint8 *data = (stbtt_uint8 *) data2; + stbtt_uint32 cmap, t; + stbtt_int32 i,numTables; + + info->data = data; + info->fontstart = fontstart; + + cmap = stbtt__find_table(data, fontstart, "cmap"); // required + info->loca = stbtt__find_table(data, fontstart, "loca"); // required + info->head = stbtt__find_table(data, fontstart, "head"); // required + info->glyf = stbtt__find_table(data, fontstart, "glyf"); // required + info->hhea = stbtt__find_table(data, fontstart, "hhea"); // required + info->hmtx = stbtt__find_table(data, fontstart, "hmtx"); // required + info->kern = stbtt__find_table(data, fontstart, "kern"); // not required + if (!cmap || !info->loca || !info->head || !info->glyf || !info->hhea || !info->hmtx) + return 0; + + t = stbtt__find_table(data, fontstart, "maxp"); + if (t) + info->numGlyphs = ttUSHORT(data+t+4); + else + info->numGlyphs = 0xffff; + + // find a cmap encoding table we understand *now* to avoid searching + // later. (todo: could make this installable) + // the same regardless of glyph. + numTables = ttUSHORT(data + cmap + 2); + info->index_map = 0; + for (i=0; i < numTables; ++i) { + stbtt_uint32 encoding_record = cmap + 4 + 8 * i; + // find an encoding we understand: + switch(ttUSHORT(data+encoding_record)) { + case STBTT_PLATFORM_ID_MICROSOFT: + switch (ttUSHORT(data+encoding_record+2)) { + case STBTT_MS_EID_UNICODE_BMP: + case STBTT_MS_EID_UNICODE_FULL: + // MS/Unicode + info->index_map = cmap + ttULONG(data+encoding_record+4); + break; + } + break; + case STBTT_PLATFORM_ID_UNICODE: + // Mac/iOS has these + // all the encodingIDs are unicode, so we don't bother to check it + info->index_map = cmap + ttULONG(data+encoding_record+4); + break; + } + } + if (info->index_map == 0) + return 0; + + info->indexToLocFormat = ttUSHORT(data+info->head + 50); + return 1; +} + +STBTT_DEF int stbtt_FindGlyphIndex(const stbtt_fontinfo *info, int unicode_codepoint) +{ + stbtt_uint8 *data = info->data; + stbtt_uint32 index_map = info->index_map; + + stbtt_uint16 format = ttUSHORT(data + index_map + 0); + if (format == 0) { // apple byte encoding + stbtt_int32 bytes = ttUSHORT(data + index_map + 2); + if (unicode_codepoint < bytes-6) + return ttBYTE(data + index_map + 6 + unicode_codepoint); + return 0; + } else if (format == 6) { + stbtt_uint32 first = ttUSHORT(data + index_map + 6); + stbtt_uint32 count = ttUSHORT(data + index_map + 8); + if ((stbtt_uint32) unicode_codepoint >= first && (stbtt_uint32) unicode_codepoint < first+count) + return ttUSHORT(data + index_map + 10 + (unicode_codepoint - first)*2); + return 0; + } else if (format == 2) { + STBTT_assert(0); // @TODO: high-byte mapping for japanese/chinese/korean + return 0; + } else if (format == 4) { // standard mapping for windows fonts: binary search collection of ranges + stbtt_uint16 segcount = ttUSHORT(data+index_map+6) >> 1; + stbtt_uint16 searchRange = ttUSHORT(data+index_map+8) >> 1; + stbtt_uint16 entrySelector = ttUSHORT(data+index_map+10); + stbtt_uint16 rangeShift = ttUSHORT(data+index_map+12) >> 1; + + // do a binary search of the segments + stbtt_uint32 endCount = index_map + 14; + stbtt_uint32 search = endCount; + + if (unicode_codepoint > 0xffff) + return 0; + + // they lie from endCount .. endCount + segCount + // but searchRange is the nearest power of two, so... + if (unicode_codepoint >= ttUSHORT(data + search + rangeShift*2)) + search += rangeShift*2; + + // now decrement to bias correctly to find smallest + search -= 2; + while (entrySelector) { + stbtt_uint16 end; + searchRange >>= 1; + end = ttUSHORT(data + search + searchRange*2); + if (unicode_codepoint > end) + search += searchRange*2; + --entrySelector; + } + search += 2; + + { + stbtt_uint16 offset, start; + stbtt_uint16 item = (stbtt_uint16) ((search - endCount) >> 1); + + STBTT_assert(unicode_codepoint <= ttUSHORT(data + endCount + 2*item)); + start = ttUSHORT(data + index_map + 14 + segcount*2 + 2 + 2*item); + if (unicode_codepoint < start) + return 0; + + offset = ttUSHORT(data + index_map + 14 + segcount*6 + 2 + 2*item); + if (offset == 0) + return (stbtt_uint16) (unicode_codepoint + ttSHORT(data + index_map + 14 + segcount*4 + 2 + 2*item)); + + return ttUSHORT(data + offset + (unicode_codepoint-start)*2 + index_map + 14 + segcount*6 + 2 + 2*item); + } + } else if (format == 12 || format == 13) { + stbtt_uint32 ngroups = ttULONG(data+index_map+12); + stbtt_int32 low,high; + low = 0; high = (stbtt_int32)ngroups; + // Binary search the right group. + while (low < high) { + stbtt_int32 mid = low + ((high-low) >> 1); // rounds down, so low <= mid < high + stbtt_uint32 start_char = ttULONG(data+index_map+16+mid*12); + stbtt_uint32 end_char = ttULONG(data+index_map+16+mid*12+4); + if ((stbtt_uint32) unicode_codepoint < start_char) + high = mid; + else if ((stbtt_uint32) unicode_codepoint > end_char) + low = mid+1; + else { + stbtt_uint32 start_glyph = ttULONG(data+index_map+16+mid*12+8); + if (format == 12) + return start_glyph + unicode_codepoint-start_char; + else // format == 13 + return start_glyph; + } + } + return 0; // not found + } + // @TODO + STBTT_assert(0); + return 0; +} + +STBTT_DEF int stbtt_GetCodepointShape(const stbtt_fontinfo *info, int unicode_codepoint, stbtt_vertex **vertices) +{ + return stbtt_GetGlyphShape(info, stbtt_FindGlyphIndex(info, unicode_codepoint), vertices); +} + +static void stbtt_setvertex(stbtt_vertex *v, stbtt_uint8 type, stbtt_int32 x, stbtt_int32 y, stbtt_int32 cx, stbtt_int32 cy) +{ + v->type = type; + v->x = (stbtt_int16) x; + v->y = (stbtt_int16) y; + v->cx = (stbtt_int16) cx; + v->cy = (stbtt_int16) cy; +} + +static int stbtt__GetGlyfOffset(const stbtt_fontinfo *info, int glyph_index) +{ + int g1,g2; + + if (glyph_index >= info->numGlyphs) return -1; // glyph index out of range + if (info->indexToLocFormat >= 2) return -1; // unknown index->glyph map format + + if (info->indexToLocFormat == 0) { + g1 = info->glyf + ttUSHORT(info->data + info->loca + glyph_index * 2) * 2; + g2 = info->glyf + ttUSHORT(info->data + info->loca + glyph_index * 2 + 2) * 2; + } else { + g1 = info->glyf + ttULONG (info->data + info->loca + glyph_index * 4); + g2 = info->glyf + ttULONG (info->data + info->loca + glyph_index * 4 + 4); + } + + return g1==g2 ? -1 : g1; // if length is 0, return -1 +} + +STBTT_DEF int stbtt_GetGlyphBox(const stbtt_fontinfo *info, int glyph_index, int *x0, int *y0, int *x1, int *y1) +{ + int g = stbtt__GetGlyfOffset(info, glyph_index); + if (g < 0) return 0; + + if (x0) *x0 = ttSHORT(info->data + g + 2); + if (y0) *y0 = ttSHORT(info->data + g + 4); + if (x1) *x1 = ttSHORT(info->data + g + 6); + if (y1) *y1 = ttSHORT(info->data + g + 8); + return 1; +} + +STBTT_DEF int stbtt_GetCodepointBox(const stbtt_fontinfo *info, int codepoint, int *x0, int *y0, int *x1, int *y1) +{ + return stbtt_GetGlyphBox(info, stbtt_FindGlyphIndex(info,codepoint), x0,y0,x1,y1); +} + +STBTT_DEF int stbtt_IsGlyphEmpty(const stbtt_fontinfo *info, int glyph_index) +{ + stbtt_int16 numberOfContours; + int g = stbtt__GetGlyfOffset(info, glyph_index); + if (g < 0) return 1; + numberOfContours = ttSHORT(info->data + g); + return numberOfContours == 0; +} + +static int stbtt__close_shape(stbtt_vertex *vertices, int num_vertices, int was_off, int start_off, + stbtt_int32 sx, stbtt_int32 sy, stbtt_int32 scx, stbtt_int32 scy, stbtt_int32 cx, stbtt_int32 cy) +{ + if (start_off) { + if (was_off) + stbtt_setvertex(&vertices[num_vertices++], STBTT_vcurve, (cx+scx)>>1, (cy+scy)>>1, cx,cy); + stbtt_setvertex(&vertices[num_vertices++], STBTT_vcurve, sx,sy,scx,scy); + } else { + if (was_off) + stbtt_setvertex(&vertices[num_vertices++], STBTT_vcurve,sx,sy,cx,cy); + else + stbtt_setvertex(&vertices[num_vertices++], STBTT_vline,sx,sy,0,0); + } + return num_vertices; +} + +STBTT_DEF int stbtt_GetGlyphShape(const stbtt_fontinfo *info, int glyph_index, stbtt_vertex **pvertices) +{ + stbtt_int16 numberOfContours; + stbtt_uint8 *endPtsOfContours; + stbtt_uint8 *data = info->data; + stbtt_vertex *vertices=0; + int num_vertices=0; + int g = stbtt__GetGlyfOffset(info, glyph_index); + + *pvertices = NULL; + + if (g < 0) return 0; + + numberOfContours = ttSHORT(data + g); + + if (numberOfContours > 0) { + stbtt_uint8 flags=0,flagcount; + stbtt_int32 ins, i,j=0,m,n, next_move, was_off=0, off, start_off=0; + stbtt_int32 x,y,cx,cy,sx,sy, scx,scy; + stbtt_uint8 *points; + endPtsOfContours = (data + g + 10); + ins = ttUSHORT(data + g + 10 + numberOfContours * 2); + points = data + g + 10 + numberOfContours * 2 + 2 + ins; + + n = 1+ttUSHORT(endPtsOfContours + numberOfContours*2-2); + + m = n + 2*numberOfContours; // a loose bound on how many vertices we might need + vertices = (stbtt_vertex *) STBTT_malloc(m * sizeof(vertices[0]), info->userdata); + if (vertices == 0) + return 0; + + next_move = 0; + flagcount=0; + + // in first pass, we load uninterpreted data into the allocated array + // above, shifted to the end of the array so we won't overwrite it when + // we create our final data starting from the front + + off = m - n; // starting offset for uninterpreted data, regardless of how m ends up being calculated + + // first load flags + + for (i=0; i < n; ++i) { + if (flagcount == 0) { + flags = *points++; + if (flags & 8) + flagcount = *points++; + } else + --flagcount; + vertices[off+i].type = flags; + } + + // now load x coordinates + x=0; + for (i=0; i < n; ++i) { + flags = vertices[off+i].type; + if (flags & 2) { + stbtt_int16 dx = *points++; + x += (flags & 16) ? dx : -dx; // ??? + } else { + if (!(flags & 16)) { + x = x + (stbtt_int16) (points[0]*256 + points[1]); + points += 2; + } + } + vertices[off+i].x = (stbtt_int16) x; + } + + // now load y coordinates + y=0; + for (i=0; i < n; ++i) { + flags = vertices[off+i].type; + if (flags & 4) { + stbtt_int16 dy = *points++; + y += (flags & 32) ? dy : -dy; // ??? + } else { + if (!(flags & 32)) { + y = y + (stbtt_int16) (points[0]*256 + points[1]); + points += 2; + } + } + vertices[off+i].y = (stbtt_int16) y; + } + + // now convert them to our format + num_vertices=0; + sx = sy = cx = cy = scx = scy = 0; + for (i=0; i < n; ++i) { + flags = vertices[off+i].type; + x = (stbtt_int16) vertices[off+i].x; + y = (stbtt_int16) vertices[off+i].y; + + if (next_move == i) { + if (i != 0) + num_vertices = stbtt__close_shape(vertices, num_vertices, was_off, start_off, sx,sy,scx,scy,cx,cy); + + // now start the new one + start_off = !(flags & 1); + if (start_off) { + // if we start off with an off-curve point, then when we need to find a point on the curve + // where we can start, and we need to save some state for when we wraparound. + scx = x; + scy = y; + if (!(vertices[off+i+1].type & 1)) { + // next point is also a curve point, so interpolate an on-point curve + sx = (x + (stbtt_int32) vertices[off+i+1].x) >> 1; + sy = (y + (stbtt_int32) vertices[off+i+1].y) >> 1; + } else { + // otherwise just use the next point as our start point + sx = (stbtt_int32) vertices[off+i+1].x; + sy = (stbtt_int32) vertices[off+i+1].y; + ++i; // we're using point i+1 as the starting point, so skip it + } + } else { + sx = x; + sy = y; + } + stbtt_setvertex(&vertices[num_vertices++], STBTT_vmove,sx,sy,0,0); + was_off = 0; + next_move = 1 + ttUSHORT(endPtsOfContours+j*2); + ++j; + } else { + if (!(flags & 1)) { // if it's a curve + if (was_off) // two off-curve control points in a row means interpolate an on-curve midpoint + stbtt_setvertex(&vertices[num_vertices++], STBTT_vcurve, (cx+x)>>1, (cy+y)>>1, cx, cy); + cx = x; + cy = y; + was_off = 1; + } else { + if (was_off) + stbtt_setvertex(&vertices[num_vertices++], STBTT_vcurve, x,y, cx, cy); + else + stbtt_setvertex(&vertices[num_vertices++], STBTT_vline, x,y,0,0); + was_off = 0; + } + } + } + num_vertices = stbtt__close_shape(vertices, num_vertices, was_off, start_off, sx,sy,scx,scy,cx,cy); + } else if (numberOfContours == -1) { + // Compound shapes. + int more = 1; + stbtt_uint8 *comp = data + g + 10; + num_vertices = 0; + vertices = 0; + while (more) { + stbtt_uint16 flags, gidx; + int comp_num_verts = 0, i; + stbtt_vertex *comp_verts = 0, *tmp = 0; + float mtx[6] = {1,0,0,1,0,0}, m, n; + + flags = ttSHORT(comp); comp+=2; + gidx = ttSHORT(comp); comp+=2; + + if (flags & 2) { // XY values + if (flags & 1) { // shorts + mtx[4] = ttSHORT(comp); comp+=2; + mtx[5] = ttSHORT(comp); comp+=2; + } else { + mtx[4] = ttCHAR(comp); comp+=1; + mtx[5] = ttCHAR(comp); comp+=1; + } + } + else { + // @TODO handle matching point + STBTT_assert(0); + } + if (flags & (1<<3)) { // WE_HAVE_A_SCALE + mtx[0] = mtx[3] = ttSHORT(comp)/16384.0f; comp+=2; + mtx[1] = mtx[2] = 0; + } else if (flags & (1<<6)) { // WE_HAVE_AN_X_AND_YSCALE + mtx[0] = ttSHORT(comp)/16384.0f; comp+=2; + mtx[1] = mtx[2] = 0; + mtx[3] = ttSHORT(comp)/16384.0f; comp+=2; + } else if (flags & (1<<7)) { // WE_HAVE_A_TWO_BY_TWO + mtx[0] = ttSHORT(comp)/16384.0f; comp+=2; + mtx[1] = ttSHORT(comp)/16384.0f; comp+=2; + mtx[2] = ttSHORT(comp)/16384.0f; comp+=2; + mtx[3] = ttSHORT(comp)/16384.0f; comp+=2; + } + + // Find transformation scales. + m = (float) STBTT_sqrt(mtx[0]*mtx[0] + mtx[1]*mtx[1]); + n = (float) STBTT_sqrt(mtx[2]*mtx[2] + mtx[3]*mtx[3]); + + // Get indexed glyph. + comp_num_verts = stbtt_GetGlyphShape(info, gidx, &comp_verts); + if (comp_num_verts > 0) { + // Transform vertices. + for (i = 0; i < comp_num_verts; ++i) { + stbtt_vertex* v = &comp_verts[i]; + stbtt_vertex_type x,y; + x=v->x; y=v->y; + v->x = (stbtt_vertex_type)(m * (mtx[0]*x + mtx[2]*y + mtx[4])); + v->y = (stbtt_vertex_type)(n * (mtx[1]*x + mtx[3]*y + mtx[5])); + x=v->cx; y=v->cy; + v->cx = (stbtt_vertex_type)(m * (mtx[0]*x + mtx[2]*y + mtx[4])); + v->cy = (stbtt_vertex_type)(n * (mtx[1]*x + mtx[3]*y + mtx[5])); + } + // Append vertices. + tmp = (stbtt_vertex*)STBTT_malloc((num_vertices+comp_num_verts)*sizeof(stbtt_vertex), info->userdata); + if (!tmp) { + if (vertices) STBTT_free(vertices, info->userdata); + if (comp_verts) STBTT_free(comp_verts, info->userdata); + return 0; + } + if (num_vertices > 0) STBTT_memcpy(tmp, vertices, num_vertices*sizeof(stbtt_vertex)); + STBTT_memcpy(tmp+num_vertices, comp_verts, comp_num_verts*sizeof(stbtt_vertex)); + if (vertices) STBTT_free(vertices, info->userdata); + vertices = tmp; + STBTT_free(comp_verts, info->userdata); + num_vertices += comp_num_verts; + } + // More components ? + more = flags & (1<<5); + } + } else if (numberOfContours < 0) { + // @TODO other compound variations? + STBTT_assert(0); + } else { + // numberOfCounters == 0, do nothing + } + + *pvertices = vertices; + return num_vertices; +} + +STBTT_DEF void stbtt_GetGlyphHMetrics(const stbtt_fontinfo *info, int glyph_index, int *advanceWidth, int *leftSideBearing) +{ + stbtt_uint16 numOfLongHorMetrics = ttUSHORT(info->data+info->hhea + 34); + if (glyph_index < numOfLongHorMetrics) { + if (advanceWidth) *advanceWidth = ttSHORT(info->data + info->hmtx + 4*glyph_index); + if (leftSideBearing) *leftSideBearing = ttSHORT(info->data + info->hmtx + 4*glyph_index + 2); + } else { + if (advanceWidth) *advanceWidth = ttSHORT(info->data + info->hmtx + 4*(numOfLongHorMetrics-1)); + if (leftSideBearing) *leftSideBearing = ttSHORT(info->data + info->hmtx + 4*numOfLongHorMetrics + 2*(glyph_index - numOfLongHorMetrics)); + } +} + +STBTT_DEF int stbtt_GetGlyphKernAdvance(const stbtt_fontinfo *info, int glyph1, int glyph2) +{ + stbtt_uint8 *data = info->data + info->kern; + stbtt_uint32 needle, straw; + int l, r, m; + + // we only look at the first table. it must be 'horizontal' and format 0. + if (!info->kern) + return 0; + if (ttUSHORT(data+2) < 1) // number of tables, need at least 1 + return 0; + if (ttUSHORT(data+8) != 1) // horizontal flag must be set in format + return 0; + + l = 0; + r = ttUSHORT(data+10) - 1; + needle = glyph1 << 16 | glyph2; + while (l <= r) { + m = (l + r) >> 1; + straw = ttULONG(data+18+(m*6)); // note: unaligned read + if (needle < straw) + r = m - 1; + else if (needle > straw) + l = m + 1; + else + return ttSHORT(data+22+(m*6)); + } + return 0; +} + +STBTT_DEF int stbtt_GetCodepointKernAdvance(const stbtt_fontinfo *info, int ch1, int ch2) +{ + if (!info->kern) // if no kerning table, don't waste time looking up both codepoint->glyphs + return 0; + return stbtt_GetGlyphKernAdvance(info, stbtt_FindGlyphIndex(info,ch1), stbtt_FindGlyphIndex(info,ch2)); +} + +STBTT_DEF void stbtt_GetCodepointHMetrics(const stbtt_fontinfo *info, int codepoint, int *advanceWidth, int *leftSideBearing) +{ + stbtt_GetGlyphHMetrics(info, stbtt_FindGlyphIndex(info,codepoint), advanceWidth, leftSideBearing); +} + +STBTT_DEF void stbtt_GetFontVMetrics(const stbtt_fontinfo *info, int *ascent, int *descent, int *lineGap) +{ + if (ascent ) *ascent = ttSHORT(info->data+info->hhea + 4); + if (descent) *descent = ttSHORT(info->data+info->hhea + 6); + if (lineGap) *lineGap = ttSHORT(info->data+info->hhea + 8); +} + +STBTT_DEF void stbtt_GetFontBoundingBox(const stbtt_fontinfo *info, int *x0, int *y0, int *x1, int *y1) +{ + *x0 = ttSHORT(info->data + info->head + 36); + *y0 = ttSHORT(info->data + info->head + 38); + *x1 = ttSHORT(info->data + info->head + 40); + *y1 = ttSHORT(info->data + info->head + 42); +} + +STBTT_DEF float stbtt_ScaleForPixelHeight(const stbtt_fontinfo *info, float height) +{ + int fheight = ttSHORT(info->data + info->hhea + 4) - ttSHORT(info->data + info->hhea + 6); + return (float) height / fheight; +} + +STBTT_DEF float stbtt_ScaleForMappingEmToPixels(const stbtt_fontinfo *info, float pixels) +{ + int unitsPerEm = ttUSHORT(info->data + info->head + 18); + return pixels / unitsPerEm; +} + +STBTT_DEF void stbtt_FreeShape(const stbtt_fontinfo *info, stbtt_vertex *v) +{ + STBTT_free(v, info->userdata); +} + +////////////////////////////////////////////////////////////////////////////// +// +// antialiasing software rasterizer +// + +STBTT_DEF void stbtt_GetGlyphBitmapBoxSubpixel(const stbtt_fontinfo *font, int glyph, float scale_x, float scale_y,float shift_x, float shift_y, int *ix0, int *iy0, int *ix1, int *iy1) +{ + int x0=0,y0=0,x1,y1; // =0 suppresses compiler warning + if (!stbtt_GetGlyphBox(font, glyph, &x0,&y0,&x1,&y1)) { + // e.g. space character + if (ix0) *ix0 = 0; + if (iy0) *iy0 = 0; + if (ix1) *ix1 = 0; + if (iy1) *iy1 = 0; + } else { + // move to integral bboxes (treating pixels as little squares, what pixels get touched)? + if (ix0) *ix0 = STBTT_ifloor( x0 * scale_x + shift_x); + if (iy0) *iy0 = STBTT_ifloor(-y1 * scale_y + shift_y); + if (ix1) *ix1 = STBTT_iceil ( x1 * scale_x + shift_x); + if (iy1) *iy1 = STBTT_iceil (-y0 * scale_y + shift_y); + } +} + +STBTT_DEF void stbtt_GetGlyphBitmapBox(const stbtt_fontinfo *font, int glyph, float scale_x, float scale_y, int *ix0, int *iy0, int *ix1, int *iy1) +{ + stbtt_GetGlyphBitmapBoxSubpixel(font, glyph, scale_x, scale_y,0.0f,0.0f, ix0, iy0, ix1, iy1); +} + +STBTT_DEF void stbtt_GetCodepointBitmapBoxSubpixel(const stbtt_fontinfo *font, int codepoint, float scale_x, float scale_y, float shift_x, float shift_y, int *ix0, int *iy0, int *ix1, int *iy1) +{ + stbtt_GetGlyphBitmapBoxSubpixel(font, stbtt_FindGlyphIndex(font,codepoint), scale_x, scale_y,shift_x,shift_y, ix0,iy0,ix1,iy1); +} + +STBTT_DEF void stbtt_GetCodepointBitmapBox(const stbtt_fontinfo *font, int codepoint, float scale_x, float scale_y, int *ix0, int *iy0, int *ix1, int *iy1) +{ + stbtt_GetCodepointBitmapBoxSubpixel(font, codepoint, scale_x, scale_y,0.0f,0.0f, ix0,iy0,ix1,iy1); +} + +////////////////////////////////////////////////////////////////////////////// +// +// Rasterizer + +typedef struct stbtt__hheap_chunk +{ + struct stbtt__hheap_chunk *next; +} stbtt__hheap_chunk; + +typedef struct stbtt__hheap +{ + struct stbtt__hheap_chunk *head; + void *first_free; + int num_remaining_in_head_chunk; +} stbtt__hheap; + +static void *stbtt__hheap_alloc(stbtt__hheap *hh, size_t size, void *userdata) +{ + if (hh->first_free) { + void *p = hh->first_free; + hh->first_free = * (void **) p; + return p; + } else { + if (hh->num_remaining_in_head_chunk == 0) { + int count = (size < 32 ? 2000 : size < 128 ? 800 : 100); + stbtt__hheap_chunk *c = (stbtt__hheap_chunk *) STBTT_malloc(sizeof(stbtt__hheap_chunk) + size * count, userdata); + if (c == NULL) + return NULL; + c->next = hh->head; + hh->head = c; + hh->num_remaining_in_head_chunk = count; + } + --hh->num_remaining_in_head_chunk; + return (char *) (hh->head) + size * hh->num_remaining_in_head_chunk; + } +} + +static void stbtt__hheap_free(stbtt__hheap *hh, void *p) +{ + *(void **) p = hh->first_free; + hh->first_free = p; +} + +static void stbtt__hheap_cleanup(stbtt__hheap *hh, void *userdata) +{ + stbtt__hheap_chunk *c = hh->head; + while (c) { + stbtt__hheap_chunk *n = c->next; + STBTT_free(c, userdata); + c = n; + } +} + +typedef struct stbtt__edge { + float x0,y0, x1,y1; + int invert; +} stbtt__edge; + + +typedef struct stbtt__active_edge +{ + struct stbtt__active_edge *next; + #if STBTT_RASTERIZER_VERSION==1 + int x,dx; + float ey; + int direction; + #elif STBTT_RASTERIZER_VERSION==2 + float fx,fdx,fdy; + float direction; + float sy; + float ey; + #else + #error "Unrecognized value of STBTT_RASTERIZER_VERSION" + #endif +} stbtt__active_edge; + +#if STBTT_RASTERIZER_VERSION == 1 +#define STBTT_FIXSHIFT 10 +#define STBTT_FIX (1 << STBTT_FIXSHIFT) +#define STBTT_FIXMASK (STBTT_FIX-1) + +static stbtt__active_edge *stbtt__new_active(stbtt__hheap *hh, stbtt__edge *e, int off_x, float start_point, void *userdata) +{ + stbtt__active_edge *z = (stbtt__active_edge *) stbtt__hheap_alloc(hh, sizeof(*z), userdata); + float dxdy = (e->x1 - e->x0) / (e->y1 - e->y0); + STBTT_assert(z != NULL); + if (!z) return z; + + // round dx down to avoid overshooting + if (dxdy < 0) + z->dx = -STBTT_ifloor(STBTT_FIX * -dxdy); + else + z->dx = STBTT_ifloor(STBTT_FIX * dxdy); + + z->x = STBTT_ifloor(STBTT_FIX * e->x0 + z->dx * (start_point - e->y0)); // use z->dx so when we offset later it's by the same amount + z->x -= off_x * STBTT_FIX; + + z->ey = e->y1; + z->next = 0; + z->direction = e->invert ? 1 : -1; + return z; +} +#elif STBTT_RASTERIZER_VERSION == 2 +static stbtt__active_edge *stbtt__new_active(stbtt__hheap *hh, stbtt__edge *e, int off_x, float start_point, void *userdata) +{ + stbtt__active_edge *z = (stbtt__active_edge *) stbtt__hheap_alloc(hh, sizeof(*z), userdata); + float dxdy = (e->x1 - e->x0) / (e->y1 - e->y0); + STBTT_assert(z != NULL); + //STBTT_assert(e->y0 <= start_point); + if (!z) return z; + z->fdx = dxdy; + z->fdy = dxdy != 0.0f ? (1.0f/dxdy) : 0.0f; + z->fx = e->x0 + dxdy * (start_point - e->y0); + z->fx -= off_x; + z->direction = e->invert ? 1.0f : -1.0f; + z->sy = e->y0; + z->ey = e->y1; + z->next = 0; + return z; +} +#else +#error "Unrecognized value of STBTT_RASTERIZER_VERSION" +#endif + +#if STBTT_RASTERIZER_VERSION == 1 +// note: this routine clips fills that extend off the edges... ideally this +// wouldn't happen, but it could happen if the truetype glyph bounding boxes +// are wrong, or if the user supplies a too-small bitmap +static void stbtt__fill_active_edges(unsigned char *scanline, int len, stbtt__active_edge *e, int max_weight) +{ + // non-zero winding fill + int x0=0, w=0; + + while (e) { + if (w == 0) { + // if we're currently at zero, we need to record the edge start point + x0 = e->x; w += e->direction; + } else { + int x1 = e->x; w += e->direction; + // if we went to zero, we need to draw + if (w == 0) { + int i = x0 >> STBTT_FIXSHIFT; + int j = x1 >> STBTT_FIXSHIFT; + + if (i < len && j >= 0) { + if (i == j) { + // x0,x1 are the same pixel, so compute combined coverage + scanline[i] = scanline[i] + (stbtt_uint8) ((x1 - x0) * max_weight >> STBTT_FIXSHIFT); + } else { + if (i >= 0) // add antialiasing for x0 + scanline[i] = scanline[i] + (stbtt_uint8) (((STBTT_FIX - (x0 & STBTT_FIXMASK)) * max_weight) >> STBTT_FIXSHIFT); + else + i = -1; // clip + + if (j < len) // add antialiasing for x1 + scanline[j] = scanline[j] + (stbtt_uint8) (((x1 & STBTT_FIXMASK) * max_weight) >> STBTT_FIXSHIFT); + else + j = len; // clip + + for (++i; i < j; ++i) // fill pixels between x0 and x1 + scanline[i] = scanline[i] + (stbtt_uint8) max_weight; + } + } + } + } + + e = e->next; + } +} + +static void stbtt__rasterize_sorted_edges(stbtt__bitmap *result, stbtt__edge *e, int n, int vsubsample, int off_x, int off_y, void *userdata) +{ + stbtt__hheap hh = { 0, 0, 0 }; + stbtt__active_edge *active = NULL; + int y,j=0; + int max_weight = (255 / vsubsample); // weight per vertical scanline + int s; // vertical subsample index + unsigned char scanline_data[512], *scanline; + + if (result->w > 512) + scanline = (unsigned char *) STBTT_malloc(result->w, userdata); + else + scanline = scanline_data; + + y = off_y * vsubsample; + e[n].y0 = (off_y + result->h) * (float) vsubsample + 1; + + while (j < result->h) { + STBTT_memset(scanline, 0, result->w); + for (s=0; s < vsubsample; ++s) { + // find center of pixel for this scanline + float scan_y = y + 0.5f; + stbtt__active_edge **step = &active; + + // update all active edges; + // remove all active edges that terminate before the center of this scanline + while (*step) { + stbtt__active_edge * z = *step; + if (z->ey <= scan_y) { + *step = z->next; // delete from list + STBTT_assert(z->direction); + z->direction = 0; + stbtt__hheap_free(&hh, z); + } else { + z->x += z->dx; // advance to position for current scanline + step = &((*step)->next); // advance through list + } + } + + // resort the list if needed + for(;;) { + int changed=0; + step = &active; + while (*step && (*step)->next) { + if ((*step)->x > (*step)->next->x) { + stbtt__active_edge *t = *step; + stbtt__active_edge *q = t->next; + + t->next = q->next; + q->next = t; + *step = q; + changed = 1; + } + step = &(*step)->next; + } + if (!changed) break; + } + + // insert all edges that start before the center of this scanline -- omit ones that also end on this scanline + while (e->y0 <= scan_y) { + if (e->y1 > scan_y) { + stbtt__active_edge *z = stbtt__new_active(&hh, e, off_x, scan_y, userdata); + if (z != NULL) { + // find insertion point + if (active == NULL) + active = z; + else if (z->x < active->x) { + // insert at front + z->next = active; + active = z; + } else { + // find thing to insert AFTER + stbtt__active_edge *p = active; + while (p->next && p->next->x < z->x) + p = p->next; + // at this point, p->next->x is NOT < z->x + z->next = p->next; + p->next = z; + } + } + } + ++e; + } + + // now process all active edges in XOR fashion + if (active) + stbtt__fill_active_edges(scanline, result->w, active, max_weight); + + ++y; + } + STBTT_memcpy(result->pixels + j * result->stride, scanline, result->w); + ++j; + } + + stbtt__hheap_cleanup(&hh, userdata); + + if (scanline != scanline_data) + STBTT_free(scanline, userdata); +} + +#elif STBTT_RASTERIZER_VERSION == 2 + +// the edge passed in here does not cross the vertical line at x or the vertical line at x+1 +// (i.e. it has already been clipped to those) +static void stbtt__handle_clipped_edge(float *scanline, int x, stbtt__active_edge *e, float x0, float y0, float x1, float y1) +{ + if (y0 == y1) return; + STBTT_assert(y0 < y1); + STBTT_assert(e->sy <= e->ey); + if (y0 > e->ey) return; + if (y1 < e->sy) return; + if (y0 < e->sy) { + x0 += (x1-x0) * (e->sy - y0) / (y1-y0); + y0 = e->sy; + } + if (y1 > e->ey) { + x1 += (x1-x0) * (e->ey - y1) / (y1-y0); + y1 = e->ey; + } + + if (x0 == x) + STBTT_assert(x1 <= x+1); + else if (x0 == x+1) + STBTT_assert(x1 >= x); + else if (x0 <= x) + STBTT_assert(x1 <= x); + else if (x0 >= x+1) + STBTT_assert(x1 >= x+1); + else + STBTT_assert(x1 >= x && x1 <= x+1); + + if (x0 <= x && x1 <= x) + scanline[x] += e->direction * (y1-y0); + else if (x0 >= x+1 && x1 >= x+1) + ; + else { + STBTT_assert(x0 >= x && x0 <= x+1 && x1 >= x && x1 <= x+1); + scanline[x] += e->direction * (y1-y0) * (1-((x0-x)+(x1-x))/2); // coverage = 1 - average x position + } +} + +static void stbtt__fill_active_edges_new(float *scanline, float *scanline_fill, int len, stbtt__active_edge *e, float y_top) +{ + float y_bottom = y_top+1; + + while (e) { + // brute force every pixel + + // compute intersection points with top & bottom + STBTT_assert(e->ey >= y_top); + + if (e->fdx == 0) { + float x0 = e->fx; + if (x0 < len) { + if (x0 >= 0) { + stbtt__handle_clipped_edge(scanline,(int) x0,e, x0,y_top, x0,y_bottom); + stbtt__handle_clipped_edge(scanline_fill-1,(int) x0+1,e, x0,y_top, x0,y_bottom); + } else { + stbtt__handle_clipped_edge(scanline_fill-1,0,e, x0,y_top, x0,y_bottom); + } + } + } else { + float x0 = e->fx; + float dx = e->fdx; + float xb = x0 + dx; + float x_top, x_bottom; + float sy0,sy1; + float dy = e->fdy; + STBTT_assert(e->sy <= y_bottom && e->ey >= y_top); + + // compute endpoints of line segment clipped to this scanline (if the + // line segment starts on this scanline. x0 is the intersection of the + // line with y_top, but that may be off the line segment. + if (e->sy > y_top) { + x_top = x0 + dx * (e->sy - y_top); + sy0 = e->sy; + } else { + x_top = x0; + sy0 = y_top; + } + if (e->ey < y_bottom) { + x_bottom = x0 + dx * (e->ey - y_top); + sy1 = e->ey; + } else { + x_bottom = xb; + sy1 = y_bottom; + } + + if (x_top >= 0 && x_bottom >= 0 && x_top < len && x_bottom < len) { + // from here on, we don't have to range check x values + + if ((int) x_top == (int) x_bottom) { + float height; + // simple case, only spans one pixel + int x = (int) x_top; + height = sy1 - sy0; + STBTT_assert(x >= 0 && x < len); + scanline[x] += e->direction * (1-((x_top - x) + (x_bottom-x))/2) * height; + scanline_fill[x] += e->direction * height; // everything right of this pixel is filled + } else { + int x,x1,x2; + float y_crossing, step, sign, area; + // covers 2+ pixels + if (x_top > x_bottom) { + // flip scanline vertically; signed area is the same + float t; + sy0 = y_bottom - (sy0 - y_top); + sy1 = y_bottom - (sy1 - y_top); + t = sy0, sy0 = sy1, sy1 = t; + t = x_bottom, x_bottom = x_top, x_top = t; + dx = -dx; + dy = -dy; + t = x0, x0 = xb, xb = t; + } + + x1 = (int) x_top; + x2 = (int) x_bottom; + // compute intersection with y axis at x1+1 + y_crossing = (x1+1 - x0) * dy + y_top; + + sign = e->direction; + // area of the rectangle covered from y0..y_crossing + area = sign * (y_crossing-sy0); + // area of the triangle (x_top,y0), (x+1,y0), (x+1,y_crossing) + scanline[x1] += area * (1-((x_top - x1)+(x1+1-x1))/2); + + step = sign * dy; + for (x = x1+1; x < x2; ++x) { + scanline[x] += area + step/2; + area += step; + } + y_crossing += dy * (x2 - (x1+1)); + + STBTT_assert(fabs(area) <= 1.01f); + + scanline[x2] += area + sign * (1-((x2-x2)+(x_bottom-x2))/2) * (sy1-y_crossing); + + scanline_fill[x2] += sign * (sy1-sy0); + } + } else { + // if edge goes outside of box we're drawing, we require + // clipping logic. since this does not match the intended use + // of this library, we use a different, very slow brute + // force implementation + int x; + for (x=0; x < len; ++x) { + // cases: + // + // there can be up to two intersections with the pixel. any intersection + // with left or right edges can be handled by splitting into two (or three) + // regions. intersections with top & bottom do not necessitate case-wise logic. + // + // the old way of doing this found the intersections with the left & right edges, + // then used some simple logic to produce up to three segments in sorted order + // from top-to-bottom. however, this had a problem: if an x edge was epsilon + // across the x border, then the corresponding y position might not be distinct + // from the other y segment, and it might ignored as an empty segment. to avoid + // that, we need to explicitly produce segments based on x positions. + + // rename variables to clear pairs + float y0 = y_top; + float x1 = (float) (x); + float x2 = (float) (x+1); + float x3 = xb; + float y3 = y_bottom; + float y1,y2; + + // x = e->x + e->dx * (y-y_top) + // (y-y_top) = (x - e->x) / e->dx + // y = (x - e->x) / e->dx + y_top + y1 = (x - x0) / dx + y_top; + y2 = (x+1 - x0) / dx + y_top; + + if (x0 < x1 && x3 > x2) { // three segments descending down-right + stbtt__handle_clipped_edge(scanline,x,e, x0,y0, x1,y1); + stbtt__handle_clipped_edge(scanline,x,e, x1,y1, x2,y2); + stbtt__handle_clipped_edge(scanline,x,e, x2,y2, x3,y3); + } else if (x3 < x1 && x0 > x2) { // three segments descending down-left + stbtt__handle_clipped_edge(scanline,x,e, x0,y0, x2,y2); + stbtt__handle_clipped_edge(scanline,x,e, x2,y2, x1,y1); + stbtt__handle_clipped_edge(scanline,x,e, x1,y1, x3,y3); + } else if (x0 < x1 && x3 > x1) { // two segments across x, down-right + stbtt__handle_clipped_edge(scanline,x,e, x0,y0, x1,y1); + stbtt__handle_clipped_edge(scanline,x,e, x1,y1, x3,y3); + } else if (x3 < x1 && x0 > x1) { // two segments across x, down-left + stbtt__handle_clipped_edge(scanline,x,e, x0,y0, x1,y1); + stbtt__handle_clipped_edge(scanline,x,e, x1,y1, x3,y3); + } else if (x0 < x2 && x3 > x2) { // two segments across x+1, down-right + stbtt__handle_clipped_edge(scanline,x,e, x0,y0, x2,y2); + stbtt__handle_clipped_edge(scanline,x,e, x2,y2, x3,y3); + } else if (x3 < x2 && x0 > x2) { // two segments across x+1, down-left + stbtt__handle_clipped_edge(scanline,x,e, x0,y0, x2,y2); + stbtt__handle_clipped_edge(scanline,x,e, x2,y2, x3,y3); + } else { // one segment + stbtt__handle_clipped_edge(scanline,x,e, x0,y0, x3,y3); + } + } + } + } + e = e->next; + } +} + +// directly AA rasterize edges w/o supersampling +static void stbtt__rasterize_sorted_edges(stbtt__bitmap *result, stbtt__edge *e, int n, int vsubsample, int off_x, int off_y, void *userdata) +{ + stbtt__hheap hh = { 0, 0, 0 }; + stbtt__active_edge *active = NULL; + int y,j=0, i; + float scanline_data[129], *scanline, *scanline2; + + if (result->w > 64) + scanline = (float *) STBTT_malloc((result->w*2+1) * sizeof(float), userdata); + else + scanline = scanline_data; + + scanline2 = scanline + result->w; + + y = off_y; + e[n].y0 = (float) (off_y + result->h) + 1; + + while (j < result->h) { + // find center of pixel for this scanline + float scan_y_top = y + 0.0f; + float scan_y_bottom = y + 1.0f; + stbtt__active_edge **step = &active; + + STBTT_memset(scanline , 0, result->w*sizeof(scanline[0])); + STBTT_memset(scanline2, 0, (result->w+1)*sizeof(scanline[0])); + + // update all active edges; + // remove all active edges that terminate before the top of this scanline + while (*step) { + stbtt__active_edge * z = *step; + if (z->ey <= scan_y_top) { + *step = z->next; // delete from list + STBTT_assert(z->direction); + z->direction = 0; + stbtt__hheap_free(&hh, z); + } else { + step = &((*step)->next); // advance through list + } + } + + // insert all edges that start before the bottom of this scanline + while (e->y0 <= scan_y_bottom) { + if (e->y0 != e->y1) { + stbtt__active_edge *z = stbtt__new_active(&hh, e, off_x, scan_y_top, userdata); + if (z != NULL) { + STBTT_assert(z->ey >= scan_y_top); + // insert at front + z->next = active; + active = z; + } + } + ++e; + } + + // now process all active edges + if (active) + stbtt__fill_active_edges_new(scanline, scanline2+1, result->w, active, scan_y_top); + + { + float sum = 0; + for (i=0; i < result->w; ++i) { + float k; + int m; + sum += scanline2[i]; + k = scanline[i] + sum; + k = (float) fabs(k)*255 + 0.5f; + m = (int) k; + if (m > 255) m = 255; + result->pixels[j*result->stride + i] = (unsigned char) m; + } + } + // advance all the edges + step = &active; + while (*step) { + stbtt__active_edge *z = *step; + z->fx += z->fdx; // advance to position for current scanline + step = &((*step)->next); // advance through list + } + + ++y; + ++j; + } + + stbtt__hheap_cleanup(&hh, userdata); + + if (scanline != scanline_data) + STBTT_free(scanline, userdata); +} +#else +#error "Unrecognized value of STBTT_RASTERIZER_VERSION" +#endif + +#define STBTT__COMPARE(a,b) ((a)->y0 < (b)->y0) + +static void stbtt__sort_edges_ins_sort(stbtt__edge *p, int n) +{ + int i,j; + for (i=1; i < n; ++i) { + stbtt__edge t = p[i], *a = &t; + j = i; + while (j > 0) { + stbtt__edge *b = &p[j-1]; + int c = STBTT__COMPARE(a,b); + if (!c) break; + p[j] = p[j-1]; + --j; + } + if (i != j) + p[j] = t; + } +} + +static void stbtt__sort_edges_quicksort(stbtt__edge *p, int n) +{ + /* threshhold for transitioning to insertion sort */ + while (n > 12) { + stbtt__edge t; + int c01,c12,c,m,i,j; + + /* compute median of three */ + m = n >> 1; + c01 = STBTT__COMPARE(&p[0],&p[m]); + c12 = STBTT__COMPARE(&p[m],&p[n-1]); + /* if 0 >= mid >= end, or 0 < mid < end, then use mid */ + if (c01 != c12) { + /* otherwise, we'll need to swap something else to middle */ + int z; + c = STBTT__COMPARE(&p[0],&p[n-1]); + /* 0>mid && midn => n; 0 0 */ + /* 0n: 0>n => 0; 0 n */ + z = (c == c12) ? 0 : n-1; + t = p[z]; + p[z] = p[m]; + p[m] = t; + } + /* now p[m] is the median-of-three */ + /* swap it to the beginning so it won't move around */ + t = p[0]; + p[0] = p[m]; + p[m] = t; + + /* partition loop */ + i=1; + j=n-1; + for(;;) { + /* handling of equality is crucial here */ + /* for sentinels & efficiency with duplicates */ + for (;;++i) { + if (!STBTT__COMPARE(&p[i], &p[0])) break; + } + for (;;--j) { + if (!STBTT__COMPARE(&p[0], &p[j])) break; + } + /* make sure we haven't crossed */ + if (i >= j) break; + t = p[i]; + p[i] = p[j]; + p[j] = t; + + ++i; + --j; + } + /* recurse on smaller side, iterate on larger */ + if (j < (n-i)) { + stbtt__sort_edges_quicksort(p,j); + p = p+i; + n = n-i; + } else { + stbtt__sort_edges_quicksort(p+i, n-i); + n = j; + } + } +} + +static void stbtt__sort_edges(stbtt__edge *p, int n) +{ + stbtt__sort_edges_quicksort(p, n); + stbtt__sort_edges_ins_sort(p, n); +} + +typedef struct +{ + float x,y; +} stbtt__point; + +static void stbtt__rasterize(stbtt__bitmap *result, stbtt__point *pts, int *wcount, int windings, float scale_x, float scale_y, float shift_x, float shift_y, int off_x, int off_y, int invert, void *userdata) +{ + float y_scale_inv = invert ? -scale_y : scale_y; + stbtt__edge *e; + int n,i,j,k,m; +#if STBTT_RASTERIZER_VERSION == 1 + int vsubsample = result->h < 8 ? 15 : 5; +#elif STBTT_RASTERIZER_VERSION == 2 + int vsubsample = 1; +#else + #error "Unrecognized value of STBTT_RASTERIZER_VERSION" +#endif + // vsubsample should divide 255 evenly; otherwise we won't reach full opacity + + // now we have to blow out the windings into explicit edge lists + n = 0; + for (i=0; i < windings; ++i) + n += wcount[i]; + + e = (stbtt__edge *) STBTT_malloc(sizeof(*e) * (n+1), userdata); // add an extra one as a sentinel + if (e == 0) return; + n = 0; + + m=0; + for (i=0; i < windings; ++i) { + stbtt__point *p = pts + m; + m += wcount[i]; + j = wcount[i]-1; + for (k=0; k < wcount[i]; j=k++) { + int a=k,b=j; + // skip the edge if horizontal + if (p[j].y == p[k].y) + continue; + // add edge from j to k to the list + e[n].invert = 0; + if (invert ? p[j].y > p[k].y : p[j].y < p[k].y) { + e[n].invert = 1; + a=j,b=k; + } + e[n].x0 = p[a].x * scale_x + shift_x; + e[n].y0 = (p[a].y * y_scale_inv + shift_y) * vsubsample; + e[n].x1 = p[b].x * scale_x + shift_x; + e[n].y1 = (p[b].y * y_scale_inv + shift_y) * vsubsample; + ++n; + } + } + + // now sort the edges by their highest point (should snap to integer, and then by x) + //STBTT_sort(e, n, sizeof(e[0]), stbtt__edge_compare); + stbtt__sort_edges(e, n); + + // now, traverse the scanlines and find the intersections on each scanline, use xor winding rule + stbtt__rasterize_sorted_edges(result, e, n, vsubsample, off_x, off_y, userdata); + + STBTT_free(e, userdata); +} + +static void stbtt__add_point(stbtt__point *points, int n, float x, float y) +{ + if (!points) return; // during first pass, it's unallocated + points[n].x = x; + points[n].y = y; +} + +// tesselate until threshhold p is happy... @TODO warped to compensate for non-linear stretching +static int stbtt__tesselate_curve(stbtt__point *points, int *num_points, float x0, float y0, float x1, float y1, float x2, float y2, float objspace_flatness_squared, int n) +{ + // midpoint + float mx = (x0 + 2*x1 + x2)/4; + float my = (y0 + 2*y1 + y2)/4; + // versus directly drawn line + float dx = (x0+x2)/2 - mx; + float dy = (y0+y2)/2 - my; + if (n > 16) // 65536 segments on one curve better be enough! + return 1; + if (dx*dx+dy*dy > objspace_flatness_squared) { // half-pixel error allowed... need to be smaller if AA + stbtt__tesselate_curve(points, num_points, x0,y0, (x0+x1)/2.0f,(y0+y1)/2.0f, mx,my, objspace_flatness_squared,n+1); + stbtt__tesselate_curve(points, num_points, mx,my, (x1+x2)/2.0f,(y1+y2)/2.0f, x2,y2, objspace_flatness_squared,n+1); + } else { + stbtt__add_point(points, *num_points,x2,y2); + *num_points = *num_points+1; + } + return 1; +} + +// returns number of contours +static stbtt__point *stbtt_FlattenCurves(stbtt_vertex *vertices, int num_verts, float objspace_flatness, int **contour_lengths, int *num_contours, void *userdata) +{ + stbtt__point *points=0; + int num_points=0; + + float objspace_flatness_squared = objspace_flatness * objspace_flatness; + int i,n=0,start=0, pass; + + // count how many "moves" there are to get the contour count + for (i=0; i < num_verts; ++i) + if (vertices[i].type == STBTT_vmove) + ++n; + + *num_contours = n; + if (n == 0) return 0; + + *contour_lengths = (int *) STBTT_malloc(sizeof(**contour_lengths) * n, userdata); + + if (*contour_lengths == 0) { + *num_contours = 0; + return 0; + } + + // make two passes through the points so we don't need to realloc + for (pass=0; pass < 2; ++pass) { + float x=0,y=0; + if (pass == 1) { + points = (stbtt__point *) STBTT_malloc(num_points * sizeof(points[0]), userdata); + if (points == NULL) goto error; + } + num_points = 0; + n= -1; + for (i=0; i < num_verts; ++i) { + switch (vertices[i].type) { + case STBTT_vmove: + // start the next contour + if (n >= 0) + (*contour_lengths)[n] = num_points - start; + ++n; + start = num_points; + + x = vertices[i].x, y = vertices[i].y; + stbtt__add_point(points, num_points++, x,y); + break; + case STBTT_vline: + x = vertices[i].x, y = vertices[i].y; + stbtt__add_point(points, num_points++, x, y); + break; + case STBTT_vcurve: + stbtt__tesselate_curve(points, &num_points, x,y, + vertices[i].cx, vertices[i].cy, + vertices[i].x, vertices[i].y, + objspace_flatness_squared, 0); + x = vertices[i].x, y = vertices[i].y; + break; + } + } + (*contour_lengths)[n] = num_points - start; + } + + return points; +error: + STBTT_free(points, userdata); + STBTT_free(*contour_lengths, userdata); + *contour_lengths = 0; + *num_contours = 0; + return NULL; +} + +STBTT_DEF void stbtt_Rasterize(stbtt__bitmap *result, float flatness_in_pixels, stbtt_vertex *vertices, int num_verts, float scale_x, float scale_y, float shift_x, float shift_y, int x_off, int y_off, int invert, void *userdata) +{ + float scale = scale_x > scale_y ? scale_y : scale_x; + int winding_count, *winding_lengths; + stbtt__point *windings = stbtt_FlattenCurves(vertices, num_verts, flatness_in_pixels / scale, &winding_lengths, &winding_count, userdata); + if (windings) { + stbtt__rasterize(result, windings, winding_lengths, winding_count, scale_x, scale_y, shift_x, shift_y, x_off, y_off, invert, userdata); + STBTT_free(winding_lengths, userdata); + STBTT_free(windings, userdata); + } +} + +STBTT_DEF void stbtt_FreeBitmap(unsigned char *bitmap, void *userdata) +{ + STBTT_free(bitmap, userdata); +} + +STBTT_DEF unsigned char *stbtt_GetGlyphBitmapSubpixel(const stbtt_fontinfo *info, float scale_x, float scale_y, float shift_x, float shift_y, int glyph, int *width, int *height, int *xoff, int *yoff) +{ + int ix0,iy0,ix1,iy1; + stbtt__bitmap gbm; + stbtt_vertex *vertices; + int num_verts = stbtt_GetGlyphShape(info, glyph, &vertices); + + if (scale_x == 0) scale_x = scale_y; + if (scale_y == 0) { + if (scale_x == 0) return NULL; + scale_y = scale_x; + } + + stbtt_GetGlyphBitmapBoxSubpixel(info, glyph, scale_x, scale_y, shift_x, shift_y, &ix0,&iy0,&ix1,&iy1); + + // now we get the size + gbm.w = (ix1 - ix0); + gbm.h = (iy1 - iy0); + gbm.pixels = NULL; // in case we error + + if (width ) *width = gbm.w; + if (height) *height = gbm.h; + if (xoff ) *xoff = ix0; + if (yoff ) *yoff = iy0; + + if (gbm.w && gbm.h) { + gbm.pixels = (unsigned char *) STBTT_malloc(gbm.w * gbm.h, info->userdata); + if (gbm.pixels) { + gbm.stride = gbm.w; + + stbtt_Rasterize(&gbm, 0.35f, vertices, num_verts, scale_x, scale_y, shift_x, shift_y, ix0, iy0, 1, info->userdata); + } + } + STBTT_free(vertices, info->userdata); + return gbm.pixels; +} + +STBTT_DEF unsigned char *stbtt_GetGlyphBitmap(const stbtt_fontinfo *info, float scale_x, float scale_y, int glyph, int *width, int *height, int *xoff, int *yoff) +{ + return stbtt_GetGlyphBitmapSubpixel(info, scale_x, scale_y, 0.0f, 0.0f, glyph, width, height, xoff, yoff); +} + +STBTT_DEF void stbtt_MakeGlyphBitmapSubpixel(const stbtt_fontinfo *info, unsigned char *output, int out_w, int out_h, int out_stride, float scale_x, float scale_y, float shift_x, float shift_y, int glyph) +{ + int ix0,iy0; + stbtt_vertex *vertices; + int num_verts = stbtt_GetGlyphShape(info, glyph, &vertices); + stbtt__bitmap gbm; + + stbtt_GetGlyphBitmapBoxSubpixel(info, glyph, scale_x, scale_y, shift_x, shift_y, &ix0,&iy0,0,0); + gbm.pixels = output; + gbm.w = out_w; + gbm.h = out_h; + gbm.stride = out_stride; + + if (gbm.w && gbm.h) + stbtt_Rasterize(&gbm, 0.35f, vertices, num_verts, scale_x, scale_y, shift_x, shift_y, ix0,iy0, 1, info->userdata); + + STBTT_free(vertices, info->userdata); +} + +STBTT_DEF void stbtt_MakeGlyphBitmap(const stbtt_fontinfo *info, unsigned char *output, int out_w, int out_h, int out_stride, float scale_x, float scale_y, int glyph) +{ + stbtt_MakeGlyphBitmapSubpixel(info, output, out_w, out_h, out_stride, scale_x, scale_y, 0.0f,0.0f, glyph); +} + +STBTT_DEF unsigned char *stbtt_GetCodepointBitmapSubpixel(const stbtt_fontinfo *info, float scale_x, float scale_y, float shift_x, float shift_y, int codepoint, int *width, int *height, int *xoff, int *yoff) +{ + return stbtt_GetGlyphBitmapSubpixel(info, scale_x, scale_y,shift_x,shift_y, stbtt_FindGlyphIndex(info,codepoint), width,height,xoff,yoff); +} + +STBTT_DEF void stbtt_MakeCodepointBitmapSubpixel(const stbtt_fontinfo *info, unsigned char *output, int out_w, int out_h, int out_stride, float scale_x, float scale_y, float shift_x, float shift_y, int codepoint) +{ + stbtt_MakeGlyphBitmapSubpixel(info, output, out_w, out_h, out_stride, scale_x, scale_y, shift_x, shift_y, stbtt_FindGlyphIndex(info,codepoint)); +} + +STBTT_DEF unsigned char *stbtt_GetCodepointBitmap(const stbtt_fontinfo *info, float scale_x, float scale_y, int codepoint, int *width, int *height, int *xoff, int *yoff) +{ + return stbtt_GetCodepointBitmapSubpixel(info, scale_x, scale_y, 0.0f,0.0f, codepoint, width,height,xoff,yoff); +} + +STBTT_DEF void stbtt_MakeCodepointBitmap(const stbtt_fontinfo *info, unsigned char *output, int out_w, int out_h, int out_stride, float scale_x, float scale_y, int codepoint) +{ + stbtt_MakeCodepointBitmapSubpixel(info, output, out_w, out_h, out_stride, scale_x, scale_y, 0.0f,0.0f, codepoint); +} + +////////////////////////////////////////////////////////////////////////////// +// +// bitmap baking +// +// This is SUPER-CRAPPY packing to keep source code small + +STBTT_DEF int stbtt_BakeFontBitmap(const unsigned char *data, int offset, // font location (use offset=0 for plain .ttf) + float pixel_height, // height of font in pixels + unsigned char *pixels, int pw, int ph, // bitmap to be filled in + int first_char, int num_chars, // characters to bake + stbtt_bakedchar *chardata) +{ + float scale; + int x,y,bottom_y, i; + stbtt_fontinfo f; + f.userdata = NULL; + if (!stbtt_InitFont(&f, data, offset)) + return -1; + STBTT_memset(pixels, 0, pw*ph); // background of 0 around pixels + x=y=1; + bottom_y = 1; + + scale = stbtt_ScaleForPixelHeight(&f, pixel_height); + + for (i=0; i < num_chars; ++i) { + int advance, lsb, x0,y0,x1,y1,gw,gh; + int g = stbtt_FindGlyphIndex(&f, first_char + i); + stbtt_GetGlyphHMetrics(&f, g, &advance, &lsb); + stbtt_GetGlyphBitmapBox(&f, g, scale,scale, &x0,&y0,&x1,&y1); + gw = x1-x0; + gh = y1-y0; + if (x + gw + 1 >= pw) + y = bottom_y, x = 1; // advance to next row + if (y + gh + 1 >= ph) // check if it fits vertically AFTER potentially moving to next row + return -i; + STBTT_assert(x+gw < pw); + STBTT_assert(y+gh < ph); + stbtt_MakeGlyphBitmap(&f, pixels+x+y*pw, gw,gh,pw, scale,scale, g); + chardata[i].x0 = (stbtt_int16) x; + chardata[i].y0 = (stbtt_int16) y; + chardata[i].x1 = (stbtt_int16) (x + gw); + chardata[i].y1 = (stbtt_int16) (y + gh); + chardata[i].xadvance = scale * advance; + chardata[i].xoff = (float) x0; + chardata[i].yoff = (float) y0; + x = x + gw + 1; + if (y+gh+1 > bottom_y) + bottom_y = y+gh+1; + } + return bottom_y; +} + +STBTT_DEF void stbtt_GetBakedQuad(stbtt_bakedchar *chardata, int pw, int ph, int char_index, float *xpos, float *ypos, stbtt_aligned_quad *q, int opengl_fillrule) +{ + float d3d_bias = opengl_fillrule ? 0 : -0.5f; + float ipw = 1.0f / pw, iph = 1.0f / ph; + stbtt_bakedchar *b = chardata + char_index; + int round_x = STBTT_ifloor((*xpos + b->xoff) + 0.5f); + int round_y = STBTT_ifloor((*ypos + b->yoff) + 0.5f); + + q->x0 = round_x + d3d_bias; + q->y0 = round_y + d3d_bias; + q->x1 = round_x + b->x1 - b->x0 + d3d_bias; + q->y1 = round_y + b->y1 - b->y0 + d3d_bias; + + q->s0 = b->x0 * ipw; + q->t0 = b->y0 * iph; + q->s1 = b->x1 * ipw; + q->t1 = b->y1 * iph; + + *xpos += b->xadvance; +} + +////////////////////////////////////////////////////////////////////////////// +// +// rectangle packing replacement routines if you don't have stb_rect_pack.h +// + +#ifndef STB_RECT_PACK_VERSION +#ifdef _MSC_VER +#define STBTT__NOTUSED(v) (void)(v) +#else +#define STBTT__NOTUSED(v) (void)sizeof(v) +#endif + +typedef int stbrp_coord; + +//////////////////////////////////////////////////////////////////////////////////// +// // +// // +// COMPILER WARNING ?!?!? // +// // +// // +// if you get a compile warning due to these symbols being defined more than // +// once, move #include "stb_rect_pack.h" before #include "stb_truetype.h" // +// // +//////////////////////////////////////////////////////////////////////////////////// + +typedef struct +{ + int width,height; + int x,y,bottom_y; +} stbrp_context; + +typedef struct +{ + unsigned char x; +} stbrp_node; + +struct stbrp_rect +{ + stbrp_coord x,y; + int id,w,h,was_packed; +}; + +static void stbrp_init_target(stbrp_context *con, int pw, int ph, stbrp_node *nodes, int num_nodes) +{ + con->width = pw; + con->height = ph; + con->x = 0; + con->y = 0; + con->bottom_y = 0; + STBTT__NOTUSED(nodes); + STBTT__NOTUSED(num_nodes); +} + +static void stbrp_pack_rects(stbrp_context *con, stbrp_rect *rects, int num_rects) +{ + int i; + for (i=0; i < num_rects; ++i) { + if (con->x + rects[i].w > con->width) { + con->x = 0; + con->y = con->bottom_y; + } + if (con->y + rects[i].h > con->height) + break; + rects[i].x = con->x; + rects[i].y = con->y; + rects[i].was_packed = 1; + con->x += rects[i].w; + if (con->y + rects[i].h > con->bottom_y) + con->bottom_y = con->y + rects[i].h; + } + for ( ; i < num_rects; ++i) + rects[i].was_packed = 0; +} +#endif + +////////////////////////////////////////////////////////////////////////////// +// +// bitmap baking +// +// This is SUPER-AWESOME (tm Ryan Gordon) packing using stb_rect_pack.h. If +// stb_rect_pack.h isn't available, it uses the BakeFontBitmap strategy. + +STBTT_DEF int stbtt_PackBegin(stbtt_pack_context *spc, unsigned char *pixels, int pw, int ph, int stride_in_bytes, int padding, void *alloc_context) +{ + stbrp_context *context = (stbrp_context *) STBTT_malloc(sizeof(*context) ,alloc_context); + int num_nodes = pw - padding; + stbrp_node *nodes = (stbrp_node *) STBTT_malloc(sizeof(*nodes ) * num_nodes,alloc_context); + + if (context == NULL || nodes == NULL) { + if (context != NULL) STBTT_free(context, alloc_context); + if (nodes != NULL) STBTT_free(nodes , alloc_context); + return 0; + } + + spc->user_allocator_context = alloc_context; + spc->width = pw; + spc->height = ph; + spc->pixels = pixels; + spc->pack_info = context; + spc->nodes = nodes; + spc->padding = padding; + spc->stride_in_bytes = stride_in_bytes != 0 ? stride_in_bytes : pw; + spc->h_oversample = 1; + spc->v_oversample = 1; + + stbrp_init_target(context, pw-padding, ph-padding, nodes, num_nodes); + + if (pixels) + STBTT_memset(pixels, 0, pw*ph); // background of 0 around pixels + + return 1; +} + +STBTT_DEF void stbtt_PackEnd (stbtt_pack_context *spc) +{ + STBTT_free(spc->nodes , spc->user_allocator_context); + STBTT_free(spc->pack_info, spc->user_allocator_context); +} + +STBTT_DEF void stbtt_PackSetOversampling(stbtt_pack_context *spc, unsigned int h_oversample, unsigned int v_oversample) +{ + STBTT_assert(h_oversample <= STBTT_MAX_OVERSAMPLE); + STBTT_assert(v_oversample <= STBTT_MAX_OVERSAMPLE); + if (h_oversample <= STBTT_MAX_OVERSAMPLE) + spc->h_oversample = h_oversample; + if (v_oversample <= STBTT_MAX_OVERSAMPLE) + spc->v_oversample = v_oversample; +} + +#define STBTT__OVER_MASK (STBTT_MAX_OVERSAMPLE-1) + +static void stbtt__h_prefilter(unsigned char *pixels, int w, int h, int stride_in_bytes, unsigned int kernel_width) +{ + unsigned char buffer[STBTT_MAX_OVERSAMPLE]; + int safe_w = w - kernel_width; + int j; + STBTT_memset(buffer, 0, STBTT_MAX_OVERSAMPLE); // suppress bogus warning from VS2013 -analyze + for (j=0; j < h; ++j) { + int i; + unsigned int total; + STBTT_memset(buffer, 0, kernel_width); + + total = 0; + + // make kernel_width a constant in common cases so compiler can optimize out the divide + switch (kernel_width) { + case 2: + for (i=0; i <= safe_w; ++i) { + total += pixels[i] - buffer[i & STBTT__OVER_MASK]; + buffer[(i+kernel_width) & STBTT__OVER_MASK] = pixels[i]; + pixels[i] = (unsigned char) (total / 2); + } + break; + case 3: + for (i=0; i <= safe_w; ++i) { + total += pixels[i] - buffer[i & STBTT__OVER_MASK]; + buffer[(i+kernel_width) & STBTT__OVER_MASK] = pixels[i]; + pixels[i] = (unsigned char) (total / 3); + } + break; + case 4: + for (i=0; i <= safe_w; ++i) { + total += pixels[i] - buffer[i & STBTT__OVER_MASK]; + buffer[(i+kernel_width) & STBTT__OVER_MASK] = pixels[i]; + pixels[i] = (unsigned char) (total / 4); + } + break; + case 5: + for (i=0; i <= safe_w; ++i) { + total += pixels[i] - buffer[i & STBTT__OVER_MASK]; + buffer[(i+kernel_width) & STBTT__OVER_MASK] = pixels[i]; + pixels[i] = (unsigned char) (total / 5); + } + break; + default: + for (i=0; i <= safe_w; ++i) { + total += pixels[i] - buffer[i & STBTT__OVER_MASK]; + buffer[(i+kernel_width) & STBTT__OVER_MASK] = pixels[i]; + pixels[i] = (unsigned char) (total / kernel_width); + } + break; + } + + for (; i < w; ++i) { + STBTT_assert(pixels[i] == 0); + total -= buffer[i & STBTT__OVER_MASK]; + pixels[i] = (unsigned char) (total / kernel_width); + } + + pixels += stride_in_bytes; + } +} + +static void stbtt__v_prefilter(unsigned char *pixels, int w, int h, int stride_in_bytes, unsigned int kernel_width) +{ + unsigned char buffer[STBTT_MAX_OVERSAMPLE]; + int safe_h = h - kernel_width; + int j; + STBTT_memset(buffer, 0, STBTT_MAX_OVERSAMPLE); // suppress bogus warning from VS2013 -analyze + for (j=0; j < w; ++j) { + int i; + unsigned int total; + STBTT_memset(buffer, 0, kernel_width); + + total = 0; + + // make kernel_width a constant in common cases so compiler can optimize out the divide + switch (kernel_width) { + case 2: + for (i=0; i <= safe_h; ++i) { + total += pixels[i*stride_in_bytes] - buffer[i & STBTT__OVER_MASK]; + buffer[(i+kernel_width) & STBTT__OVER_MASK] = pixels[i*stride_in_bytes]; + pixels[i*stride_in_bytes] = (unsigned char) (total / 2); + } + break; + case 3: + for (i=0; i <= safe_h; ++i) { + total += pixels[i*stride_in_bytes] - buffer[i & STBTT__OVER_MASK]; + buffer[(i+kernel_width) & STBTT__OVER_MASK] = pixels[i*stride_in_bytes]; + pixels[i*stride_in_bytes] = (unsigned char) (total / 3); + } + break; + case 4: + for (i=0; i <= safe_h; ++i) { + total += pixels[i*stride_in_bytes] - buffer[i & STBTT__OVER_MASK]; + buffer[(i+kernel_width) & STBTT__OVER_MASK] = pixels[i*stride_in_bytes]; + pixels[i*stride_in_bytes] = (unsigned char) (total / 4); + } + break; + case 5: + for (i=0; i <= safe_h; ++i) { + total += pixels[i*stride_in_bytes] - buffer[i & STBTT__OVER_MASK]; + buffer[(i+kernel_width) & STBTT__OVER_MASK] = pixels[i*stride_in_bytes]; + pixels[i*stride_in_bytes] = (unsigned char) (total / 5); + } + break; + default: + for (i=0; i <= safe_h; ++i) { + total += pixels[i*stride_in_bytes] - buffer[i & STBTT__OVER_MASK]; + buffer[(i+kernel_width) & STBTT__OVER_MASK] = pixels[i*stride_in_bytes]; + pixels[i*stride_in_bytes] = (unsigned char) (total / kernel_width); + } + break; + } + + for (; i < h; ++i) { + STBTT_assert(pixels[i*stride_in_bytes] == 0); + total -= buffer[i & STBTT__OVER_MASK]; + pixels[i*stride_in_bytes] = (unsigned char) (total / kernel_width); + } + + pixels += 1; + } +} + +static float stbtt__oversample_shift(int oversample) +{ + if (!oversample) + return 0.0f; + + // The prefilter is a box filter of width "oversample", + // which shifts phase by (oversample - 1)/2 pixels in + // oversampled space. We want to shift in the opposite + // direction to counter this. + return (float)-(oversample - 1) / (2.0f * (float)oversample); +} + +// rects array must be big enough to accommodate all characters in the given ranges +STBTT_DEF int stbtt_PackFontRangesGatherRects(stbtt_pack_context *spc, stbtt_fontinfo *info, stbtt_pack_range *ranges, int num_ranges, stbrp_rect *rects) +{ + int i,j,k; + + k=0; + for (i=0; i < num_ranges; ++i) { + float fh = ranges[i].font_size; + float scale = fh > 0 ? stbtt_ScaleForPixelHeight(info, fh) : stbtt_ScaleForMappingEmToPixels(info, -fh); + ranges[i].h_oversample = (unsigned char) spc->h_oversample; + ranges[i].v_oversample = (unsigned char) spc->v_oversample; + for (j=0; j < ranges[i].num_chars; ++j) { + int x0,y0,x1,y1; + int codepoint = ranges[i].array_of_unicode_codepoints == NULL ? ranges[i].first_unicode_codepoint_in_range + j : ranges[i].array_of_unicode_codepoints[j]; + int glyph = stbtt_FindGlyphIndex(info, codepoint); + stbtt_GetGlyphBitmapBoxSubpixel(info,glyph, + scale * spc->h_oversample, + scale * spc->v_oversample, + 0,0, + &x0,&y0,&x1,&y1); + rects[k].w = (stbrp_coord) (x1-x0 + spc->padding + spc->h_oversample-1); + rects[k].h = (stbrp_coord) (y1-y0 + spc->padding + spc->v_oversample-1); + ++k; + } + } + + return k; +} + +// rects array must be big enough to accommodate all characters in the given ranges +STBTT_DEF int stbtt_PackFontRangesRenderIntoRects(stbtt_pack_context *spc, stbtt_fontinfo *info, stbtt_pack_range *ranges, int num_ranges, stbrp_rect *rects) +{ + int i,j,k, return_value = 1; + + // save current values + int old_h_over = spc->h_oversample; + int old_v_over = spc->v_oversample; + + k = 0; + for (i=0; i < num_ranges; ++i) { + float fh = ranges[i].font_size; + float scale = fh > 0 ? stbtt_ScaleForPixelHeight(info, fh) : stbtt_ScaleForMappingEmToPixels(info, -fh); + float recip_h,recip_v,sub_x,sub_y; + spc->h_oversample = ranges[i].h_oversample; + spc->v_oversample = ranges[i].v_oversample; + recip_h = 1.0f / spc->h_oversample; + recip_v = 1.0f / spc->v_oversample; + sub_x = stbtt__oversample_shift(spc->h_oversample); + sub_y = stbtt__oversample_shift(spc->v_oversample); + for (j=0; j < ranges[i].num_chars; ++j) { + stbrp_rect *r = &rects[k]; + if (r->was_packed) { + stbtt_packedchar *bc = &ranges[i].chardata_for_range[j]; + int advance, lsb, x0,y0,x1,y1; + int codepoint = ranges[i].array_of_unicode_codepoints == NULL ? ranges[i].first_unicode_codepoint_in_range + j : ranges[i].array_of_unicode_codepoints[j]; + int glyph = stbtt_FindGlyphIndex(info, codepoint); + stbrp_coord pad = (stbrp_coord) spc->padding; + + // pad on left and top + r->x += pad; + r->y += pad; + r->w -= pad; + r->h -= pad; + stbtt_GetGlyphHMetrics(info, glyph, &advance, &lsb); + stbtt_GetGlyphBitmapBox(info, glyph, + scale * spc->h_oversample, + scale * spc->v_oversample, + &x0,&y0,&x1,&y1); + stbtt_MakeGlyphBitmapSubpixel(info, + spc->pixels + r->x + r->y*spc->stride_in_bytes, + r->w - spc->h_oversample+1, + r->h - spc->v_oversample+1, + spc->stride_in_bytes, + scale * spc->h_oversample, + scale * spc->v_oversample, + 0,0, + glyph); + + if (spc->h_oversample > 1) + stbtt__h_prefilter(spc->pixels + r->x + r->y*spc->stride_in_bytes, + r->w, r->h, spc->stride_in_bytes, + spc->h_oversample); + + if (spc->v_oversample > 1) + stbtt__v_prefilter(spc->pixels + r->x + r->y*spc->stride_in_bytes, + r->w, r->h, spc->stride_in_bytes, + spc->v_oversample); + + bc->x0 = (stbtt_int16) r->x; + bc->y0 = (stbtt_int16) r->y; + bc->x1 = (stbtt_int16) (r->x + r->w); + bc->y1 = (stbtt_int16) (r->y + r->h); + bc->xadvance = scale * advance; + bc->xoff = (float) x0 * recip_h + sub_x; + bc->yoff = (float) y0 * recip_v + sub_y; + bc->xoff2 = (x0 + r->w) * recip_h + sub_x; + bc->yoff2 = (y0 + r->h) * recip_v + sub_y; + } else { + return_value = 0; // if any fail, report failure + } + + ++k; + } + } + + // restore original values + spc->h_oversample = old_h_over; + spc->v_oversample = old_v_over; + + return return_value; +} + +STBTT_DEF void stbtt_PackFontRangesPackRects(stbtt_pack_context *spc, stbrp_rect *rects, int num_rects) +{ + stbrp_pack_rects((stbrp_context *) spc->pack_info, rects, num_rects); +} + +STBTT_DEF int stbtt_PackFontRanges(stbtt_pack_context *spc, unsigned char *fontdata, int font_index, stbtt_pack_range *ranges, int num_ranges) +{ + stbtt_fontinfo info; + int i,j,n, return_value = 1; + //stbrp_context *context = (stbrp_context *) spc->pack_info; + stbrp_rect *rects; + + // flag all characters as NOT packed + for (i=0; i < num_ranges; ++i) + for (j=0; j < ranges[i].num_chars; ++j) + ranges[i].chardata_for_range[j].x0 = + ranges[i].chardata_for_range[j].y0 = + ranges[i].chardata_for_range[j].x1 = + ranges[i].chardata_for_range[j].y1 = 0; + + n = 0; + for (i=0; i < num_ranges; ++i) + n += ranges[i].num_chars; + + rects = (stbrp_rect *) STBTT_malloc(sizeof(*rects) * n, spc->user_allocator_context); + if (rects == NULL) + return 0; + + info.userdata = spc->user_allocator_context; + stbtt_InitFont(&info, fontdata, stbtt_GetFontOffsetForIndex(fontdata,font_index)); + + n = stbtt_PackFontRangesGatherRects(spc, &info, ranges, num_ranges, rects); + + stbtt_PackFontRangesPackRects(spc, rects, n); + + return_value = stbtt_PackFontRangesRenderIntoRects(spc, &info, ranges, num_ranges, rects); + + STBTT_free(rects, spc->user_allocator_context); + return return_value; +} + +STBTT_DEF int stbtt_PackFontRange(stbtt_pack_context *spc, unsigned char *fontdata, int font_index, float font_size, + int first_unicode_codepoint_in_range, int num_chars_in_range, stbtt_packedchar *chardata_for_range) +{ + stbtt_pack_range range; + range.first_unicode_codepoint_in_range = first_unicode_codepoint_in_range; + range.array_of_unicode_codepoints = NULL; + range.num_chars = num_chars_in_range; + range.chardata_for_range = chardata_for_range; + range.font_size = font_size; + return stbtt_PackFontRanges(spc, fontdata, font_index, &range, 1); +} + +STBTT_DEF void stbtt_GetPackedQuad(stbtt_packedchar *chardata, int pw, int ph, int char_index, float *xpos, float *ypos, stbtt_aligned_quad *q, int align_to_integer) +{ + float ipw = 1.0f / pw, iph = 1.0f / ph; + stbtt_packedchar *b = chardata + char_index; + + if (align_to_integer) { + float x = (float) STBTT_ifloor((*xpos + b->xoff) + 0.5f); + float y = (float) STBTT_ifloor((*ypos + b->yoff) + 0.5f); + q->x0 = x; + q->y0 = y; + q->x1 = x + b->xoff2 - b->xoff; + q->y1 = y + b->yoff2 - b->yoff; + } else { + q->x0 = *xpos + b->xoff; + q->y0 = *ypos + b->yoff; + q->x1 = *xpos + b->xoff2; + q->y1 = *ypos + b->yoff2; + } + + q->s0 = b->x0 * ipw; + q->t0 = b->y0 * iph; + q->s1 = b->x1 * ipw; + q->t1 = b->y1 * iph; + + *xpos += b->xadvance; +} + + +////////////////////////////////////////////////////////////////////////////// +// +// font name matching -- recommended not to use this +// + +// check if a utf8 string contains a prefix which is the utf16 string; if so return length of matching utf8 string +static stbtt_int32 stbtt__CompareUTF8toUTF16_bigendian_prefix(const stbtt_uint8 *s1, stbtt_int32 len1, const stbtt_uint8 *s2, stbtt_int32 len2) +{ + stbtt_int32 i=0; + + // convert utf16 to utf8 and compare the results while converting + while (len2) { + stbtt_uint16 ch = s2[0]*256 + s2[1]; + if (ch < 0x80) { + if (i >= len1) return -1; + if (s1[i++] != ch) return -1; + } else if (ch < 0x800) { + if (i+1 >= len1) return -1; + if (s1[i++] != 0xc0 + (ch >> 6)) return -1; + if (s1[i++] != 0x80 + (ch & 0x3f)) return -1; + } else if (ch >= 0xd800 && ch < 0xdc00) { + stbtt_uint32 c; + stbtt_uint16 ch2 = s2[2]*256 + s2[3]; + if (i+3 >= len1) return -1; + c = ((ch - 0xd800) << 10) + (ch2 - 0xdc00) + 0x10000; + if (s1[i++] != 0xf0 + (c >> 18)) return -1; + if (s1[i++] != 0x80 + ((c >> 12) & 0x3f)) return -1; + if (s1[i++] != 0x80 + ((c >> 6) & 0x3f)) return -1; + if (s1[i++] != 0x80 + ((c ) & 0x3f)) return -1; + s2 += 2; // plus another 2 below + len2 -= 2; + } else if (ch >= 0xdc00 && ch < 0xe000) { + return -1; + } else { + if (i+2 >= len1) return -1; + if (s1[i++] != 0xe0 + (ch >> 12)) return -1; + if (s1[i++] != 0x80 + ((ch >> 6) & 0x3f)) return -1; + if (s1[i++] != 0x80 + ((ch ) & 0x3f)) return -1; + } + s2 += 2; + len2 -= 2; + } + return i; +} + +STBTT_DEF int stbtt_CompareUTF8toUTF16_bigendian(const char *s1, int len1, const char *s2, int len2) +{ + return len1 == stbtt__CompareUTF8toUTF16_bigendian_prefix((const stbtt_uint8*) s1, len1, (const stbtt_uint8*) s2, len2); +} + +// returns results in whatever encoding you request... but note that 2-byte encodings +// will be BIG-ENDIAN... use stbtt_CompareUTF8toUTF16_bigendian() to compare +STBTT_DEF const char *stbtt_GetFontNameString(const stbtt_fontinfo *font, int *length, int platformID, int encodingID, int languageID, int nameID) +{ + stbtt_int32 i,count,stringOffset; + stbtt_uint8 *fc = font->data; + stbtt_uint32 offset = font->fontstart; + stbtt_uint32 nm = stbtt__find_table(fc, offset, "name"); + if (!nm) return NULL; + + count = ttUSHORT(fc+nm+2); + stringOffset = nm + ttUSHORT(fc+nm+4); + for (i=0; i < count; ++i) { + stbtt_uint32 loc = nm + 6 + 12 * i; + if (platformID == ttUSHORT(fc+loc+0) && encodingID == ttUSHORT(fc+loc+2) + && languageID == ttUSHORT(fc+loc+4) && nameID == ttUSHORT(fc+loc+6)) { + *length = ttUSHORT(fc+loc+8); + return (const char *) (fc+stringOffset+ttUSHORT(fc+loc+10)); + } + } + return NULL; +} + +static int stbtt__matchpair(stbtt_uint8 *fc, stbtt_uint32 nm, stbtt_uint8 *name, stbtt_int32 nlen, stbtt_int32 target_id, stbtt_int32 next_id) +{ + stbtt_int32 i; + stbtt_int32 count = ttUSHORT(fc+nm+2); + stbtt_int32 stringOffset = nm + ttUSHORT(fc+nm+4); + + for (i=0; i < count; ++i) { + stbtt_uint32 loc = nm + 6 + 12 * i; + stbtt_int32 id = ttUSHORT(fc+loc+6); + if (id == target_id) { + // find the encoding + stbtt_int32 platform = ttUSHORT(fc+loc+0), encoding = ttUSHORT(fc+loc+2), language = ttUSHORT(fc+loc+4); + + // is this a Unicode encoding? + if (platform == 0 || (platform == 3 && encoding == 1) || (platform == 3 && encoding == 10)) { + stbtt_int32 slen = ttUSHORT(fc+loc+8); + stbtt_int32 off = ttUSHORT(fc+loc+10); + + // check if there's a prefix match + stbtt_int32 matchlen = stbtt__CompareUTF8toUTF16_bigendian_prefix(name, nlen, fc+stringOffset+off,slen); + if (matchlen >= 0) { + // check for target_id+1 immediately following, with same encoding & language + if (i+1 < count && ttUSHORT(fc+loc+12+6) == next_id && ttUSHORT(fc+loc+12) == platform && ttUSHORT(fc+loc+12+2) == encoding && ttUSHORT(fc+loc+12+4) == language) { + slen = ttUSHORT(fc+loc+12+8); + off = ttUSHORT(fc+loc+12+10); + if (slen == 0) { + if (matchlen == nlen) + return 1; + } else if (matchlen < nlen && name[matchlen] == ' ') { + ++matchlen; + if (stbtt_CompareUTF8toUTF16_bigendian((char*) (name+matchlen), nlen-matchlen, (char*)(fc+stringOffset+off),slen)) + return 1; + } + } else { + // if nothing immediately following + if (matchlen == nlen) + return 1; + } + } + } + + // @TODO handle other encodings + } + } + return 0; +} + +static int stbtt__matches(stbtt_uint8 *fc, stbtt_uint32 offset, stbtt_uint8 *name, stbtt_int32 flags) +{ + stbtt_int32 nlen = (stbtt_int32) STBTT_strlen((char *) name); + stbtt_uint32 nm,hd; + if (!stbtt__isfont(fc+offset)) return 0; + + // check italics/bold/underline flags in macStyle... + if (flags) { + hd = stbtt__find_table(fc, offset, "head"); + if ((ttUSHORT(fc+hd+44) & 7) != (flags & 7)) return 0; + } + + nm = stbtt__find_table(fc, offset, "name"); + if (!nm) return 0; + + if (flags) { + // if we checked the macStyle flags, then just check the family and ignore the subfamily + if (stbtt__matchpair(fc, nm, name, nlen, 16, -1)) return 1; + if (stbtt__matchpair(fc, nm, name, nlen, 1, -1)) return 1; + if (stbtt__matchpair(fc, nm, name, nlen, 3, -1)) return 1; + } else { + if (stbtt__matchpair(fc, nm, name, nlen, 16, 17)) return 1; + if (stbtt__matchpair(fc, nm, name, nlen, 1, 2)) return 1; + if (stbtt__matchpair(fc, nm, name, nlen, 3, -1)) return 1; + } + + return 0; +} + +STBTT_DEF int stbtt_FindMatchingFont(const unsigned char *font_collection, const char *name_utf8, stbtt_int32 flags) +{ + stbtt_int32 i; + for (i=0;;++i) { + stbtt_int32 off = stbtt_GetFontOffsetForIndex(font_collection, i); + if (off < 0) return off; + if (stbtt__matches((stbtt_uint8 *) font_collection, off, (stbtt_uint8*) name_utf8, flags)) + return off; + } +} + +#endif // STB_TRUETYPE_IMPLEMENTATION + + +// FULL VERSION HISTORY +// +// 1.09 (2016-01-16) warning fix; avoid crash on outofmem; use alloc userdata for PackFontRanges +// 1.08 (2015-09-13) document stbtt_Rasterize(); fixes for vertical & horizontal edges +// 1.07 (2015-08-01) allow PackFontRanges to accept arrays of sparse codepoints; +// allow PackFontRanges to pack and render in separate phases; +// fix stbtt_GetFontOFfsetForIndex (never worked for non-0 input?); +// fixed an assert() bug in the new rasterizer +// replace assert() with STBTT_assert() in new rasterizer +// 1.06 (2015-07-14) performance improvements (~35% faster on x86 and x64 on test machine) +// also more precise AA rasterizer, except if shapes overlap +// remove need for STBTT_sort +// 1.05 (2015-04-15) fix misplaced definitions for STBTT_STATIC +// 1.04 (2015-04-15) typo in example +// 1.03 (2015-04-12) STBTT_STATIC, fix memory leak in new packing, various fixes +// 1.02 (2014-12-10) fix various warnings & compile issues w/ stb_rect_pack, C++ +// 1.01 (2014-12-08) fix subpixel position when oversampling to exactly match +// non-oversampled; STBTT_POINT_SIZE for packed case only +// 1.00 (2014-12-06) add new PackBegin etc. API, w/ support for oversampling +// 0.99 (2014-09-18) fix multiple bugs with subpixel rendering (ryg) +// 0.9 (2014-08-07) support certain mac/iOS fonts without an MS platformID +// 0.8b (2014-07-07) fix a warning +// 0.8 (2014-05-25) fix a few more warnings +// 0.7 (2013-09-25) bugfix: subpixel glyph bug fixed in 0.5 had come back +// 0.6c (2012-07-24) improve documentation +// 0.6b (2012-07-20) fix a few more warnings +// 0.6 (2012-07-17) fix warnings; added stbtt_ScaleForMappingEmToPixels, +// stbtt_GetFontBoundingBox, stbtt_IsGlyphEmpty +// 0.5 (2011-12-09) bugfixes: +// subpixel glyph renderer computed wrong bounding box +// first vertex of shape can be off-curve (FreeSans) +// 0.4b (2011-12-03) fixed an error in the font baking example +// 0.4 (2011-12-01) kerning, subpixel rendering (tor) +// bugfixes for: +// codepoint-to-glyph conversion using table fmt=12 +// codepoint-to-glyph conversion using table fmt=4 +// stbtt_GetBakedQuad with non-square texture (Zer) +// updated Hello World! sample to use kerning and subpixel +// fixed some warnings +// 0.3 (2009-06-24) cmap fmt=12, compound shapes (MM) +// userdata, malloc-from-userdata, non-zero fill (stb) +// 0.2 (2009-03-11) Fix unsigned/signed char warnings +// 0.1 (2009-03-09) First public release +// diff --git a/phonelibs/openblas/libopenblas.so b/phonelibs/openblas/libopenblas.so new file mode 120000 index 00000000000000..7a792bc9071885 --- /dev/null +++ b/phonelibs/openblas/libopenblas.so @@ -0,0 +1 @@ +libopenblas_armv8p-r0.2.19.so \ No newline at end of file diff --git a/phonelibs/openblas/libopenblas_armv8p-r0.2.19.so b/phonelibs/openblas/libopenblas_armv8p-r0.2.19.so new file mode 100755 index 00000000000000..ace58c8a13122f Binary files /dev/null and b/phonelibs/openblas/libopenblas_armv8p-r0.2.19.so differ diff --git a/phonelibs/opencl/include/CL/cl.h b/phonelibs/opencl/include/CL/cl.h new file mode 100644 index 00000000000000..0086319f5faf1b --- /dev/null +++ b/phonelibs/opencl/include/CL/cl.h @@ -0,0 +1,1452 @@ +/******************************************************************************* + * Copyright (c) 2008-2015 The Khronos Group Inc. + * + * Permission is hereby granted, free of charge, to any person obtaining a + * copy of this software and/or associated documentation files (the + * "Materials"), to deal in the Materials without restriction, including + * without limitation the rights to use, copy, modify, merge, publish, + * distribute, sublicense, and/or sell copies of the Materials, and to + * permit persons to whom the Materials are furnished to do so, subject to + * the following conditions: + * + * The above copyright notice and this permission notice shall be included + * in all copies or substantial portions of the Materials. + * + * MODIFICATIONS TO THIS FILE MAY MEAN IT NO LONGER ACCURATELY REFLECTS + * KHRONOS STANDARDS. THE UNMODIFIED, NORMATIVE VERSIONS OF KHRONOS + * SPECIFICATIONS AND HEADER INFORMATION ARE LOCATED AT + * https://www.khronos.org/registry/ + * + * THE MATERIALS ARE PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, + * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. + * IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY + * CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, + * TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE + * MATERIALS OR THE USE OR OTHER DEALINGS IN THE MATERIALS. + ******************************************************************************/ + +#ifndef __OPENCL_CL_H +#define __OPENCL_CL_H + +#ifdef __APPLE__ +#include +#else +#include +#endif + +#ifdef __cplusplus +extern "C" { +#endif + +/******************************************************************************/ + +typedef struct _cl_platform_id * cl_platform_id; +typedef struct _cl_device_id * cl_device_id; +typedef struct _cl_context * cl_context; +typedef struct _cl_command_queue * cl_command_queue; +typedef struct _cl_mem * cl_mem; +typedef struct _cl_program * cl_program; +typedef struct _cl_kernel * cl_kernel; +typedef struct _cl_event * cl_event; +typedef struct _cl_sampler * cl_sampler; + +typedef cl_uint cl_bool; /* WARNING! Unlike cl_ types in cl_platform.h, cl_bool is not guaranteed to be the same size as the bool in kernels. */ +typedef cl_ulong cl_bitfield; +typedef cl_bitfield cl_device_type; +typedef cl_uint cl_platform_info; +typedef cl_uint cl_device_info; +typedef cl_bitfield cl_device_fp_config; +typedef cl_uint cl_device_mem_cache_type; +typedef cl_uint cl_device_local_mem_type; +typedef cl_bitfield cl_device_exec_capabilities; +typedef cl_bitfield cl_device_svm_capabilities; +typedef cl_bitfield cl_command_queue_properties; +typedef intptr_t cl_device_partition_property; +typedef cl_bitfield cl_device_affinity_domain; + +typedef intptr_t cl_context_properties; +typedef cl_uint cl_context_info; +typedef cl_bitfield cl_queue_properties; +typedef cl_uint cl_command_queue_info; +typedef cl_uint cl_channel_order; +typedef cl_uint cl_channel_type; +typedef cl_bitfield cl_mem_flags; +typedef cl_bitfield cl_svm_mem_flags; +typedef cl_uint cl_mem_object_type; +typedef cl_uint cl_mem_info; +typedef cl_bitfield cl_mem_migration_flags; +typedef cl_uint cl_image_info; +typedef cl_uint cl_buffer_create_type; +typedef cl_uint cl_addressing_mode; +typedef cl_uint cl_filter_mode; +typedef cl_uint cl_sampler_info; +typedef cl_bitfield cl_map_flags; +typedef intptr_t cl_pipe_properties; +typedef cl_uint cl_pipe_info; +typedef cl_uint cl_program_info; +typedef cl_uint cl_program_build_info; +typedef cl_uint cl_program_binary_type; +typedef cl_int cl_build_status; +typedef cl_uint cl_kernel_info; +typedef cl_uint cl_kernel_arg_info; +typedef cl_uint cl_kernel_arg_address_qualifier; +typedef cl_uint cl_kernel_arg_access_qualifier; +typedef cl_bitfield cl_kernel_arg_type_qualifier; +typedef cl_uint cl_kernel_work_group_info; +typedef cl_uint cl_kernel_sub_group_info; +typedef cl_uint cl_event_info; +typedef cl_uint cl_command_type; +typedef cl_uint cl_profiling_info; +typedef cl_bitfield cl_sampler_properties; +typedef cl_uint cl_kernel_exec_info; + +typedef struct _cl_image_format { + cl_channel_order image_channel_order; + cl_channel_type image_channel_data_type; +} cl_image_format; + +typedef struct _cl_image_desc { + cl_mem_object_type image_type; + size_t image_width; + size_t image_height; + size_t image_depth; + size_t image_array_size; + size_t image_row_pitch; + size_t image_slice_pitch; + cl_uint num_mip_levels; + cl_uint num_samples; +#ifdef __GNUC__ + __extension__ /* Prevents warnings about anonymous union in -pedantic builds */ +#endif + union { + cl_mem buffer; + cl_mem mem_object; + }; +} cl_image_desc; + +typedef struct _cl_buffer_region { + size_t origin; + size_t size; +} cl_buffer_region; + + +/******************************************************************************/ + +/* Error Codes */ +#define CL_SUCCESS 0 +#define CL_DEVICE_NOT_FOUND -1 +#define CL_DEVICE_NOT_AVAILABLE -2 +#define CL_COMPILER_NOT_AVAILABLE -3 +#define CL_MEM_OBJECT_ALLOCATION_FAILURE -4 +#define CL_OUT_OF_RESOURCES -5 +#define CL_OUT_OF_HOST_MEMORY -6 +#define CL_PROFILING_INFO_NOT_AVAILABLE -7 +#define CL_MEM_COPY_OVERLAP -8 +#define CL_IMAGE_FORMAT_MISMATCH -9 +#define CL_IMAGE_FORMAT_NOT_SUPPORTED -10 +#define CL_BUILD_PROGRAM_FAILURE -11 +#define CL_MAP_FAILURE -12 +#define CL_MISALIGNED_SUB_BUFFER_OFFSET -13 +#define CL_EXEC_STATUS_ERROR_FOR_EVENTS_IN_WAIT_LIST -14 +#define CL_COMPILE_PROGRAM_FAILURE -15 +#define CL_LINKER_NOT_AVAILABLE -16 +#define CL_LINK_PROGRAM_FAILURE -17 +#define CL_DEVICE_PARTITION_FAILED -18 +#define CL_KERNEL_ARG_INFO_NOT_AVAILABLE -19 + +#define CL_INVALID_VALUE -30 +#define CL_INVALID_DEVICE_TYPE -31 +#define CL_INVALID_PLATFORM -32 +#define CL_INVALID_DEVICE -33 +#define CL_INVALID_CONTEXT -34 +#define CL_INVALID_QUEUE_PROPERTIES -35 +#define CL_INVALID_COMMAND_QUEUE -36 +#define CL_INVALID_HOST_PTR -37 +#define CL_INVALID_MEM_OBJECT -38 +#define CL_INVALID_IMAGE_FORMAT_DESCRIPTOR -39 +#define CL_INVALID_IMAGE_SIZE -40 +#define CL_INVALID_SAMPLER -41 +#define CL_INVALID_BINARY -42 +#define CL_INVALID_BUILD_OPTIONS -43 +#define CL_INVALID_PROGRAM -44 +#define CL_INVALID_PROGRAM_EXECUTABLE -45 +#define CL_INVALID_KERNEL_NAME -46 +#define CL_INVALID_KERNEL_DEFINITION -47 +#define CL_INVALID_KERNEL -48 +#define CL_INVALID_ARG_INDEX -49 +#define CL_INVALID_ARG_VALUE -50 +#define CL_INVALID_ARG_SIZE -51 +#define CL_INVALID_KERNEL_ARGS -52 +#define CL_INVALID_WORK_DIMENSION -53 +#define CL_INVALID_WORK_GROUP_SIZE -54 +#define CL_INVALID_WORK_ITEM_SIZE -55 +#define CL_INVALID_GLOBAL_OFFSET -56 +#define CL_INVALID_EVENT_WAIT_LIST -57 +#define CL_INVALID_EVENT -58 +#define CL_INVALID_OPERATION -59 +#define CL_INVALID_GL_OBJECT -60 +#define CL_INVALID_BUFFER_SIZE -61 +#define CL_INVALID_MIP_LEVEL -62 +#define CL_INVALID_GLOBAL_WORK_SIZE -63 +#define CL_INVALID_PROPERTY -64 +#define CL_INVALID_IMAGE_DESCRIPTOR -65 +#define CL_INVALID_COMPILER_OPTIONS -66 +#define CL_INVALID_LINKER_OPTIONS -67 +#define CL_INVALID_DEVICE_PARTITION_COUNT -68 +#define CL_INVALID_PIPE_SIZE -69 +#define CL_INVALID_DEVICE_QUEUE -70 + +/* OpenCL Version */ +#define CL_VERSION_1_0 1 +#define CL_VERSION_1_1 1 +#define CL_VERSION_1_2 1 +#define CL_VERSION_2_0 1 +#define CL_VERSION_2_1 1 + +/* cl_bool */ +#define CL_FALSE 0 +#define CL_TRUE 1 +#define CL_BLOCKING CL_TRUE +#define CL_NON_BLOCKING CL_FALSE + +/* cl_platform_info */ +#define CL_PLATFORM_PROFILE 0x0900 +#define CL_PLATFORM_VERSION 0x0901 +#define CL_PLATFORM_NAME 0x0902 +#define CL_PLATFORM_VENDOR 0x0903 +#define CL_PLATFORM_EXTENSIONS 0x0904 +#define CL_PLATFORM_HOST_TIMER_RESOLUTION 0x0905 + +/* cl_device_type - bitfield */ +#define CL_DEVICE_TYPE_DEFAULT (1 << 0) +#define CL_DEVICE_TYPE_CPU (1 << 1) +#define CL_DEVICE_TYPE_GPU (1 << 2) +#define CL_DEVICE_TYPE_ACCELERATOR (1 << 3) +#define CL_DEVICE_TYPE_CUSTOM (1 << 4) +#define CL_DEVICE_TYPE_ALL 0xFFFFFFFF + +/* cl_device_info */ +#define CL_DEVICE_TYPE 0x1000 +#define CL_DEVICE_VENDOR_ID 0x1001 +#define CL_DEVICE_MAX_COMPUTE_UNITS 0x1002 +#define CL_DEVICE_MAX_WORK_ITEM_DIMENSIONS 0x1003 +#define CL_DEVICE_MAX_WORK_GROUP_SIZE 0x1004 +#define CL_DEVICE_MAX_WORK_ITEM_SIZES 0x1005 +#define CL_DEVICE_PREFERRED_VECTOR_WIDTH_CHAR 0x1006 +#define CL_DEVICE_PREFERRED_VECTOR_WIDTH_SHORT 0x1007 +#define CL_DEVICE_PREFERRED_VECTOR_WIDTH_INT 0x1008 +#define CL_DEVICE_PREFERRED_VECTOR_WIDTH_LONG 0x1009 +#define CL_DEVICE_PREFERRED_VECTOR_WIDTH_FLOAT 0x100A +#define CL_DEVICE_PREFERRED_VECTOR_WIDTH_DOUBLE 0x100B +#define CL_DEVICE_MAX_CLOCK_FREQUENCY 0x100C +#define CL_DEVICE_ADDRESS_BITS 0x100D +#define CL_DEVICE_MAX_READ_IMAGE_ARGS 0x100E +#define CL_DEVICE_MAX_WRITE_IMAGE_ARGS 0x100F +#define CL_DEVICE_MAX_MEM_ALLOC_SIZE 0x1010 +#define CL_DEVICE_IMAGE2D_MAX_WIDTH 0x1011 +#define CL_DEVICE_IMAGE2D_MAX_HEIGHT 0x1012 +#define CL_DEVICE_IMAGE3D_MAX_WIDTH 0x1013 +#define CL_DEVICE_IMAGE3D_MAX_HEIGHT 0x1014 +#define CL_DEVICE_IMAGE3D_MAX_DEPTH 0x1015 +#define CL_DEVICE_IMAGE_SUPPORT 0x1016 +#define CL_DEVICE_MAX_PARAMETER_SIZE 0x1017 +#define CL_DEVICE_MAX_SAMPLERS 0x1018 +#define CL_DEVICE_MEM_BASE_ADDR_ALIGN 0x1019 +#define CL_DEVICE_MIN_DATA_TYPE_ALIGN_SIZE 0x101A +#define CL_DEVICE_SINGLE_FP_CONFIG 0x101B +#define CL_DEVICE_GLOBAL_MEM_CACHE_TYPE 0x101C +#define CL_DEVICE_GLOBAL_MEM_CACHELINE_SIZE 0x101D +#define CL_DEVICE_GLOBAL_MEM_CACHE_SIZE 0x101E +#define CL_DEVICE_GLOBAL_MEM_SIZE 0x101F +#define CL_DEVICE_MAX_CONSTANT_BUFFER_SIZE 0x1020 +#define CL_DEVICE_MAX_CONSTANT_ARGS 0x1021 +#define CL_DEVICE_LOCAL_MEM_TYPE 0x1022 +#define CL_DEVICE_LOCAL_MEM_SIZE 0x1023 +#define CL_DEVICE_ERROR_CORRECTION_SUPPORT 0x1024 +#define CL_DEVICE_PROFILING_TIMER_RESOLUTION 0x1025 +#define CL_DEVICE_ENDIAN_LITTLE 0x1026 +#define CL_DEVICE_AVAILABLE 0x1027 +#define CL_DEVICE_COMPILER_AVAILABLE 0x1028 +#define CL_DEVICE_EXECUTION_CAPABILITIES 0x1029 +#define CL_DEVICE_QUEUE_PROPERTIES 0x102A /* deprecated */ +#define CL_DEVICE_QUEUE_ON_HOST_PROPERTIES 0x102A +#define CL_DEVICE_NAME 0x102B +#define CL_DEVICE_VENDOR 0x102C +#define CL_DRIVER_VERSION 0x102D +#define CL_DEVICE_PROFILE 0x102E +#define CL_DEVICE_VERSION 0x102F +#define CL_DEVICE_EXTENSIONS 0x1030 +#define CL_DEVICE_PLATFORM 0x1031 +#define CL_DEVICE_DOUBLE_FP_CONFIG 0x1032 +/* 0x1033 reserved for CL_DEVICE_HALF_FP_CONFIG */ +#define CL_DEVICE_PREFERRED_VECTOR_WIDTH_HALF 0x1034 +#define CL_DEVICE_HOST_UNIFIED_MEMORY 0x1035 /* deprecated */ +#define CL_DEVICE_NATIVE_VECTOR_WIDTH_CHAR 0x1036 +#define CL_DEVICE_NATIVE_VECTOR_WIDTH_SHORT 0x1037 +#define CL_DEVICE_NATIVE_VECTOR_WIDTH_INT 0x1038 +#define CL_DEVICE_NATIVE_VECTOR_WIDTH_LONG 0x1039 +#define CL_DEVICE_NATIVE_VECTOR_WIDTH_FLOAT 0x103A +#define CL_DEVICE_NATIVE_VECTOR_WIDTH_DOUBLE 0x103B +#define CL_DEVICE_NATIVE_VECTOR_WIDTH_HALF 0x103C +#define CL_DEVICE_OPENCL_C_VERSION 0x103D +#define CL_DEVICE_LINKER_AVAILABLE 0x103E +#define CL_DEVICE_BUILT_IN_KERNELS 0x103F +#define CL_DEVICE_IMAGE_MAX_BUFFER_SIZE 0x1040 +#define CL_DEVICE_IMAGE_MAX_ARRAY_SIZE 0x1041 +#define CL_DEVICE_PARENT_DEVICE 0x1042 +#define CL_DEVICE_PARTITION_MAX_SUB_DEVICES 0x1043 +#define CL_DEVICE_PARTITION_PROPERTIES 0x1044 +#define CL_DEVICE_PARTITION_AFFINITY_DOMAIN 0x1045 +#define CL_DEVICE_PARTITION_TYPE 0x1046 +#define CL_DEVICE_REFERENCE_COUNT 0x1047 +#define CL_DEVICE_PREFERRED_INTEROP_USER_SYNC 0x1048 +#define CL_DEVICE_PRINTF_BUFFER_SIZE 0x1049 +#define CL_DEVICE_IMAGE_PITCH_ALIGNMENT 0x104A +#define CL_DEVICE_IMAGE_BASE_ADDRESS_ALIGNMENT 0x104B +#define CL_DEVICE_MAX_READ_WRITE_IMAGE_ARGS 0x104C +#define CL_DEVICE_MAX_GLOBAL_VARIABLE_SIZE 0x104D +#define CL_DEVICE_QUEUE_ON_DEVICE_PROPERTIES 0x104E +#define CL_DEVICE_QUEUE_ON_DEVICE_PREFERRED_SIZE 0x104F +#define CL_DEVICE_QUEUE_ON_DEVICE_MAX_SIZE 0x1050 +#define CL_DEVICE_MAX_ON_DEVICE_QUEUES 0x1051 +#define CL_DEVICE_MAX_ON_DEVICE_EVENTS 0x1052 +#define CL_DEVICE_SVM_CAPABILITIES 0x1053 +#define CL_DEVICE_GLOBAL_VARIABLE_PREFERRED_TOTAL_SIZE 0x1054 +#define CL_DEVICE_MAX_PIPE_ARGS 0x1055 +#define CL_DEVICE_PIPE_MAX_ACTIVE_RESERVATIONS 0x1056 +#define CL_DEVICE_PIPE_MAX_PACKET_SIZE 0x1057 +#define CL_DEVICE_PREFERRED_PLATFORM_ATOMIC_ALIGNMENT 0x1058 +#define CL_DEVICE_PREFERRED_GLOBAL_ATOMIC_ALIGNMENT 0x1059 +#define CL_DEVICE_PREFERRED_LOCAL_ATOMIC_ALIGNMENT 0x105A +#define CL_DEVICE_IL_VERSION 0x105B +#define CL_DEVICE_MAX_NUM_SUB_GROUPS 0x105C +#define CL_DEVICE_SUB_GROUP_INDEPENDENT_FORWARD_PROGRESS 0x105D + +/* cl_device_fp_config - bitfield */ +#define CL_FP_DENORM (1 << 0) +#define CL_FP_INF_NAN (1 << 1) +#define CL_FP_ROUND_TO_NEAREST (1 << 2) +#define CL_FP_ROUND_TO_ZERO (1 << 3) +#define CL_FP_ROUND_TO_INF (1 << 4) +#define CL_FP_FMA (1 << 5) +#define CL_FP_SOFT_FLOAT (1 << 6) +#define CL_FP_CORRECTLY_ROUNDED_DIVIDE_SQRT (1 << 7) + +/* cl_device_mem_cache_type */ +#define CL_NONE 0x0 +#define CL_READ_ONLY_CACHE 0x1 +#define CL_READ_WRITE_CACHE 0x2 + +/* cl_device_local_mem_type */ +#define CL_LOCAL 0x1 +#define CL_GLOBAL 0x2 + +/* cl_device_exec_capabilities - bitfield */ +#define CL_EXEC_KERNEL (1 << 0) +#define CL_EXEC_NATIVE_KERNEL (1 << 1) + +/* cl_command_queue_properties - bitfield */ +#define CL_QUEUE_OUT_OF_ORDER_EXEC_MODE_ENABLE (1 << 0) +#define CL_QUEUE_PROFILING_ENABLE (1 << 1) +#define CL_QUEUE_ON_DEVICE (1 << 2) +#define CL_QUEUE_ON_DEVICE_DEFAULT (1 << 3) + +/* cl_context_info */ +#define CL_CONTEXT_REFERENCE_COUNT 0x1080 +#define CL_CONTEXT_DEVICES 0x1081 +#define CL_CONTEXT_PROPERTIES 0x1082 +#define CL_CONTEXT_NUM_DEVICES 0x1083 + +/* cl_context_properties */ +#define CL_CONTEXT_PLATFORM 0x1084 +#define CL_CONTEXT_INTEROP_USER_SYNC 0x1085 + +/* cl_device_partition_property */ +#define CL_DEVICE_PARTITION_EQUALLY 0x1086 +#define CL_DEVICE_PARTITION_BY_COUNTS 0x1087 +#define CL_DEVICE_PARTITION_BY_COUNTS_LIST_END 0x0 +#define CL_DEVICE_PARTITION_BY_AFFINITY_DOMAIN 0x1088 + +/* cl_device_affinity_domain */ +#define CL_DEVICE_AFFINITY_DOMAIN_NUMA (1 << 0) +#define CL_DEVICE_AFFINITY_DOMAIN_L4_CACHE (1 << 1) +#define CL_DEVICE_AFFINITY_DOMAIN_L3_CACHE (1 << 2) +#define CL_DEVICE_AFFINITY_DOMAIN_L2_CACHE (1 << 3) +#define CL_DEVICE_AFFINITY_DOMAIN_L1_CACHE (1 << 4) +#define CL_DEVICE_AFFINITY_DOMAIN_NEXT_PARTITIONABLE (1 << 5) + +/* cl_device_svm_capabilities */ +#define CL_DEVICE_SVM_COARSE_GRAIN_BUFFER (1 << 0) +#define CL_DEVICE_SVM_FINE_GRAIN_BUFFER (1 << 1) +#define CL_DEVICE_SVM_FINE_GRAIN_SYSTEM (1 << 2) +#define CL_DEVICE_SVM_ATOMICS (1 << 3) + +/* cl_command_queue_info */ +#define CL_QUEUE_CONTEXT 0x1090 +#define CL_QUEUE_DEVICE 0x1091 +#define CL_QUEUE_REFERENCE_COUNT 0x1092 +#define CL_QUEUE_PROPERTIES 0x1093 +#define CL_QUEUE_SIZE 0x1094 +#define CL_QUEUE_DEVICE_DEFAULT 0x1095 + +/* cl_mem_flags and cl_svm_mem_flags - bitfield */ +#define CL_MEM_READ_WRITE (1 << 0) +#define CL_MEM_WRITE_ONLY (1 << 1) +#define CL_MEM_READ_ONLY (1 << 2) +#define CL_MEM_USE_HOST_PTR (1 << 3) +#define CL_MEM_ALLOC_HOST_PTR (1 << 4) +#define CL_MEM_COPY_HOST_PTR (1 << 5) +/* reserved (1 << 6) */ +#define CL_MEM_HOST_WRITE_ONLY (1 << 7) +#define CL_MEM_HOST_READ_ONLY (1 << 8) +#define CL_MEM_HOST_NO_ACCESS (1 << 9) +#define CL_MEM_SVM_FINE_GRAIN_BUFFER (1 << 10) /* used by cl_svm_mem_flags only */ +#define CL_MEM_SVM_ATOMICS (1 << 11) /* used by cl_svm_mem_flags only */ +#define CL_MEM_KERNEL_READ_AND_WRITE (1 << 12) + +/* cl_mem_migration_flags - bitfield */ +#define CL_MIGRATE_MEM_OBJECT_HOST (1 << 0) +#define CL_MIGRATE_MEM_OBJECT_CONTENT_UNDEFINED (1 << 1) + +/* cl_channel_order */ +#define CL_R 0x10B0 +#define CL_A 0x10B1 +#define CL_RG 0x10B2 +#define CL_RA 0x10B3 +#define CL_RGB 0x10B4 +#define CL_RGBA 0x10B5 +#define CL_BGRA 0x10B6 +#define CL_ARGB 0x10B7 +#define CL_INTENSITY 0x10B8 +#define CL_LUMINANCE 0x10B9 +#define CL_Rx 0x10BA +#define CL_RGx 0x10BB +#define CL_RGBx 0x10BC +#define CL_DEPTH 0x10BD +#define CL_DEPTH_STENCIL 0x10BE +#define CL_sRGB 0x10BF +#define CL_sRGBx 0x10C0 +#define CL_sRGBA 0x10C1 +#define CL_sBGRA 0x10C2 +#define CL_ABGR 0x10C3 + +/* cl_channel_type */ +#define CL_SNORM_INT8 0x10D0 +#define CL_SNORM_INT16 0x10D1 +#define CL_UNORM_INT8 0x10D2 +#define CL_UNORM_INT16 0x10D3 +#define CL_UNORM_SHORT_565 0x10D4 +#define CL_UNORM_SHORT_555 0x10D5 +#define CL_UNORM_INT_101010 0x10D6 +#define CL_SIGNED_INT8 0x10D7 +#define CL_SIGNED_INT16 0x10D8 +#define CL_SIGNED_INT32 0x10D9 +#define CL_UNSIGNED_INT8 0x10DA +#define CL_UNSIGNED_INT16 0x10DB +#define CL_UNSIGNED_INT32 0x10DC +#define CL_HALF_FLOAT 0x10DD +#define CL_FLOAT 0x10DE +#define CL_UNORM_INT24 0x10DF +#define CL_UNORM_INT_101010_2 0x10E0 + +/* cl_mem_object_type */ +#define CL_MEM_OBJECT_BUFFER 0x10F0 +#define CL_MEM_OBJECT_IMAGE2D 0x10F1 +#define CL_MEM_OBJECT_IMAGE3D 0x10F2 +#define CL_MEM_OBJECT_IMAGE2D_ARRAY 0x10F3 +#define CL_MEM_OBJECT_IMAGE1D 0x10F4 +#define CL_MEM_OBJECT_IMAGE1D_ARRAY 0x10F5 +#define CL_MEM_OBJECT_IMAGE1D_BUFFER 0x10F6 +#define CL_MEM_OBJECT_PIPE 0x10F7 + +/* cl_mem_info */ +#define CL_MEM_TYPE 0x1100 +#define CL_MEM_FLAGS 0x1101 +#define CL_MEM_SIZE 0x1102 +#define CL_MEM_HOST_PTR 0x1103 +#define CL_MEM_MAP_COUNT 0x1104 +#define CL_MEM_REFERENCE_COUNT 0x1105 +#define CL_MEM_CONTEXT 0x1106 +#define CL_MEM_ASSOCIATED_MEMOBJECT 0x1107 +#define CL_MEM_OFFSET 0x1108 +#define CL_MEM_USES_SVM_POINTER 0x1109 + +/* cl_image_info */ +#define CL_IMAGE_FORMAT 0x1110 +#define CL_IMAGE_ELEMENT_SIZE 0x1111 +#define CL_IMAGE_ROW_PITCH 0x1112 +#define CL_IMAGE_SLICE_PITCH 0x1113 +#define CL_IMAGE_WIDTH 0x1114 +#define CL_IMAGE_HEIGHT 0x1115 +#define CL_IMAGE_DEPTH 0x1116 +#define CL_IMAGE_ARRAY_SIZE 0x1117 +#define CL_IMAGE_BUFFER 0x1118 +#define CL_IMAGE_NUM_MIP_LEVELS 0x1119 +#define CL_IMAGE_NUM_SAMPLES 0x111A + +/* cl_pipe_info */ +#define CL_PIPE_PACKET_SIZE 0x1120 +#define CL_PIPE_MAX_PACKETS 0x1121 + +/* cl_addressing_mode */ +#define CL_ADDRESS_NONE 0x1130 +#define CL_ADDRESS_CLAMP_TO_EDGE 0x1131 +#define CL_ADDRESS_CLAMP 0x1132 +#define CL_ADDRESS_REPEAT 0x1133 +#define CL_ADDRESS_MIRRORED_REPEAT 0x1134 + +/* cl_filter_mode */ +#define CL_FILTER_NEAREST 0x1140 +#define CL_FILTER_LINEAR 0x1141 + +/* cl_sampler_info */ +#define CL_SAMPLER_REFERENCE_COUNT 0x1150 +#define CL_SAMPLER_CONTEXT 0x1151 +#define CL_SAMPLER_NORMALIZED_COORDS 0x1152 +#define CL_SAMPLER_ADDRESSING_MODE 0x1153 +#define CL_SAMPLER_FILTER_MODE 0x1154 +#define CL_SAMPLER_MIP_FILTER_MODE 0x1155 +#define CL_SAMPLER_LOD_MIN 0x1156 +#define CL_SAMPLER_LOD_MAX 0x1157 + +/* cl_map_flags - bitfield */ +#define CL_MAP_READ (1 << 0) +#define CL_MAP_WRITE (1 << 1) +#define CL_MAP_WRITE_INVALIDATE_REGION (1 << 2) + +/* cl_program_info */ +#define CL_PROGRAM_REFERENCE_COUNT 0x1160 +#define CL_PROGRAM_CONTEXT 0x1161 +#define CL_PROGRAM_NUM_DEVICES 0x1162 +#define CL_PROGRAM_DEVICES 0x1163 +#define CL_PROGRAM_SOURCE 0x1164 +#define CL_PROGRAM_BINARY_SIZES 0x1165 +#define CL_PROGRAM_BINARIES 0x1166 +#define CL_PROGRAM_NUM_KERNELS 0x1167 +#define CL_PROGRAM_KERNEL_NAMES 0x1168 +#define CL_PROGRAM_IL 0x1169 + +/* cl_program_build_info */ +#define CL_PROGRAM_BUILD_STATUS 0x1181 +#define CL_PROGRAM_BUILD_OPTIONS 0x1182 +#define CL_PROGRAM_BUILD_LOG 0x1183 +#define CL_PROGRAM_BINARY_TYPE 0x1184 +#define CL_PROGRAM_BUILD_GLOBAL_VARIABLE_TOTAL_SIZE 0x1185 + +/* cl_program_binary_type */ +#define CL_PROGRAM_BINARY_TYPE_NONE 0x0 +#define CL_PROGRAM_BINARY_TYPE_COMPILED_OBJECT 0x1 +#define CL_PROGRAM_BINARY_TYPE_LIBRARY 0x2 +#define CL_PROGRAM_BINARY_TYPE_EXECUTABLE 0x4 + +/* cl_build_status */ +#define CL_BUILD_SUCCESS 0 +#define CL_BUILD_NONE -1 +#define CL_BUILD_ERROR -2 +#define CL_BUILD_IN_PROGRESS -3 + +/* cl_kernel_info */ +#define CL_KERNEL_FUNCTION_NAME 0x1190 +#define CL_KERNEL_NUM_ARGS 0x1191 +#define CL_KERNEL_REFERENCE_COUNT 0x1192 +#define CL_KERNEL_CONTEXT 0x1193 +#define CL_KERNEL_PROGRAM 0x1194 +#define CL_KERNEL_ATTRIBUTES 0x1195 +#define CL_KERNEL_MAX_NUM_SUB_GROUPS 0x11B9 +#define CL_KERNEL_COMPILE_NUM_SUB_GROUPS 0x11BA + +/* cl_kernel_arg_info */ +#define CL_KERNEL_ARG_ADDRESS_QUALIFIER 0x1196 +#define CL_KERNEL_ARG_ACCESS_QUALIFIER 0x1197 +#define CL_KERNEL_ARG_TYPE_NAME 0x1198 +#define CL_KERNEL_ARG_TYPE_QUALIFIER 0x1199 +#define CL_KERNEL_ARG_NAME 0x119A + +/* cl_kernel_arg_address_qualifier */ +#define CL_KERNEL_ARG_ADDRESS_GLOBAL 0x119B +#define CL_KERNEL_ARG_ADDRESS_LOCAL 0x119C +#define CL_KERNEL_ARG_ADDRESS_CONSTANT 0x119D +#define CL_KERNEL_ARG_ADDRESS_PRIVATE 0x119E + +/* cl_kernel_arg_access_qualifier */ +#define CL_KERNEL_ARG_ACCESS_READ_ONLY 0x11A0 +#define CL_KERNEL_ARG_ACCESS_WRITE_ONLY 0x11A1 +#define CL_KERNEL_ARG_ACCESS_READ_WRITE 0x11A2 +#define CL_KERNEL_ARG_ACCESS_NONE 0x11A3 + +/* cl_kernel_arg_type_qualifer */ +#define CL_KERNEL_ARG_TYPE_NONE 0 +#define CL_KERNEL_ARG_TYPE_CONST (1 << 0) +#define CL_KERNEL_ARG_TYPE_RESTRICT (1 << 1) +#define CL_KERNEL_ARG_TYPE_VOLATILE (1 << 2) +#define CL_KERNEL_ARG_TYPE_PIPE (1 << 3) + +/* cl_kernel_work_group_info */ +#define CL_KERNEL_WORK_GROUP_SIZE 0x11B0 +#define CL_KERNEL_COMPILE_WORK_GROUP_SIZE 0x11B1 +#define CL_KERNEL_LOCAL_MEM_SIZE 0x11B2 +#define CL_KERNEL_PREFERRED_WORK_GROUP_SIZE_MULTIPLE 0x11B3 +#define CL_KERNEL_PRIVATE_MEM_SIZE 0x11B4 +#define CL_KERNEL_GLOBAL_WORK_SIZE 0x11B5 + +/* cl_kernel_sub_group_info */ +#define CL_KERNEL_MAX_SUB_GROUP_SIZE_FOR_NDRANGE 0x2033 +#define CL_KERNEL_SUB_GROUP_COUNT_FOR_NDRANGE 0x2034 +#define CL_KERNEL_LOCAL_SIZE_FOR_SUB_GROUP_COUNT 0x11B8 + +/* cl_kernel_exec_info */ +#define CL_KERNEL_EXEC_INFO_SVM_PTRS 0x11B6 +#define CL_KERNEL_EXEC_INFO_SVM_FINE_GRAIN_SYSTEM 0x11B7 + +/* cl_event_info */ +#define CL_EVENT_COMMAND_QUEUE 0x11D0 +#define CL_EVENT_COMMAND_TYPE 0x11D1 +#define CL_EVENT_REFERENCE_COUNT 0x11D2 +#define CL_EVENT_COMMAND_EXECUTION_STATUS 0x11D3 +#define CL_EVENT_CONTEXT 0x11D4 + +/* cl_command_type */ +#define CL_COMMAND_NDRANGE_KERNEL 0x11F0 +#define CL_COMMAND_TASK 0x11F1 +#define CL_COMMAND_NATIVE_KERNEL 0x11F2 +#define CL_COMMAND_READ_BUFFER 0x11F3 +#define CL_COMMAND_WRITE_BUFFER 0x11F4 +#define CL_COMMAND_COPY_BUFFER 0x11F5 +#define CL_COMMAND_READ_IMAGE 0x11F6 +#define CL_COMMAND_WRITE_IMAGE 0x11F7 +#define CL_COMMAND_COPY_IMAGE 0x11F8 +#define CL_COMMAND_COPY_IMAGE_TO_BUFFER 0x11F9 +#define CL_COMMAND_COPY_BUFFER_TO_IMAGE 0x11FA +#define CL_COMMAND_MAP_BUFFER 0x11FB +#define CL_COMMAND_MAP_IMAGE 0x11FC +#define CL_COMMAND_UNMAP_MEM_OBJECT 0x11FD +#define CL_COMMAND_MARKER 0x11FE +#define CL_COMMAND_ACQUIRE_GL_OBJECTS 0x11FF +#define CL_COMMAND_RELEASE_GL_OBJECTS 0x1200 +#define CL_COMMAND_READ_BUFFER_RECT 0x1201 +#define CL_COMMAND_WRITE_BUFFER_RECT 0x1202 +#define CL_COMMAND_COPY_BUFFER_RECT 0x1203 +#define CL_COMMAND_USER 0x1204 +#define CL_COMMAND_BARRIER 0x1205 +#define CL_COMMAND_MIGRATE_MEM_OBJECTS 0x1206 +#define CL_COMMAND_FILL_BUFFER 0x1207 +#define CL_COMMAND_FILL_IMAGE 0x1208 +#define CL_COMMAND_SVM_FREE 0x1209 +#define CL_COMMAND_SVM_MEMCPY 0x120A +#define CL_COMMAND_SVM_MEMFILL 0x120B +#define CL_COMMAND_SVM_MAP 0x120C +#define CL_COMMAND_SVM_UNMAP 0x120D + +/* command execution status */ +#define CL_COMPLETE 0x0 +#define CL_RUNNING 0x1 +#define CL_SUBMITTED 0x2 +#define CL_QUEUED 0x3 + +/* cl_buffer_create_type */ +#define CL_BUFFER_CREATE_TYPE_REGION 0x1220 + +/* cl_profiling_info */ +#define CL_PROFILING_COMMAND_QUEUED 0x1280 +#define CL_PROFILING_COMMAND_SUBMIT 0x1281 +#define CL_PROFILING_COMMAND_START 0x1282 +#define CL_PROFILING_COMMAND_END 0x1283 +#define CL_PROFILING_COMMAND_COMPLETE 0x1284 + +/********************************************************************************************************/ + +/* Platform API */ +extern CL_API_ENTRY cl_int CL_API_CALL +clGetPlatformIDs(cl_uint /* num_entries */, + cl_platform_id * /* platforms */, + cl_uint * /* num_platforms */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clGetPlatformInfo(cl_platform_id /* platform */, + cl_platform_info /* param_name */, + size_t /* param_value_size */, + void * /* param_value */, + size_t * /* param_value_size_ret */) CL_API_SUFFIX__VERSION_1_0; + +/* Device APIs */ +extern CL_API_ENTRY cl_int CL_API_CALL +clGetDeviceIDs(cl_platform_id /* platform */, + cl_device_type /* device_type */, + cl_uint /* num_entries */, + cl_device_id * /* devices */, + cl_uint * /* num_devices */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clGetDeviceInfo(cl_device_id /* device */, + cl_device_info /* param_name */, + size_t /* param_value_size */, + void * /* param_value */, + size_t * /* param_value_size_ret */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clCreateSubDevices(cl_device_id /* in_device */, + const cl_device_partition_property * /* properties */, + cl_uint /* num_devices */, + cl_device_id * /* out_devices */, + cl_uint * /* num_devices_ret */) CL_API_SUFFIX__VERSION_1_2; + +extern CL_API_ENTRY cl_int CL_API_CALL +clRetainDevice(cl_device_id /* device */) CL_API_SUFFIX__VERSION_1_2; + +extern CL_API_ENTRY cl_int CL_API_CALL +clReleaseDevice(cl_device_id /* device */) CL_API_SUFFIX__VERSION_1_2; + +extern CL_API_ENTRY cl_int CL_API_CALL +clSetDefaultDeviceCommandQueue(cl_context /* context */, + cl_device_id /* device */, + cl_command_queue /* command_queue */) CL_API_SUFFIX__VERSION_2_1; + +extern CL_API_ENTRY cl_int CL_API_CALL +clGetDeviceAndHostTimer(cl_device_id /* device */, + cl_ulong* /* device_timestamp */, + cl_ulong* /* host_timestamp */) CL_API_SUFFIX__VERSION_2_1; + +extern CL_API_ENTRY cl_int CL_API_CALL +clGetHostTimer(cl_device_id /* device */, + cl_ulong * /* host_timestamp */) CL_API_SUFFIX__VERSION_2_1; + + +/* Context APIs */ +extern CL_API_ENTRY cl_context CL_API_CALL +clCreateContext(const cl_context_properties * /* properties */, + cl_uint /* num_devices */, + const cl_device_id * /* devices */, + void (CL_CALLBACK * /* pfn_notify */)(const char *, const void *, size_t, void *), + void * /* user_data */, + cl_int * /* errcode_ret */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_context CL_API_CALL +clCreateContextFromType(const cl_context_properties * /* properties */, + cl_device_type /* device_type */, + void (CL_CALLBACK * /* pfn_notify*/ )(const char *, const void *, size_t, void *), + void * /* user_data */, + cl_int * /* errcode_ret */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clRetainContext(cl_context /* context */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clReleaseContext(cl_context /* context */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clGetContextInfo(cl_context /* context */, + cl_context_info /* param_name */, + size_t /* param_value_size */, + void * /* param_value */, + size_t * /* param_value_size_ret */) CL_API_SUFFIX__VERSION_1_0; + +/* Command Queue APIs */ +extern CL_API_ENTRY cl_command_queue CL_API_CALL +clCreateCommandQueueWithProperties(cl_context /* context */, + cl_device_id /* device */, + const cl_queue_properties * /* properties */, + cl_int * /* errcode_ret */) CL_API_SUFFIX__VERSION_2_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clRetainCommandQueue(cl_command_queue /* command_queue */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clReleaseCommandQueue(cl_command_queue /* command_queue */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clGetCommandQueueInfo(cl_command_queue /* command_queue */, + cl_command_queue_info /* param_name */, + size_t /* param_value_size */, + void * /* param_value */, + size_t * /* param_value_size_ret */) CL_API_SUFFIX__VERSION_1_0; + +/* Memory Object APIs */ +extern CL_API_ENTRY cl_mem CL_API_CALL +clCreateBuffer(cl_context /* context */, + cl_mem_flags /* flags */, + size_t /* size */, + void * /* host_ptr */, + cl_int * /* errcode_ret */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_mem CL_API_CALL +clCreateSubBuffer(cl_mem /* buffer */, + cl_mem_flags /* flags */, + cl_buffer_create_type /* buffer_create_type */, + const void * /* buffer_create_info */, + cl_int * /* errcode_ret */) CL_API_SUFFIX__VERSION_1_1; + +extern CL_API_ENTRY cl_mem CL_API_CALL +clCreateImage(cl_context /* context */, + cl_mem_flags /* flags */, + const cl_image_format * /* image_format */, + const cl_image_desc * /* image_desc */, + void * /* host_ptr */, + cl_int * /* errcode_ret */) CL_API_SUFFIX__VERSION_1_2; + +extern CL_API_ENTRY cl_mem CL_API_CALL +clCreatePipe(cl_context /* context */, + cl_mem_flags /* flags */, + cl_uint /* pipe_packet_size */, + cl_uint /* pipe_max_packets */, + const cl_pipe_properties * /* properties */, + cl_int * /* errcode_ret */) CL_API_SUFFIX__VERSION_2_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clRetainMemObject(cl_mem /* memobj */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clReleaseMemObject(cl_mem /* memobj */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clGetSupportedImageFormats(cl_context /* context */, + cl_mem_flags /* flags */, + cl_mem_object_type /* image_type */, + cl_uint /* num_entries */, + cl_image_format * /* image_formats */, + cl_uint * /* num_image_formats */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clGetMemObjectInfo(cl_mem /* memobj */, + cl_mem_info /* param_name */, + size_t /* param_value_size */, + void * /* param_value */, + size_t * /* param_value_size_ret */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clGetImageInfo(cl_mem /* image */, + cl_image_info /* param_name */, + size_t /* param_value_size */, + void * /* param_value */, + size_t * /* param_value_size_ret */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clGetPipeInfo(cl_mem /* pipe */, + cl_pipe_info /* param_name */, + size_t /* param_value_size */, + void * /* param_value */, + size_t * /* param_value_size_ret */) CL_API_SUFFIX__VERSION_2_0; + + +extern CL_API_ENTRY cl_int CL_API_CALL +clSetMemObjectDestructorCallback(cl_mem /* memobj */, + void (CL_CALLBACK * /*pfn_notify*/)( cl_mem /* memobj */, void* /*user_data*/), + void * /*user_data */ ) CL_API_SUFFIX__VERSION_1_1; + +/* SVM Allocation APIs */ +extern CL_API_ENTRY void * CL_API_CALL +clSVMAlloc(cl_context /* context */, + cl_svm_mem_flags /* flags */, + size_t /* size */, + cl_uint /* alignment */) CL_API_SUFFIX__VERSION_2_0; + +extern CL_API_ENTRY void CL_API_CALL +clSVMFree(cl_context /* context */, + void * /* svm_pointer */) CL_API_SUFFIX__VERSION_2_0; + +/* Sampler APIs */ +extern CL_API_ENTRY cl_sampler CL_API_CALL +clCreateSamplerWithProperties(cl_context /* context */, + const cl_sampler_properties * /* normalized_coords */, + cl_int * /* errcode_ret */) CL_API_SUFFIX__VERSION_2_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clRetainSampler(cl_sampler /* sampler */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clReleaseSampler(cl_sampler /* sampler */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clGetSamplerInfo(cl_sampler /* sampler */, + cl_sampler_info /* param_name */, + size_t /* param_value_size */, + void * /* param_value */, + size_t * /* param_value_size_ret */) CL_API_SUFFIX__VERSION_1_0; + +/* Program Object APIs */ +extern CL_API_ENTRY cl_program CL_API_CALL +clCreateProgramWithSource(cl_context /* context */, + cl_uint /* count */, + const char ** /* strings */, + const size_t * /* lengths */, + cl_int * /* errcode_ret */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_program CL_API_CALL +clCreateProgramWithBinary(cl_context /* context */, + cl_uint /* num_devices */, + const cl_device_id * /* device_list */, + const size_t * /* lengths */, + const unsigned char ** /* binaries */, + cl_int * /* binary_status */, + cl_int * /* errcode_ret */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_program CL_API_CALL +clCreateProgramWithBuiltInKernels(cl_context /* context */, + cl_uint /* num_devices */, + const cl_device_id * /* device_list */, + const char * /* kernel_names */, + cl_int * /* errcode_ret */) CL_API_SUFFIX__VERSION_1_2; + +extern CL_API_ENTRY cl_program CL_API_CALL +clCreateProgramWithIL(cl_context /* context */, + const void* /* il */, + size_t /* length */, + cl_int* /* errcode_ret */) CL_API_SUFFIX__VERSION_2_1; + + +extern CL_API_ENTRY cl_int CL_API_CALL +clRetainProgram(cl_program /* program */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clReleaseProgram(cl_program /* program */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clBuildProgram(cl_program /* program */, + cl_uint /* num_devices */, + const cl_device_id * /* device_list */, + const char * /* options */, + void (CL_CALLBACK * /* pfn_notify */)(cl_program /* program */, void * /* user_data */), + void * /* user_data */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clCompileProgram(cl_program /* program */, + cl_uint /* num_devices */, + const cl_device_id * /* device_list */, + const char * /* options */, + cl_uint /* num_input_headers */, + const cl_program * /* input_headers */, + const char ** /* header_include_names */, + void (CL_CALLBACK * /* pfn_notify */)(cl_program /* program */, void * /* user_data */), + void * /* user_data */) CL_API_SUFFIX__VERSION_1_2; + +extern CL_API_ENTRY cl_program CL_API_CALL +clLinkProgram(cl_context /* context */, + cl_uint /* num_devices */, + const cl_device_id * /* device_list */, + const char * /* options */, + cl_uint /* num_input_programs */, + const cl_program * /* input_programs */, + void (CL_CALLBACK * /* pfn_notify */)(cl_program /* program */, void * /* user_data */), + void * /* user_data */, + cl_int * /* errcode_ret */ ) CL_API_SUFFIX__VERSION_1_2; + + +extern CL_API_ENTRY cl_int CL_API_CALL +clUnloadPlatformCompiler(cl_platform_id /* platform */) CL_API_SUFFIX__VERSION_1_2; + +extern CL_API_ENTRY cl_int CL_API_CALL +clGetProgramInfo(cl_program /* program */, + cl_program_info /* param_name */, + size_t /* param_value_size */, + void * /* param_value */, + size_t * /* param_value_size_ret */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clGetProgramBuildInfo(cl_program /* program */, + cl_device_id /* device */, + cl_program_build_info /* param_name */, + size_t /* param_value_size */, + void * /* param_value */, + size_t * /* param_value_size_ret */) CL_API_SUFFIX__VERSION_1_0; + +/* Kernel Object APIs */ +extern CL_API_ENTRY cl_kernel CL_API_CALL +clCreateKernel(cl_program /* program */, + const char * /* kernel_name */, + cl_int * /* errcode_ret */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clCreateKernelsInProgram(cl_program /* program */, + cl_uint /* num_kernels */, + cl_kernel * /* kernels */, + cl_uint * /* num_kernels_ret */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_kernel CL_API_CALL +clCloneKernel(cl_kernel /* source_kernel */, + cl_int* /* errcode_ret */) CL_API_SUFFIX__VERSION_2_1; + +extern CL_API_ENTRY cl_int CL_API_CALL +clRetainKernel(cl_kernel /* kernel */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clReleaseKernel(cl_kernel /* kernel */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clSetKernelArg(cl_kernel /* kernel */, + cl_uint /* arg_index */, + size_t /* arg_size */, + const void * /* arg_value */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clSetKernelArgSVMPointer(cl_kernel /* kernel */, + cl_uint /* arg_index */, + const void * /* arg_value */) CL_API_SUFFIX__VERSION_2_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clSetKernelExecInfo(cl_kernel /* kernel */, + cl_kernel_exec_info /* param_name */, + size_t /* param_value_size */, + const void * /* param_value */) CL_API_SUFFIX__VERSION_2_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clGetKernelInfo(cl_kernel /* kernel */, + cl_kernel_info /* param_name */, + size_t /* param_value_size */, + void * /* param_value */, + size_t * /* param_value_size_ret */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clGetKernelArgInfo(cl_kernel /* kernel */, + cl_uint /* arg_indx */, + cl_kernel_arg_info /* param_name */, + size_t /* param_value_size */, + void * /* param_value */, + size_t * /* param_value_size_ret */) CL_API_SUFFIX__VERSION_1_2; + +extern CL_API_ENTRY cl_int CL_API_CALL +clGetKernelWorkGroupInfo(cl_kernel /* kernel */, + cl_device_id /* device */, + cl_kernel_work_group_info /* param_name */, + size_t /* param_value_size */, + void * /* param_value */, + size_t * /* param_value_size_ret */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clGetKernelSubGroupInfo(cl_kernel /* kernel */, + cl_device_id /* device */, + cl_kernel_sub_group_info /* param_name */, + size_t /* input_value_size */, + const void* /*input_value */, + size_t /* param_value_size */, + void* /* param_value */, + size_t* /* param_value_size_ret */ ) CL_API_SUFFIX__VERSION_2_1; + + +/* Event Object APIs */ +extern CL_API_ENTRY cl_int CL_API_CALL +clWaitForEvents(cl_uint /* num_events */, + const cl_event * /* event_list */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clGetEventInfo(cl_event /* event */, + cl_event_info /* param_name */, + size_t /* param_value_size */, + void * /* param_value */, + size_t * /* param_value_size_ret */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_event CL_API_CALL +clCreateUserEvent(cl_context /* context */, + cl_int * /* errcode_ret */) CL_API_SUFFIX__VERSION_1_1; + +extern CL_API_ENTRY cl_int CL_API_CALL +clRetainEvent(cl_event /* event */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clReleaseEvent(cl_event /* event */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clSetUserEventStatus(cl_event /* event */, + cl_int /* execution_status */) CL_API_SUFFIX__VERSION_1_1; + +extern CL_API_ENTRY cl_int CL_API_CALL +clSetEventCallback( cl_event /* event */, + cl_int /* command_exec_callback_type */, + void (CL_CALLBACK * /* pfn_notify */)(cl_event, cl_int, void *), + void * /* user_data */) CL_API_SUFFIX__VERSION_1_1; + +/* Profiling APIs */ +extern CL_API_ENTRY cl_int CL_API_CALL +clGetEventProfilingInfo(cl_event /* event */, + cl_profiling_info /* param_name */, + size_t /* param_value_size */, + void * /* param_value */, + size_t * /* param_value_size_ret */) CL_API_SUFFIX__VERSION_1_0; + +/* Flush and Finish APIs */ +extern CL_API_ENTRY cl_int CL_API_CALL +clFlush(cl_command_queue /* command_queue */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clFinish(cl_command_queue /* command_queue */) CL_API_SUFFIX__VERSION_1_0; + +/* Enqueued Commands APIs */ +extern CL_API_ENTRY cl_int CL_API_CALL +clEnqueueReadBuffer(cl_command_queue /* command_queue */, + cl_mem /* buffer */, + cl_bool /* blocking_read */, + size_t /* offset */, + size_t /* size */, + void * /* ptr */, + cl_uint /* num_events_in_wait_list */, + const cl_event * /* event_wait_list */, + cl_event * /* event */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clEnqueueReadBufferRect(cl_command_queue /* command_queue */, + cl_mem /* buffer */, + cl_bool /* blocking_read */, + const size_t * /* buffer_offset */, + const size_t * /* host_offset */, + const size_t * /* region */, + size_t /* buffer_row_pitch */, + size_t /* buffer_slice_pitch */, + size_t /* host_row_pitch */, + size_t /* host_slice_pitch */, + void * /* ptr */, + cl_uint /* num_events_in_wait_list */, + const cl_event * /* event_wait_list */, + cl_event * /* event */) CL_API_SUFFIX__VERSION_1_1; + +extern CL_API_ENTRY cl_int CL_API_CALL +clEnqueueWriteBuffer(cl_command_queue /* command_queue */, + cl_mem /* buffer */, + cl_bool /* blocking_write */, + size_t /* offset */, + size_t /* size */, + const void * /* ptr */, + cl_uint /* num_events_in_wait_list */, + const cl_event * /* event_wait_list */, + cl_event * /* event */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clEnqueueWriteBufferRect(cl_command_queue /* command_queue */, + cl_mem /* buffer */, + cl_bool /* blocking_write */, + const size_t * /* buffer_offset */, + const size_t * /* host_offset */, + const size_t * /* region */, + size_t /* buffer_row_pitch */, + size_t /* buffer_slice_pitch */, + size_t /* host_row_pitch */, + size_t /* host_slice_pitch */, + const void * /* ptr */, + cl_uint /* num_events_in_wait_list */, + const cl_event * /* event_wait_list */, + cl_event * /* event */) CL_API_SUFFIX__VERSION_1_1; + +extern CL_API_ENTRY cl_int CL_API_CALL +clEnqueueFillBuffer(cl_command_queue /* command_queue */, + cl_mem /* buffer */, + const void * /* pattern */, + size_t /* pattern_size */, + size_t /* offset */, + size_t /* size */, + cl_uint /* num_events_in_wait_list */, + const cl_event * /* event_wait_list */, + cl_event * /* event */) CL_API_SUFFIX__VERSION_1_2; + +extern CL_API_ENTRY cl_int CL_API_CALL +clEnqueueCopyBuffer(cl_command_queue /* command_queue */, + cl_mem /* src_buffer */, + cl_mem /* dst_buffer */, + size_t /* src_offset */, + size_t /* dst_offset */, + size_t /* size */, + cl_uint /* num_events_in_wait_list */, + const cl_event * /* event_wait_list */, + cl_event * /* event */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clEnqueueCopyBufferRect(cl_command_queue /* command_queue */, + cl_mem /* src_buffer */, + cl_mem /* dst_buffer */, + const size_t * /* src_origin */, + const size_t * /* dst_origin */, + const size_t * /* region */, + size_t /* src_row_pitch */, + size_t /* src_slice_pitch */, + size_t /* dst_row_pitch */, + size_t /* dst_slice_pitch */, + cl_uint /* num_events_in_wait_list */, + const cl_event * /* event_wait_list */, + cl_event * /* event */) CL_API_SUFFIX__VERSION_1_1; + +extern CL_API_ENTRY cl_int CL_API_CALL +clEnqueueReadImage(cl_command_queue /* command_queue */, + cl_mem /* image */, + cl_bool /* blocking_read */, + const size_t * /* origin[3] */, + const size_t * /* region[3] */, + size_t /* row_pitch */, + size_t /* slice_pitch */, + void * /* ptr */, + cl_uint /* num_events_in_wait_list */, + const cl_event * /* event_wait_list */, + cl_event * /* event */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clEnqueueWriteImage(cl_command_queue /* command_queue */, + cl_mem /* image */, + cl_bool /* blocking_write */, + const size_t * /* origin[3] */, + const size_t * /* region[3] */, + size_t /* input_row_pitch */, + size_t /* input_slice_pitch */, + const void * /* ptr */, + cl_uint /* num_events_in_wait_list */, + const cl_event * /* event_wait_list */, + cl_event * /* event */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clEnqueueFillImage(cl_command_queue /* command_queue */, + cl_mem /* image */, + const void * /* fill_color */, + const size_t * /* origin[3] */, + const size_t * /* region[3] */, + cl_uint /* num_events_in_wait_list */, + const cl_event * /* event_wait_list */, + cl_event * /* event */) CL_API_SUFFIX__VERSION_1_2; + +extern CL_API_ENTRY cl_int CL_API_CALL +clEnqueueCopyImage(cl_command_queue /* command_queue */, + cl_mem /* src_image */, + cl_mem /* dst_image */, + const size_t * /* src_origin[3] */, + const size_t * /* dst_origin[3] */, + const size_t * /* region[3] */, + cl_uint /* num_events_in_wait_list */, + const cl_event * /* event_wait_list */, + cl_event * /* event */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clEnqueueCopyImageToBuffer(cl_command_queue /* command_queue */, + cl_mem /* src_image */, + cl_mem /* dst_buffer */, + const size_t * /* src_origin[3] */, + const size_t * /* region[3] */, + size_t /* dst_offset */, + cl_uint /* num_events_in_wait_list */, + const cl_event * /* event_wait_list */, + cl_event * /* event */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clEnqueueCopyBufferToImage(cl_command_queue /* command_queue */, + cl_mem /* src_buffer */, + cl_mem /* dst_image */, + size_t /* src_offset */, + const size_t * /* dst_origin[3] */, + const size_t * /* region[3] */, + cl_uint /* num_events_in_wait_list */, + const cl_event * /* event_wait_list */, + cl_event * /* event */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY void * CL_API_CALL +clEnqueueMapBuffer(cl_command_queue /* command_queue */, + cl_mem /* buffer */, + cl_bool /* blocking_map */, + cl_map_flags /* map_flags */, + size_t /* offset */, + size_t /* size */, + cl_uint /* num_events_in_wait_list */, + const cl_event * /* event_wait_list */, + cl_event * /* event */, + cl_int * /* errcode_ret */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY void * CL_API_CALL +clEnqueueMapImage(cl_command_queue /* command_queue */, + cl_mem /* image */, + cl_bool /* blocking_map */, + cl_map_flags /* map_flags */, + const size_t * /* origin[3] */, + const size_t * /* region[3] */, + size_t * /* image_row_pitch */, + size_t * /* image_slice_pitch */, + cl_uint /* num_events_in_wait_list */, + const cl_event * /* event_wait_list */, + cl_event * /* event */, + cl_int * /* errcode_ret */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clEnqueueUnmapMemObject(cl_command_queue /* command_queue */, + cl_mem /* memobj */, + void * /* mapped_ptr */, + cl_uint /* num_events_in_wait_list */, + const cl_event * /* event_wait_list */, + cl_event * /* event */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clEnqueueMigrateMemObjects(cl_command_queue /* command_queue */, + cl_uint /* num_mem_objects */, + const cl_mem * /* mem_objects */, + cl_mem_migration_flags /* flags */, + cl_uint /* num_events_in_wait_list */, + const cl_event * /* event_wait_list */, + cl_event * /* event */) CL_API_SUFFIX__VERSION_1_2; + +extern CL_API_ENTRY cl_int CL_API_CALL +clEnqueueNDRangeKernel(cl_command_queue /* command_queue */, + cl_kernel /* kernel */, + cl_uint /* work_dim */, + const size_t * /* global_work_offset */, + const size_t * /* global_work_size */, + const size_t * /* local_work_size */, + cl_uint /* num_events_in_wait_list */, + const cl_event * /* event_wait_list */, + cl_event * /* event */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clEnqueueNativeKernel(cl_command_queue /* command_queue */, + void (CL_CALLBACK * /*user_func*/)(void *), + void * /* args */, + size_t /* cb_args */, + cl_uint /* num_mem_objects */, + const cl_mem * /* mem_list */, + const void ** /* args_mem_loc */, + cl_uint /* num_events_in_wait_list */, + const cl_event * /* event_wait_list */, + cl_event * /* event */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clEnqueueMarkerWithWaitList(cl_command_queue /* command_queue */, + cl_uint /* num_events_in_wait_list */, + const cl_event * /* event_wait_list */, + cl_event * /* event */) CL_API_SUFFIX__VERSION_1_2; + +extern CL_API_ENTRY cl_int CL_API_CALL +clEnqueueBarrierWithWaitList(cl_command_queue /* command_queue */, + cl_uint /* num_events_in_wait_list */, + const cl_event * /* event_wait_list */, + cl_event * /* event */) CL_API_SUFFIX__VERSION_1_2; + +extern CL_API_ENTRY cl_int CL_API_CALL +clEnqueueSVMFree(cl_command_queue /* command_queue */, + cl_uint /* num_svm_pointers */, + void *[] /* svm_pointers[] */, + void (CL_CALLBACK * /*pfn_free_func*/)(cl_command_queue /* queue */, + cl_uint /* num_svm_pointers */, + void *[] /* svm_pointers[] */, + void * /* user_data */), + void * /* user_data */, + cl_uint /* num_events_in_wait_list */, + const cl_event * /* event_wait_list */, + cl_event * /* event */) CL_API_SUFFIX__VERSION_2_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clEnqueueSVMMemcpy(cl_command_queue /* command_queue */, + cl_bool /* blocking_copy */, + void * /* dst_ptr */, + const void * /* src_ptr */, + size_t /* size */, + cl_uint /* num_events_in_wait_list */, + const cl_event * /* event_wait_list */, + cl_event * /* event */) CL_API_SUFFIX__VERSION_2_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clEnqueueSVMMemFill(cl_command_queue /* command_queue */, + void * /* svm_ptr */, + const void * /* pattern */, + size_t /* pattern_size */, + size_t /* size */, + cl_uint /* num_events_in_wait_list */, + const cl_event * /* event_wait_list */, + cl_event * /* event */) CL_API_SUFFIX__VERSION_2_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clEnqueueSVMMap(cl_command_queue /* command_queue */, + cl_bool /* blocking_map */, + cl_map_flags /* flags */, + void * /* svm_ptr */, + size_t /* size */, + cl_uint /* num_events_in_wait_list */, + const cl_event * /* event_wait_list */, + cl_event * /* event */) CL_API_SUFFIX__VERSION_2_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clEnqueueSVMUnmap(cl_command_queue /* command_queue */, + void * /* svm_ptr */, + cl_uint /* num_events_in_wait_list */, + const cl_event * /* event_wait_list */, + cl_event * /* event */) CL_API_SUFFIX__VERSION_2_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clEnqueueSVMMigrateMem(cl_command_queue /* command_queue */, + cl_uint /* num_svm_pointers */, + const void ** /* svm_pointers */, + const size_t * /* sizes */, + cl_mem_migration_flags /* flags */, + cl_uint /* num_events_in_wait_list */, + const cl_event * /* event_wait_list */, + cl_event * /* event */) CL_API_SUFFIX__VERSION_2_1; + + +/* Extension function access + * + * Returns the extension function address for the given function name, + * or NULL if a valid function can not be found. The client must + * check to make sure the address is not NULL, before using or + * calling the returned function address. + */ +extern CL_API_ENTRY void * CL_API_CALL +clGetExtensionFunctionAddressForPlatform(cl_platform_id /* platform */, + const char * /* func_name */) CL_API_SUFFIX__VERSION_1_2; + + +/* Deprecated OpenCL 1.1 APIs */ +extern CL_API_ENTRY CL_EXT_PREFIX__VERSION_1_1_DEPRECATED cl_mem CL_API_CALL +clCreateImage2D(cl_context /* context */, + cl_mem_flags /* flags */, + const cl_image_format * /* image_format */, + size_t /* image_width */, + size_t /* image_height */, + size_t /* image_row_pitch */, + void * /* host_ptr */, + cl_int * /* errcode_ret */) CL_EXT_SUFFIX__VERSION_1_1_DEPRECATED; + +extern CL_API_ENTRY CL_EXT_PREFIX__VERSION_1_1_DEPRECATED cl_mem CL_API_CALL +clCreateImage3D(cl_context /* context */, + cl_mem_flags /* flags */, + const cl_image_format * /* image_format */, + size_t /* image_width */, + size_t /* image_height */, + size_t /* image_depth */, + size_t /* image_row_pitch */, + size_t /* image_slice_pitch */, + void * /* host_ptr */, + cl_int * /* errcode_ret */) CL_EXT_SUFFIX__VERSION_1_1_DEPRECATED; + +extern CL_API_ENTRY CL_EXT_PREFIX__VERSION_1_1_DEPRECATED cl_int CL_API_CALL +clEnqueueMarker(cl_command_queue /* command_queue */, + cl_event * /* event */) CL_EXT_SUFFIX__VERSION_1_1_DEPRECATED; + +extern CL_API_ENTRY CL_EXT_PREFIX__VERSION_1_1_DEPRECATED cl_int CL_API_CALL +clEnqueueWaitForEvents(cl_command_queue /* command_queue */, + cl_uint /* num_events */, + const cl_event * /* event_list */) CL_EXT_SUFFIX__VERSION_1_1_DEPRECATED; + +extern CL_API_ENTRY CL_EXT_PREFIX__VERSION_1_1_DEPRECATED cl_int CL_API_CALL +clEnqueueBarrier(cl_command_queue /* command_queue */) CL_EXT_SUFFIX__VERSION_1_1_DEPRECATED; + +extern CL_API_ENTRY CL_EXT_PREFIX__VERSION_1_1_DEPRECATED cl_int CL_API_CALL +clUnloadCompiler(void) CL_EXT_SUFFIX__VERSION_1_1_DEPRECATED; + +extern CL_API_ENTRY CL_EXT_PREFIX__VERSION_1_1_DEPRECATED void * CL_API_CALL +clGetExtensionFunctionAddress(const char * /* func_name */) CL_EXT_SUFFIX__VERSION_1_1_DEPRECATED; + +/* Deprecated OpenCL 2.0 APIs */ +extern CL_API_ENTRY CL_EXT_PREFIX__VERSION_1_2_DEPRECATED cl_command_queue CL_API_CALL +clCreateCommandQueue(cl_context /* context */, + cl_device_id /* device */, + cl_command_queue_properties /* properties */, + cl_int * /* errcode_ret */) CL_EXT_SUFFIX__VERSION_1_2_DEPRECATED; + + +extern CL_API_ENTRY CL_EXT_PREFIX__VERSION_1_2_DEPRECATED cl_sampler CL_API_CALL +clCreateSampler(cl_context /* context */, + cl_bool /* normalized_coords */, + cl_addressing_mode /* addressing_mode */, + cl_filter_mode /* filter_mode */, + cl_int * /* errcode_ret */) CL_EXT_SUFFIX__VERSION_1_2_DEPRECATED; + +extern CL_API_ENTRY CL_EXT_PREFIX__VERSION_1_2_DEPRECATED cl_int CL_API_CALL +clEnqueueTask(cl_command_queue /* command_queue */, + cl_kernel /* kernel */, + cl_uint /* num_events_in_wait_list */, + const cl_event * /* event_wait_list */, + cl_event * /* event */) CL_EXT_SUFFIX__VERSION_1_2_DEPRECATED; + +#ifdef __cplusplus +} +#endif + +#endif /* __OPENCL_CL_H */ + diff --git a/phonelibs/opencl/include/CL/cl_d3d10.h b/phonelibs/opencl/include/CL/cl_d3d10.h new file mode 100644 index 00000000000000..d5960a43f72123 --- /dev/null +++ b/phonelibs/opencl/include/CL/cl_d3d10.h @@ -0,0 +1,131 @@ +/********************************************************************************** + * Copyright (c) 2008-2015 The Khronos Group Inc. + * + * Permission is hereby granted, free of charge, to any person obtaining a + * copy of this software and/or associated documentation files (the + * "Materials"), to deal in the Materials without restriction, including + * without limitation the rights to use, copy, modify, merge, publish, + * distribute, sublicense, and/or sell copies of the Materials, and to + * permit persons to whom the Materials are furnished to do so, subject to + * the following conditions: + * + * The above copyright notice and this permission notice shall be included + * in all copies or substantial portions of the Materials. + * + * MODIFICATIONS TO THIS FILE MAY MEAN IT NO LONGER ACCURATELY REFLECTS + * KHRONOS STANDARDS. THE UNMODIFIED, NORMATIVE VERSIONS OF KHRONOS + * SPECIFICATIONS AND HEADER INFORMATION ARE LOCATED AT + * https://www.khronos.org/registry/ + * + * THE MATERIALS ARE PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, + * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. + * IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY + * CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, + * TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE + * MATERIALS OR THE USE OR OTHER DEALINGS IN THE MATERIALS. + **********************************************************************************/ + +/* $Revision: 11708 $ on $Date: 2010-06-13 23:36:24 -0700 (Sun, 13 Jun 2010) $ */ + +#ifndef __OPENCL_CL_D3D10_H +#define __OPENCL_CL_D3D10_H + +#include +#include +#include + +#ifdef __cplusplus +extern "C" { +#endif + +/****************************************************************************** + * cl_khr_d3d10_sharing */ +#define cl_khr_d3d10_sharing 1 + +typedef cl_uint cl_d3d10_device_source_khr; +typedef cl_uint cl_d3d10_device_set_khr; + +/******************************************************************************/ + +/* Error Codes */ +#define CL_INVALID_D3D10_DEVICE_KHR -1002 +#define CL_INVALID_D3D10_RESOURCE_KHR -1003 +#define CL_D3D10_RESOURCE_ALREADY_ACQUIRED_KHR -1004 +#define CL_D3D10_RESOURCE_NOT_ACQUIRED_KHR -1005 + +/* cl_d3d10_device_source_nv */ +#define CL_D3D10_DEVICE_KHR 0x4010 +#define CL_D3D10_DXGI_ADAPTER_KHR 0x4011 + +/* cl_d3d10_device_set_nv */ +#define CL_PREFERRED_DEVICES_FOR_D3D10_KHR 0x4012 +#define CL_ALL_DEVICES_FOR_D3D10_KHR 0x4013 + +/* cl_context_info */ +#define CL_CONTEXT_D3D10_DEVICE_KHR 0x4014 +#define CL_CONTEXT_D3D10_PREFER_SHARED_RESOURCES_KHR 0x402C + +/* cl_mem_info */ +#define CL_MEM_D3D10_RESOURCE_KHR 0x4015 + +/* cl_image_info */ +#define CL_IMAGE_D3D10_SUBRESOURCE_KHR 0x4016 + +/* cl_command_type */ +#define CL_COMMAND_ACQUIRE_D3D10_OBJECTS_KHR 0x4017 +#define CL_COMMAND_RELEASE_D3D10_OBJECTS_KHR 0x4018 + +/******************************************************************************/ + +typedef CL_API_ENTRY cl_int (CL_API_CALL *clGetDeviceIDsFromD3D10KHR_fn)( + cl_platform_id platform, + cl_d3d10_device_source_khr d3d_device_source, + void * d3d_object, + cl_d3d10_device_set_khr d3d_device_set, + cl_uint num_entries, + cl_device_id * devices, + cl_uint * num_devices) CL_API_SUFFIX__VERSION_1_0; + +typedef CL_API_ENTRY cl_mem (CL_API_CALL *clCreateFromD3D10BufferKHR_fn)( + cl_context context, + cl_mem_flags flags, + ID3D10Buffer * resource, + cl_int * errcode_ret) CL_API_SUFFIX__VERSION_1_0; + +typedef CL_API_ENTRY cl_mem (CL_API_CALL *clCreateFromD3D10Texture2DKHR_fn)( + cl_context context, + cl_mem_flags flags, + ID3D10Texture2D * resource, + UINT subresource, + cl_int * errcode_ret) CL_API_SUFFIX__VERSION_1_0; + +typedef CL_API_ENTRY cl_mem (CL_API_CALL *clCreateFromD3D10Texture3DKHR_fn)( + cl_context context, + cl_mem_flags flags, + ID3D10Texture3D * resource, + UINT subresource, + cl_int * errcode_ret) CL_API_SUFFIX__VERSION_1_0; + +typedef CL_API_ENTRY cl_int (CL_API_CALL *clEnqueueAcquireD3D10ObjectsKHR_fn)( + cl_command_queue command_queue, + cl_uint num_objects, + const cl_mem * mem_objects, + cl_uint num_events_in_wait_list, + const cl_event * event_wait_list, + cl_event * event) CL_API_SUFFIX__VERSION_1_0; + +typedef CL_API_ENTRY cl_int (CL_API_CALL *clEnqueueReleaseD3D10ObjectsKHR_fn)( + cl_command_queue command_queue, + cl_uint num_objects, + const cl_mem * mem_objects, + cl_uint num_events_in_wait_list, + const cl_event * event_wait_list, + cl_event * event) CL_API_SUFFIX__VERSION_1_0; + +#ifdef __cplusplus +} +#endif + +#endif /* __OPENCL_CL_D3D10_H */ + diff --git a/phonelibs/opencl/include/CL/cl_d3d11.h b/phonelibs/opencl/include/CL/cl_d3d11.h new file mode 100644 index 00000000000000..39f9072398a29a --- /dev/null +++ b/phonelibs/opencl/include/CL/cl_d3d11.h @@ -0,0 +1,131 @@ +/********************************************************************************** + * Copyright (c) 2008-2015 The Khronos Group Inc. + * + * Permission is hereby granted, free of charge, to any person obtaining a + * copy of this software and/or associated documentation files (the + * "Materials"), to deal in the Materials without restriction, including + * without limitation the rights to use, copy, modify, merge, publish, + * distribute, sublicense, and/or sell copies of the Materials, and to + * permit persons to whom the Materials are furnished to do so, subject to + * the following conditions: + * + * The above copyright notice and this permission notice shall be included + * in all copies or substantial portions of the Materials. + * + * MODIFICATIONS TO THIS FILE MAY MEAN IT NO LONGER ACCURATELY REFLECTS + * KHRONOS STANDARDS. THE UNMODIFIED, NORMATIVE VERSIONS OF KHRONOS + * SPECIFICATIONS AND HEADER INFORMATION ARE LOCATED AT + * https://www.khronos.org/registry/ + * + * THE MATERIALS ARE PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, + * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. + * IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY + * CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, + * TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE + * MATERIALS OR THE USE OR OTHER DEALINGS IN THE MATERIALS. + **********************************************************************************/ + +/* $Revision: 11708 $ on $Date: 2010-06-13 23:36:24 -0700 (Sun, 13 Jun 2010) $ */ + +#ifndef __OPENCL_CL_D3D11_H +#define __OPENCL_CL_D3D11_H + +#include +#include +#include + +#ifdef __cplusplus +extern "C" { +#endif + +/****************************************************************************** + * cl_khr_d3d11_sharing */ +#define cl_khr_d3d11_sharing 1 + +typedef cl_uint cl_d3d11_device_source_khr; +typedef cl_uint cl_d3d11_device_set_khr; + +/******************************************************************************/ + +/* Error Codes */ +#define CL_INVALID_D3D11_DEVICE_KHR -1006 +#define CL_INVALID_D3D11_RESOURCE_KHR -1007 +#define CL_D3D11_RESOURCE_ALREADY_ACQUIRED_KHR -1008 +#define CL_D3D11_RESOURCE_NOT_ACQUIRED_KHR -1009 + +/* cl_d3d11_device_source */ +#define CL_D3D11_DEVICE_KHR 0x4019 +#define CL_D3D11_DXGI_ADAPTER_KHR 0x401A + +/* cl_d3d11_device_set */ +#define CL_PREFERRED_DEVICES_FOR_D3D11_KHR 0x401B +#define CL_ALL_DEVICES_FOR_D3D11_KHR 0x401C + +/* cl_context_info */ +#define CL_CONTEXT_D3D11_DEVICE_KHR 0x401D +#define CL_CONTEXT_D3D11_PREFER_SHARED_RESOURCES_KHR 0x402D + +/* cl_mem_info */ +#define CL_MEM_D3D11_RESOURCE_KHR 0x401E + +/* cl_image_info */ +#define CL_IMAGE_D3D11_SUBRESOURCE_KHR 0x401F + +/* cl_command_type */ +#define CL_COMMAND_ACQUIRE_D3D11_OBJECTS_KHR 0x4020 +#define CL_COMMAND_RELEASE_D3D11_OBJECTS_KHR 0x4021 + +/******************************************************************************/ + +typedef CL_API_ENTRY cl_int (CL_API_CALL *clGetDeviceIDsFromD3D11KHR_fn)( + cl_platform_id platform, + cl_d3d11_device_source_khr d3d_device_source, + void * d3d_object, + cl_d3d11_device_set_khr d3d_device_set, + cl_uint num_entries, + cl_device_id * devices, + cl_uint * num_devices) CL_API_SUFFIX__VERSION_1_2; + +typedef CL_API_ENTRY cl_mem (CL_API_CALL *clCreateFromD3D11BufferKHR_fn)( + cl_context context, + cl_mem_flags flags, + ID3D11Buffer * resource, + cl_int * errcode_ret) CL_API_SUFFIX__VERSION_1_2; + +typedef CL_API_ENTRY cl_mem (CL_API_CALL *clCreateFromD3D11Texture2DKHR_fn)( + cl_context context, + cl_mem_flags flags, + ID3D11Texture2D * resource, + UINT subresource, + cl_int * errcode_ret) CL_API_SUFFIX__VERSION_1_2; + +typedef CL_API_ENTRY cl_mem (CL_API_CALL *clCreateFromD3D11Texture3DKHR_fn)( + cl_context context, + cl_mem_flags flags, + ID3D11Texture3D * resource, + UINT subresource, + cl_int * errcode_ret) CL_API_SUFFIX__VERSION_1_2; + +typedef CL_API_ENTRY cl_int (CL_API_CALL *clEnqueueAcquireD3D11ObjectsKHR_fn)( + cl_command_queue command_queue, + cl_uint num_objects, + const cl_mem * mem_objects, + cl_uint num_events_in_wait_list, + const cl_event * event_wait_list, + cl_event * event) CL_API_SUFFIX__VERSION_1_2; + +typedef CL_API_ENTRY cl_int (CL_API_CALL *clEnqueueReleaseD3D11ObjectsKHR_fn)( + cl_command_queue command_queue, + cl_uint num_objects, + const cl_mem * mem_objects, + cl_uint num_events_in_wait_list, + const cl_event * event_wait_list, + cl_event * event) CL_API_SUFFIX__VERSION_1_2; + +#ifdef __cplusplus +} +#endif + +#endif /* __OPENCL_CL_D3D11_H */ + diff --git a/phonelibs/opencl/include/CL/cl_dx9_media_sharing.h b/phonelibs/opencl/include/CL/cl_dx9_media_sharing.h new file mode 100644 index 00000000000000..2729e8b9e89a10 --- /dev/null +++ b/phonelibs/opencl/include/CL/cl_dx9_media_sharing.h @@ -0,0 +1,132 @@ +/********************************************************************************** + * Copyright (c) 2008-2015 The Khronos Group Inc. + * + * Permission is hereby granted, free of charge, to any person obtaining a + * copy of this software and/or associated documentation files (the + * "Materials"), to deal in the Materials without restriction, including + * without limitation the rights to use, copy, modify, merge, publish, + * distribute, sublicense, and/or sell copies of the Materials, and to + * permit persons to whom the Materials are furnished to do so, subject to + * the following conditions: + * + * The above copyright notice and this permission notice shall be included + * in all copies or substantial portions of the Materials. + * + * MODIFICATIONS TO THIS FILE MAY MEAN IT NO LONGER ACCURATELY REFLECTS + * KHRONOS STANDARDS. THE UNMODIFIED, NORMATIVE VERSIONS OF KHRONOS + * SPECIFICATIONS AND HEADER INFORMATION ARE LOCATED AT + * https://www.khronos.org/registry/ + * + * THE MATERIALS ARE PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, + * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. + * IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY + * CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, + * TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE + * MATERIALS OR THE USE OR OTHER DEALINGS IN THE MATERIALS. + **********************************************************************************/ + +/* $Revision: 11708 $ on $Date: 2010-06-13 23:36:24 -0700 (Sun, 13 Jun 2010) $ */ + +#ifndef __OPENCL_CL_DX9_MEDIA_SHARING_H +#define __OPENCL_CL_DX9_MEDIA_SHARING_H + +#include +#include + +#ifdef __cplusplus +extern "C" { +#endif + +/******************************************************************************/ +/* cl_khr_dx9_media_sharing */ +#define cl_khr_dx9_media_sharing 1 + +typedef cl_uint cl_dx9_media_adapter_type_khr; +typedef cl_uint cl_dx9_media_adapter_set_khr; + +#if defined(_WIN32) +#include +typedef struct _cl_dx9_surface_info_khr +{ + IDirect3DSurface9 *resource; + HANDLE shared_handle; +} cl_dx9_surface_info_khr; +#endif + + +/******************************************************************************/ + +/* Error Codes */ +#define CL_INVALID_DX9_MEDIA_ADAPTER_KHR -1010 +#define CL_INVALID_DX9_MEDIA_SURFACE_KHR -1011 +#define CL_DX9_MEDIA_SURFACE_ALREADY_ACQUIRED_KHR -1012 +#define CL_DX9_MEDIA_SURFACE_NOT_ACQUIRED_KHR -1013 + +/* cl_media_adapter_type_khr */ +#define CL_ADAPTER_D3D9_KHR 0x2020 +#define CL_ADAPTER_D3D9EX_KHR 0x2021 +#define CL_ADAPTER_DXVA_KHR 0x2022 + +/* cl_media_adapter_set_khr */ +#define CL_PREFERRED_DEVICES_FOR_DX9_MEDIA_ADAPTER_KHR 0x2023 +#define CL_ALL_DEVICES_FOR_DX9_MEDIA_ADAPTER_KHR 0x2024 + +/* cl_context_info */ +#define CL_CONTEXT_ADAPTER_D3D9_KHR 0x2025 +#define CL_CONTEXT_ADAPTER_D3D9EX_KHR 0x2026 +#define CL_CONTEXT_ADAPTER_DXVA_KHR 0x2027 + +/* cl_mem_info */ +#define CL_MEM_DX9_MEDIA_ADAPTER_TYPE_KHR 0x2028 +#define CL_MEM_DX9_MEDIA_SURFACE_INFO_KHR 0x2029 + +/* cl_image_info */ +#define CL_IMAGE_DX9_MEDIA_PLANE_KHR 0x202A + +/* cl_command_type */ +#define CL_COMMAND_ACQUIRE_DX9_MEDIA_SURFACES_KHR 0x202B +#define CL_COMMAND_RELEASE_DX9_MEDIA_SURFACES_KHR 0x202C + +/******************************************************************************/ + +typedef CL_API_ENTRY cl_int (CL_API_CALL *clGetDeviceIDsFromDX9MediaAdapterKHR_fn)( + cl_platform_id platform, + cl_uint num_media_adapters, + cl_dx9_media_adapter_type_khr * media_adapter_type, + void * media_adapters, + cl_dx9_media_adapter_set_khr media_adapter_set, + cl_uint num_entries, + cl_device_id * devices, + cl_uint * num_devices) CL_API_SUFFIX__VERSION_1_2; + +typedef CL_API_ENTRY cl_mem (CL_API_CALL *clCreateFromDX9MediaSurfaceKHR_fn)( + cl_context context, + cl_mem_flags flags, + cl_dx9_media_adapter_type_khr adapter_type, + void * surface_info, + cl_uint plane, + cl_int * errcode_ret) CL_API_SUFFIX__VERSION_1_2; + +typedef CL_API_ENTRY cl_int (CL_API_CALL *clEnqueueAcquireDX9MediaSurfacesKHR_fn)( + cl_command_queue command_queue, + cl_uint num_objects, + const cl_mem * mem_objects, + cl_uint num_events_in_wait_list, + const cl_event * event_wait_list, + cl_event * event) CL_API_SUFFIX__VERSION_1_2; + +typedef CL_API_ENTRY cl_int (CL_API_CALL *clEnqueueReleaseDX9MediaSurfacesKHR_fn)( + cl_command_queue command_queue, + cl_uint num_objects, + const cl_mem * mem_objects, + cl_uint num_events_in_wait_list, + const cl_event * event_wait_list, + cl_event * event) CL_API_SUFFIX__VERSION_1_2; + +#ifdef __cplusplus +} +#endif + +#endif /* __OPENCL_CL_DX9_MEDIA_SHARING_H */ + diff --git a/phonelibs/opencl/include/CL/cl_egl.h b/phonelibs/opencl/include/CL/cl_egl.h new file mode 100644 index 00000000000000..a765bd5266c02f --- /dev/null +++ b/phonelibs/opencl/include/CL/cl_egl.h @@ -0,0 +1,136 @@ +/******************************************************************************* + * Copyright (c) 2008-2015 The Khronos Group Inc. + * + * Permission is hereby granted, free of charge, to any person obtaining a + * copy of this software and/or associated documentation files (the + * "Materials"), to deal in the Materials without restriction, including + * without limitation the rights to use, copy, modify, merge, publish, + * distribute, sublicense, and/or sell copies of the Materials, and to + * permit persons to whom the Materials are furnished to do so, subject to + * the following conditions: + * + * The above copyright notice and this permission notice shall be included + * in all copies or substantial portions of the Materials. + * + * MODIFICATIONS TO THIS FILE MAY MEAN IT NO LONGER ACCURATELY REFLECTS + * KHRONOS STANDARDS. THE UNMODIFIED, NORMATIVE VERSIONS OF KHRONOS + * SPECIFICATIONS AND HEADER INFORMATION ARE LOCATED AT + * https://www.khronos.org/registry/ + * + * THE MATERIALS ARE PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, + * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. + * IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY + * CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, + * TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE + * MATERIALS OR THE USE OR OTHER DEALINGS IN THE MATERIALS. + ******************************************************************************/ + +#ifndef __OPENCL_CL_EGL_H +#define __OPENCL_CL_EGL_H + +#ifdef __APPLE__ + +#else +#include +#endif + +#ifdef __cplusplus +extern "C" { +#endif + + +/* Command type for events created with clEnqueueAcquireEGLObjectsKHR */ +#define CL_COMMAND_EGL_FENCE_SYNC_OBJECT_KHR 0x202F +#define CL_COMMAND_ACQUIRE_EGL_OBJECTS_KHR 0x202D +#define CL_COMMAND_RELEASE_EGL_OBJECTS_KHR 0x202E + +/* Error type for clCreateFromEGLImageKHR */ +#define CL_INVALID_EGL_OBJECT_KHR -1093 +#define CL_EGL_RESOURCE_NOT_ACQUIRED_KHR -1092 + +/* CLeglImageKHR is an opaque handle to an EGLImage */ +typedef void* CLeglImageKHR; + +/* CLeglDisplayKHR is an opaque handle to an EGLDisplay */ +typedef void* CLeglDisplayKHR; + +/* CLeglSyncKHR is an opaque handle to an EGLSync object */ +typedef void* CLeglSyncKHR; + +/* properties passed to clCreateFromEGLImageKHR */ +typedef intptr_t cl_egl_image_properties_khr; + + +#define cl_khr_egl_image 1 + +extern CL_API_ENTRY cl_mem CL_API_CALL +clCreateFromEGLImageKHR(cl_context /* context */, + CLeglDisplayKHR /* egldisplay */, + CLeglImageKHR /* eglimage */, + cl_mem_flags /* flags */, + const cl_egl_image_properties_khr * /* properties */, + cl_int * /* errcode_ret */) CL_API_SUFFIX__VERSION_1_0; + +typedef CL_API_ENTRY cl_mem (CL_API_CALL *clCreateFromEGLImageKHR_fn)( + cl_context context, + CLeglDisplayKHR egldisplay, + CLeglImageKHR eglimage, + cl_mem_flags flags, + const cl_egl_image_properties_khr * properties, + cl_int * errcode_ret); + + +extern CL_API_ENTRY cl_int CL_API_CALL +clEnqueueAcquireEGLObjectsKHR(cl_command_queue /* command_queue */, + cl_uint /* num_objects */, + const cl_mem * /* mem_objects */, + cl_uint /* num_events_in_wait_list */, + const cl_event * /* event_wait_list */, + cl_event * /* event */) CL_API_SUFFIX__VERSION_1_0; + +typedef CL_API_ENTRY cl_int (CL_API_CALL *clEnqueueAcquireEGLObjectsKHR_fn)( + cl_command_queue command_queue, + cl_uint num_objects, + const cl_mem * mem_objects, + cl_uint num_events_in_wait_list, + const cl_event * event_wait_list, + cl_event * event); + + +extern CL_API_ENTRY cl_int CL_API_CALL +clEnqueueReleaseEGLObjectsKHR(cl_command_queue /* command_queue */, + cl_uint /* num_objects */, + const cl_mem * /* mem_objects */, + cl_uint /* num_events_in_wait_list */, + const cl_event * /* event_wait_list */, + cl_event * /* event */) CL_API_SUFFIX__VERSION_1_0; + +typedef CL_API_ENTRY cl_int (CL_API_CALL *clEnqueueReleaseEGLObjectsKHR_fn)( + cl_command_queue command_queue, + cl_uint num_objects, + const cl_mem * mem_objects, + cl_uint num_events_in_wait_list, + const cl_event * event_wait_list, + cl_event * event); + + +#define cl_khr_egl_event 1 + +extern CL_API_ENTRY cl_event CL_API_CALL +clCreateEventFromEGLSyncKHR(cl_context /* context */, + CLeglSyncKHR /* sync */, + CLeglDisplayKHR /* display */, + cl_int * /* errcode_ret */) CL_API_SUFFIX__VERSION_1_0; + +typedef CL_API_ENTRY cl_event (CL_API_CALL *clCreateEventFromEGLSyncKHR_fn)( + cl_context context, + CLeglSyncKHR sync, + CLeglDisplayKHR display, + cl_int * errcode_ret); + +#ifdef __cplusplus +} +#endif + +#endif /* __OPENCL_CL_EGL_H */ diff --git a/phonelibs/opencl/include/CL/cl_ext.h b/phonelibs/opencl/include/CL/cl_ext.h new file mode 100644 index 00000000000000..7941583895c57b --- /dev/null +++ b/phonelibs/opencl/include/CL/cl_ext.h @@ -0,0 +1,391 @@ +/******************************************************************************* + * Copyright (c) 2008-2015 The Khronos Group Inc. + * + * Permission is hereby granted, free of charge, to any person obtaining a + * copy of this software and/or associated documentation files (the + * "Materials"), to deal in the Materials without restriction, including + * without limitation the rights to use, copy, modify, merge, publish, + * distribute, sublicense, and/or sell copies of the Materials, and to + * permit persons to whom the Materials are furnished to do so, subject to + * the following conditions: + * + * The above copyright notice and this permission notice shall be included + * in all copies or substantial portions of the Materials. + * + * MODIFICATIONS TO THIS FILE MAY MEAN IT NO LONGER ACCURATELY REFLECTS + * KHRONOS STANDARDS. THE UNMODIFIED, NORMATIVE VERSIONS OF KHRONOS + * SPECIFICATIONS AND HEADER INFORMATION ARE LOCATED AT + * https://www.khronos.org/registry/ + * + * THE MATERIALS ARE PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, + * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. + * IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY + * CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, + * TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE + * MATERIALS OR THE USE OR OTHER DEALINGS IN THE MATERIALS. + ******************************************************************************/ + +/* $Revision: 11928 $ on $Date: 2010-07-13 09:04:56 -0700 (Tue, 13 Jul 2010) $ */ + +/* cl_ext.h contains OpenCL extensions which don't have external */ +/* (OpenGL, D3D) dependencies. */ + +#ifndef __CL_EXT_H +#define __CL_EXT_H + +#ifdef __cplusplus +extern "C" { +#endif + +#ifdef __APPLE__ + #include + #include +#else + #include +#endif + +/* cl_khr_fp16 extension - no extension #define since it has no functions */ +#define CL_DEVICE_HALF_FP_CONFIG 0x1033 + +/* Memory object destruction + * + * Apple extension for use to manage externally allocated buffers used with cl_mem objects with CL_MEM_USE_HOST_PTR + * + * Registers a user callback function that will be called when the memory object is deleted and its resources + * freed. Each call to clSetMemObjectCallbackFn registers the specified user callback function on a callback + * stack associated with memobj. The registered user callback functions are called in the reverse order in + * which they were registered. The user callback functions are called and then the memory object is deleted + * and its resources freed. This provides a mechanism for the application (and libraries) using memobj to be + * notified when the memory referenced by host_ptr, specified when the memory object is created and used as + * the storage bits for the memory object, can be reused or freed. + * + * The application may not call CL api's with the cl_mem object passed to the pfn_notify. + * + * Please check for the "cl_APPLE_SetMemObjectDestructor" extension using clGetDeviceInfo(CL_DEVICE_EXTENSIONS) + * before using. + */ +#define cl_APPLE_SetMemObjectDestructor 1 +cl_int CL_API_ENTRY clSetMemObjectDestructorAPPLE( cl_mem /* memobj */, + void (* /*pfn_notify*/)( cl_mem /* memobj */, void* /*user_data*/), + void * /*user_data */ ) CL_EXT_SUFFIX__VERSION_1_0; + + +/* Context Logging Functions + * + * The next three convenience functions are intended to be used as the pfn_notify parameter to clCreateContext(). + * Please check for the "cl_APPLE_ContextLoggingFunctions" extension using clGetDeviceInfo(CL_DEVICE_EXTENSIONS) + * before using. + * + * clLogMessagesToSystemLog fowards on all log messages to the Apple System Logger + */ +#define cl_APPLE_ContextLoggingFunctions 1 +extern void CL_API_ENTRY clLogMessagesToSystemLogAPPLE( const char * /* errstr */, + const void * /* private_info */, + size_t /* cb */, + void * /* user_data */ ) CL_EXT_SUFFIX__VERSION_1_0; + +/* clLogMessagesToStdout sends all log messages to the file descriptor stdout */ +extern void CL_API_ENTRY clLogMessagesToStdoutAPPLE( const char * /* errstr */, + const void * /* private_info */, + size_t /* cb */, + void * /* user_data */ ) CL_EXT_SUFFIX__VERSION_1_0; + +/* clLogMessagesToStderr sends all log messages to the file descriptor stderr */ +extern void CL_API_ENTRY clLogMessagesToStderrAPPLE( const char * /* errstr */, + const void * /* private_info */, + size_t /* cb */, + void * /* user_data */ ) CL_EXT_SUFFIX__VERSION_1_0; + + +/************************ +* cl_khr_icd extension * +************************/ +#define cl_khr_icd 1 + +/* cl_platform_info */ +#define CL_PLATFORM_ICD_SUFFIX_KHR 0x0920 + +/* Additional Error Codes */ +#define CL_PLATFORM_NOT_FOUND_KHR -1001 + +extern CL_API_ENTRY cl_int CL_API_CALL +clIcdGetPlatformIDsKHR(cl_uint /* num_entries */, + cl_platform_id * /* platforms */, + cl_uint * /* num_platforms */); + +typedef CL_API_ENTRY cl_int (CL_API_CALL *clIcdGetPlatformIDsKHR_fn)( + cl_uint /* num_entries */, + cl_platform_id * /* platforms */, + cl_uint * /* num_platforms */); + + +/* Extension: cl_khr_image2D_buffer + * + * This extension allows a 2D image to be created from a cl_mem buffer without a copy. + * The type associated with a 2D image created from a buffer in an OpenCL program is image2d_t. + * Both the sampler and sampler-less read_image built-in functions are supported for 2D images + * and 2D images created from a buffer. Similarly, the write_image built-ins are also supported + * for 2D images created from a buffer. + * + * When the 2D image from buffer is created, the client must specify the width, + * height, image format (i.e. channel order and channel data type) and optionally the row pitch + * + * The pitch specified must be a multiple of CL_DEVICE_IMAGE_PITCH_ALIGNMENT pixels. + * The base address of the buffer must be aligned to CL_DEVICE_IMAGE_BASE_ADDRESS_ALIGNMENT pixels. + */ + +/************************************* + * cl_khr_initalize_memory extension * + *************************************/ + +#define CL_CONTEXT_MEMORY_INITIALIZE_KHR 0x2030 + + +/************************************** + * cl_khr_terminate_context extension * + **************************************/ + +#define CL_DEVICE_TERMINATE_CAPABILITY_KHR 0x2031 +#define CL_CONTEXT_TERMINATE_KHR 0x2032 + +#define cl_khr_terminate_context 1 +extern CL_API_ENTRY cl_int CL_API_CALL clTerminateContextKHR(cl_context /* context */) CL_EXT_SUFFIX__VERSION_1_2; + +typedef CL_API_ENTRY cl_int (CL_API_CALL *clTerminateContextKHR_fn)(cl_context /* context */) CL_EXT_SUFFIX__VERSION_1_2; + + +/* + * Extension: cl_khr_spir + * + * This extension adds support to create an OpenCL program object from a + * Standard Portable Intermediate Representation (SPIR) instance + */ + +#define CL_DEVICE_SPIR_VERSIONS 0x40E0 +#define CL_PROGRAM_BINARY_TYPE_INTERMEDIATE 0x40E1 + + +/****************************************** +* cl_nv_device_attribute_query extension * +******************************************/ +/* cl_nv_device_attribute_query extension - no extension #define since it has no functions */ +#define CL_DEVICE_COMPUTE_CAPABILITY_MAJOR_NV 0x4000 +#define CL_DEVICE_COMPUTE_CAPABILITY_MINOR_NV 0x4001 +#define CL_DEVICE_REGISTERS_PER_BLOCK_NV 0x4002 +#define CL_DEVICE_WARP_SIZE_NV 0x4003 +#define CL_DEVICE_GPU_OVERLAP_NV 0x4004 +#define CL_DEVICE_KERNEL_EXEC_TIMEOUT_NV 0x4005 +#define CL_DEVICE_INTEGRATED_MEMORY_NV 0x4006 + +/********************************* +* cl_amd_device_attribute_query * +*********************************/ +#define CL_DEVICE_PROFILING_TIMER_OFFSET_AMD 0x4036 + +/********************************* +* cl_arm_printf extension +*********************************/ +#define CL_PRINTF_CALLBACK_ARM 0x40B0 +#define CL_PRINTF_BUFFERSIZE_ARM 0x40B1 + +#ifdef CL_VERSION_1_1 + /*********************************** + * cl_ext_device_fission extension * + ***********************************/ + #define cl_ext_device_fission 1 + + extern CL_API_ENTRY cl_int CL_API_CALL + clReleaseDeviceEXT( cl_device_id /*device*/ ) CL_EXT_SUFFIX__VERSION_1_1; + + typedef CL_API_ENTRY cl_int + (CL_API_CALL *clReleaseDeviceEXT_fn)( cl_device_id /*device*/ ) CL_EXT_SUFFIX__VERSION_1_1; + + extern CL_API_ENTRY cl_int CL_API_CALL + clRetainDeviceEXT( cl_device_id /*device*/ ) CL_EXT_SUFFIX__VERSION_1_1; + + typedef CL_API_ENTRY cl_int + (CL_API_CALL *clRetainDeviceEXT_fn)( cl_device_id /*device*/ ) CL_EXT_SUFFIX__VERSION_1_1; + + typedef cl_ulong cl_device_partition_property_ext; + extern CL_API_ENTRY cl_int CL_API_CALL + clCreateSubDevicesEXT( cl_device_id /*in_device*/, + const cl_device_partition_property_ext * /* properties */, + cl_uint /*num_entries*/, + cl_device_id * /*out_devices*/, + cl_uint * /*num_devices*/ ) CL_EXT_SUFFIX__VERSION_1_1; + + typedef CL_API_ENTRY cl_int + ( CL_API_CALL * clCreateSubDevicesEXT_fn)( cl_device_id /*in_device*/, + const cl_device_partition_property_ext * /* properties */, + cl_uint /*num_entries*/, + cl_device_id * /*out_devices*/, + cl_uint * /*num_devices*/ ) CL_EXT_SUFFIX__VERSION_1_1; + + /* cl_device_partition_property_ext */ + #define CL_DEVICE_PARTITION_EQUALLY_EXT 0x4050 + #define CL_DEVICE_PARTITION_BY_COUNTS_EXT 0x4051 + #define CL_DEVICE_PARTITION_BY_NAMES_EXT 0x4052 + #define CL_DEVICE_PARTITION_BY_AFFINITY_DOMAIN_EXT 0x4053 + + /* clDeviceGetInfo selectors */ + #define CL_DEVICE_PARENT_DEVICE_EXT 0x4054 + #define CL_DEVICE_PARTITION_TYPES_EXT 0x4055 + #define CL_DEVICE_AFFINITY_DOMAINS_EXT 0x4056 + #define CL_DEVICE_REFERENCE_COUNT_EXT 0x4057 + #define CL_DEVICE_PARTITION_STYLE_EXT 0x4058 + + /* error codes */ + #define CL_DEVICE_PARTITION_FAILED_EXT -1057 + #define CL_INVALID_PARTITION_COUNT_EXT -1058 + #define CL_INVALID_PARTITION_NAME_EXT -1059 + + /* CL_AFFINITY_DOMAINs */ + #define CL_AFFINITY_DOMAIN_L1_CACHE_EXT 0x1 + #define CL_AFFINITY_DOMAIN_L2_CACHE_EXT 0x2 + #define CL_AFFINITY_DOMAIN_L3_CACHE_EXT 0x3 + #define CL_AFFINITY_DOMAIN_L4_CACHE_EXT 0x4 + #define CL_AFFINITY_DOMAIN_NUMA_EXT 0x10 + #define CL_AFFINITY_DOMAIN_NEXT_FISSIONABLE_EXT 0x100 + + /* cl_device_partition_property_ext list terminators */ + #define CL_PROPERTIES_LIST_END_EXT ((cl_device_partition_property_ext) 0) + #define CL_PARTITION_BY_COUNTS_LIST_END_EXT ((cl_device_partition_property_ext) 0) + #define CL_PARTITION_BY_NAMES_LIST_END_EXT ((cl_device_partition_property_ext) 0 - 1) + +/********************************* +* cl_qcom_ext_host_ptr extension +*********************************/ + +#define CL_MEM_EXT_HOST_PTR_QCOM (1 << 29) + +#define CL_DEVICE_EXT_MEM_PADDING_IN_BYTES_QCOM 0x40A0 +#define CL_DEVICE_PAGE_SIZE_QCOM 0x40A1 +#define CL_IMAGE_ROW_ALIGNMENT_QCOM 0x40A2 +#define CL_IMAGE_SLICE_ALIGNMENT_QCOM 0x40A3 +#define CL_MEM_HOST_UNCACHED_QCOM 0x40A4 +#define CL_MEM_HOST_WRITEBACK_QCOM 0x40A5 +#define CL_MEM_HOST_WRITETHROUGH_QCOM 0x40A6 +#define CL_MEM_HOST_WRITE_COMBINING_QCOM 0x40A7 + +typedef cl_uint cl_image_pitch_info_qcom; + +extern CL_API_ENTRY cl_int CL_API_CALL +clGetDeviceImageInfoQCOM(cl_device_id device, + size_t image_width, + size_t image_height, + const cl_image_format *image_format, + cl_image_pitch_info_qcom param_name, + size_t param_value_size, + void *param_value, + size_t *param_value_size_ret); + +typedef struct _cl_mem_ext_host_ptr +{ + /* Type of external memory allocation. */ + /* Legal values will be defined in layered extensions. */ + cl_uint allocation_type; + + /* Host cache policy for this external memory allocation. */ + cl_uint host_cache_policy; + +} cl_mem_ext_host_ptr; + +/********************************* +* cl_qcom_ion_host_ptr extension +*********************************/ + +#define CL_MEM_ION_HOST_PTR_QCOM 0x40A8 + +typedef struct _cl_mem_ion_host_ptr +{ + /* Type of external memory allocation. */ + /* Must be CL_MEM_ION_HOST_PTR_QCOM for ION allocations. */ + cl_mem_ext_host_ptr ext_host_ptr; + + /* ION file descriptor */ + int ion_filedesc; + + /* Host pointer to the ION allocated memory */ + void* ion_hostptr; + +} cl_mem_ion_host_ptr; + +#endif /* CL_VERSION_1_1 */ + + +#ifdef CL_VERSION_2_0 +/********************************* +* cl_khr_sub_groups extension +*********************************/ +#define cl_khr_sub_groups 1 + +typedef cl_uint cl_kernel_sub_group_info_khr; + +/* cl_khr_sub_group_info */ +#define CL_KERNEL_MAX_SUB_GROUP_SIZE_FOR_NDRANGE_KHR 0x2033 +#define CL_KERNEL_SUB_GROUP_COUNT_FOR_NDRANGE_KHR 0x2034 + +extern CL_API_ENTRY cl_int CL_API_CALL +clGetKernelSubGroupInfoKHR(cl_kernel /* in_kernel */, + cl_device_id /*in_device*/, + cl_kernel_sub_group_info_khr /* param_name */, + size_t /*input_value_size*/, + const void * /*input_value*/, + size_t /*param_value_size*/, + void* /*param_value*/, + size_t* /*param_value_size_ret*/ ) CL_EXT_SUFFIX__VERSION_2_0_DEPRECATED; + +typedef CL_API_ENTRY cl_int + ( CL_API_CALL * clGetKernelSubGroupInfoKHR_fn)(cl_kernel /* in_kernel */, + cl_device_id /*in_device*/, + cl_kernel_sub_group_info_khr /* param_name */, + size_t /*input_value_size*/, + const void * /*input_value*/, + size_t /*param_value_size*/, + void* /*param_value*/, + size_t* /*param_value_size_ret*/ ) CL_EXT_SUFFIX__VERSION_2_0_DEPRECATED; +#endif /* CL_VERSION_2_0 */ + +#ifdef CL_VERSION_2_1 +/********************************* +* cl_khr_priority_hints extension +*********************************/ +#define cl_khr_priority_hints 1 + +typedef cl_uint cl_queue_priority_khr; + +/* cl_command_queue_properties */ +#define CL_QUEUE_PRIORITY_KHR 0x1096 + +/* cl_queue_priority_khr */ +#define CL_QUEUE_PRIORITY_HIGH_KHR (1<<0) +#define CL_QUEUE_PRIORITY_MED_KHR (1<<1) +#define CL_QUEUE_PRIORITY_LOW_KHR (1<<2) + +#endif /* CL_VERSION_2_1 */ + +#ifdef CL_VERSION_2_1 +/********************************* +* cl_khr_throttle_hints extension +*********************************/ +#define cl_khr_throttle_hints 1 + +typedef cl_uint cl_queue_throttle_khr; + +/* cl_command_queue_properties */ +#define CL_QUEUE_THROTTLE_KHR 0x1097 + +/* cl_queue_throttle_khr */ +#define CL_QUEUE_THROTTLE_HIGH_KHR (1<<0) +#define CL_QUEUE_THROTTLE_MED_KHR (1<<1) +#define CL_QUEUE_THROTTLE_LOW_KHR (1<<2) + +#endif /* CL_VERSION_2_1 */ + +#ifdef __cplusplus +} +#endif + + +#endif /* __CL_EXT_H */ diff --git a/phonelibs/opencl/include/CL/cl_gl.h b/phonelibs/opencl/include/CL/cl_gl.h new file mode 100644 index 00000000000000..945daa83d7f712 --- /dev/null +++ b/phonelibs/opencl/include/CL/cl_gl.h @@ -0,0 +1,167 @@ +/********************************************************************************** + * Copyright (c) 2008-2015 The Khronos Group Inc. + * + * Permission is hereby granted, free of charge, to any person obtaining a + * copy of this software and/or associated documentation files (the + * "Materials"), to deal in the Materials without restriction, including + * without limitation the rights to use, copy, modify, merge, publish, + * distribute, sublicense, and/or sell copies of the Materials, and to + * permit persons to whom the Materials are furnished to do so, subject to + * the following conditions: + * + * The above copyright notice and this permission notice shall be included + * in all copies or substantial portions of the Materials. + * + * MODIFICATIONS TO THIS FILE MAY MEAN IT NO LONGER ACCURATELY REFLECTS + * KHRONOS STANDARDS. THE UNMODIFIED, NORMATIVE VERSIONS OF KHRONOS + * SPECIFICATIONS AND HEADER INFORMATION ARE LOCATED AT + * https://www.khronos.org/registry/ + * + * THE MATERIALS ARE PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, + * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. + * IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY + * CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, + * TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE + * MATERIALS OR THE USE OR OTHER DEALINGS IN THE MATERIALS. + **********************************************************************************/ + +#ifndef __OPENCL_CL_GL_H +#define __OPENCL_CL_GL_H + +#ifdef __APPLE__ +#include +#else +#include +#endif + +#ifdef __cplusplus +extern "C" { +#endif + +typedef cl_uint cl_gl_object_type; +typedef cl_uint cl_gl_texture_info; +typedef cl_uint cl_gl_platform_info; +typedef struct __GLsync *cl_GLsync; + +/* cl_gl_object_type = 0x2000 - 0x200F enum values are currently taken */ +#define CL_GL_OBJECT_BUFFER 0x2000 +#define CL_GL_OBJECT_TEXTURE2D 0x2001 +#define CL_GL_OBJECT_TEXTURE3D 0x2002 +#define CL_GL_OBJECT_RENDERBUFFER 0x2003 +#define CL_GL_OBJECT_TEXTURE2D_ARRAY 0x200E +#define CL_GL_OBJECT_TEXTURE1D 0x200F +#define CL_GL_OBJECT_TEXTURE1D_ARRAY 0x2010 +#define CL_GL_OBJECT_TEXTURE_BUFFER 0x2011 + +/* cl_gl_texture_info */ +#define CL_GL_TEXTURE_TARGET 0x2004 +#define CL_GL_MIPMAP_LEVEL 0x2005 +#define CL_GL_NUM_SAMPLES 0x2012 + + +extern CL_API_ENTRY cl_mem CL_API_CALL +clCreateFromGLBuffer(cl_context /* context */, + cl_mem_flags /* flags */, + cl_GLuint /* bufobj */, + int * /* errcode_ret */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_mem CL_API_CALL +clCreateFromGLTexture(cl_context /* context */, + cl_mem_flags /* flags */, + cl_GLenum /* target */, + cl_GLint /* miplevel */, + cl_GLuint /* texture */, + cl_int * /* errcode_ret */) CL_API_SUFFIX__VERSION_1_2; + +extern CL_API_ENTRY cl_mem CL_API_CALL +clCreateFromGLRenderbuffer(cl_context /* context */, + cl_mem_flags /* flags */, + cl_GLuint /* renderbuffer */, + cl_int * /* errcode_ret */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clGetGLObjectInfo(cl_mem /* memobj */, + cl_gl_object_type * /* gl_object_type */, + cl_GLuint * /* gl_object_name */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clGetGLTextureInfo(cl_mem /* memobj */, + cl_gl_texture_info /* param_name */, + size_t /* param_value_size */, + void * /* param_value */, + size_t * /* param_value_size_ret */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clEnqueueAcquireGLObjects(cl_command_queue /* command_queue */, + cl_uint /* num_objects */, + const cl_mem * /* mem_objects */, + cl_uint /* num_events_in_wait_list */, + const cl_event * /* event_wait_list */, + cl_event * /* event */) CL_API_SUFFIX__VERSION_1_0; + +extern CL_API_ENTRY cl_int CL_API_CALL +clEnqueueReleaseGLObjects(cl_command_queue /* command_queue */, + cl_uint /* num_objects */, + const cl_mem * /* mem_objects */, + cl_uint /* num_events_in_wait_list */, + const cl_event * /* event_wait_list */, + cl_event * /* event */) CL_API_SUFFIX__VERSION_1_0; + + +/* Deprecated OpenCL 1.1 APIs */ +extern CL_API_ENTRY CL_EXT_PREFIX__VERSION_1_1_DEPRECATED cl_mem CL_API_CALL +clCreateFromGLTexture2D(cl_context /* context */, + cl_mem_flags /* flags */, + cl_GLenum /* target */, + cl_GLint /* miplevel */, + cl_GLuint /* texture */, + cl_int * /* errcode_ret */) CL_EXT_SUFFIX__VERSION_1_1_DEPRECATED; + +extern CL_API_ENTRY CL_EXT_PREFIX__VERSION_1_1_DEPRECATED cl_mem CL_API_CALL +clCreateFromGLTexture3D(cl_context /* context */, + cl_mem_flags /* flags */, + cl_GLenum /* target */, + cl_GLint /* miplevel */, + cl_GLuint /* texture */, + cl_int * /* errcode_ret */) CL_EXT_SUFFIX__VERSION_1_1_DEPRECATED; + +/* cl_khr_gl_sharing extension */ + +#define cl_khr_gl_sharing 1 + +typedef cl_uint cl_gl_context_info; + +/* Additional Error Codes */ +#define CL_INVALID_GL_SHAREGROUP_REFERENCE_KHR -1000 + +/* cl_gl_context_info */ +#define CL_CURRENT_DEVICE_FOR_GL_CONTEXT_KHR 0x2006 +#define CL_DEVICES_FOR_GL_CONTEXT_KHR 0x2007 + +/* Additional cl_context_properties */ +#define CL_GL_CONTEXT_KHR 0x2008 +#define CL_EGL_DISPLAY_KHR 0x2009 +#define CL_GLX_DISPLAY_KHR 0x200A +#define CL_WGL_HDC_KHR 0x200B +#define CL_CGL_SHAREGROUP_KHR 0x200C + +extern CL_API_ENTRY cl_int CL_API_CALL +clGetGLContextInfoKHR(const cl_context_properties * /* properties */, + cl_gl_context_info /* param_name */, + size_t /* param_value_size */, + void * /* param_value */, + size_t * /* param_value_size_ret */) CL_API_SUFFIX__VERSION_1_0; + +typedef CL_API_ENTRY cl_int (CL_API_CALL *clGetGLContextInfoKHR_fn)( + const cl_context_properties * properties, + cl_gl_context_info param_name, + size_t param_value_size, + void * param_value, + size_t * param_value_size_ret); + +#ifdef __cplusplus +} +#endif + +#endif /* __OPENCL_CL_GL_H */ diff --git a/phonelibs/opencl/include/CL/cl_gl_ext.h b/phonelibs/opencl/include/CL/cl_gl_ext.h new file mode 100644 index 00000000000000..e3c14c6408c441 --- /dev/null +++ b/phonelibs/opencl/include/CL/cl_gl_ext.h @@ -0,0 +1,74 @@ +/********************************************************************************** + * Copyright (c) 2008-2015 The Khronos Group Inc. + * + * Permission is hereby granted, free of charge, to any person obtaining a + * copy of this software and/or associated documentation files (the + * "Materials"), to deal in the Materials without restriction, including + * without limitation the rights to use, copy, modify, merge, publish, + * distribute, sublicense, and/or sell copies of the Materials, and to + * permit persons to whom the Materials are furnished to do so, subject to + * the following conditions: + * + * The above copyright notice and this permission notice shall be included + * in all copies or substantial portions of the Materials. + * + * MODIFICATIONS TO THIS FILE MAY MEAN IT NO LONGER ACCURATELY REFLECTS + * KHRONOS STANDARDS. THE UNMODIFIED, NORMATIVE VERSIONS OF KHRONOS + * SPECIFICATIONS AND HEADER INFORMATION ARE LOCATED AT + * https://www.khronos.org/registry/ + * + * THE MATERIALS ARE PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, + * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. + * IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY + * CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, + * TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE + * MATERIALS OR THE USE OR OTHER DEALINGS IN THE MATERIALS. + **********************************************************************************/ + +/* $Revision: 11708 $ on $Date: 2010-06-13 23:36:24 -0700 (Sun, 13 Jun 2010) $ */ + +/* cl_gl_ext.h contains vendor (non-KHR) OpenCL extensions which have */ +/* OpenGL dependencies. */ + +#ifndef __OPENCL_CL_GL_EXT_H +#define __OPENCL_CL_GL_EXT_H + +#ifdef __cplusplus +extern "C" { +#endif + +#ifdef __APPLE__ + #include +#else + #include +#endif + +/* + * For each extension, follow this template + * cl_VEN_extname extension */ +/* #define cl_VEN_extname 1 + * ... define new types, if any + * ... define new tokens, if any + * ... define new APIs, if any + * + * If you need GLtypes here, mirror them with a cl_GLtype, rather than including a GL header + * This allows us to avoid having to decide whether to include GL headers or GLES here. + */ + +/* + * cl_khr_gl_event extension + * See section 9.9 in the OpenCL 1.1 spec for more information + */ +#define CL_COMMAND_GL_FENCE_SYNC_OBJECT_KHR 0x200D + +extern CL_API_ENTRY cl_event CL_API_CALL +clCreateEventFromGLsyncKHR(cl_context /* context */, + cl_GLsync /* cl_GLsync */, + cl_int * /* errcode_ret */) CL_EXT_SUFFIX__VERSION_1_1; + +#ifdef __cplusplus +} +#endif + +#endif /* __OPENCL_CL_GL_EXT_H */ diff --git a/phonelibs/opencl/include/CL/cl_platform.h b/phonelibs/opencl/include/CL/cl_platform.h new file mode 100644 index 00000000000000..4e334a2918390d --- /dev/null +++ b/phonelibs/opencl/include/CL/cl_platform.h @@ -0,0 +1,1333 @@ +/********************************************************************************** + * Copyright (c) 2008-2015 The Khronos Group Inc. + * + * Permission is hereby granted, free of charge, to any person obtaining a + * copy of this software and/or associated documentation files (the + * "Materials"), to deal in the Materials without restriction, including + * without limitation the rights to use, copy, modify, merge, publish, + * distribute, sublicense, and/or sell copies of the Materials, and to + * permit persons to whom the Materials are furnished to do so, subject to + * the following conditions: + * + * The above copyright notice and this permission notice shall be included + * in all copies or substantial portions of the Materials. + * + * MODIFICATIONS TO THIS FILE MAY MEAN IT NO LONGER ACCURATELY REFLECTS + * KHRONOS STANDARDS. THE UNMODIFIED, NORMATIVE VERSIONS OF KHRONOS + * SPECIFICATIONS AND HEADER INFORMATION ARE LOCATED AT + * https://www.khronos.org/registry/ + * + * THE MATERIALS ARE PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, + * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. + * IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY + * CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, + * TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE + * MATERIALS OR THE USE OR OTHER DEALINGS IN THE MATERIALS. + **********************************************************************************/ + +/* $Revision: 11803 $ on $Date: 2010-06-25 10:02:12 -0700 (Fri, 25 Jun 2010) $ */ + +#ifndef __CL_PLATFORM_H +#define __CL_PLATFORM_H + +#ifdef __APPLE__ + /* Contains #defines for AVAILABLE_MAC_OS_X_VERSION_10_6_AND_LATER below */ + #include +#endif + +#ifdef __cplusplus +extern "C" { +#endif + +#if defined(_WIN32) + #define CL_API_ENTRY + #define CL_API_CALL __stdcall + #define CL_CALLBACK __stdcall +#else + #define CL_API_ENTRY + #define CL_API_CALL + #define CL_CALLBACK +#endif + +/* + * Deprecation flags refer to the last version of the header in which the + * feature was not deprecated. + * + * E.g. VERSION_1_1_DEPRECATED means the feature is present in 1.1 without + * deprecation but is deprecated in versions later than 1.1. + */ + +#ifdef __APPLE__ + #define CL_EXTENSION_WEAK_LINK __attribute__((weak_import)) + #define CL_API_SUFFIX__VERSION_1_0 AVAILABLE_MAC_OS_X_VERSION_10_6_AND_LATER + #define CL_EXT_SUFFIX__VERSION_1_0 CL_EXTENSION_WEAK_LINK AVAILABLE_MAC_OS_X_VERSION_10_6_AND_LATER + #define CL_API_SUFFIX__VERSION_1_1 AVAILABLE_MAC_OS_X_VERSION_10_7_AND_LATER + #define GCL_API_SUFFIX__VERSION_1_1 AVAILABLE_MAC_OS_X_VERSION_10_7_AND_LATER + #define CL_EXT_SUFFIX__VERSION_1_1 CL_EXTENSION_WEAK_LINK AVAILABLE_MAC_OS_X_VERSION_10_7_AND_LATER + #define CL_EXT_SUFFIX__VERSION_1_0_DEPRECATED CL_EXTENSION_WEAK_LINK AVAILABLE_MAC_OS_X_VERSION_10_6_AND_LATER_BUT_DEPRECATED_IN_MAC_OS_X_VERSION_10_7 + + #ifdef AVAILABLE_MAC_OS_X_VERSION_10_8_AND_LATER + #define CL_API_SUFFIX__VERSION_1_2 AVAILABLE_MAC_OS_X_VERSION_10_8_AND_LATER + #define GCL_API_SUFFIX__VERSION_1_2 AVAILABLE_MAC_OS_X_VERSION_10_8_AND_LATER + #define CL_EXT_SUFFIX__VERSION_1_2 CL_EXTENSION_WEAK_LINK AVAILABLE_MAC_OS_X_VERSION_10_8_AND_LATER + #define CL_EXT_PREFIX__VERSION_1_1_DEPRECATED + #define CL_EXT_SUFFIX__VERSION_1_1_DEPRECATED CL_EXTENSION_WEAK_LINK AVAILABLE_MAC_OS_X_VERSION_10_7_AND_LATER_BUT_DEPRECATED_IN_MAC_OS_X_VERSION_10_8 + #else + #warning This path should never happen outside of internal operating system development. AvailabilityMacros do not function correctly here! + #define CL_API_SUFFIX__VERSION_1_2 AVAILABLE_MAC_OS_X_VERSION_10_7_AND_LATER + #define GCL_API_SUFFIX__VERSION_1_2 AVAILABLE_MAC_OS_X_VERSION_10_7_AND_LATER + #define CL_EXT_SUFFIX__VERSION_1_2 CL_EXTENSION_WEAK_LINK AVAILABLE_MAC_OS_X_VERSION_10_7_AND_LATER + #define CL_EXT_SUFFIX__VERSION_1_1_DEPRECATED CL_EXTENSION_WEAK_LINK AVAILABLE_MAC_OS_X_VERSION_10_7_AND_LATER + #endif +#else + #define CL_EXTENSION_WEAK_LINK + #define CL_API_SUFFIX__VERSION_1_0 + #define CL_EXT_SUFFIX__VERSION_1_0 + #define CL_API_SUFFIX__VERSION_1_1 + #define CL_EXT_SUFFIX__VERSION_1_1 + #define CL_API_SUFFIX__VERSION_1_2 + #define CL_EXT_SUFFIX__VERSION_1_2 + #define CL_API_SUFFIX__VERSION_2_0 + #define CL_EXT_SUFFIX__VERSION_2_0 + #define CL_API_SUFFIX__VERSION_2_1 + #define CL_EXT_SUFFIX__VERSION_2_1 + + #ifdef __GNUC__ + #ifdef CL_USE_DEPRECATED_OPENCL_1_0_APIS + #define CL_EXT_SUFFIX__VERSION_1_0_DEPRECATED + #define CL_EXT_PREFIX__VERSION_1_0_DEPRECATED + #else + #define CL_EXT_SUFFIX__VERSION_1_0_DEPRECATED __attribute__((deprecated)) + #define CL_EXT_PREFIX__VERSION_1_0_DEPRECATED + #endif + + #ifdef CL_USE_DEPRECATED_OPENCL_1_1_APIS + #define CL_EXT_SUFFIX__VERSION_1_1_DEPRECATED + #define CL_EXT_PREFIX__VERSION_1_1_DEPRECATED + #else + #define CL_EXT_SUFFIX__VERSION_1_1_DEPRECATED __attribute__((deprecated)) + #define CL_EXT_PREFIX__VERSION_1_1_DEPRECATED + #endif + + #ifdef CL_USE_DEPRECATED_OPENCL_1_2_APIS + #define CL_EXT_SUFFIX__VERSION_1_2_DEPRECATED + #define CL_EXT_PREFIX__VERSION_1_2_DEPRECATED + #else + #define CL_EXT_SUFFIX__VERSION_1_2_DEPRECATED __attribute__((deprecated)) + #define CL_EXT_PREFIX__VERSION_1_2_DEPRECATED + #endif + + #ifdef CL_USE_DEPRECATED_OPENCL_2_0_APIS + #define CL_EXT_SUFFIX__VERSION_2_0_DEPRECATED + #define CL_EXT_PREFIX__VERSION_2_0_DEPRECATED + #else + #define CL_EXT_SUFFIX__VERSION_2_0_DEPRECATED __attribute__((deprecated)) + #define CL_EXT_PREFIX__VERSION_2_0_DEPRECATED + #endif + #elif _WIN32 + #ifdef CL_USE_DEPRECATED_OPENCL_1_0_APIS + #define CL_EXT_SUFFIX__VERSION_1_0_DEPRECATED + #define CL_EXT_PREFIX__VERSION_1_0_DEPRECATED + #else + #define CL_EXT_SUFFIX__VERSION_1_0_DEPRECATED + #define CL_EXT_PREFIX__VERSION_1_0_DEPRECATED __declspec(deprecated) + #endif + + #ifdef CL_USE_DEPRECATED_OPENCL_1_1_APIS + #define CL_EXT_SUFFIX__VERSION_1_1_DEPRECATED + #define CL_EXT_PREFIX__VERSION_1_1_DEPRECATED + #else + #define CL_EXT_SUFFIX__VERSION_1_1_DEPRECATED + #define CL_EXT_PREFIX__VERSION_1_1_DEPRECATED __declspec(deprecated) + #endif + + #ifdef CL_USE_DEPRECATED_OPENCL_1_2_APIS + #define CL_EXT_SUFFIX__VERSION_1_2_DEPRECATED + #define CL_EXT_PREFIX__VERSION_1_2_DEPRECATED + #else + #define CL_EXT_SUFFIX__VERSION_1_2_DEPRECATED + #define CL_EXT_PREFIX__VERSION_1_2_DEPRECATED __declspec(deprecated) + #endif + + #ifdef CL_USE_DEPRECATED_OPENCL_2_0_APIS + #define CL_EXT_SUFFIX__VERSION_2_0_DEPRECATED + #define CL_EXT_PREFIX__VERSION_2_0_DEPRECATED + #else + #define CL_EXT_SUFFIX__VERSION_2_0_DEPRECATED + #define CL_EXT_PREFIX__VERSION_2_0_DEPRECATED __declspec(deprecated) + #endif + #else + #define CL_EXT_SUFFIX__VERSION_1_0_DEPRECATED + #define CL_EXT_PREFIX__VERSION_1_0_DEPRECATED + + #define CL_EXT_SUFFIX__VERSION_1_1_DEPRECATED + #define CL_EXT_PREFIX__VERSION_1_1_DEPRECATED + + #define CL_EXT_SUFFIX__VERSION_1_2_DEPRECATED + #define CL_EXT_PREFIX__VERSION_1_2_DEPRECATED + + #define CL_EXT_SUFFIX__VERSION_2_0_DEPRECATED + #define CL_EXT_PREFIX__VERSION_2_0_DEPRECATED + #endif +#endif + +#if (defined (_WIN32) && defined(_MSC_VER)) + +/* scalar types */ +typedef signed __int8 cl_char; +typedef unsigned __int8 cl_uchar; +typedef signed __int16 cl_short; +typedef unsigned __int16 cl_ushort; +typedef signed __int32 cl_int; +typedef unsigned __int32 cl_uint; +typedef signed __int64 cl_long; +typedef unsigned __int64 cl_ulong; + +typedef unsigned __int16 cl_half; +typedef float cl_float; +typedef double cl_double; + +/* Macro names and corresponding values defined by OpenCL */ +#define CL_CHAR_BIT 8 +#define CL_SCHAR_MAX 127 +#define CL_SCHAR_MIN (-127-1) +#define CL_CHAR_MAX CL_SCHAR_MAX +#define CL_CHAR_MIN CL_SCHAR_MIN +#define CL_UCHAR_MAX 255 +#define CL_SHRT_MAX 32767 +#define CL_SHRT_MIN (-32767-1) +#define CL_USHRT_MAX 65535 +#define CL_INT_MAX 2147483647 +#define CL_INT_MIN (-2147483647-1) +#define CL_UINT_MAX 0xffffffffU +#define CL_LONG_MAX ((cl_long) 0x7FFFFFFFFFFFFFFFLL) +#define CL_LONG_MIN ((cl_long) -0x7FFFFFFFFFFFFFFFLL - 1LL) +#define CL_ULONG_MAX ((cl_ulong) 0xFFFFFFFFFFFFFFFFULL) + +#define CL_FLT_DIG 6 +#define CL_FLT_MANT_DIG 24 +#define CL_FLT_MAX_10_EXP +38 +#define CL_FLT_MAX_EXP +128 +#define CL_FLT_MIN_10_EXP -37 +#define CL_FLT_MIN_EXP -125 +#define CL_FLT_RADIX 2 +#define CL_FLT_MAX 340282346638528859811704183484516925440.0f +#define CL_FLT_MIN 1.175494350822287507969e-38f +#define CL_FLT_EPSILON 0x1.0p-23f + +#define CL_DBL_DIG 15 +#define CL_DBL_MANT_DIG 53 +#define CL_DBL_MAX_10_EXP +308 +#define CL_DBL_MAX_EXP +1024 +#define CL_DBL_MIN_10_EXP -307 +#define CL_DBL_MIN_EXP -1021 +#define CL_DBL_RADIX 2 +#define CL_DBL_MAX 179769313486231570814527423731704356798070567525844996598917476803157260780028538760589558632766878171540458953514382464234321326889464182768467546703537516986049910576551282076245490090389328944075868508455133942304583236903222948165808559332123348274797826204144723168738177180919299881250404026184124858368.0 +#define CL_DBL_MIN 2.225073858507201383090e-308 +#define CL_DBL_EPSILON 2.220446049250313080847e-16 + +#define CL_M_E 2.718281828459045090796 +#define CL_M_LOG2E 1.442695040888963387005 +#define CL_M_LOG10E 0.434294481903251816668 +#define CL_M_LN2 0.693147180559945286227 +#define CL_M_LN10 2.302585092994045901094 +#define CL_M_PI 3.141592653589793115998 +#define CL_M_PI_2 1.570796326794896557999 +#define CL_M_PI_4 0.785398163397448278999 +#define CL_M_1_PI 0.318309886183790691216 +#define CL_M_2_PI 0.636619772367581382433 +#define CL_M_2_SQRTPI 1.128379167095512558561 +#define CL_M_SQRT2 1.414213562373095145475 +#define CL_M_SQRT1_2 0.707106781186547572737 + +#define CL_M_E_F 2.71828174591064f +#define CL_M_LOG2E_F 1.44269502162933f +#define CL_M_LOG10E_F 0.43429449200630f +#define CL_M_LN2_F 0.69314718246460f +#define CL_M_LN10_F 2.30258512496948f +#define CL_M_PI_F 3.14159274101257f +#define CL_M_PI_2_F 1.57079637050629f +#define CL_M_PI_4_F 0.78539818525314f +#define CL_M_1_PI_F 0.31830987334251f +#define CL_M_2_PI_F 0.63661974668503f +#define CL_M_2_SQRTPI_F 1.12837922573090f +#define CL_M_SQRT2_F 1.41421353816986f +#define CL_M_SQRT1_2_F 0.70710676908493f + +#define CL_NAN (CL_INFINITY - CL_INFINITY) +#define CL_HUGE_VALF ((cl_float) 1e50) +#define CL_HUGE_VAL ((cl_double) 1e500) +#define CL_MAXFLOAT CL_FLT_MAX +#define CL_INFINITY CL_HUGE_VALF + +#else + +#include + +/* scalar types */ +typedef int8_t cl_char; +typedef uint8_t cl_uchar; +typedef int16_t cl_short __attribute__((aligned(2))); +typedef uint16_t cl_ushort __attribute__((aligned(2))); +typedef int32_t cl_int __attribute__((aligned(4))); +typedef uint32_t cl_uint __attribute__((aligned(4))); +typedef int64_t cl_long __attribute__((aligned(8))); +typedef uint64_t cl_ulong __attribute__((aligned(8))); + +typedef uint16_t cl_half __attribute__((aligned(2))); +typedef float cl_float __attribute__((aligned(4))); +typedef double cl_double __attribute__((aligned(8))); + +/* Macro names and corresponding values defined by OpenCL */ +#define CL_CHAR_BIT 8 +#define CL_SCHAR_MAX 127 +#define CL_SCHAR_MIN (-127-1) +#define CL_CHAR_MAX CL_SCHAR_MAX +#define CL_CHAR_MIN CL_SCHAR_MIN +#define CL_UCHAR_MAX 255 +#define CL_SHRT_MAX 32767 +#define CL_SHRT_MIN (-32767-1) +#define CL_USHRT_MAX 65535 +#define CL_INT_MAX 2147483647 +#define CL_INT_MIN (-2147483647-1) +#define CL_UINT_MAX 0xffffffffU +#define CL_LONG_MAX ((cl_long) 0x7FFFFFFFFFFFFFFFLL) +#define CL_LONG_MIN ((cl_long) -0x7FFFFFFFFFFFFFFFLL - 1LL) +#define CL_ULONG_MAX ((cl_ulong) 0xFFFFFFFFFFFFFFFFULL) + +#define CL_FLT_DIG 6 +#define CL_FLT_MANT_DIG 24 +#define CL_FLT_MAX_10_EXP +38 +#define CL_FLT_MAX_EXP +128 +#define CL_FLT_MIN_10_EXP -37 +#define CL_FLT_MIN_EXP -125 +#define CL_FLT_RADIX 2 +#define CL_FLT_MAX 0x1.fffffep127f +#define CL_FLT_MIN 0x1.0p-126f +#define CL_FLT_EPSILON 0x1.0p-23f + +#define CL_DBL_DIG 15 +#define CL_DBL_MANT_DIG 53 +#define CL_DBL_MAX_10_EXP +308 +#define CL_DBL_MAX_EXP +1024 +#define CL_DBL_MIN_10_EXP -307 +#define CL_DBL_MIN_EXP -1021 +#define CL_DBL_RADIX 2 +#define CL_DBL_MAX 0x1.fffffffffffffp1023 +#define CL_DBL_MIN 0x1.0p-1022 +#define CL_DBL_EPSILON 0x1.0p-52 + +#define CL_M_E 2.718281828459045090796 +#define CL_M_LOG2E 1.442695040888963387005 +#define CL_M_LOG10E 0.434294481903251816668 +#define CL_M_LN2 0.693147180559945286227 +#define CL_M_LN10 2.302585092994045901094 +#define CL_M_PI 3.141592653589793115998 +#define CL_M_PI_2 1.570796326794896557999 +#define CL_M_PI_4 0.785398163397448278999 +#define CL_M_1_PI 0.318309886183790691216 +#define CL_M_2_PI 0.636619772367581382433 +#define CL_M_2_SQRTPI 1.128379167095512558561 +#define CL_M_SQRT2 1.414213562373095145475 +#define CL_M_SQRT1_2 0.707106781186547572737 + +#define CL_M_E_F 2.71828174591064f +#define CL_M_LOG2E_F 1.44269502162933f +#define CL_M_LOG10E_F 0.43429449200630f +#define CL_M_LN2_F 0.69314718246460f +#define CL_M_LN10_F 2.30258512496948f +#define CL_M_PI_F 3.14159274101257f +#define CL_M_PI_2_F 1.57079637050629f +#define CL_M_PI_4_F 0.78539818525314f +#define CL_M_1_PI_F 0.31830987334251f +#define CL_M_2_PI_F 0.63661974668503f +#define CL_M_2_SQRTPI_F 1.12837922573090f +#define CL_M_SQRT2_F 1.41421353816986f +#define CL_M_SQRT1_2_F 0.70710676908493f + +#if defined( __GNUC__ ) + #define CL_HUGE_VALF __builtin_huge_valf() + #define CL_HUGE_VAL __builtin_huge_val() + #define CL_NAN __builtin_nanf( "" ) +#else + #define CL_HUGE_VALF ((cl_float) 1e50) + #define CL_HUGE_VAL ((cl_double) 1e500) + float nanf( const char * ); + #define CL_NAN nanf( "" ) +#endif +#define CL_MAXFLOAT CL_FLT_MAX +#define CL_INFINITY CL_HUGE_VALF + +#endif + +#include + +/* Mirror types to GL types. Mirror types allow us to avoid deciding which 87s to load based on whether we are using GL or GLES here. */ +typedef unsigned int cl_GLuint; +typedef int cl_GLint; +typedef unsigned int cl_GLenum; + +/* + * Vector types + * + * Note: OpenCL requires that all types be naturally aligned. + * This means that vector types must be naturally aligned. + * For example, a vector of four floats must be aligned to + * a 16 byte boundary (calculated as 4 * the natural 4-byte + * alignment of the float). The alignment qualifiers here + * will only function properly if your compiler supports them + * and if you don't actively work to defeat them. For example, + * in order for a cl_float4 to be 16 byte aligned in a struct, + * the start of the struct must itself be 16-byte aligned. + * + * Maintaining proper alignment is the user's responsibility. + */ + +/* Define basic vector types */ +#if defined( __VEC__ ) + #include /* may be omitted depending on compiler. AltiVec spec provides no way to detect whether the header is required. */ + typedef vector unsigned char __cl_uchar16; + typedef vector signed char __cl_char16; + typedef vector unsigned short __cl_ushort8; + typedef vector signed short __cl_short8; + typedef vector unsigned int __cl_uint4; + typedef vector signed int __cl_int4; + typedef vector float __cl_float4; + #define __CL_UCHAR16__ 1 + #define __CL_CHAR16__ 1 + #define __CL_USHORT8__ 1 + #define __CL_SHORT8__ 1 + #define __CL_UINT4__ 1 + #define __CL_INT4__ 1 + #define __CL_FLOAT4__ 1 +#endif + +#if defined( __SSE__ ) + #if defined( __MINGW64__ ) + #include + #else + #include + #endif + #if defined( __GNUC__ ) + typedef float __cl_float4 __attribute__((vector_size(16))); + #else + typedef __m128 __cl_float4; + #endif + #define __CL_FLOAT4__ 1 +#endif + +#if defined( __SSE2__ ) + #if defined( __MINGW64__ ) + #include + #else + #include + #endif + #if defined( __GNUC__ ) + typedef cl_uchar __cl_uchar16 __attribute__((vector_size(16))); + typedef cl_char __cl_char16 __attribute__((vector_size(16))); + typedef cl_ushort __cl_ushort8 __attribute__((vector_size(16))); + typedef cl_short __cl_short8 __attribute__((vector_size(16))); + typedef cl_uint __cl_uint4 __attribute__((vector_size(16))); + typedef cl_int __cl_int4 __attribute__((vector_size(16))); + typedef cl_ulong __cl_ulong2 __attribute__((vector_size(16))); + typedef cl_long __cl_long2 __attribute__((vector_size(16))); + typedef cl_double __cl_double2 __attribute__((vector_size(16))); + #else + typedef __m128i __cl_uchar16; + typedef __m128i __cl_char16; + typedef __m128i __cl_ushort8; + typedef __m128i __cl_short8; + typedef __m128i __cl_uint4; + typedef __m128i __cl_int4; + typedef __m128i __cl_ulong2; + typedef __m128i __cl_long2; + typedef __m128d __cl_double2; + #endif + #define __CL_UCHAR16__ 1 + #define __CL_CHAR16__ 1 + #define __CL_USHORT8__ 1 + #define __CL_SHORT8__ 1 + #define __CL_INT4__ 1 + #define __CL_UINT4__ 1 + #define __CL_ULONG2__ 1 + #define __CL_LONG2__ 1 + #define __CL_DOUBLE2__ 1 +#endif + +#if defined( __MMX__ ) + #include + #if defined( __GNUC__ ) + typedef cl_uchar __cl_uchar8 __attribute__((vector_size(8))); + typedef cl_char __cl_char8 __attribute__((vector_size(8))); + typedef cl_ushort __cl_ushort4 __attribute__((vector_size(8))); + typedef cl_short __cl_short4 __attribute__((vector_size(8))); + typedef cl_uint __cl_uint2 __attribute__((vector_size(8))); + typedef cl_int __cl_int2 __attribute__((vector_size(8))); + typedef cl_ulong __cl_ulong1 __attribute__((vector_size(8))); + typedef cl_long __cl_long1 __attribute__((vector_size(8))); + typedef cl_float __cl_float2 __attribute__((vector_size(8))); + #else + typedef __m64 __cl_uchar8; + typedef __m64 __cl_char8; + typedef __m64 __cl_ushort4; + typedef __m64 __cl_short4; + typedef __m64 __cl_uint2; + typedef __m64 __cl_int2; + typedef __m64 __cl_ulong1; + typedef __m64 __cl_long1; + typedef __m64 __cl_float2; + #endif + #define __CL_UCHAR8__ 1 + #define __CL_CHAR8__ 1 + #define __CL_USHORT4__ 1 + #define __CL_SHORT4__ 1 + #define __CL_INT2__ 1 + #define __CL_UINT2__ 1 + #define __CL_ULONG1__ 1 + #define __CL_LONG1__ 1 + #define __CL_FLOAT2__ 1 +#endif + +#if defined( __AVX__ ) + #if defined( __MINGW64__ ) + #include + #else + #include + #endif + #if defined( __GNUC__ ) + typedef cl_float __cl_float8 __attribute__((vector_size(32))); + typedef cl_double __cl_double4 __attribute__((vector_size(32))); + #else + typedef __m256 __cl_float8; + typedef __m256d __cl_double4; + #endif + #define __CL_FLOAT8__ 1 + #define __CL_DOUBLE4__ 1 +#endif + +/* Define capabilities for anonymous struct members. */ +#if defined( __GNUC__) && ! defined( __STRICT_ANSI__ ) +#define __CL_HAS_ANON_STRUCT__ 1 +#define __CL_ANON_STRUCT__ __extension__ +#elif defined( _WIN32) && (_MSC_VER >= 1500) + /* Microsoft Developer Studio 2008 supports anonymous structs, but + * complains by default. */ +#define __CL_HAS_ANON_STRUCT__ 1 +#define __CL_ANON_STRUCT__ + /* Disable warning C4201: nonstandard extension used : nameless + * struct/union */ +#pragma warning( push ) +#pragma warning( disable : 4201 ) +#else +#define __CL_HAS_ANON_STRUCT__ 0 +#define __CL_ANON_STRUCT__ +#endif + +/* Define alignment keys */ +#if defined( __GNUC__ ) + #define CL_ALIGNED(_x) __attribute__ ((aligned(_x))) +#elif defined( _WIN32) && (_MSC_VER) + /* Alignment keys neutered on windows because MSVC can't swallow function arguments with alignment requirements */ + /* http://msdn.microsoft.com/en-us/library/373ak2y1%28VS.71%29.aspx */ + /* #include */ + /* #define CL_ALIGNED(_x) _CRT_ALIGN(_x) */ + #define CL_ALIGNED(_x) +#else + #warning Need to implement some method to align data here + #define CL_ALIGNED(_x) +#endif + +/* Indicate whether .xyzw, .s0123 and .hi.lo are supported */ +#if __CL_HAS_ANON_STRUCT__ + /* .xyzw and .s0123...{f|F} are supported */ + #define CL_HAS_NAMED_VECTOR_FIELDS 1 + /* .hi and .lo are supported */ + #define CL_HAS_HI_LO_VECTOR_FIELDS 1 +#endif + +/* Define cl_vector types */ + +/* ---- cl_charn ---- */ +typedef union +{ + cl_char CL_ALIGNED(2) s[2]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_char x, y; }; + __CL_ANON_STRUCT__ struct{ cl_char s0, s1; }; + __CL_ANON_STRUCT__ struct{ cl_char lo, hi; }; +#endif +#if defined( __CL_CHAR2__) + __cl_char2 v2; +#endif +}cl_char2; + +typedef union +{ + cl_char CL_ALIGNED(4) s[4]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_char x, y, z, w; }; + __CL_ANON_STRUCT__ struct{ cl_char s0, s1, s2, s3; }; + __CL_ANON_STRUCT__ struct{ cl_char2 lo, hi; }; +#endif +#if defined( __CL_CHAR2__) + __cl_char2 v2[2]; +#endif +#if defined( __CL_CHAR4__) + __cl_char4 v4; +#endif +}cl_char4; + +/* cl_char3 is identical in size, alignment and behavior to cl_char4. See section 6.1.5. */ +typedef cl_char4 cl_char3; + +typedef union +{ + cl_char CL_ALIGNED(8) s[8]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_char x, y, z, w; }; + __CL_ANON_STRUCT__ struct{ cl_char s0, s1, s2, s3, s4, s5, s6, s7; }; + __CL_ANON_STRUCT__ struct{ cl_char4 lo, hi; }; +#endif +#if defined( __CL_CHAR2__) + __cl_char2 v2[4]; +#endif +#if defined( __CL_CHAR4__) + __cl_char4 v4[2]; +#endif +#if defined( __CL_CHAR8__ ) + __cl_char8 v8; +#endif +}cl_char8; + +typedef union +{ + cl_char CL_ALIGNED(16) s[16]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_char x, y, z, w, __spacer4, __spacer5, __spacer6, __spacer7, __spacer8, __spacer9, sa, sb, sc, sd, se, sf; }; + __CL_ANON_STRUCT__ struct{ cl_char s0, s1, s2, s3, s4, s5, s6, s7, s8, s9, sA, sB, sC, sD, sE, sF; }; + __CL_ANON_STRUCT__ struct{ cl_char8 lo, hi; }; +#endif +#if defined( __CL_CHAR2__) + __cl_char2 v2[8]; +#endif +#if defined( __CL_CHAR4__) + __cl_char4 v4[4]; +#endif +#if defined( __CL_CHAR8__ ) + __cl_char8 v8[2]; +#endif +#if defined( __CL_CHAR16__ ) + __cl_char16 v16; +#endif +}cl_char16; + + +/* ---- cl_ucharn ---- */ +typedef union +{ + cl_uchar CL_ALIGNED(2) s[2]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_uchar x, y; }; + __CL_ANON_STRUCT__ struct{ cl_uchar s0, s1; }; + __CL_ANON_STRUCT__ struct{ cl_uchar lo, hi; }; +#endif +#if defined( __cl_uchar2__) + __cl_uchar2 v2; +#endif +}cl_uchar2; + +typedef union +{ + cl_uchar CL_ALIGNED(4) s[4]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_uchar x, y, z, w; }; + __CL_ANON_STRUCT__ struct{ cl_uchar s0, s1, s2, s3; }; + __CL_ANON_STRUCT__ struct{ cl_uchar2 lo, hi; }; +#endif +#if defined( __CL_UCHAR2__) + __cl_uchar2 v2[2]; +#endif +#if defined( __CL_UCHAR4__) + __cl_uchar4 v4; +#endif +}cl_uchar4; + +/* cl_uchar3 is identical in size, alignment and behavior to cl_uchar4. See section 6.1.5. */ +typedef cl_uchar4 cl_uchar3; + +typedef union +{ + cl_uchar CL_ALIGNED(8) s[8]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_uchar x, y, z, w; }; + __CL_ANON_STRUCT__ struct{ cl_uchar s0, s1, s2, s3, s4, s5, s6, s7; }; + __CL_ANON_STRUCT__ struct{ cl_uchar4 lo, hi; }; +#endif +#if defined( __CL_UCHAR2__) + __cl_uchar2 v2[4]; +#endif +#if defined( __CL_UCHAR4__) + __cl_uchar4 v4[2]; +#endif +#if defined( __CL_UCHAR8__ ) + __cl_uchar8 v8; +#endif +}cl_uchar8; + +typedef union +{ + cl_uchar CL_ALIGNED(16) s[16]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_uchar x, y, z, w, __spacer4, __spacer5, __spacer6, __spacer7, __spacer8, __spacer9, sa, sb, sc, sd, se, sf; }; + __CL_ANON_STRUCT__ struct{ cl_uchar s0, s1, s2, s3, s4, s5, s6, s7, s8, s9, sA, sB, sC, sD, sE, sF; }; + __CL_ANON_STRUCT__ struct{ cl_uchar8 lo, hi; }; +#endif +#if defined( __CL_UCHAR2__) + __cl_uchar2 v2[8]; +#endif +#if defined( __CL_UCHAR4__) + __cl_uchar4 v4[4]; +#endif +#if defined( __CL_UCHAR8__ ) + __cl_uchar8 v8[2]; +#endif +#if defined( __CL_UCHAR16__ ) + __cl_uchar16 v16; +#endif +}cl_uchar16; + + +/* ---- cl_shortn ---- */ +typedef union +{ + cl_short CL_ALIGNED(4) s[2]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_short x, y; }; + __CL_ANON_STRUCT__ struct{ cl_short s0, s1; }; + __CL_ANON_STRUCT__ struct{ cl_short lo, hi; }; +#endif +#if defined( __CL_SHORT2__) + __cl_short2 v2; +#endif +}cl_short2; + +typedef union +{ + cl_short CL_ALIGNED(8) s[4]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_short x, y, z, w; }; + __CL_ANON_STRUCT__ struct{ cl_short s0, s1, s2, s3; }; + __CL_ANON_STRUCT__ struct{ cl_short2 lo, hi; }; +#endif +#if defined( __CL_SHORT2__) + __cl_short2 v2[2]; +#endif +#if defined( __CL_SHORT4__) + __cl_short4 v4; +#endif +}cl_short4; + +/* cl_short3 is identical in size, alignment and behavior to cl_short4. See section 6.1.5. */ +typedef cl_short4 cl_short3; + +typedef union +{ + cl_short CL_ALIGNED(16) s[8]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_short x, y, z, w; }; + __CL_ANON_STRUCT__ struct{ cl_short s0, s1, s2, s3, s4, s5, s6, s7; }; + __CL_ANON_STRUCT__ struct{ cl_short4 lo, hi; }; +#endif +#if defined( __CL_SHORT2__) + __cl_short2 v2[4]; +#endif +#if defined( __CL_SHORT4__) + __cl_short4 v4[2]; +#endif +#if defined( __CL_SHORT8__ ) + __cl_short8 v8; +#endif +}cl_short8; + +typedef union +{ + cl_short CL_ALIGNED(32) s[16]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_short x, y, z, w, __spacer4, __spacer5, __spacer6, __spacer7, __spacer8, __spacer9, sa, sb, sc, sd, se, sf; }; + __CL_ANON_STRUCT__ struct{ cl_short s0, s1, s2, s3, s4, s5, s6, s7, s8, s9, sA, sB, sC, sD, sE, sF; }; + __CL_ANON_STRUCT__ struct{ cl_short8 lo, hi; }; +#endif +#if defined( __CL_SHORT2__) + __cl_short2 v2[8]; +#endif +#if defined( __CL_SHORT4__) + __cl_short4 v4[4]; +#endif +#if defined( __CL_SHORT8__ ) + __cl_short8 v8[2]; +#endif +#if defined( __CL_SHORT16__ ) + __cl_short16 v16; +#endif +}cl_short16; + + +/* ---- cl_ushortn ---- */ +typedef union +{ + cl_ushort CL_ALIGNED(4) s[2]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_ushort x, y; }; + __CL_ANON_STRUCT__ struct{ cl_ushort s0, s1; }; + __CL_ANON_STRUCT__ struct{ cl_ushort lo, hi; }; +#endif +#if defined( __CL_USHORT2__) + __cl_ushort2 v2; +#endif +}cl_ushort2; + +typedef union +{ + cl_ushort CL_ALIGNED(8) s[4]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_ushort x, y, z, w; }; + __CL_ANON_STRUCT__ struct{ cl_ushort s0, s1, s2, s3; }; + __CL_ANON_STRUCT__ struct{ cl_ushort2 lo, hi; }; +#endif +#if defined( __CL_USHORT2__) + __cl_ushort2 v2[2]; +#endif +#if defined( __CL_USHORT4__) + __cl_ushort4 v4; +#endif +}cl_ushort4; + +/* cl_ushort3 is identical in size, alignment and behavior to cl_ushort4. See section 6.1.5. */ +typedef cl_ushort4 cl_ushort3; + +typedef union +{ + cl_ushort CL_ALIGNED(16) s[8]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_ushort x, y, z, w; }; + __CL_ANON_STRUCT__ struct{ cl_ushort s0, s1, s2, s3, s4, s5, s6, s7; }; + __CL_ANON_STRUCT__ struct{ cl_ushort4 lo, hi; }; +#endif +#if defined( __CL_USHORT2__) + __cl_ushort2 v2[4]; +#endif +#if defined( __CL_USHORT4__) + __cl_ushort4 v4[2]; +#endif +#if defined( __CL_USHORT8__ ) + __cl_ushort8 v8; +#endif +}cl_ushort8; + +typedef union +{ + cl_ushort CL_ALIGNED(32) s[16]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_ushort x, y, z, w, __spacer4, __spacer5, __spacer6, __spacer7, __spacer8, __spacer9, sa, sb, sc, sd, se, sf; }; + __CL_ANON_STRUCT__ struct{ cl_ushort s0, s1, s2, s3, s4, s5, s6, s7, s8, s9, sA, sB, sC, sD, sE, sF; }; + __CL_ANON_STRUCT__ struct{ cl_ushort8 lo, hi; }; +#endif +#if defined( __CL_USHORT2__) + __cl_ushort2 v2[8]; +#endif +#if defined( __CL_USHORT4__) + __cl_ushort4 v4[4]; +#endif +#if defined( __CL_USHORT8__ ) + __cl_ushort8 v8[2]; +#endif +#if defined( __CL_USHORT16__ ) + __cl_ushort16 v16; +#endif +}cl_ushort16; + +/* ---- cl_intn ---- */ +typedef union +{ + cl_int CL_ALIGNED(8) s[2]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_int x, y; }; + __CL_ANON_STRUCT__ struct{ cl_int s0, s1; }; + __CL_ANON_STRUCT__ struct{ cl_int lo, hi; }; +#endif +#if defined( __CL_INT2__) + __cl_int2 v2; +#endif +}cl_int2; + +typedef union +{ + cl_int CL_ALIGNED(16) s[4]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_int x, y, z, w; }; + __CL_ANON_STRUCT__ struct{ cl_int s0, s1, s2, s3; }; + __CL_ANON_STRUCT__ struct{ cl_int2 lo, hi; }; +#endif +#if defined( __CL_INT2__) + __cl_int2 v2[2]; +#endif +#if defined( __CL_INT4__) + __cl_int4 v4; +#endif +}cl_int4; + +/* cl_int3 is identical in size, alignment and behavior to cl_int4. See section 6.1.5. */ +typedef cl_int4 cl_int3; + +typedef union +{ + cl_int CL_ALIGNED(32) s[8]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_int x, y, z, w; }; + __CL_ANON_STRUCT__ struct{ cl_int s0, s1, s2, s3, s4, s5, s6, s7; }; + __CL_ANON_STRUCT__ struct{ cl_int4 lo, hi; }; +#endif +#if defined( __CL_INT2__) + __cl_int2 v2[4]; +#endif +#if defined( __CL_INT4__) + __cl_int4 v4[2]; +#endif +#if defined( __CL_INT8__ ) + __cl_int8 v8; +#endif +}cl_int8; + +typedef union +{ + cl_int CL_ALIGNED(64) s[16]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_int x, y, z, w, __spacer4, __spacer5, __spacer6, __spacer7, __spacer8, __spacer9, sa, sb, sc, sd, se, sf; }; + __CL_ANON_STRUCT__ struct{ cl_int s0, s1, s2, s3, s4, s5, s6, s7, s8, s9, sA, sB, sC, sD, sE, sF; }; + __CL_ANON_STRUCT__ struct{ cl_int8 lo, hi; }; +#endif +#if defined( __CL_INT2__) + __cl_int2 v2[8]; +#endif +#if defined( __CL_INT4__) + __cl_int4 v4[4]; +#endif +#if defined( __CL_INT8__ ) + __cl_int8 v8[2]; +#endif +#if defined( __CL_INT16__ ) + __cl_int16 v16; +#endif +}cl_int16; + + +/* ---- cl_uintn ---- */ +typedef union +{ + cl_uint CL_ALIGNED(8) s[2]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_uint x, y; }; + __CL_ANON_STRUCT__ struct{ cl_uint s0, s1; }; + __CL_ANON_STRUCT__ struct{ cl_uint lo, hi; }; +#endif +#if defined( __CL_UINT2__) + __cl_uint2 v2; +#endif +}cl_uint2; + +typedef union +{ + cl_uint CL_ALIGNED(16) s[4]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_uint x, y, z, w; }; + __CL_ANON_STRUCT__ struct{ cl_uint s0, s1, s2, s3; }; + __CL_ANON_STRUCT__ struct{ cl_uint2 lo, hi; }; +#endif +#if defined( __CL_UINT2__) + __cl_uint2 v2[2]; +#endif +#if defined( __CL_UINT4__) + __cl_uint4 v4; +#endif +}cl_uint4; + +/* cl_uint3 is identical in size, alignment and behavior to cl_uint4. See section 6.1.5. */ +typedef cl_uint4 cl_uint3; + +typedef union +{ + cl_uint CL_ALIGNED(32) s[8]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_uint x, y, z, w; }; + __CL_ANON_STRUCT__ struct{ cl_uint s0, s1, s2, s3, s4, s5, s6, s7; }; + __CL_ANON_STRUCT__ struct{ cl_uint4 lo, hi; }; +#endif +#if defined( __CL_UINT2__) + __cl_uint2 v2[4]; +#endif +#if defined( __CL_UINT4__) + __cl_uint4 v4[2]; +#endif +#if defined( __CL_UINT8__ ) + __cl_uint8 v8; +#endif +}cl_uint8; + +typedef union +{ + cl_uint CL_ALIGNED(64) s[16]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_uint x, y, z, w, __spacer4, __spacer5, __spacer6, __spacer7, __spacer8, __spacer9, sa, sb, sc, sd, se, sf; }; + __CL_ANON_STRUCT__ struct{ cl_uint s0, s1, s2, s3, s4, s5, s6, s7, s8, s9, sA, sB, sC, sD, sE, sF; }; + __CL_ANON_STRUCT__ struct{ cl_uint8 lo, hi; }; +#endif +#if defined( __CL_UINT2__) + __cl_uint2 v2[8]; +#endif +#if defined( __CL_UINT4__) + __cl_uint4 v4[4]; +#endif +#if defined( __CL_UINT8__ ) + __cl_uint8 v8[2]; +#endif +#if defined( __CL_UINT16__ ) + __cl_uint16 v16; +#endif +}cl_uint16; + +/* ---- cl_longn ---- */ +typedef union +{ + cl_long CL_ALIGNED(16) s[2]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_long x, y; }; + __CL_ANON_STRUCT__ struct{ cl_long s0, s1; }; + __CL_ANON_STRUCT__ struct{ cl_long lo, hi; }; +#endif +#if defined( __CL_LONG2__) + __cl_long2 v2; +#endif +}cl_long2; + +typedef union +{ + cl_long CL_ALIGNED(32) s[4]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_long x, y, z, w; }; + __CL_ANON_STRUCT__ struct{ cl_long s0, s1, s2, s3; }; + __CL_ANON_STRUCT__ struct{ cl_long2 lo, hi; }; +#endif +#if defined( __CL_LONG2__) + __cl_long2 v2[2]; +#endif +#if defined( __CL_LONG4__) + __cl_long4 v4; +#endif +}cl_long4; + +/* cl_long3 is identical in size, alignment and behavior to cl_long4. See section 6.1.5. */ +typedef cl_long4 cl_long3; + +typedef union +{ + cl_long CL_ALIGNED(64) s[8]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_long x, y, z, w; }; + __CL_ANON_STRUCT__ struct{ cl_long s0, s1, s2, s3, s4, s5, s6, s7; }; + __CL_ANON_STRUCT__ struct{ cl_long4 lo, hi; }; +#endif +#if defined( __CL_LONG2__) + __cl_long2 v2[4]; +#endif +#if defined( __CL_LONG4__) + __cl_long4 v4[2]; +#endif +#if defined( __CL_LONG8__ ) + __cl_long8 v8; +#endif +}cl_long8; + +typedef union +{ + cl_long CL_ALIGNED(128) s[16]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_long x, y, z, w, __spacer4, __spacer5, __spacer6, __spacer7, __spacer8, __spacer9, sa, sb, sc, sd, se, sf; }; + __CL_ANON_STRUCT__ struct{ cl_long s0, s1, s2, s3, s4, s5, s6, s7, s8, s9, sA, sB, sC, sD, sE, sF; }; + __CL_ANON_STRUCT__ struct{ cl_long8 lo, hi; }; +#endif +#if defined( __CL_LONG2__) + __cl_long2 v2[8]; +#endif +#if defined( __CL_LONG4__) + __cl_long4 v4[4]; +#endif +#if defined( __CL_LONG8__ ) + __cl_long8 v8[2]; +#endif +#if defined( __CL_LONG16__ ) + __cl_long16 v16; +#endif +}cl_long16; + + +/* ---- cl_ulongn ---- */ +typedef union +{ + cl_ulong CL_ALIGNED(16) s[2]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_ulong x, y; }; + __CL_ANON_STRUCT__ struct{ cl_ulong s0, s1; }; + __CL_ANON_STRUCT__ struct{ cl_ulong lo, hi; }; +#endif +#if defined( __CL_ULONG2__) + __cl_ulong2 v2; +#endif +}cl_ulong2; + +typedef union +{ + cl_ulong CL_ALIGNED(32) s[4]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_ulong x, y, z, w; }; + __CL_ANON_STRUCT__ struct{ cl_ulong s0, s1, s2, s3; }; + __CL_ANON_STRUCT__ struct{ cl_ulong2 lo, hi; }; +#endif +#if defined( __CL_ULONG2__) + __cl_ulong2 v2[2]; +#endif +#if defined( __CL_ULONG4__) + __cl_ulong4 v4; +#endif +}cl_ulong4; + +/* cl_ulong3 is identical in size, alignment and behavior to cl_ulong4. See section 6.1.5. */ +typedef cl_ulong4 cl_ulong3; + +typedef union +{ + cl_ulong CL_ALIGNED(64) s[8]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_ulong x, y, z, w; }; + __CL_ANON_STRUCT__ struct{ cl_ulong s0, s1, s2, s3, s4, s5, s6, s7; }; + __CL_ANON_STRUCT__ struct{ cl_ulong4 lo, hi; }; +#endif +#if defined( __CL_ULONG2__) + __cl_ulong2 v2[4]; +#endif +#if defined( __CL_ULONG4__) + __cl_ulong4 v4[2]; +#endif +#if defined( __CL_ULONG8__ ) + __cl_ulong8 v8; +#endif +}cl_ulong8; + +typedef union +{ + cl_ulong CL_ALIGNED(128) s[16]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_ulong x, y, z, w, __spacer4, __spacer5, __spacer6, __spacer7, __spacer8, __spacer9, sa, sb, sc, sd, se, sf; }; + __CL_ANON_STRUCT__ struct{ cl_ulong s0, s1, s2, s3, s4, s5, s6, s7, s8, s9, sA, sB, sC, sD, sE, sF; }; + __CL_ANON_STRUCT__ struct{ cl_ulong8 lo, hi; }; +#endif +#if defined( __CL_ULONG2__) + __cl_ulong2 v2[8]; +#endif +#if defined( __CL_ULONG4__) + __cl_ulong4 v4[4]; +#endif +#if defined( __CL_ULONG8__ ) + __cl_ulong8 v8[2]; +#endif +#if defined( __CL_ULONG16__ ) + __cl_ulong16 v16; +#endif +}cl_ulong16; + + +/* --- cl_floatn ---- */ + +typedef union +{ + cl_float CL_ALIGNED(8) s[2]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_float x, y; }; + __CL_ANON_STRUCT__ struct{ cl_float s0, s1; }; + __CL_ANON_STRUCT__ struct{ cl_float lo, hi; }; +#endif +#if defined( __CL_FLOAT2__) + __cl_float2 v2; +#endif +}cl_float2; + +typedef union +{ + cl_float CL_ALIGNED(16) s[4]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_float x, y, z, w; }; + __CL_ANON_STRUCT__ struct{ cl_float s0, s1, s2, s3; }; + __CL_ANON_STRUCT__ struct{ cl_float2 lo, hi; }; +#endif +#if defined( __CL_FLOAT2__) + __cl_float2 v2[2]; +#endif +#if defined( __CL_FLOAT4__) + __cl_float4 v4; +#endif +}cl_float4; + +/* cl_float3 is identical in size, alignment and behavior to cl_float4. See section 6.1.5. */ +typedef cl_float4 cl_float3; + +typedef union +{ + cl_float CL_ALIGNED(32) s[8]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_float x, y, z, w; }; + __CL_ANON_STRUCT__ struct{ cl_float s0, s1, s2, s3, s4, s5, s6, s7; }; + __CL_ANON_STRUCT__ struct{ cl_float4 lo, hi; }; +#endif +#if defined( __CL_FLOAT2__) + __cl_float2 v2[4]; +#endif +#if defined( __CL_FLOAT4__) + __cl_float4 v4[2]; +#endif +#if defined( __CL_FLOAT8__ ) + __cl_float8 v8; +#endif +}cl_float8; + +typedef union +{ + cl_float CL_ALIGNED(64) s[16]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_float x, y, z, w, __spacer4, __spacer5, __spacer6, __spacer7, __spacer8, __spacer9, sa, sb, sc, sd, se, sf; }; + __CL_ANON_STRUCT__ struct{ cl_float s0, s1, s2, s3, s4, s5, s6, s7, s8, s9, sA, sB, sC, sD, sE, sF; }; + __CL_ANON_STRUCT__ struct{ cl_float8 lo, hi; }; +#endif +#if defined( __CL_FLOAT2__) + __cl_float2 v2[8]; +#endif +#if defined( __CL_FLOAT4__) + __cl_float4 v4[4]; +#endif +#if defined( __CL_FLOAT8__ ) + __cl_float8 v8[2]; +#endif +#if defined( __CL_FLOAT16__ ) + __cl_float16 v16; +#endif +}cl_float16; + +/* --- cl_doublen ---- */ + +typedef union +{ + cl_double CL_ALIGNED(16) s[2]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_double x, y; }; + __CL_ANON_STRUCT__ struct{ cl_double s0, s1; }; + __CL_ANON_STRUCT__ struct{ cl_double lo, hi; }; +#endif +#if defined( __CL_DOUBLE2__) + __cl_double2 v2; +#endif +}cl_double2; + +typedef union +{ + cl_double CL_ALIGNED(32) s[4]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_double x, y, z, w; }; + __CL_ANON_STRUCT__ struct{ cl_double s0, s1, s2, s3; }; + __CL_ANON_STRUCT__ struct{ cl_double2 lo, hi; }; +#endif +#if defined( __CL_DOUBLE2__) + __cl_double2 v2[2]; +#endif +#if defined( __CL_DOUBLE4__) + __cl_double4 v4; +#endif +}cl_double4; + +/* cl_double3 is identical in size, alignment and behavior to cl_double4. See section 6.1.5. */ +typedef cl_double4 cl_double3; + +typedef union +{ + cl_double CL_ALIGNED(64) s[8]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_double x, y, z, w; }; + __CL_ANON_STRUCT__ struct{ cl_double s0, s1, s2, s3, s4, s5, s6, s7; }; + __CL_ANON_STRUCT__ struct{ cl_double4 lo, hi; }; +#endif +#if defined( __CL_DOUBLE2__) + __cl_double2 v2[4]; +#endif +#if defined( __CL_DOUBLE4__) + __cl_double4 v4[2]; +#endif +#if defined( __CL_DOUBLE8__ ) + __cl_double8 v8; +#endif +}cl_double8; + +typedef union +{ + cl_double CL_ALIGNED(128) s[16]; +#if __CL_HAS_ANON_STRUCT__ + __CL_ANON_STRUCT__ struct{ cl_double x, y, z, w, __spacer4, __spacer5, __spacer6, __spacer7, __spacer8, __spacer9, sa, sb, sc, sd, se, sf; }; + __CL_ANON_STRUCT__ struct{ cl_double s0, s1, s2, s3, s4, s5, s6, s7, s8, s9, sA, sB, sC, sD, sE, sF; }; + __CL_ANON_STRUCT__ struct{ cl_double8 lo, hi; }; +#endif +#if defined( __CL_DOUBLE2__) + __cl_double2 v2[8]; +#endif +#if defined( __CL_DOUBLE4__) + __cl_double4 v4[4]; +#endif +#if defined( __CL_DOUBLE8__ ) + __cl_double8 v8[2]; +#endif +#if defined( __CL_DOUBLE16__ ) + __cl_double16 v16; +#endif +}cl_double16; + +/* Macro to facilitate debugging + * Usage: + * Place CL_PROGRAM_STRING_DEBUG_INFO on the line before the first line of your source. + * The first line ends with: CL_PROGRAM_STRING_DEBUG_INFO \" + * Each line thereafter of OpenCL C source must end with: \n\ + * The last line ends in "; + * + * Example: + * + * const char *my_program = CL_PROGRAM_STRING_DEBUG_INFO "\ + * kernel void foo( int a, float * b ) \n\ + * { \n\ + * // my comment \n\ + * *b[ get_global_id(0)] = a; \n\ + * } \n\ + * "; + * + * This should correctly set up the line, (column) and file information for your source + * string so you can do source level debugging. + */ +#define __CL_STRINGIFY( _x ) # _x +#define _CL_STRINGIFY( _x ) __CL_STRINGIFY( _x ) +#define CL_PROGRAM_STRING_DEBUG_INFO "#line " _CL_STRINGIFY(__LINE__) " \"" __FILE__ "\" \n\n" + +#ifdef __cplusplus +} +#endif + +#undef __CL_HAS_ANON_STRUCT__ +#undef __CL_ANON_STRUCT__ +#if defined( _WIN32) && (_MSC_VER >= 1500) +#pragma warning( pop ) +#endif + +#endif /* __CL_PLATFORM_H */ diff --git a/phonelibs/opencl/include/CL/opencl.h b/phonelibs/opencl/include/CL/opencl.h new file mode 100644 index 00000000000000..9855cd75e7da06 --- /dev/null +++ b/phonelibs/opencl/include/CL/opencl.h @@ -0,0 +1,59 @@ +/******************************************************************************* + * Copyright (c) 2008-2015 The Khronos Group Inc. + * + * Permission is hereby granted, free of charge, to any person obtaining a + * copy of this software and/or associated documentation files (the + * "Materials"), to deal in the Materials without restriction, including + * without limitation the rights to use, copy, modify, merge, publish, + * distribute, sublicense, and/or sell copies of the Materials, and to + * permit persons to whom the Materials are furnished to do so, subject to + * the following conditions: + * + * The above copyright notice and this permission notice shall be included + * in all copies or substantial portions of the Materials. + * + * MODIFICATIONS TO THIS FILE MAY MEAN IT NO LONGER ACCURATELY REFLECTS + * KHRONOS STANDARDS. THE UNMODIFIED, NORMATIVE VERSIONS OF KHRONOS + * SPECIFICATIONS AND HEADER INFORMATION ARE LOCATED AT + * https://www.khronos.org/registry/ + * + * THE MATERIALS ARE PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, + * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. + * IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY + * CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, + * TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE + * MATERIALS OR THE USE OR OTHER DEALINGS IN THE MATERIALS. + ******************************************************************************/ + +/* $Revision: 11708 $ on $Date: 2010-06-13 23:36:24 -0700 (Sun, 13 Jun 2010) $ */ + +#ifndef __OPENCL_H +#define __OPENCL_H + +#ifdef __cplusplus +extern "C" { +#endif + +#ifdef __APPLE__ + +#include +#include +#include +#include + +#else + +#include +#include +#include +#include + +#endif + +#ifdef __cplusplus +} +#endif + +#endif /* __OPENCL_H */ + diff --git a/phonelibs/qpoases/EXAMPLES/example1.cpp b/phonelibs/qpoases/EXAMPLES/example1.cpp new file mode 100644 index 00000000000000..92b47fc93798d2 --- /dev/null +++ b/phonelibs/qpoases/EXAMPLES/example1.cpp @@ -0,0 +1,74 @@ +/* + * This file is part of qpOASES. + * + * qpOASES -- An Implementation of the Online Active Set Strategy. + * Copyright (C) 2007-2008 by Hans Joachim Ferreau 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 EXAMPLES/example1.cpp + * \author Hans Joachim Ferreau + * \version 1.3embedded + * \date 2007-2008 + * + * Very simple example for testing qpOASES (using QProblem class). + */ + + +#include + + +/** Example for qpOASES main function using the QProblem class. */ +int main( ) +{ + /* Setup data of first QP. */ + real_t H[2*2] = { 1.0, 0.0, 0.0, 0.5 }; + real_t A[1*2] = { 1.0, 1.0 }; + real_t g[2] = { 1.5, 1.0 }; + real_t lb[2] = { 0.5, -2.0 }; + real_t ub[2] = { 5.0, 2.0 }; + real_t lbA[1] = { -1.0 }; + real_t ubA[1] = { 2.0 }; + + /* Setup data of second QP. */ + real_t g_new[2] = { 1.0, 1.5 }; + real_t lb_new[2] = { 0.0, -1.0 }; + real_t ub_new[2] = { 5.0, -0.5 }; + real_t lbA_new[1] = { -2.0 }; + real_t ubA_new[1] = { 1.0 }; + + + /* Setting up QProblem object. */ + QProblem example( 2,1 ); + + /* Solve first QP. */ + int nWSR = 10; + example.init( H,g,A,lb,ub,lbA,ubA, nWSR,0 ); + + /* Solve second QP. */ + nWSR = 10; + example.hotstart( g_new,lb_new,ub_new,lbA_new,ubA_new, nWSR,0 ); + + return 0; +} + + +/* + * end of file + */ diff --git a/phonelibs/qpoases/EXAMPLES/example1b.cpp b/phonelibs/qpoases/EXAMPLES/example1b.cpp new file mode 100644 index 00000000000000..331f19d8da0cbc --- /dev/null +++ b/phonelibs/qpoases/EXAMPLES/example1b.cpp @@ -0,0 +1,69 @@ +/* + * This file is part of qpOASES. + * + * qpOASES -- An Implementation of the Online Active Set Strategy. + * Copyright (C) 2007-2008 by Hans Joachim Ferreau 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 EXAMPLES/example1b.cpp + * \author Hans Joachim Ferreau + * \version 1.3 + * \date 2007-2008 + * + * Very simple example for testing qpOASES using the QProblemB class. + */ + + +#include + + +/** Example for qpOASES main function using the QProblemB class. */ +int main( ) +{ + /* Setup data of first QP. */ + real_t H[2*2] = { 1.0, 0.0, 0.0, 0.5 }; + real_t g[2] = { 1.5, 1.0 }; + real_t lb[2] = { 0.5, -2.0 }; + real_t ub[2] = { 5.0, 2.0 }; + + /* Setup data of second QP. */ + real_t g_new[2] = { 1.0, 1.5 }; + real_t lb_new[2] = { 0.0, -1.0 }; + real_t ub_new[2] = { 5.0, -0.5 }; + + + /* Setting up QProblemB object. */ + QProblemB example( 2 ); + + /* Solve first QP. */ + int nWSR = 10; + example.init( H,g,lb,ub, nWSR,0 ); + + /* Solve second QP. */ + nWSR = 10; + example.hotstart( g_new,lb_new,ub_new, nWSR,0 ); + + return 0; +} + + +/* + * end of file + */ diff --git a/phonelibs/qpoases/INCLUDE/Bounds.hpp b/phonelibs/qpoases/INCLUDE/Bounds.hpp new file mode 100644 index 00000000000000..1fbd28ab38d342 --- /dev/null +++ b/phonelibs/qpoases/INCLUDE/Bounds.hpp @@ -0,0 +1,189 @@ +/* + * This file is part of qpOASES. + * + * qpOASES -- An Implementation of the Online Active Set Strategy. + * Copyright (C) 2007-2008 by Hans Joachim Ferreau 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/Bounds.hpp + * \author Hans Joachim Ferreau + * \version 1.3embedded + * \date 2007-2008 + * + * Declaration of the Bounds class designed to manage working sets of + * bounds within a QProblem. + */ + + +#ifndef QPOASES_BOUNDS_HPP +#define QPOASES_BOUNDS_HPP + + +#include + + + +/** This class manages working sets of bounds by storing + * index sets and other status information. + * + * \author Hans Joachim Ferreau + * \version 1.3embedded + * \date 2007-2008 + */ +class Bounds : public SubjectTo +{ + /* + * PUBLIC MEMBER FUNCTIONS + */ + public: + /** Default constructor. */ + Bounds( ); + + /** Copy constructor (deep copy). */ + Bounds( const Bounds& rhs /**< Rhs object. */ + ); + + /** Destructor. */ + ~Bounds( ); + + /** Assignment operator (deep copy). */ + Bounds& operator=( const Bounds& rhs /**< Rhs object. */ + ); + + + /** Pseudo-constructor takes the number of bounds. + * \return SUCCESSFUL_RETURN */ + returnValue init( 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 setupBound( 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 setupAllFree( ); + + + /** 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 moveFixedToFree( 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 moveFreeToFixed( int _number, /**< Number of bound to be fixed. */ + SubjectToStatus _status /**< Status of bound to be fixed. */ + ); + + /** Swaps the indices of two free bounds within the index set. + * \return SUCCESSFUL_RETURN \n + RET_SWAPINDEX_FAILED */ + returnValue swapFree( int number1, /**< Number of first constraint or bound. */ + int number2 /**< Number of second constraint or bound. */ + ); + + + /** Returns number of variables. + * \return Number of variables. */ + inline int getNV( ) const; + + /** Returns number of implicitly fixed variables. + * \return Number of implicitly fixed variables. */ + inline int getNFV( ) const; + + /** Returns number of bounded (but possibly free) variables. + * \return Number of bounded (but possibly free) variables. */ + inline int getNBV( ) const; + + /** Returns number of unbounded variables. + * \return Number of unbounded variables. */ + inline int getNUV( ) const; + + + /** Sets number of implicitly fixed variables. + * \return SUCCESSFUL_RETURN */ + inline returnValue setNFV( int n /**< Number of implicitly fixed variables. */ + ); + + /** Sets number of bounded (but possibly free) variables. + * \return SUCCESSFUL_RETURN */ + inline returnValue setNBV( int n /**< Number of bounded (but possibly free) variables. */ + ); + + /** Sets number of unbounded variables. + * \return SUCCESSFUL_RETURN */ + inline returnValue setNUV( int n /**< Number of unbounded variables */ + ); + + + /** Returns number of free variables. + * \return Number of free variables. */ + inline int getNFR( ); + + /** Returns number of fixed variables. + * \return Number of fixed variables. */ + inline int getNFX( ); + + + /** Returns a pointer to free variables index list. + * \return Pointer to free variables index list. */ + inline Indexlist* getFree( ); + + /** Returns a pointer to fixed variables index list. + * \return Pointer to fixed variables index list. */ + inline Indexlist* getFixed( ); + + + /* + * PROTECTED MEMBER VARIABLES + */ + protected: + int nV; /**< Number of variables (nV = nFV + nBV + nUV). */ + int nFV; /**< Number of implicitly fixed variables. */ + int nBV; /**< Number of bounded (but possibly free) variables. */ + int nUV; /**< Number of unbounded variables. */ + + Indexlist free; /**< Index list of free variables. */ + Indexlist fixed; /**< Index list of fixed variables. */ +}; + +#include + +#endif /* QPOASES_BOUNDS_HPP */ + + +/* + * end of file + */ diff --git a/phonelibs/qpoases/INCLUDE/Constants.hpp b/phonelibs/qpoases/INCLUDE/Constants.hpp new file mode 100644 index 00000000000000..8293fa514c6a9c --- /dev/null +++ b/phonelibs/qpoases/INCLUDE/Constants.hpp @@ -0,0 +1,108 @@ +/* + * This file is part of qpOASES. + * + * qpOASES -- An Implementation of the Online Active Set Strategy. + * Copyright (C) 2007-2008 by Hans Joachim Ferreau 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/Constants.hpp + * \author Hans Joachim Ferreau + * \version 1.3embedded + * \date 2008 + * + * Definition of all global constants. + */ + + +#ifndef QPOASES_CONSTANTS_HPP +#define QPOASES_CONSTANTS_HPP + +#ifndef QPOASES_CUSTOM_INTERFACE +#include "acado_qpoases_interface.hpp" +#else + #define XSTR(x) #x + #define STR(x) XSTR(x) + #include STR(QPOASES_CUSTOM_INTERFACE) +#endif + +/** Maximum number of variables within a QP formulation. + Note: this value has to be positive! */ +const int NVMAX = QPOASES_NVMAX; + +/** Maximum number of constraints within a QP formulation. + Note: this value has to be positive! */ +const int NCMAX = QPOASES_NCMAX; + +/** Redefinition of NCMAX used for memory allocation, to avoid zero sized arrays + and compiler errors. */ +const int NCMAX_ALLOC = (NCMAX == 0) ? 1 : NCMAX; + +/**< Maximum number of working set recalculations. + Note: this value has to be positive! */ +const int NWSRMAX = QPOASES_NWSRMAX; + +/** Desired KKT tolerance of QP solution; a warning RET_INACCURATE_SOLUTION is + * issued if this tolerance is not met. + * Note: this value has to be positive! */ +const real_t DESIREDACCURACY = (real_t) 1.0e-3; + +/** Critical KKT tolerance of QP solution; an error is issued if this + * tolerance is not met. + * Note: this value has to be positive! */ +const real_t CRITICALACCURACY = (real_t) 1.0e-2; + + + +/** Numerical value of machine precision (min eps, s.t. 1+eps > 1). + Note: this value has to be positive! */ +const real_t EPS = (real_t) QPOASES_EPS; + +/** Numerical value of zero (for situations in which it would be + * unreasonable to compare with 0.0). + * Note: this value has to be positive! */ +const real_t ZERO = (real_t) 1.0e-50; + +/** Numerical value of infinity (e.g. for non-existing bounds). + * Note: this value has to be positive! */ +const real_t INFTY = (real_t) 1.0e12; + + +/** Lower/upper (constraints') bound tolerance (an inequality constraint + * whose lower and upper bound differ by less than BOUNDTOL is regarded + * to be an equality constraint). + * Note: this value has to be positive! */ +const real_t BOUNDTOL = (real_t) 1.0e-10; + +/** Offset for relaxing (constraints') bounds at beginning of an initial homotopy. + * Note: this value has to be positive! */ +const real_t BOUNDRELAXATION = (real_t) 1.0e3; + + +/** Factor that determines physical lengths of index lists. + * Note: this value has to be greater than 1! */ +const int INDEXLISTFACTOR = 5; + + +#endif /* QPOASES_CONSTANTS_HPP */ + + +/* + * end of file + */ diff --git a/phonelibs/qpoases/INCLUDE/Constraints.hpp b/phonelibs/qpoases/INCLUDE/Constraints.hpp new file mode 100644 index 00000000000000..0b78747e29afeb --- /dev/null +++ b/phonelibs/qpoases/INCLUDE/Constraints.hpp @@ -0,0 +1,181 @@ +/* + * This file is part of qpOASES. + * + * qpOASES -- An Implementation of the Online Active Set Strategy. + * Copyright (C) 2007-2008 by Hans Joachim Ferreau 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/Constraints.hpp + * \author Hans Joachim Ferreau + * \version 1.3embedded + * \date 2007-2008 + * + * Declaration of the Constraints class designed to manage working sets of + * constraints within a QProblem. + */ + + +#ifndef QPOASES_CONSTRAINTS_HPP +#define QPOASES_CONSTRAINTS_HPP + + +#include + + + +/** This class manages working sets of constraints by storing + * index sets and other status information. + * + * \author Hans Joachim Ferreau + * \version 1.3embedded + * \date 2007-2008 + */ +class Constraints : public SubjectTo +{ + /* + * PUBLIC MEMBER FUNCTIONS + */ + public: + /** Default constructor. */ + Constraints( ); + + /** Copy constructor (deep copy). */ + Constraints( const Constraints& rhs /**< Rhs object. */ + ); + + /** Destructor. */ + ~Constraints( ); + + /** Assignment operator (deep copy). */ + Constraints& operator=( const Constraints& rhs /**< Rhs object. */ + ); + + + /** Pseudo-constructor takes the number of constraints. + * \return SUCCESSFUL_RETURN */ + returnValue init( 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 setupConstraint( 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 setupAllInactive( ); + + + /** Moves index of a constraint from index list of active to that of inactive constraints. + * \return SUCCESSFUL_RETURN \n + RET_MOVING_CONSTRAINT_FAILED */ + returnValue moveActiveToInactive( 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 moveInactiveToActive( int _number, /**< Number of constraint to become active. */ + SubjectToStatus _status /**< Status of constraint to become active. */ + ); + + + /** Returns the number of constraints. + * \return Number of constraints. */ + inline int getNC( ) const; + + /** Returns the number of implicit equality constraints. + * \return Number of implicit equality constraints. */ + inline int getNEC( ) const; + + /** Returns the number of "real" inequality constraints. + * \return Number of "real" inequality constraints. */ + inline int getNIC( ) const; + + /** Returns the number of unbounded constraints (i.e. without any bounds). + * \return Number of unbounded constraints (i.e. without any bounds). */ + inline int getNUC( ) const; + + + /** Sets number of implicit equality constraints. + * \return SUCCESSFUL_RETURN */ + inline returnValue setNEC( int n /**< Number of implicit equality constraints. */ + ); + + /** Sets number of "real" inequality constraints. + * \return SUCCESSFUL_RETURN */ + inline returnValue setNIC( int n /**< Number of "real" inequality constraints. */ + ); + + /** Sets number of unbounded constraints (i.e. without any bounds). + * \return SUCCESSFUL_RETURN */ + inline returnValue setNUC( int n /**< Number of unbounded constraints (i.e. without any bounds). */ + ); + + + /** Returns the number of active constraints. + * \return Number of constraints. */ + inline int getNAC( ); + + /** Returns the number of inactive constraints. + * \return Number of constraints. */ + inline int getNIAC( ); + + + /** Returns a pointer to active constraints index list. + * \return Pointer to active constraints index list. */ + inline Indexlist* getActive( ); + + /** Returns a pointer to inactive constraints index list. + * \return Pointer to inactive constraints index list. */ + inline Indexlist* getInactive( ); + + + /* + * PROTECTED MEMBER VARIABLES + */ + protected: + int nC; /**< Number of constraints (nC = nEC + nIC + nUC). */ + int nEC; /**< Number of implicit equality constraints. */ + int nIC; /**< Number of "real" inequality constraints. */ + int nUC; /**< Number of unbounded constraints (i.e. without any bounds). */ + + Indexlist active; /**< Index list of active constraints. */ + Indexlist inactive; /**< Index list of inactive constraints. */ +}; + + +#include + +#endif /* QPOASES_CONSTRAINTS_HPP */ + + +/* + * end of file + */ diff --git a/phonelibs/qpoases/INCLUDE/CyclingManager.hpp b/phonelibs/qpoases/INCLUDE/CyclingManager.hpp new file mode 100644 index 00000000000000..9b5c064a0bd7a4 --- /dev/null +++ b/phonelibs/qpoases/INCLUDE/CyclingManager.hpp @@ -0,0 +1,126 @@ +/* + * This file is part of qpOASES. + * + * qpOASES -- An Implementation of the Online Active Set Strategy. + * Copyright (C) 2007-2008 by Hans Joachim Ferreau 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/CyclingManager.hpp + * \author Hans Joachim Ferreau + * \version 1.3embedded + * \date 2007-2008 + * + * Declaration of the CyclingManager class designed to detect + * and handle possible cycling during QP iterations. + */ + + +#ifndef QPOASES_CYCLINGMANAGER_HPP +#define QPOASES_CYCLINGMANAGER_HPP + + +#include + + + +/** This class is intended to detect and handle possible cycling during QP iterations. + * As cycling seems to occur quite rarely, this class is NOT FULLY IMPLEMENTED YET! + * + * \author Hans Joachim Ferreau + * \version 1.3embedded + * \date 2007-2008 + */ +class CyclingManager +{ + /* + * PUBLIC MEMBER FUNCTIONS + */ + public: + /** Default constructor. */ + CyclingManager( ); + + /** Copy constructor (deep copy). */ + CyclingManager( const CyclingManager& rhs /**< Rhs object. */ + ); + + /** Destructor. */ + ~CyclingManager( ); + + /** Copy asingment operator (deep copy). */ + CyclingManager& operator=( const CyclingManager& rhs /**< Rhs object. */ + ); + + + /** Pseudo-constructor which takes the number of bounds/constraints. + * \return SUCCESSFUL_RETURN */ + returnValue init( int _nV, /**< Number of bounds to be managed. */ + int _nC /**< Number of constraints to be managed. */ + ); + + + /** Stores index of a bound/constraint that might cause cycling. + * \return SUCCESSFUL_RETURN \n + RET_INDEX_OUT_OF_BOUNDS */ + returnValue setCyclingStatus( int number, /**< Number of bound/constraint. */ + BooleanType isBound, /**< Flag that indicates if given number corresponds to a + * bound (BT_TRUE) or a constraint (BT_FALSE). */ + CyclingStatus _status /**< Cycling status of bound/constraint. */ + ); + + /** Returns if bound/constraint might cause cycling. + * \return BT_TRUE: bound/constraint might cause cycling \n + BT_FALSE: otherwise */ + CyclingStatus getCyclingStatus( int number, /**< Number of bound/constraint. */ + BooleanType isBound /**< Flag that indicates if given number corresponds to + * a bound (BT_TRUE) or a constraint (BT_FALSE). */ + ) const; + + + /** Clears all previous cycling information. + * \return SUCCESSFUL_RETURN */ + returnValue clearCyclingData( ); + + + /** Returns if cycling was detected. + * \return BT_TRUE iff cycling was detected. */ + inline BooleanType isCyclingDetected( ) const; + + + /* + * PROTECTED MEMBER VARIABLES + */ + protected: + int nV; /**< Number of managed bounds. */ + int nC; /**< Number of managed constraints. */ + + CyclingStatus status[NVMAX+NCMAX]; /**< Array to store cycling status of all bounds/constraints. */ + + BooleanType cyclingDetected; /**< Flag if cycling was detected. */ +}; + + +#include + +#endif /* QPOASES_CYCLINGMANAGER_HPP */ + + +/* + * end of file + */ diff --git a/phonelibs/qpoases/INCLUDE/EXTRAS/SolutionAnalysis.hpp b/phonelibs/qpoases/INCLUDE/EXTRAS/SolutionAnalysis.hpp new file mode 100644 index 00000000000000..056bb26f02d09d --- /dev/null +++ b/phonelibs/qpoases/INCLUDE/EXTRAS/SolutionAnalysis.hpp @@ -0,0 +1,107 @@ +/* + * This file is part of qpOASES. + * + * qpOASES -- An Implementation of the Online Active Set Strategy. + * Copyright (C) 2007-2008 by Hans Joachim Ferreau 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/EXTRAS/SolutionAnalysis.hpp + * \author Milan Vukov, Boris Houska, Hans Joachim Ferreau + * \version 1.3embedded + * \date 2012 + * + * Solution analysis class, based on a class in the standard version of the qpOASES + */ + + +// + +#ifndef QPOASES_SOLUTIONANALYSIS_HPP +#define QPOASES_SOLUTIONANALYSIS_HPP + +#include + +/** Enables the computation of variance as is in the standard version of qpOASES */ +#define QPOASES_USE_OLD_VERSION 0 + +#if QPOASES_USE_OLD_VERSION +#define KKT_DIM (2 * NVMAX + NCMAX) +#endif + +class SolutionAnalysis +{ +public: + + /** Default constructor. */ + SolutionAnalysis( ); + + /** Copy constructor (deep copy). */ + SolutionAnalysis( const SolutionAnalysis& rhs /**< Rhs object. */ + ); + + /** Destructor. */ + ~SolutionAnalysis( ); + + /** Copy asingment operator (deep copy). */ + SolutionAnalysis& operator=( const SolutionAnalysis& rhs /**< Rhs object. */ + ); + + /** A routine for computation of inverse of the Hessian matrix. */ + returnValue getHessianInverse( + QProblem* qp, /** QP */ + real_t* hessianInverse /** Inverse of the Hessian matrix*/ + ); + + /** A routine for computation of inverse of the Hessian matrix. */ + returnValue getHessianInverse( QProblemB* qp, /** QP */ + real_t* hessianInverse /** Inverse of the Hessian matrix*/ + ); + +#if QPOASES_USE_OLD_VERSION + returnValue getVarianceCovariance( + QProblem* qp, + real_t* g_b_bA_VAR, + real_t* Primal_Dual_VAR + ); +#endif + +private: + + real_t delta_g_cov[ NVMAX ]; /** A covariance-vector of g */ + real_t delta_lb_cov[ NVMAX ]; /** A covariance-vector of lb */ + real_t delta_ub_cov[ NVMAX ]; /** A covariance-vector of ub */ + real_t delta_lbA_cov[ NCMAX_ALLOC ]; /** A covariance-vector of lbA */ + real_t delta_ubA_cov[ NCMAX_ALLOC ]; /** A covariance-vector of ubA */ + +#if QPOASES_USE_OLD_VERSION + real_t K[KKT_DIM * KKT_DIM]; /** A matrix to store an intermediate result */ +#endif + + int FR_idx[ NVMAX ]; /** Index array for free variables */ + int FX_idx[ NVMAX ]; /** Index array for fixed variables */ + int AC_idx[ NCMAX_ALLOC ]; /** Index array for active constraints */ + + real_t delta_xFR[ NVMAX ]; /** QP reaction, primal, w.r.t. free */ + real_t delta_xFX[ NVMAX ]; /** QP reaction, primal, w.r.t. fixed */ + real_t delta_yAC[ NVMAX ]; /** QP reaction, dual, w.r.t. active */ + real_t delta_yFX[ NVMAX ]; /** QP reaction, dual, w.r.t. fixed*/ +}; + +#endif // QPOASES_SOLUTIONANALYSIS_HPP diff --git a/phonelibs/qpoases/INCLUDE/Indexlist.hpp b/phonelibs/qpoases/INCLUDE/Indexlist.hpp new file mode 100644 index 00000000000000..18e3494e3f656c --- /dev/null +++ b/phonelibs/qpoases/INCLUDE/Indexlist.hpp @@ -0,0 +1,154 @@ +/* + * This file is part of qpOASES. + * + * qpOASES -- An Implementation of the Online Active Set Strategy. + * Copyright (C) 2007-2008 by Hans Joachim Ferreau 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/Indexlist.hpp + * \author Hans Joachim Ferreau + * \version 1.3embedded + * \date 2007-2008 + * + * Declaration of the Indexlist class designed to manage index lists of + * constraints and bounds within a SubjectTo object. + */ + + +#ifndef QPOASES_INDEXLIST_HPP +#define QPOASES_INDEXLIST_HPP + + +#include + + +/** This class manages index lists. + * + * \author Hans Joachim Ferreau + * \version 1.3embedded + * \date 2007-2008 + */ +class Indexlist +{ + /* + * PUBLIC MEMBER FUNCTIONS + */ + public: + /** Default constructor. */ + Indexlist( ); + + /** Copy constructor (deep copy). */ + Indexlist( const Indexlist& rhs /**< Rhs object. */ + ); + + /** Destructor. */ + ~Indexlist( ); + + /** Assingment operator (deep copy). */ + Indexlist& operator=( const Indexlist& rhs /**< Rhs object. */ + ); + + /** Pseudo-constructor. + * \return SUCCESSFUL_RETURN */ + returnValue init( ); + + + /** Creates an array of all numbers within the index set in correct order. + * \return SUCCESSFUL_RETURN \n + RET_INDEXLIST_CORRUPTED */ + returnValue getNumberArray( int* const numberarray /**< Output: Array of numbers (NULL on error). */ + ) const; + + + /** Determines the index within the index list at with a given number is stored. + * \return >= 0: Index of given number. \n + -1: Number not found. */ + int getIndex( int givennumber /**< Number whose index shall be determined. */ + ) const; + + /** Determines the physical index within the index list at with a given number is stored. + * \return >= 0: Index of given number. \n + -1: Number not found. */ + int getPhysicalIndex( int givennumber /**< Number whose physical index shall be determined. */ + ) const; + + /** Returns the number stored at a given physical index. + * \return >= 0: Number stored at given physical index. \n + -RET_INDEXLIST_OUTOFBOUNDS */ + int getNumber( int physicalindex /**< Physical index of the number to be returned. */ + ) const; + + + /** Returns the current length of the index list. + * \return Current length of the index list. */ + inline int getLength( ); + + /** Returns last number within the index list. + * \return Last number within the index list. */ + inline int getLastNumber( ) const; + + + /** Adds number to index list. + * \return SUCCESSFUL_RETURN \n + RET_INDEXLIST_MUST_BE_REORDERD \n + RET_INDEXLIST_EXCEEDS_MAX_LENGTH */ + returnValue addNumber( int addnumber /**< Number to be added. */ + ); + + /** Removes number from index list. + * \return SUCCESSFUL_RETURN */ + returnValue removeNumber( int removenumber /**< Number to be removed. */ + ); + + /** Swaps two numbers within index list. + * \return SUCCESSFUL_RETURN */ + returnValue swapNumbers( 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 */ + inline BooleanType isMember( int _number /**< Number to be tested for membership. */ + ) const; + + + /* + * PROTECTED MEMBER VARIABLES + */ + protected: + int number[INDEXLISTFACTOR*(NVMAX+NCMAX)]; /**< Array to store numbers of constraints or bounds. */ + int next[INDEXLISTFACTOR*(NVMAX+NCMAX)]; /**< Array to store physical index of successor. */ + int previous[INDEXLISTFACTOR*(NVMAX+NCMAX)]; /**< Array to store physical index of predecossor. */ + 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. */ +}; + + +#include + +#endif /* QPOASES_INDEXLIST_HPP */ + + +/* + * end of file + */ diff --git a/phonelibs/qpoases/INCLUDE/MessageHandling.hpp b/phonelibs/qpoases/INCLUDE/MessageHandling.hpp new file mode 100644 index 00000000000000..f0b0c79a473b85 --- /dev/null +++ b/phonelibs/qpoases/INCLUDE/MessageHandling.hpp @@ -0,0 +1,415 @@ +/* + * This file is part of qpOASES. + * + * qpOASES -- An Implementation of the Online Active Set Strategy. + * Copyright (C) 2007-2008 by Hans Joachim Ferreau 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/MessageHandling.hpp + * \author Hans Joachim Ferreau + * \version 1.3embedded + * \date 2007-2008 + * + * Declaration of the MessageHandling class including global return values. + */ + + +#ifndef QPOASES_MESSAGEHANDLING_HPP +#define QPOASES_MESSAGEHANDLING_HPP + +// #define PC_DEBUG + +#ifdef PC_DEBUG + #include + + /** Defines an alias for FILE from stdio.h. */ + #define myFILE FILE + /** Defines an alias for stderr from stdio.h. */ + #define myStderr stderr + /** Defines an alias for stdout from stdio.h. */ + #define myStdout stdout +#else + /** Defines an alias for FILE from stdio.h. */ + #define myFILE int + /** Defines an alias for stderr from stdio.h. */ + #define myStderr 0 + /** Defines an alias for stdout from stdio.h. */ + #define myStdout 0 +#endif + + +#include +#include + + +/** Defines symbols for global return values. \n + * Important: All return values are assumed to be nonnegative! */ +enum returnValue +{ +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 occured is not yet known. */ +RET_PRINTLEVEL_CHANGED, /**< 10 Print level changed. */ +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. */ +RET_ADDINDEX_FAILED, /**< Cannot swap between different indexsets. */ +RET_SWAPINDEX_FAILED, /**< 20 Adding index to index set failed. */ +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. */ +/* QProblem */ +RET_QP_ALREADY_INITIALISED, /**< QProblem has already been initialised. */ +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, /**< 30 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_SUCCESSFUL, /**< Initialisation done. */ +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_EXTERN_SOLVER, /**< No extern QP solver available. */ +RET_QP_UNBOUNDED, /**< 40 QP is unbounded. */ +RET_QP_INFEASIBLE, /**< QP is infeasible. */ +RET_QP_NOT_SOLVED, /**< Problems occured while solving QP with standard solver. */ +RET_QP_SOLVED, /**< QP successfully solved. */ +RET_UNABLE_TO_SOLVE_QP, /**< Problems occured while solving QP. */ +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, /**< 50 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. */ +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, /**< 60 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. */ +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, /**< 70 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. */ +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, /**< 80 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 contraint matrix successfully resolved. */ +RET_ENSURELI_FAILED, /**< Failed to ensure linear indepence of active contraint matrix. */ +RET_ENSURELI_FAILED_TQ, /**< Abnormal termination due to TQ factorisation. */ +RET_ENSURELI_FAILED_NOINDEX, /**< No index found, QP probably infeasible. */ +RET_ENSURELI_FAILED_CYCLING, /**< Cycling detected, QP probably infeasible. */ +RET_BOUND_ALREADY_ACTIVE, /**< Bound is already active. */ +RET_ALL_BOUNDS_ACTIVE, /**< 90 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_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. */ +/* 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, /**< 100 Unable to read from file. */ +RET_FILEDATA_INCONSISTENT, /**< File contains inconsistent data. */ +/* SolutionAnalysis */ +RET_NO_SOLUTION, /**< QP solution does not satisfy KKT optimality conditions. */ +RET_INACCURATE_SOLUTION /**< KKT optimality conditions not satisfied to sufficient accuracy. */ +}; + + + +/** This class handles all kinds of messages (errors, warnings, infos) initiated + * by qpOASES modules and stores the correspoding global preferences. + * + * \author Hans Joachim Ferreau (special thanks to Leonard Wirsching) + * \version 1.3embedded + * \date 2007-2008 + */ +class MessageHandling +{ + /* + * INTERNAL DATA STRUCTURES + */ + public: + /** Data structure for entries in global message list. */ + 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; + + + /* + * PUBLIC MEMBER FUNCTIONS + */ + public: + /** Default constructor. */ + MessageHandling( ); + + /** Constructor which takes the desired output file. */ + MessageHandling( myFILE* _outputFile /**< Output file. */ + ); + + /** Constructor which takes the desired visibility states. */ + MessageHandling( VisibilityStatus _errorVisibility, /**< Visibility status for error messages. */ + VisibilityStatus _warningVisibility,/**< Visibility status for warning messages. */ + VisibilityStatus _infoVisibility /**< Visibility status for info messages. */ + ); + + /** Constructor which takes the desired output file and desired visibility states. */ + MessageHandling( myFILE* _outputFile, /**< Output file. */ + VisibilityStatus _errorVisibility, /**< Visibility status for error messages. */ + VisibilityStatus _warningVisibility,/**< Visibility status for warning messages. */ + VisibilityStatus _infoVisibility /**< Visibility status for info messages. */ + ); + + /** Copy constructor (deep copy). */ + MessageHandling( const MessageHandling& rhs /**< Rhs object. */ + ); + + /** Destructor. */ + ~MessageHandling( ); + + /** Assignment operator (deep copy). */ + MessageHandling& operator=( const MessageHandling& rhs /**< Rhs object. */ + ); + + + /** 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 throwError( + 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 myStderr. + * 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 throwWarning( + 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 myStderr. + * 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 throwInfo( + 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 myStderr. + * 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 reset( ); + + + /** Prints a complete list of all messages to output file. + * \return SUCCESSFUL_RETURN */ + returnValue listAllMessages( ); + + + /** Returns visibility status for error messages. + * \return Visibility status for error messages. */ + inline VisibilityStatus getErrorVisibilityStatus( ) const; + + /** Returns visibility status for warning messages. + * \return Visibility status for warning messages. */ + inline VisibilityStatus getWarningVisibilityStatus( ) const; + + /** Returns visibility status for info messages. + * \return Visibility status for info messages. */ + inline VisibilityStatus getInfoVisibilityStatus( ) const; + + /** Returns pointer to output file. + * \return Pointer to output file. */ + inline myFILE* getOutputFile( ) const; + + /** Returns error count value. + * \return Error count value. */ + inline int getErrorCount( ) const; + + + /** Changes visibility status for error messages. */ + inline void setErrorVisibilityStatus( VisibilityStatus _errorVisibility /**< New visibility status for error messages. */ + ); + + /** Changes visibility status for warning messages. */ + inline void setWarningVisibilityStatus( VisibilityStatus _warningVisibility /**< New visibility status for warning messages. */ + ); + + /** Changes visibility status for info messages. */ + inline void setInfoVisibilityStatus( VisibilityStatus _infoVisibility /**< New visibility status for info messages. */ + ); + + /** Changes output file for messages. */ + inline void setOutputFile( myFILE* _outputFile /**< New output file for messages. */ + ); + + /** Changes error count. + * \return SUCCESSFUL_RETURN \n + * RET_INVALID_ARGUMENT */ + inline returnValue setErrorCount( int _errorCount /**< New error count value. */ + ); + + /** Return the error code string. */ + static const char* getErrorString(int error); + + /* + * PROTECTED MEMBER FUNCTIONS + */ + protected: + /** Prints a info message to myStderr (auxiliary function). + * \return Error/warning/info number returned by sub function call + */ + returnValue throwMessage( + 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 myStderr. + * 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. */ + ); + + + /* + * PROTECTED MEMBER VARIABLES + */ + protected: + VisibilityStatus errorVisibility; /**< Error messages visible? */ + VisibilityStatus warningVisibility; /**< Warning messages visible? */ + VisibilityStatus infoVisibility; /**< Info messages visible? */ + + myFILE* outputFile; /**< Output file for messages. */ + + int errorCount; /**< Counts number of errors (for nicer output only). */ +}; + + +#ifndef __FUNCTION__ + /** Ensures that __FUNCTION__ macro is defined. */ + #define __FUNCTION__ 0 +#endif + +#ifndef __FILE__ + /** Ensures that __FILE__ macro is defined. */ + #define __FILE__ 0 +#endif + +#ifndef __LINE__ + /** Ensures that __LINE__ macro is defined. */ + #define __LINE__ 0 +#endif + + +/** Short version of throwError with default values, only returnValue is needed */ +#define THROWERROR(retval) ( getGlobalMessageHandler( )->throwError((retval),0,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE) ) + +/** Short version of throwWarning with default values, only returnValue is needed */ +#define THROWWARNING(retval) ( getGlobalMessageHandler( )->throwWarning((retval),0,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE) ) + +/** Short version of throwInfo with default values, only returnValue is needed */ +#define THROWINFO(retval) ( getGlobalMessageHandler( )->throwInfo((retval),0,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE) ) + + +/** Returns a pointer to global message handler. + * \return Pointer to global message handler. + */ +MessageHandling* getGlobalMessageHandler( ); + + +#include + +#endif /* QPOASES_MESSAGEHANDLING_HPP */ + + +/* + * end of file + */ diff --git a/phonelibs/qpoases/INCLUDE/QProblem.hpp b/phonelibs/qpoases/INCLUDE/QProblem.hpp new file mode 100644 index 00000000000000..68fc1af9c53a79 --- /dev/null +++ b/phonelibs/qpoases/INCLUDE/QProblem.hpp @@ -0,0 +1,666 @@ +/* + * This file is part of qpOASES. + * + * qpOASES -- An Implementation of the Online Active Set Strategy. + * Copyright (C) 2007-2008 by Hans Joachim Ferreau 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/QProblem.hpp + * \author Hans Joachim Ferreau + * \version 1.3embedded + * \date 2007-2008 + * + * Declaration of the QProblem class which is able to use the newly + * developed online active set strategy for parametric quadratic programming. + */ + + + +#ifndef QPOASES_QPROBLEM_HPP +#define QPOASES_QPROBLEM_HPP + + +#include +#include +#include + + +/** 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 + * \version 1.3embedded + * \date 2007-2008 + */ +class QProblem : public QProblemB +{ + /* allow SolutionAnalysis class to access private members */ + friend class SolutionAnalysis; + + /* + * PUBLIC MEMBER FUNCTIONS + */ + public: + /** Default constructor. */ + QProblem( ); + + /** Constructor which takes the QP dimensions only. */ + QProblem( int _nV, /**< Number of variables. */ + int _nC /**< Number of constraints. */ + ); + + /** Copy constructor (deep copy). */ + QProblem( const QProblem& rhs /**< Rhs object. */ + ); + + /** Destructor. */ + ~QProblem( ); + + /** Assignment operator (deep copy). */ + QProblem& operator=( const QProblem& rhs /**< Rhs object. */ + ); + + + /** Clears all data structures of QProblemB except for QP data. + * \return SUCCESSFUL_RETURN \n + RET_RESET_FAILED */ + returnValue reset( ); + + + /** Initialises a QProblem with given QP data and solves it + * using an initial homotopy with empty working set (at most nWSR iterations). + * \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 \n + RET_INACCURATE_SOLUTION \n + RET_NO_SOLUTION */ + returnValue init( const real_t* const _H, /**< Hessian 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). \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. */ + const real_t* const yOpt = 0, /**< Initial guess for dual solution vector. */ + real_t* const cputime = 0 /**< Output: CPU time required to initialise QP. */ + ); + + + /** Initialises a QProblem with given QP data and solves it + * using an initial homotopy with empty working set (at most nWSR iterations). + * \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 \n + RET_INACCURATE_SOLUTION \n + RET_NO_SOLUTION */ + returnValue init( const real_t* const _H, /**< Hessian matrix. */ + const real_t* const _R, /**< Cholesky factorization of the Hessian 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). \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. */ + const real_t* const yOpt = 0, /**< Initial guess for dual solution vector. */ + real_t* const cputime = 0 /**< Output: CPU time required to initialise QP. */ + ); + + + /** Solves QProblem using online active set strategy. + * \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_INACCURATE_SOLUTION \n + RET_NO_SOLUTION */ + returnValue hotstart( 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 /**< Output: CPU time required to solve QP (or to perform nWSR iterations). */ + ); + + + /** Returns constraint matrix of the QP (deep copy). + * \return SUCCESSFUL_RETURN */ + inline returnValue getA( real_t* const _A /**< Array of appropriate dimension for copying constraint matrix.*/ + ) const; + + /** Returns a single row of constraint matrix of the QP (deep copy). + * \return SUCCESSFUL_RETURN \n + RET_INDEX_OUT_OF_BOUNDS */ + inline returnValue getA( int number, /**< Number of entry to be returned. */ + real_t* const row /**< Array of appropriate dimension for copying (number)th constraint. */ + ) const; + + /** Returns lower constraints' bound vector of the QP (deep copy). + * \return SUCCESSFUL_RETURN */ + inline returnValue getLBA( real_t* const _lbA /**< Array of appropriate dimension for copying lower constraints' bound vector.*/ + ) const; + + /** Returns single entry of lower constraints' bound vector of the QP. + * \return SUCCESSFUL_RETURN \n + RET_INDEX_OUT_OF_BOUNDS */ + inline returnValue getLBA( int number, /**< Number of entry to be returned. */ + real_t& value /**< Output: lbA[number].*/ + ) const; + + /** Returns upper constraints' bound vector of the QP (deep copy). + * \return SUCCESSFUL_RETURN */ + inline returnValue getUBA( real_t* const _ubA /**< Array of appropriate dimension for copying upper constraints' bound vector.*/ + ) const; + + /** Returns single entry of upper constraints' bound vector of the QP. + * \return SUCCESSFUL_RETURN \n + RET_INDEX_OUT_OF_BOUNDS */ + inline returnValue getUBA( int number, /**< Number of entry to be returned. */ + real_t& value /**< Output: ubA[number].*/ + ) const; + + + /** Returns current constraints object of the QP (deep copy). + * \return SUCCESSFUL_RETURN */ + inline returnValue getConstraints( Constraints* const _constraints /** Output: Constraints object. */ + ) const; + + + /** Returns the number of constraints. + * \return Number of constraints. */ + inline int getNC( ) const; + + /** Returns the number of (implicitly defined) equality constraints. + * \return Number of (implicitly defined) equality constraints. */ + inline int getNEC( ) const; + + /** Returns the number of active constraints. + * \return Number of active constraints. */ + inline int getNAC( ); + + /** Returns the number of inactive constraints. + * \return Number of inactive constraints. */ + inline int getNIAC( ); + + /** Returns the dimension of null space. + * \return Dimension of null space. */ + int getNZ( ); + + + /** Returns the dual solution vector (deep copy). + * \return SUCCESSFUL_RETURN \n + RET_QP_NOT_SOLVED */ + returnValue getDualSolution( real_t* const yOpt /**< Output: Dual solution vector (if QP has been solved). */ + ) const; + + + /* + * PROTECTED MEMBER FUNCTIONS + */ + protected: + /** Determines type of constraints and bounds (i.e. implicitly fixed, unbounded etc.). + * \return SUCCESSFUL_RETURN \n + RET_SETUPSUBJECTTOTYPE_FAILED */ + returnValue setupSubjectToType( ); + + /** Computes the Cholesky decomposition R of the projected Hessian (i.e. R^T*R = Z^T*H*Z). + * \return SUCCESSFUL_RETURN \n + * RET_INDEXLIST_CORRUPTED */ + returnValue setupCholeskyDecompositionProjected( ); + + /** Initialises TQ factorisation of A (i.e. A*Q = [0 T]) if NO constraint is active. + * \return SUCCESSFUL_RETURN \n + RET_INDEXLIST_CORRUPTED */ + returnValue setupTQfactorisation( ); + + + /** 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. + * \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 solveInitialQP( const real_t* const xOpt, /**< Optimal primal solution vector. + * A NULL pointer can be passed. */ + const real_t* const yOpt, /**< Optimal dual solution vector. + * A NULL pointer can be passed. */ + const Bounds* const guessedBounds, /**< Guessed working set of bounds for solution (xOpt,yOpt). + * A NULL pointer can be passed. */ + const Constraints* const guessedConstraints, /**< Optimal working set of constraints for solution (xOpt,yOpt). + * 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 /**< Output: CPU time required to solve QP (or to perform nWSR iterations). */ + ); + + /** 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 obtainAuxiliaryWorkingSet( 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. */ + const Bounds* const guessedBounds, /**< Guessed working set of bounds for solution (xOpt,yOpt). */ + const 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. */ + ) const; + + /** Setups 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 setupAuxiliaryWorkingSet( const Bounds* const auxiliaryBounds, /**< Working set of bounds for auxiliary QP. */ + const 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. */ + ); + + /** Setups the optimal primal/dual solution of the auxiliary initial QP. + * \return SUCCESSFUL_RETURN */ + returnValue setupAuxiliaryQPsolution( 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. */ + ); + + /** Setups 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 setupAuxiliaryQPgradient( ); + + /** Setups (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 setupAuxiliaryQPbounds( const Bounds* const auxiliaryBounds, /**< Working set of bounds for auxiliary QP. */ + const 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 addConstraint( 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. */ + ); + + /** 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 addConstraint_checkLI( 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 addConstraint_ensureLI( 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 addBound( 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. */ + ); + + /** 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 addBound_checkLI( 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 addBound_ensureLI( 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 removeConstraint( int number, /**< Number of constraint to be removed from active set. */ + BooleanType updateCholesky /**< Flag indicating if Cholesky decomposition shall be updated. */ + ); + + /** Removes a bounds from active set. + * \return SUCCESSFUL_RETURN \n + RET_BOUND_NOT_ACTIVE \n + RET_HESSIAN_NOT_SPD \n + RET_REMOVEBOUND_FAILED */ + returnValue removeBound( int number, /**< Number of bound to be removed from active set. */ + BooleanType updateCholesky /**< Flag indicating if Cholesky decomposition shall be updated. */ + ); + + + /** 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 backsolveR( 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 backsolveR( 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 */ + ); + + + /** 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 backsolveT( 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 hotstart_determineDataShift(const int* const FX_idx, /**< Index array of fixed variables. */ + const int* const AC_idx, /**< Index array of active constraints. */ + 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 hotstart_determineStepDirection(const int* const FR_idx, /**< Index array of free variables. */ + const int* const FX_idx, /**< Index array of fixed variables. */ + const int* const AC_idx, /**< Index array of active constraints. */ + 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. + * \return SUCCESSFUL_RETURN */ + returnValue hotstart_determineStepLength( const int* const FR_idx, /**< Index array of free variables. */ + const int* const FX_idx, /**< Index array of fixed variables. */ + const int* const AC_idx, /**< Index array of active constraints. */ + const int* const IAC_idx, /**< Index array of inactive constraints. */ + 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. */ + real_t* const delta_Ax, /**< Output: Step in vector Ax. */ + 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. */ + ); + + /** Performs a step along the homotopy path (and updates active set). + * \return SUCCESSFUL_RETURN \n + RET_OPTIMAL_SOLUTION_FOUND \n + RET_REMOVE_FROM_ACTIVESET_FAILED \n + RET_ADD_TO_ACTIVESET_FAILED \n + RET_QP_INFEASIBLE */ + returnValue hotstart_performStep( const int* const FR_idx, /**< Index array of free variables. */ + const int* const FX_idx, /**< Index array of fixed variables. */ + const int* const AC_idx, /**< Index array of active constraints. */ + const int* const IAC_idx, /**< Index array of inactive constraints. */ + 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. */ + 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. */ + const real_t* const delta_Ax, /**< Step in vector Ax. */ + int BC_idx, /**< Index of blocking constraint. */ + SubjectToStatus BC_status, /**< Status of blocking constraint. */ + BooleanType BC_isBound /**< Indicates if blocking constraint is a bound. */ + ); + + + /** Checks if lower/upper (constraints') bounds remain consistent + * (i.e. if lb <= ub and lbA <= ubA ) during the current step. + * \return BT_TRUE iff (constraints") bounds remain consistent + */ + BooleanType areBoundsConsistent( 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_lbA, /**< Step direction of lower constraints' bounds. */ + const real_t* const delta_ubA /**< Step direction of upper constraints' bounds. */ + ) const; + + + /** Setups internal QP data. + * \return SUCCESSFUL_RETURN \n + RET_INVALID_ARGUMENTS */ + returnValue setupQPdata( const real_t* const _H, /**< Hessian matrix. */ + const real_t* const _R, /**< Cholesky factorization of the Hessian 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). \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. */ + ); + + + #ifdef PC_DEBUG /* Define print functions only for debugging! */ + + /** Prints concise information on the current iteration. + * \return SUCCESSFUL_RETURN \n */ + returnValue printIteration( int iteration, /**< 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. */ + ); + + /** Prints concise information on the current iteration. + * NOTE: ONLY DEFINED FOR SUPPRESSING A COMPILER WARNING!! + * \return SUCCESSFUL_RETURN \n */ + returnValue printIteration( int iteration, /**< Number of current iteration. */ + int BC_idx, /**< Index of blocking bound. */ + SubjectToStatus BC_status /**< Status of blocking bound. */ + ); + + #endif /* PC_DEBUG */ + + + /** Determines the maximum violation of the KKT optimality conditions + * of the current iterate within the QProblem object. + * \return SUCCESSFUL_RETURN \n + * RET_INACCURATE_SOLUTION \n + * RET_NO_SOLUTION */ + returnValue checkKKTconditions( ); + + + /** Sets constraint matrix of the QP. \n + (Remark: Also internal vector Ax is recomputed!) + * \return SUCCESSFUL_RETURN */ + inline returnValue setA( const real_t* const A_new /**< New constraint matrix (with correct dimension!). */ + ); + + /** Changes single row of constraint matrix of the QP. \n + (Remark: Also correponding component of internal vector Ax is recomputed!) + * \return SUCCESSFUL_RETURN \n + RET_INDEX_OUT_OF_BOUNDS */ + inline returnValue setA( int number, /**< Number of row to be changed. */ + const real_t* const value /**< New (number)th constraint (with correct dimension!). */ + ); + + + /** Sets constraints' lower bound vector of the QP. + * \return SUCCESSFUL_RETURN */ + inline returnValue setLBA( 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_INDEX_OUT_OF_BOUNDS */ + inline returnValue setLBA( 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 */ + inline returnValue setUBA( 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_INDEX_OUT_OF_BOUNDS */ + inline returnValue setUBA( int number, /**< Number of entry to be changed. */ + real_t value /**< New value for entry of upper constraints' bound vector (with correct dimension!). */ + ); + + + /* + * PROTECTED MEMBER VARIABLES + */ + protected: + real_t A[NCMAX_ALLOC*NVMAX]; /**< Constraint matrix. */ + real_t lbA[NCMAX_ALLOC]; /**< Lower constraints' bound vector. */ + real_t ubA[NCMAX_ALLOC]; /**< Upper constraints' bound vector. */ + + Constraints constraints; /**< Data structure for problem's constraints. */ + + real_t T[NVMAX*NVMAX]; /**< Reverse triangular matrix, A = [0 T]*Q'. */ + real_t Q[NVMAX*NVMAX]; /**< Orthonormal quadratic matrix, A = [0 T]*Q'. */ + int sizeT; /**< Matrix T is stored in a (sizeT x sizeT) array. */ + + real_t Ax[NCMAX_ALLOC]; /**< Stores the current product A*x (for increased efficiency only). */ + + CyclingManager cyclingManager; /**< Data structure for storing (possible) cycling information (NOT YET IMPLEMENTED!). */ +}; + + +#include + +#endif /* QPOASES_QPROBLEM_HPP */ + + +/* + * end of file + */ diff --git a/phonelibs/qpoases/INCLUDE/QProblemB.hpp b/phonelibs/qpoases/INCLUDE/QProblemB.hpp new file mode 100644 index 00000000000000..8b3acb82bddab4 --- /dev/null +++ b/phonelibs/qpoases/INCLUDE/QProblemB.hpp @@ -0,0 +1,628 @@ +/* + * This file is part of qpOASES. + * + * qpOASES -- An Implementation of the Online Active Set Strategy. + * Copyright (C) 2007-2008 by Hans Joachim Ferreau 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/QProblemB.hpp + * \author Hans Joachim Ferreau + * \version 1.3embedded + * \date 2007-2008 + * + * 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_HPP +#define QPOASES_QPROBLEMB_HPP + + +#include + + + +class SolutionAnalysis; + +/** Class for setting up and solving quadratic programs with (simple) bounds only. + * The main feature is the possibily to use the newly developed online active set strategy + * for parametric quadratic programming. + * + * \author Hans Joachim Ferreau + * \version 1.3embedded + * \date 2007-2008 + */ +class QProblemB +{ + /* allow SolutionAnalysis class to access private members */ + friend class SolutionAnalysis; + + /* + * PUBLIC MEMBER FUNCTIONS + */ + public: + /** Default constructor. */ + QProblemB( ); + + /** Constructor which takes the QP dimension only. */ + QProblemB( int _nV /**< Number of variables. */ + ); + + /** Copy constructor (deep copy). */ + QProblemB( const QProblemB& rhs /**< Rhs object. */ + ); + + /** Destructor. */ + ~QProblemB( ); + + /** Assignment operator (deep copy). */ + QProblemB& operator=( const QProblemB& rhs /**< Rhs object. */ + ); + + + /** Clears all data structures of QProblemB except for QP data. + * \return SUCCESSFUL_RETURN \n + RET_RESET_FAILED */ + returnValue reset( ); + + + /** Initialises a QProblemB with given QP data and solves it + * using an initial homotopy with empty working set (at most nWSR iterations). + * \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 \n + RET_INACCURATE_SOLUTION \n + RET_NO_SOLUTION */ + returnValue init( const real_t* const _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. */ + const real_t* const yOpt = 0, /**< Initial guess for dual solution vector. */ + real_t* const cputime = 0 /**< Output: CPU time required to initialise QP. */ + ); + + + /** Initialises a QProblemB with given QP data and solves it + * using an initial homotopy with empty working set (at most nWSR iterations). + * \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 \n + RET_INACCURATE_SOLUTION \n + RET_NO_SOLUTION */ + returnValue init( const real_t* const _H, /**< Hessian matrix. */ + const real_t* const _R, /**< Cholesky factorization of the 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. */ + const real_t* const yOpt = 0, /**< Initial guess for dual solution vector. */ + real_t* const cputime = 0 /**< Output: CPU time required to initialise QP. */ + ); + + + /** Solves an initialised QProblemB using online active set strategy. + * \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_INACCURATE_SOLUTION \n + RET_NO_SOLUTION */ + returnValue hotstart( 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 /**< Output: CPU time required to solve QP (or to perform nWSR iterations). */ + ); + + + /** Returns Hessian matrix of the QP (deep copy). + * \return SUCCESSFUL_RETURN */ + inline returnValue getH( real_t* const _H /**< Array of appropriate dimension for copying Hessian matrix.*/ + ) const; + + /** Returns gradient vector of the QP (deep copy). + * \return SUCCESSFUL_RETURN */ + inline returnValue getG( real_t* const _g /**< Array of appropriate dimension for copying gradient vector.*/ + ) const; + + /** Returns lower bound vector of the QP (deep copy). + * \return SUCCESSFUL_RETURN */ + inline returnValue getLB( real_t* const _lb /**< Array of appropriate dimension for copying lower bound vector.*/ + ) const; + + /** Returns single entry of lower bound vector of the QP. + * \return SUCCESSFUL_RETURN \n + RET_INDEX_OUT_OF_BOUNDS */ + inline returnValue getLB( int number, /**< Number of entry to be returned. */ + real_t& value /**< Output: lb[number].*/ + ) const; + + /** Returns upper bound vector of the QP (deep copy). + * \return SUCCESSFUL_RETURN */ + inline returnValue getUB( real_t* const _ub /**< Array of appropriate dimension for copying upper bound vector.*/ + ) const; + + /** Returns single entry of upper bound vector of the QP. + * \return SUCCESSFUL_RETURN \n + RET_INDEX_OUT_OF_BOUNDS */ + inline returnValue getUB( int number, /**< Number of entry to be returned. */ + real_t& value /**< Output: ub[number].*/ + ) const; + + + /** Returns current bounds object of the QP (deep copy). + * \return SUCCESSFUL_RETURN */ + inline returnValue getBounds( Bounds* const _bounds /** Output: Bounds object. */ + ) const; + + + /** Returns the number of variables. + * \return Number of variables. */ + inline int getNV( ) const; + + /** Returns the number of free variables. + * \return Number of free variables. */ + inline int getNFR( ); + + /** Returns the number of fixed variables. + * \return Number of fixed variables. */ + inline int getNFX( ); + + /** Returns the number of implicitly fixed variables. + * \return Number of implicitly fixed variables. */ + inline int getNFV( ) const; + + /** Returns the dimension of null space. + * \return Dimension of null space. */ + int getNZ( ); + + + /** 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 getObjVal( ) const; + + /** Returns the objective function value at an arbitrary point x. + * \return Objective function value at point x */ + real_t getObjVal( const real_t* const _x /**< Point at which the objective function shall be evaluated. */ + ) const; + + /** Returns the primal solution vector. + * \return SUCCESSFUL_RETURN \n + RET_QP_NOT_SOLVED */ + returnValue getPrimalSolution( real_t* const xOpt /**< Output: Primal solution vector (if QP has been solved). */ + ) const; + + /** Returns the dual solution vector. + * \return SUCCESSFUL_RETURN \n + RET_QP_NOT_SOLVED */ + returnValue getDualSolution( real_t* const yOpt /**< Output: Dual solution vector (if QP has been solved). */ + ) const; + + + /** Returns status of the solution process. + * \return Status of solution process. */ + inline QProblemStatus getStatus( ) const; + + + /** Returns if the QProblem object is initialised. + * \return BT_TRUE: QProblemB initialised \n + BT_FALSE: QProblemB not initialised */ + inline BooleanType isInitialised( ) const; + + /** Returns if the QP has been solved. + * \return BT_TRUE: QProblemB solved \n + BT_FALSE: QProblemB not solved */ + inline BooleanType isSolved( ) const; + + /** Returns if the QP is infeasible. + * \return BT_TRUE: QP infeasible \n + BT_FALSE: QP feasible (or not known to be infeasible!) */ + inline BooleanType isInfeasible( ) const; + + /** Returns if the QP is unbounded. + * \return BT_TRUE: QP unbounded \n + BT_FALSE: QP unbounded (or not known to be unbounded!) */ + inline BooleanType isUnbounded( ) const; + + + /** Returns the print level. + * \return Print level. */ + inline PrintLevel getPrintLevel( ) const; + + /** Changes the print level. + * \return SUCCESSFUL_RETURN */ + returnValue setPrintLevel( PrintLevel _printlevel /**< New print level. */ + ); + + + /** Returns Hessian type flag (type is not determined due to this call!). + * \return Hessian type. */ + inline HessianType getHessianType( ) const; + + /** Changes the print level. + * \return SUCCESSFUL_RETURN */ + inline returnValue setHessianType( HessianType _hessianType /**< New Hessian type. */ + ); + + + /* + * PROTECTED MEMBER FUNCTIONS + */ + protected: + /** Checks if Hessian happens to be the identity matrix, + * and sets corresponding status flag (otherwise the flag remains unaltered!). + * \return SUCCESSFUL_RETURN */ + returnValue checkForIdentityHessian( ); + + /** Determines type of constraints and bounds (i.e. implicitly fixed, unbounded etc.). + * \return SUCCESSFUL_RETURN \n + RET_SETUPSUBJECTTOTYPE_FAILED */ + returnValue setupSubjectToType( ); + + /** Computes the Cholesky decomposition R 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! + * \return SUCCESSFUL_RETURN \n + * RET_INDEXLIST_CORRUPTED */ + returnValue setupCholeskyDecomposition( ); + + + /** 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. + * \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 solveInitialQP( const real_t* const xOpt, /**< Optimal primal solution vector. + * A NULL pointer can be passed. */ + const real_t* const yOpt, /**< Optimal dual solution vector. + * A NULL pointer can be passed. */ + const Bounds* const guessedBounds, /**< Guessed working set for solution (xOpt,yOpt). + * 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 /**< Output: CPU time required to solve QP (or to perform nWSR iterations). */ + ); + + + /** 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 obtainAuxiliaryWorkingSet( 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. */ + const Bounds* const guessedBounds, /**< Guessed working set for solution (xOpt,yOpt). */ + Bounds* auxiliaryBounds /**< Input: Allocated bound object. \n + * Ouput: Working set for auxiliary QP. */ + ) const; + + /** Setups 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 setupAuxiliaryWorkingSet( const 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. */ + ); + + /** Setups the optimal primal/dual solution of the auxiliary initial QP. + * \return SUCCESSFUL_RETURN */ + returnValue setupAuxiliaryQPsolution( 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. */ + ); + + /** Setups 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 initialised!). + * \return SUCCESSFUL_RETURN */ + returnValue setupAuxiliaryQPgradient( ); + + /** Setups 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 setupAuxiliaryQPbounds( BooleanType useRelaxation /**< Flag indicating if inactive bounds shall be relaxed. */ + ); + + + /** Adds a bound to active set (specialised version for the case where no constraints exist). + * \return SUCCESSFUL_RETURN \n + RET_ADDBOUND_FAILED */ + returnValue addBound( 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 removeBound( int number, /**< Number of bound to be removed from active set. */ + BooleanType updateCholesky /**< Flag indicating if Cholesky decomposition shall be updated. */ + ); + + + /** 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 backsolveR( 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 backsolveR( 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 hotstart_determineDataShift(const int* const FX_idx, /**< Index array of fixed variables. */ + 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. */ + ); + + + /** Checks if lower/upper bounds remain consistent + * (i.e. if lb <= ub) during the current step. + * \return BT_TRUE iff bounds remain consistent + */ + BooleanType areBoundsConsistent( const real_t* const delta_lb, /**< Step direction of lower bounds. */ + const real_t* const delta_ub /**< Step direction of upper bounds. */ + ) const; + + + /** Setups internal QP data. + * \return SUCCESSFUL_RETURN \n + RET_INVALID_ARGUMENTS */ + returnValue setupQPdata( const real_t* const _H, /**< Hessian matrix. */ + const real_t* const _R, /**< Cholesky factorization of the 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 Hessian matrix of the QP. + * \return SUCCESSFUL_RETURN */ + inline returnValue setH( const real_t* const H_new /**< New Hessian matrix (with correct dimension!). */ + ); + + /** Changes gradient vector of the QP. + * \return SUCCESSFUL_RETURN */ + inline returnValue setG( const real_t* const g_new /**< New gradient vector (with correct dimension!). */ + ); + + /** Changes lower bound vector of the QP. + * \return SUCCESSFUL_RETURN */ + inline returnValue setLB( 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 */ + inline returnValue setLB( 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 */ + inline returnValue setUB( 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 */ + inline returnValue setUB( 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 */ + inline void 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. */ + ) const; + + /** Applies Givens matrix determined by c and s (cf. computeGivens). + * \return SUCCESSFUL_RETURN */ + inline void applyGivens( real_t c, /**< Cosine entry of Givens matrix. */ + real_t s, /**< Sine entry of Givens matrix. */ + 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. */ + ) const; + + + /* + * PRIVATE MEMBER FUNCTIONS + */ + private: + /** Determines step direction of the homotopy path. + * \return SUCCESSFUL_RETURN \n + RET_STEPDIRECTION_FAILED_CHOLESKY */ + returnValue hotstart_determineStepDirection(const int* const FR_idx, /**< Index array of free variables. */ + const int* const FX_idx, /**< Index array of fixed variables. */ + 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. + * \return SUCCESSFUL_RETURN */ + returnValue hotstart_determineStepLength( const int* const FR_idx, /**< Index array of free variables. */ + const int* const FX_idx, /**< Index array of fixed variables. */ + 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_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. */ + ); + + /** Performs a step along the homotopy path (and updates active set). + * \return SUCCESSFUL_RETURN \n + RET_OPTIMAL_SOLUTION_FOUND \n + RET_REMOVE_FROM_ACTIVESET_FAILED \n + RET_ADD_TO_ACTIVESET_FAILED \n + RET_QP_INFEASIBLE */ + returnValue hotstart_performStep( const int* const FR_idx, /**< Index array of free variables. */ + const int* const FX_idx, /**< Index array of fixed variables. */ + 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. */ + 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, /**< Index of blocking constraint. */ + SubjectToStatus BC_status /**< Status of blocking constraint. */ + ); + + + #ifdef PC_DEBUG /* Define print functions only for debugging! */ + + /** Prints concise information on the current iteration. + * \return SUCCESSFUL_RETURN \n */ + returnValue printIteration( int iteration, /**< Number of current iteration. */ + int BC_idx, /**< Index of blocking bound. */ + SubjectToStatus BC_status /**< Status of blocking bound. */ + ); + + #endif /* PC_DEBUG */ + + + /** Determines the maximum violation of the KKT optimality conditions + * of the current iterate within the QProblemB object. + * \return SUCCESSFUL_RETURN \n + * RET_INACCURATE_SOLUTION \n + * RET_NO_SOLUTION */ + returnValue checkKKTconditions( ); + + + /* + * PROTECTED MEMBER VARIABLES + */ + protected: + real_t H[NVMAX*NVMAX]; /**< Hessian matrix. */ + BooleanType hasHessian; /**< Flag indicating whether H contains Hessian or corresponding Cholesky factor R; \sa init. */ + + real_t g[NVMAX]; /**< Gradient. */ + real_t lb[NVMAX]; /**< Lower bound vector (on variables). */ + real_t ub[NVMAX]; /**< Upper bound vector (on variables). */ + + Bounds bounds; /**< Data structure for problem's bounds. */ + + real_t R[NVMAX*NVMAX]; /**< Cholesky decomposition of H (i.e. H = R^T*R). */ + BooleanType hasCholesky; /**< Flag indicating whether Cholesky decomposition has already been setup. */ + + real_t x[NVMAX]; /**< Primal solution vector. */ + real_t y[NVMAX+NCMAX]; /**< Dual solution vector. */ + + real_t tau; /**< Last homotopy step length. */ + + QProblemStatus status; /**< Current status of the solution process. */ + + BooleanType infeasible; /**< QP infeasible? */ + BooleanType unbounded; /**< QP unbounded? */ + + HessianType hessianType; /**< Type of Hessian matrix. */ + + PrintLevel printlevel; /**< Print level. */ + + int count; /**< Counts the number of hotstart function calls (internal usage only!). */ +}; + + +#include + +#endif /* QPOASES_QPROBLEMB_HPP */ + + +/* + * end of file + */ diff --git a/phonelibs/qpoases/INCLUDE/SubjectTo.hpp b/phonelibs/qpoases/INCLUDE/SubjectTo.hpp new file mode 100644 index 00000000000000..a014843ceabb24 --- /dev/null +++ b/phonelibs/qpoases/INCLUDE/SubjectTo.hpp @@ -0,0 +1,178 @@ +/* + * This file is part of qpOASES. + * + * qpOASES -- An Implementation of the Online Active Set Strategy. + * Copyright (C) 2007-2008 by Hans Joachim Ferreau 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/SubjectTo.hpp + * \author Hans Joachim Ferreau + * \version 1.3embedded + * \date 2007-2008 + * + * Declaration of the SubjectTo class designed to manage working sets of + * constraints and bounds within a QProblem. + */ + + +#ifndef QPOASES_SUBJECTTO_HPP +#define QPOASES_SUBJECTTO_HPP + + +#include + + + +/** This class manages working sets of constraints and bounds by storing + * index sets and other status information. + * + * \author Hans Joachim Ferreau + * \version 1.3embedded + * \date 2007-2008 + */ +class SubjectTo +{ + /* + * PUBLIC MEMBER FUNCTIONS + */ + public: + /** Default constructor. */ + SubjectTo( ); + + /** Copy constructor (deep copy). */ + SubjectTo( const SubjectTo& rhs /**< Rhs object. */ + ); + + /** Destructor. */ + ~SubjectTo( ); + + /** Assignment operator (deep copy). */ + SubjectTo& operator=( const SubjectTo& rhs /**< Rhs object. */ + ); + + + /** Pseudo-constructor takes the number of constraints or bounds. + * \return SUCCESSFUL_RETURN */ + returnValue init( int n /**< Number of constraints or bounds. */ + ); + + + /** Returns type of (constraints') bound. + * \return Type of (constraints') bound \n + RET_INDEX_OUT_OF_BOUNDS */ + inline SubjectToType getType( int i /**< Number of (constraints') bound. */ + ) const ; + + /** Returns status of (constraints') bound. + * \return Status of (constraints') bound \n + ST_UNDEFINED */ + inline SubjectToStatus getStatus( int i /**< Number of (constraints') bound. */ + ) const; + + + /** Sets type of (constraints') bound. + * \return SUCCESSFUL_RETURN \n + RET_INDEX_OUT_OF_BOUNDS */ + inline returnValue setType( 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 */ + inline returnValue setStatus( int i, /**< Number of (constraints') bound. */ + SubjectToStatus value /**< Status of (constraints') bound. */ + ); + + + /** Sets status of lower (constraints') bounds. */ + inline void setNoLower( BooleanType _status /**< Status of lower (constraints') bounds. */ + ); + + /** Sets status of upper (constraints') bounds. */ + inline void setNoUpper( 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. */ + inline BooleanType isNoLower( ) const; + + /** Returns status of upper bounds. + * \return BT_TRUE if there is no upper (constraints') bound on any variable. */ + inline BooleanType isNoUpper( ) const; + + + /* + * PROTECTED MEMBER FUNCTIONS + */ + protected: + /** Adds the index of a new constraint or bound to index set. + * \return SUCCESSFUL_RETURN \n + RET_ADDINDEX_FAILED */ + returnValue addIndex( Indexlist* const indexlist, /**< Index list to which the new index shall be added. */ + int newnumber, /**< Number of new constraint or bound. */ + SubjectToStatus newstatus /**< Status of new constraint or bound. */ + ); + + /** Removes the index of a constraint or bound from index set. + * \return SUCCESSFUL_RETURN \n + RET_UNKNOWN_BUG */ + returnValue removeIndex( Indexlist* const indexlist, /**< Index list from which the new index shall be removed. */ + int removenumber /**< Number of constraint or bound to be removed. */ + ); + + /** Swaps the indices of two constraints or bounds within the index set. + * \return SUCCESSFUL_RETURN \n + RET_SWAPINDEX_FAILED */ + returnValue swapIndex( Indexlist* const indexlist, /**< Index list in which the indices shold be swapped. */ + int number1, /**< Number of first constraint or bound. */ + int number2 /**< Number of second constraint or bound. */ + ); + + + /* + * PROTECTED MEMBER VARIABLES + */ + protected: + SubjectToType type[NVMAX+NCMAX]; /**< Type of constraints/bounds. */ + SubjectToStatus status[NVMAX+NCMAX]; /**< Status of constraints/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. */ + + + /* + * PRIVATE MEMBER VARIABLES + */ + private: + int size; +}; + + + +#include + +#endif /* QPOASES_SUBJECTTO_HPP */ + + +/* + * end of file + */ diff --git a/phonelibs/qpoases/INCLUDE/Types.hpp b/phonelibs/qpoases/INCLUDE/Types.hpp new file mode 100644 index 00000000000000..330f187c1e3d47 --- /dev/null +++ b/phonelibs/qpoases/INCLUDE/Types.hpp @@ -0,0 +1,131 @@ +/* + * This file is part of qpOASES. + * + * qpOASES -- An Implementation of the Online Active Set Strategy. + * Copyright (C) 2007-2008 by Hans Joachim Ferreau 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/Types.hpp + * \author Hans Joachim Ferreau + * \version 1.3embedded + * \date 2008 + * + * Declaration of all non-built-in types (except for classes). + */ + + +#ifndef QPOASES_TYPES_HPP +#define QPOASES_TYPES_HPP + + + +/** Define real_t for facilitating switching between double and float. */ +// typedef double real_t; + + +/** Summarises all possible logical values. */ +enum BooleanType +{ + BT_FALSE, /**< Logical value for "false". */ + BT_TRUE /**< Logical value for "true". */ +}; + + +/** Summarises all possible print levels. Print levels are used to describe + * the desired amount of output during runtime of qpOASES. */ +enum PrintLevel +{ + 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. */ +}; + + +/** Defines visibility status of a message. */ +enum VisibilityStatus +{ + VS_VISIBLE, /**< Message visible. */ + VS_HIDDEN /**< Message not visible. */ +}; + + +/** Summarises all possible states of the (S)QProblem(B) object during the +solution process of a QP sequence. */ +enum QProblemStatus +{ + 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. */ +}; + + +/** Summarises all possible types of bounds and constraints. */ +enum SubjectToType +{ + 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_UNKNOWN /**< Type of bound/constraint unknown. */ +}; + + +/** Summarises all possible states of bounds and constraints. */ +enum SubjectToStatus +{ + ST_INACTIVE, /**< Bound/constraint is inactive. */ + ST_LOWER, /**< Bound/constraint is at its lower bound. */ + ST_UPPER, /**< Bound/constraint is at its upper bound. */ + ST_UNDEFINED /**< Status of bound/constraint undefined. */ +}; + + +/** Summarises all possible cycling states of bounds and constraints. */ +enum CyclingStatus +{ + CYC_NOT_INVOLVED, /**< Bound/constraint is not involved in current cycling. */ + CYC_PREV_ADDED, /**< Bound/constraint has previously been added during the current cycling. */ + CYC_PREV_REMOVED /**< Bound/constraint has previously been removed during the current cycling. */ +}; + + +/** Summarises all possible types of the QP's Hessian matrix. */ +enum HessianType +{ + HST_SEMIDEF, /**< Hessian is positive semi-definite. */ + HST_POSDEF_NULLSPACE, /**< Hessian is positive definite on null space of active bounds/constraints. */ + HST_POSDEF, /**< Hessian is (strictly) positive definite. */ + HST_IDENTITY /**< Hessian is identity matrix. */ +}; + + + +#endif /* QPOASES_TYPES_HPP */ + + +/* + * end of file + */ diff --git a/phonelibs/qpoases/INCLUDE/Utils.hpp b/phonelibs/qpoases/INCLUDE/Utils.hpp new file mode 100644 index 00000000000000..16546a991b1945 --- /dev/null +++ b/phonelibs/qpoases/INCLUDE/Utils.hpp @@ -0,0 +1,197 @@ +/* + * This file is part of qpOASES. + * + * qpOASES -- An Implementation of the Online Active Set Strategy. + * Copyright (C) 2007-2008 by Hans Joachim Ferreau 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/Utils.hpp + * \author Hans Joachim Ferreau + * \version 1.3embedded + * \date 2007-2008 + * + * Declaration of global utility functions for working with qpOASES. + */ + + +#ifndef QPOASES_UTILS_HPP +#define QPOASES_UTILS_HPP + + +#include + + +#ifdef PC_DEBUG /* Define print functions only for debugging! */ + +/** Prints a vector. + * \return SUCCESSFUL_RETURN */ +returnValue print( const real_t* const v, /**< Vector to be printed. */ + int n /**< Length of vector. */ + ); + +/** Prints a permuted vector. + * \return SUCCESSFUL_RETURN */ +returnValue print( 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 print( 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 print( 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 print( 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 print( 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 print( const int* const index, /**< Index array to be printed. */ + int n /**< Length of index array. */ + ); + +/** Prints a named index array. + * \return SUCCESSFUL_RETURN */ +returnValue print( 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 myPrintf( const char* s /**< String to be written. */ + ); + + +/** Prints qpOASES copyright notice. + * \return SUCCESSFUL_RETURN */ +returnValue printCopyrightNotice( ); + + +/** Reads a real_t matrix from file. + * \return SUCCESSFUL_RETURN \n + RET_UNABLE_TO_OPEN_FILE \n + RET_UNABLE_TO_READ_FILE */ +returnValue readFromFile( 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 readFromFile( 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 readFromFile( 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 writeIntoFile( 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 writeIntoFile( 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 writeIntoFile( 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). */ + ); + +#endif /* PC_DEBUG */ + + +/** Returns the current system time. + * \return current system time */ +real_t getCPUtime( ); + + +/** Returns the Euclidean norm of a vector. + * \return 0: successful */ +real_t getNorm( const real_t* const v, /**< Vector. */ + int n /**< Vector's dimension. */ + ); + +/** Returns the absolute value of a real_t. + * \return Absolute value of a real_t */ +inline real_t getAbs( real_t x /**< Input argument. */ + ); + + + +#include + +#endif /* QPOASES_UTILS_HPP */ + + +/* + * end of file + */ diff --git a/phonelibs/qpoases/LICENSE.txt b/phonelibs/qpoases/LICENSE.txt new file mode 100644 index 00000000000000..5faba9d48ce750 --- /dev/null +++ b/phonelibs/qpoases/LICENSE.txt @@ -0,0 +1,504 @@ + GNU LESSER GENERAL PUBLIC LICENSE + Version 2.1, February 1999 + + Copyright (C) 1991, 1999 Free Software Foundation, Inc. + 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA + Everyone is permitted to copy and distribute verbatim copies + of this license document, but changing it is not allowed. + +[This is the first released version of the Lesser GPL. It also counts + as the successor of the GNU Library Public License, version 2, hence + the version number 2.1.] + + Preamble + + The licenses for most software are designed to take away your +freedom to share and change it. By contrast, the GNU General Public +Licenses are intended to guarantee your freedom to share and change +free software--to make sure the software is free for all its users. + + This license, the Lesser General Public License, applies to some +specially designated software packages--typically libraries--of the +Free Software Foundation and other authors who decide to use it. You +can use it too, but we suggest you first think carefully about whether +this license or the ordinary General Public License is the better +strategy to use in any particular case, based on the explanations below. + + When we speak of free software, we are referring to freedom of use, +not price. Our General Public Licenses are designed to make sure that +you have the freedom to distribute copies of free software (and charge +for this service if you wish); that you receive source code or can get +it if you want it; that you can change the software and use pieces of +it in new free programs; and that you are informed that you can do +these things. + + To protect your rights, we need to make restrictions that forbid +distributors to deny you these rights or to ask you to surrender these +rights. These restrictions translate to certain responsibilities for +you if you distribute copies of the library or if you modify it. + + For example, if you distribute copies of the library, whether gratis +or for a fee, you must give the recipients all the rights that we gave +you. You must make sure that they, too, receive or can get the source +code. If you link other code with the library, you must provide +complete object files to the recipients, so that they can relink them +with the library after making changes to the library and recompiling +it. And you must show them these terms so they know their rights. + + We protect your rights with a two-step method: (1) we copyright the +library, and (2) we offer you this license, which gives you legal +permission to copy, distribute and/or modify the library. + + To protect each distributor, we want to make it very clear that +there is no warranty for the free library. Also, if the library is +modified by someone else and passed on, the recipients should know +that what they have is not the original version, so that the original +author's reputation will not be affected by problems that might be +introduced by others. + + Finally, software patents pose a constant threat to the existence of +any free program. We wish to make sure that a company cannot +effectively restrict the users of a free program by obtaining a +restrictive license from a patent holder. Therefore, we insist that +any patent license obtained for a version of the library must be +consistent with the full freedom of use specified in this license. + + Most GNU software, including some libraries, is covered by the +ordinary GNU General Public License. This license, the GNU Lesser +General Public License, applies to certain designated libraries, and +is quite different from the ordinary General Public License. We use +this license for certain libraries in order to permit linking those +libraries into non-free programs. + + When a program is linked with a library, whether statically or using +a shared library, the combination of the two is legally speaking a +combined work, a derivative of the original library. The ordinary +General Public License therefore permits such linking only if the +entire combination fits its criteria of freedom. The Lesser General +Public License permits more lax criteria for linking other code with +the library. + + We call this license the "Lesser" General Public License because it +does Less to protect the user's freedom than the ordinary General +Public License. It also provides other free software developers Less +of an advantage over competing non-free programs. These disadvantages +are the reason we use the ordinary General Public License for many +libraries. However, the Lesser license provides advantages in certain +special circumstances. + + For example, on rare occasions, there may be a special need to +encourage the widest possible use of a certain library, so that it becomes +a de-facto standard. To achieve this, non-free programs must be +allowed to use the library. A more frequent case is that a free +library does the same job as widely used non-free libraries. In this +case, there is little to gain by limiting the free library to free +software only, so we use the Lesser General Public License. + + In other cases, permission to use a particular library in non-free +programs enables a greater number of people to use a large body of +free software. For example, permission to use the GNU C Library in +non-free programs enables many more people to use the whole GNU +operating system, as well as its variant, the GNU/Linux operating +system. + + Although the Lesser General Public License is Less protective of the +users' freedom, it does ensure that the user of a program that is +linked with the Library has the freedom and the wherewithal to run +that program using a modified version of the Library. + + The precise terms and conditions for copying, distribution and +modification follow. Pay close attention to the difference between a +"work based on the library" and a "work that uses the library". The +former contains code derived from the library, whereas the latter must +be combined with the library in order to run. + + GNU LESSER GENERAL PUBLIC LICENSE + TERMS AND CONDITIONS FOR COPYING, DISTRIBUTION AND MODIFICATION + + 0. This License Agreement applies to any software library or other +program which contains a notice placed by the copyright holder or +other authorized party saying it may be distributed under the terms of +this Lesser General Public License (also called "this License"). +Each licensee is addressed as "you". + + A "library" means a collection of software functions and/or data +prepared so as to be conveniently linked with application programs +(which use some of those functions and data) to form executables. + + The "Library", below, refers to any such software library or work +which has been distributed under these terms. A "work based on the +Library" means either the Library or any derivative work under +copyright law: that is to say, a work containing the Library or a +portion of it, either verbatim or with modifications and/or translated +straightforwardly into another language. (Hereinafter, translation is +included without limitation in the term "modification".) + + "Source code" for a work means the preferred form of the work for +making modifications to it. For a library, complete source code means +all the source code for all modules it contains, plus any associated +interface definition files, plus the scripts used to control compilation +and installation of the library. + + Activities other than copying, distribution and modification are not +covered by this License; they are outside its scope. The act of +running a program using the Library is not restricted, and output from +such a program is covered only if its contents constitute a work based +on the Library (independent of the use of the Library in a tool for +writing it). Whether that is true depends on what the Library does +and what the program that uses the Library does. + + 1. You may copy and distribute verbatim copies of the Library's +complete source code as you receive it, in any medium, provided that +you conspicuously and appropriately publish on each copy an +appropriate copyright notice and disclaimer of warranty; keep intact +all the notices that refer to this License and to the absence of any +warranty; and distribute a copy of this License along with the +Library. + + You may charge a fee for the physical act of transferring a copy, +and you may at your option offer warranty protection in exchange for a +fee. + + 2. You may modify your copy or copies of the Library or any portion +of it, thus forming a work based on the Library, and copy and +distribute such modifications or work under the terms of Section 1 +above, provided that you also meet all of these conditions: + + a) The modified work must itself be a software library. + + b) You must cause the files modified to carry prominent notices + stating that you changed the files and the date of any change. + + c) You must cause the whole of the work to be licensed at no + charge to all third parties under the terms of this License. + + d) If a facility in the modified Library refers to a function or a + table of data to be supplied by an application program that uses + the facility, other than as an argument passed when the facility + is invoked, then you must make a good faith effort to ensure that, + in the event an application does not supply such function or + table, the facility still operates, and performs whatever part of + its purpose remains meaningful. + + (For example, a function in a library to compute square roots has + a purpose that is entirely well-defined independent of the + application. Therefore, Subsection 2d requires that any + application-supplied function or table used by this function must + be optional: if the application does not supply it, the square + root function must still compute square roots.) + +These requirements apply to the modified work as a whole. If +identifiable sections of that work are not derived from the Library, +and can be reasonably considered independent and separate works in +themselves, then this License, and its terms, do not apply to those +sections when you distribute them as separate works. But when you +distribute the same sections as part of a whole which is a work based +on the Library, the distribution of the whole must be on the terms of +this License, whose permissions for other licensees extend to the +entire whole, and thus to each and every part regardless of who wrote +it. + +Thus, it is not the intent of this section to claim rights or contest +your rights to work written entirely by you; rather, the intent is to +exercise the right to control the distribution of derivative or +collective works based on the Library. + +In addition, mere aggregation of another work not based on the Library +with the Library (or with a work based on the Library) on a volume of +a storage or distribution medium does not bring the other work under +the scope of this License. + + 3. You may opt to apply the terms of the ordinary GNU General Public +License instead of this License to a given copy of the Library. To do +this, you must alter all the notices that refer to this License, so +that they refer to the ordinary GNU General Public License, version 2, +instead of to this License. (If a newer version than version 2 of the +ordinary GNU General Public License has appeared, then you can specify +that version instead if you wish.) Do not make any other change in +these notices. + + Once this change is made in a given copy, it is irreversible for +that copy, so the ordinary GNU General Public License applies to all +subsequent copies and derivative works made from that copy. + + This option is useful when you wish to copy part of the code of +the Library into a program that is not a library. + + 4. You may copy and distribute the Library (or a portion or +derivative of it, under Section 2) in object code or executable form +under the terms of Sections 1 and 2 above provided that you accompany +it with the complete corresponding machine-readable source code, which +must be distributed under the terms of Sections 1 and 2 above on a +medium customarily used for software interchange. + + If distribution of object code is made by offering access to copy +from a designated place, then offering equivalent access to copy the +source code from the same place satisfies the requirement to +distribute the source code, even though third parties are not +compelled to copy the source along with the object code. + + 5. A program that contains no derivative of any portion of the +Library, but is designed to work with the Library by being compiled or +linked with it, is called a "work that uses the Library". Such a +work, in isolation, is not a derivative work of the Library, and +therefore falls outside the scope of this License. + + However, linking a "work that uses the Library" with the Library +creates an executable that is a derivative of the Library (because it +contains portions of the Library), rather than a "work that uses the +library". The executable is therefore covered by this License. +Section 6 states terms for distribution of such executables. + + When a "work that uses the Library" uses material from a header file +that is part of the Library, the object code for the work may be a +derivative work of the Library even though the source code is not. +Whether this is true is especially significant if the work can be +linked without the Library, or if the work is itself a library. The +threshold for this to be true is not precisely defined by law. + + If such an object file uses only numerical parameters, data +structure layouts and accessors, and small macros and small inline +functions (ten lines or less in length), then the use of the object +file is unrestricted, regardless of whether it is legally a derivative +work. (Executables containing this object code plus portions of the +Library will still fall under Section 6.) + + Otherwise, if the work is a derivative of the Library, you may +distribute the object code for the work under the terms of Section 6. +Any executables containing that work also fall under Section 6, +whether or not they are linked directly with the Library itself. + + 6. As an exception to the Sections above, you may also combine or +link a "work that uses the Library" with the Library to produce a +work containing portions of the Library, and distribute that work +under terms of your choice, provided that the terms permit +modification of the work for the customer's own use and reverse +engineering for debugging such modifications. + + You must give prominent notice with each copy of the work that the +Library is used in it and that the Library and its use are covered by +this License. You must supply a copy of this License. If the work +during execution displays copyright notices, you must include the +copyright notice for the Library among them, as well as a reference +directing the user to the copy of this License. Also, you must do one +of these things: + + a) Accompany the work with the complete corresponding + machine-readable source code for the Library including whatever + changes were used in the work (which must be distributed under + Sections 1 and 2 above); and, if the work is an executable linked + with the Library, with the complete machine-readable "work that + uses the Library", as object code and/or source code, so that the + user can modify the Library and then relink to produce a modified + executable containing the modified Library. (It is understood + that the user who changes the contents of definitions files in the + Library will not necessarily be able to recompile the application + to use the modified definitions.) + + b) Use a suitable shared library mechanism for linking with the + Library. A suitable mechanism is one that (1) uses at run time a + copy of the library already present on the user's computer system, + rather than copying library functions into the executable, and (2) + will operate properly with a modified version of the library, if + the user installs one, as long as the modified version is + interface-compatible with the version that the work was made with. + + c) Accompany the work with a written offer, valid for at + least three years, to give the same user the materials + specified in Subsection 6a, above, for a charge no more + than the cost of performing this distribution. + + d) If distribution of the work is made by offering access to copy + from a designated place, offer equivalent access to copy the above + specified materials from the same place. + + e) Verify that the user has already received a copy of these + materials or that you have already sent this user a copy. + + For an executable, the required form of the "work that uses the +Library" must include any data and utility programs needed for +reproducing the executable from it. However, as a special exception, +the materials to be distributed need not include anything that is +normally distributed (in either source or binary form) with the major +components (compiler, kernel, and so on) of the operating system on +which the executable runs, unless that component itself accompanies +the executable. + + It may happen that this requirement contradicts the license +restrictions of other proprietary libraries that do not normally +accompany the operating system. Such a contradiction means you cannot +use both them and the Library together in an executable that you +distribute. + + 7. You may place library facilities that are a work based on the +Library side-by-side in a single library together with other library +facilities not covered by this License, and distribute such a combined +library, provided that the separate distribution of the work based on +the Library and of the other library facilities is otherwise +permitted, and provided that you do these two things: + + a) Accompany the combined library with a copy of the same work + based on the Library, uncombined with any other library + facilities. This must be distributed under the terms of the + Sections above. + + b) Give prominent notice with the combined library of the fact + that part of it is a work based on the Library, and explaining + where to find the accompanying uncombined form of the same work. + + 8. You may not copy, modify, sublicense, link with, or distribute +the Library except as expressly provided under this License. Any +attempt otherwise to copy, modify, sublicense, link with, or +distribute the Library is void, and will automatically terminate your +rights under this License. However, parties who have received copies, +or rights, from you under this License will not have their licenses +terminated so long as such parties remain in full compliance. + + 9. You are not required to accept this License, since you have not +signed it. However, nothing else grants you permission to modify or +distribute the Library or its derivative works. These actions are +prohibited by law if you do not accept this License. Therefore, by +modifying or distributing the Library (or any work based on the +Library), you indicate your acceptance of this License to do so, and +all its terms and conditions for copying, distributing or modifying +the Library or works based on it. + + 10. Each time you redistribute the Library (or any work based on the +Library), the recipient automatically receives a license from the +original licensor to copy, distribute, link with or modify the Library +subject to these terms and conditions. You may not impose any further +restrictions on the recipients' exercise of the rights granted herein. +You are not responsible for enforcing compliance by third parties with +this License. + + 11. If, as a consequence of a court judgment or allegation of patent +infringement or for any other reason (not limited to patent issues), +conditions are imposed on you (whether by court order, agreement or +otherwise) that contradict the conditions of this License, they do not +excuse you from the conditions of this License. If you cannot +distribute so as to satisfy simultaneously your obligations under this +License and any other pertinent obligations, then as a consequence you +may not distribute the Library at all. For example, if a patent +license would not permit royalty-free redistribution of the Library by +all those who receive copies directly or indirectly through you, then +the only way you could satisfy both it and this License would be to +refrain entirely from distribution of the Library. + +If any portion of this section is held invalid or unenforceable under any +particular circumstance, the balance of the section is intended to apply, +and the section as a whole is intended to apply in other circumstances. + +It is not the purpose of this section to induce you to infringe any +patents or other property right claims or to contest validity of any +such claims; this section has the sole purpose of protecting the +integrity of the free software distribution system which is +implemented by public license practices. Many people have made +generous contributions to the wide range of software distributed +through that system in reliance on consistent application of that +system; it is up to the author/donor to decide if he or she is willing +to distribute software through any other system and a licensee cannot +impose that choice. + +This section is intended to make thoroughly clear what is believed to +be a consequence of the rest of this License. + + 12. If the distribution and/or use of the Library is restricted in +certain countries either by patents or by copyrighted interfaces, the +original copyright holder who places the Library under this License may add +an explicit geographical distribution limitation excluding those countries, +so that distribution is permitted only in or among countries not thus +excluded. In such case, this License incorporates the limitation as if +written in the body of this License. + + 13. The Free Software Foundation may publish revised and/or new +versions of the Lesser General Public License from time to time. +Such new versions will be similar in spirit to the present version, +but may differ in detail to address new problems or concerns. + +Each version is given a distinguishing version number. If the Library +specifies a version number of this License which applies to it and +"any later version", you have the option of following the terms and +conditions either of that version or of any later version published by +the Free Software Foundation. If the Library does not specify a +license version number, you may choose any version ever published by +the Free Software Foundation. + + 14. If you wish to incorporate parts of the Library into other free +programs whose distribution conditions are incompatible with these, +write to the author to ask for permission. For software which is +copyrighted by the Free Software Foundation, write to the Free +Software Foundation; we sometimes make exceptions for this. Our +decision will be guided by the two goals of preserving the free status +of all derivatives of our free software and of promoting the sharing +and reuse of software generally. + + NO WARRANTY + + 15. BECAUSE THE LIBRARY IS LICENSED FREE OF CHARGE, THERE IS NO +WARRANTY FOR THE LIBRARY, TO THE EXTENT PERMITTED BY APPLICABLE LAW. +EXCEPT WHEN OTHERWISE STATED IN WRITING THE COPYRIGHT HOLDERS AND/OR +OTHER PARTIES PROVIDE THE LIBRARY "AS IS" WITHOUT WARRANTY OF ANY +KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING, BUT NOT LIMITED TO, THE +IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR +PURPOSE. THE ENTIRE RISK AS TO THE QUALITY AND PERFORMANCE OF THE +LIBRARY IS WITH YOU. SHOULD THE LIBRARY PROVE DEFECTIVE, YOU ASSUME +THE COST OF ALL NECESSARY SERVICING, REPAIR OR CORRECTION. + + 16. IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN +WRITING WILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MAY MODIFY +AND/OR REDISTRIBUTE THE LIBRARY AS PERMITTED ABOVE, BE LIABLE TO YOU +FOR DAMAGES, INCLUDING ANY GENERAL, SPECIAL, INCIDENTAL OR +CONSEQUENTIAL DAMAGES ARISING OUT OF THE USE OR INABILITY TO USE THE +LIBRARY (INCLUDING BUT NOT LIMITED TO LOSS OF DATA OR DATA BEING +RENDERED INACCURATE OR LOSSES SUSTAINED BY YOU OR THIRD PARTIES OR A +FAILURE OF THE LIBRARY TO OPERATE WITH ANY OTHER SOFTWARE), EVEN IF +SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH +DAMAGES. + + END OF TERMS AND CONDITIONS + + How to Apply These Terms to Your New Libraries + + If you develop a new library, and you want it to be of the greatest +possible use to the public, we recommend making it free software that +everyone can redistribute and change. You can do so by permitting +redistribution under these terms (or, alternatively, under the terms of the +ordinary General Public License). + + To apply these terms, attach the following notices to the library. It is +safest to attach them to the start of each source file to most effectively +convey the exclusion of warranty; and each file should have at least the +"copyright" line and a pointer to where the full notice is found. + + + Copyright (C) + + This library 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. + + This library 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 this library; if not, write to the Free Software + Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA + +Also add information on how to contact you by electronic and paper mail. + +You should also get your employer (if you work as a programmer) or your +school, if any, to sign a "copyright disclaimer" for the library, if +necessary. Here is a sample; alter the names: + + Yoyodyne, Inc., hereby disclaims all copyright interest in the + library `Frob' (a library for tweaking knobs) written by James Random Hacker. + + , 1 April 1990 + Ty Coon, President of Vice + +That's all there is to it! + + diff --git a/phonelibs/qpoases/README.txt b/phonelibs/qpoases/README.txt new file mode 100644 index 00000000000000..37175d9192bdbe --- /dev/null +++ b/phonelibs/qpoases/README.txt @@ -0,0 +1,92 @@ +## +## qpOASES -- An Implementation of the Online Active Set Strategy. +## Copyright (C) 2007-2008 by Hans Joachim Ferreau 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 +## + + + +INTRODUCTION +============= + +qpOASES is an open-source C++ implementation of the recently proposed +online active set strategy (see [1], [2]), which was inspired by important +observations from the field of parametric quadratic programming. It has +several theoretical features that make it particularly suited for model +predictive control (MPC) applications. + +The software package qpOASES implements these ideas and has already been +successfully used for closed-loop control of a real-world Diesel engine [3]. + + +References: + +[1] H.J. Ferreau. An Online Active Set Strategy for Fast Solution of +Parametric Quadratic Programs with Applications to Predictive Engine Control. +Diplom thesis, University of Heidelberg, 2006. + +[2] H.J. Ferreau, H.G. Bock, M. Diehl. An online active set strategy to +overcome the limitations of explicit MPC. International Journal of Robust +and Nonlinear Control, 18 (8), pp. 816-830, 2008. + +[3] H.J. Ferreau, P. Ortner, P. Langthaler, L. del Re, M. Diehl. Predictive +Control of a Real-World Diesel Engine using an Extended Online Active Set +Strategy. Annual Reviews in Control, 31 (2), pp. 293-301, 2007. + + + +GETTING STARTED +================ + +1. For installation, usage and additional information on this software package + see the qpOASES User's Manual located at ./DOC/manual.pdf! + + +2. The file ./LICENSE.txt contains a copy of the GNU Lesser General Public + License. Please read it carefully before using qpOASES! + + +3. The whole software package can be downloaded from + + http://homes.esat.kuleuven.be/~optec/software/qpOASES/ + + On this webpage you will also find a list of frequently asked questions. + + + +CONTACT THE AUTHORS +==================== + +If you have got questions, remarks or comments on qpOASES +please contact the main author: + + Hans Joachim Ferreau + Katholieke Universiteit Leuven + Department of Electrical Engineering (ESAT) + Kasteelpark Arenberg 10, bus 2446 + B-3001 Leuven-Heverlee, Belgium + + Phone: +32 16 32 03 63 + E-mail: joachim.ferreau@esat.kuleuven.be + qpOASES@esat.kuleuven.be + +Also bug reports and source code extensions are most welcome! + + + +## +## end of file +## diff --git a/phonelibs/qpoases/SRC/Bounds.cpp b/phonelibs/qpoases/SRC/Bounds.cpp new file mode 100644 index 00000000000000..236ab2f62d284b --- /dev/null +++ b/phonelibs/qpoases/SRC/Bounds.cpp @@ -0,0 +1,252 @@ +/* + * This file is part of qpOASES. + * + * qpOASES -- An Implementation of the Online Active Set Strategy. + * Copyright (C) 2007-2008 by Hans Joachim Ferreau 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 SRC/Bounds.cpp + * \author Hans Joachim Ferreau + * \version 1.3embedded + * \date 2007-2008 + * + * Implementation of the Bounds class designed to manage working sets of + * bounds within a QProblem. + */ + + +#include + + + +/***************************************************************************** + * P U B L I C * + *****************************************************************************/ + + +/* + * B o u n d s + */ +Bounds::Bounds( ) : SubjectTo( ), + nV( 0 ), + nFV( 0 ), + nBV( 0 ), + nUV( 0 ) +{ +} + + +/* + * B o u n d s + */ +Bounds::Bounds( const Bounds& rhs ) : SubjectTo( rhs ), + nV( rhs.nV ), + nFV( rhs.nFV ), + nBV( rhs.nBV ), + nUV( rhs.nUV ) +{ + free = rhs.free; + fixed = rhs.fixed; +} + + +/* + * ~ B o u n d s + */ +Bounds::~Bounds( ) +{ +} + + +/* + * o p e r a t o r = + */ +Bounds& Bounds::operator=( const Bounds& rhs ) +{ + if ( this != &rhs ) + { + SubjectTo::operator=( rhs ); + + nV = rhs.nV; + nFV = rhs.nFV; + nBV = rhs.nBV; + nUV = rhs.nUV; + + free = rhs.free; + fixed = rhs.fixed; + } + + return *this; +} + + +/* + * i n i t + */ +returnValue Bounds::init( int n ) +{ + nV = n; + nFV = 0; + nBV = 0; + nUV = 0; + + free.init( ); + fixed.init( ); + + return SubjectTo::init( n ); +} + + +/* + * s e t u p B o u n d + */ +returnValue Bounds::setupBound( int _number, SubjectToStatus _status + ) +{ + /* consistency check */ + if ( ( _number < 0 ) || ( _number >= getNV( ) ) ) + return THROWERROR( RET_INDEX_OUT_OF_BOUNDS ); + + /* Add bound index to respective index list. */ + switch ( _status ) + { + case ST_INACTIVE: + if ( this->addIndex( this->getFree( ),_number,_status ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_SETUP_BOUND_FAILED ); + break; + + case ST_LOWER: + if ( this->addIndex( this->getFixed( ),_number,_status ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_SETUP_BOUND_FAILED ); + break; + + case ST_UPPER: + if ( this->addIndex( this->getFixed( ),_number,_status ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_SETUP_BOUND_FAILED ); + break; + + default: + return THROWERROR( RET_INVALID_ARGUMENTS ); + } + + return SUCCESSFUL_RETURN; +} + + +/* + * s e t u p A l l F r e e + */ +returnValue Bounds::setupAllFree( ) +{ + int i; + + /* 1) Place unbounded variables at the beginning of the index list of free variables. */ + for( i=0; i= getNV( ) ) ) + return THROWERROR( RET_INDEX_OUT_OF_BOUNDS ); + + /* Move index from indexlist of fixed variables to that of free ones. */ + if ( this->removeIndex( this->getFixed( ),_number ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_MOVING_BOUND_FAILED ); + + if ( this->addIndex( this->getFree( ),_number,ST_INACTIVE ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_MOVING_BOUND_FAILED ); + + return SUCCESSFUL_RETURN; +} + + +/* + * m o v e F r e e T o F i x e d + */ +returnValue Bounds::moveFreeToFixed( int _number, SubjectToStatus _status + ) +{ + /* consistency check */ + if ( ( _number < 0 ) || ( _number >= getNV( ) ) ) + return THROWERROR( RET_INDEX_OUT_OF_BOUNDS ); + + /* Move index from indexlist of free variables to that of fixed ones. */ + if ( this->removeIndex( this->getFree( ),_number ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_MOVING_BOUND_FAILED ); + + if ( this->addIndex( this->getFixed( ),_number,_status ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_MOVING_BOUND_FAILED ); + + return SUCCESSFUL_RETURN; +} + + +/* + * s w a p F r e e + */ +returnValue Bounds::swapFree( int number1, int number2 + ) +{ + /* consistency check */ + if ( ( number1 < 0 ) || ( number1 >= getNV( ) ) || ( number2 < 0 ) || ( number2 >= getNV( ) ) ) + return THROWERROR( RET_INDEX_OUT_OF_BOUNDS ); + + /* Swap index within indexlist of free variables. */ + return this->swapIndex( this->getFree( ),number1,number2 ); +} + + +/* + * end of file + */ diff --git a/phonelibs/qpoases/SRC/Bounds.ipp b/phonelibs/qpoases/SRC/Bounds.ipp new file mode 100644 index 00000000000000..d0e7dbbf0904f7 --- /dev/null +++ b/phonelibs/qpoases/SRC/Bounds.ipp @@ -0,0 +1,144 @@ +/* + * This file is part of qpOASES. + * + * qpOASES -- An Implementation of the Online Active Set Strategy. + * Copyright (C) 2007-2008 by Hans Joachim Ferreau 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 SRC/Bounds.ipp + * \author Hans Joachim Ferreau + * \version 1.3embedded + * \date 2007-2008 + * + * Implementation of inlined member functions of the Bounds class designed + * to manage working sets of bounds within a QProblem. + */ + + +/***************************************************************************** + * P U B L I C * + *****************************************************************************/ + +/* + * g e t N V + */ +inline int Bounds::getNV( ) const +{ + return nV; +} + + +/* + * g e t N F X + */ +inline int Bounds::getNFV( ) const +{ + return nFV; +} + + +/* + * g e t N B V + */ +inline int Bounds::getNBV( ) const +{ + return nBV; +} + + +/* + * g e t N U V + */ +inline int Bounds::getNUV( ) const +{ + return nUV; +} + + + +/* + * s e t N F X + */ +inline returnValue Bounds::setNFV( int n ) +{ + nFV = n; + return SUCCESSFUL_RETURN; +} + + +/* + * s e t N B V + */ +inline returnValue Bounds::setNBV( int n ) +{ + nBV = n; + return SUCCESSFUL_RETURN; +} + + +/* + * s e t N U V + */ +inline returnValue Bounds::setNUV( int n ) +{ + nUV = n; + return SUCCESSFUL_RETURN; +} + + +/* + * g e t N F R + */ +inline int Bounds::getNFR( ) +{ + return free.getLength( ); +} + + +/* + * g e t N F X + */ +inline int Bounds::getNFX( ) +{ + return fixed.getLength( ); +} + + +/* + * g e t F r e e + */ +inline Indexlist* Bounds::getFree( ) +{ + return &free; +} + + +/* + * g e t F i x e d + */ +inline Indexlist* Bounds::getFixed( ) +{ + return &fixed; +} + + +/* + * end of file + */ diff --git a/phonelibs/qpoases/SRC/Constraints.cpp b/phonelibs/qpoases/SRC/Constraints.cpp new file mode 100644 index 00000000000000..81fc6ce8679d23 --- /dev/null +++ b/phonelibs/qpoases/SRC/Constraints.cpp @@ -0,0 +1,248 @@ +/* + * This file is part of qpOASES. + * + * qpOASES -- An Implementation of the Online Active Set Strategy. + * Copyright (C) 2007-2008 by Hans Joachim Ferreau 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 SRC/Constraints.cpp + * \author Hans Joachim Ferreau + * \version 1.3embedded + * \date 2007-2008 + * + * Implementation of the Constraints class designed to manage working sets of + * constraints within a QProblem. + */ + + +#include + + +/***************************************************************************** + * P U B L I C * + *****************************************************************************/ + + +/* + * C o n s t r a i n t s + */ +Constraints::Constraints( ) : SubjectTo( ), + nC( 0 ), + nEC( 0 ), + nIC( 0 ), + nUC( 0 ) +{ +} + + +/* + * C o n s t r a i n t s + */ +Constraints::Constraints( const Constraints& rhs ) : SubjectTo( rhs ), + nC( rhs.nC ), + nEC( rhs.nEC ), + nIC( rhs.nIC ), + nUC( rhs.nUC ) +{ + active = rhs.active; + inactive = rhs.inactive; +} + + +/* + * ~ C o n s t r a i n t s + */ +Constraints::~Constraints( ) +{ +} + + +/* + * o p e r a t o r = + */ +Constraints& Constraints::operator=( const Constraints& rhs ) +{ + if ( this != &rhs ) + { + SubjectTo::operator=( rhs ); + + nC = rhs.nC; + nEC = rhs.nEC; + nIC = rhs.nIC; + nUC = rhs.nUC; + + active = rhs.active; + inactive = rhs.inactive; + } + + return *this; +} + + +/* + * i n i t + */ +returnValue Constraints::init( int n ) +{ + nC = n; + nEC = 0; + nIC = 0; + nUC = 0; + + active.init( ); + inactive.init( ); + + return SubjectTo::init( n ); +} + + +/* + * s e t u p C o n s t r a i n t + */ +returnValue Constraints::setupConstraint( int _number, SubjectToStatus _status + ) +{ + /* consistency check */ + if ( ( _number < 0 ) || ( _number >= getNC( ) ) ) + return THROWERROR( RET_INDEX_OUT_OF_BOUNDS ); + + /* Add constraint index to respective index list. */ + switch ( _status ) + { + case ST_INACTIVE: + if ( this->addIndex( this->getInactive( ),_number,_status ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_SETUP_CONSTRAINT_FAILED ); + break; + + case ST_LOWER: + if ( this->addIndex( this->getActive( ),_number,_status ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_SETUP_CONSTRAINT_FAILED ); + break; + + case ST_UPPER: + if ( this->addIndex( this->getActive( ),_number,_status ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_SETUP_CONSTRAINT_FAILED ); + break; + + default: + return THROWERROR( RET_INVALID_ARGUMENTS ); + } + + return SUCCESSFUL_RETURN; +} + + +/* + * s e t u p A l l I n a c t i v e + */ +returnValue Constraints::setupAllInactive( ) +{ + int i; + + + /* 1) Place unbounded constraints at the beginning of the index list of inactive constraints. */ + for( i=0; i= getNC( ) ) ) + return THROWERROR( RET_INDEX_OUT_OF_BOUNDS ); + + /* Move index from indexlist of active constraints to that of inactive ones. */ + if ( this->removeIndex( this->getActive( ),_number ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_MOVING_BOUND_FAILED ); + + if ( this->addIndex( this->getInactive( ),_number,ST_INACTIVE ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_MOVING_BOUND_FAILED ); + + return SUCCESSFUL_RETURN; +} + + +/* + * m o v e I n a c t i v e T o A c t i v e + */ +returnValue Constraints::moveInactiveToActive( int _number, SubjectToStatus _status + ) +{ + /* consistency check */ + if ( ( _number < 0 ) || ( _number >= getNC( ) ) ) + return THROWERROR( RET_INDEX_OUT_OF_BOUNDS ); + + /* Move index from indexlist of inactive constraints to that of active ones. */ + if ( this->removeIndex( this->getInactive( ),_number ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_MOVING_BOUND_FAILED ); + + if ( this->addIndex( this->getActive( ),_number,_status ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_MOVING_BOUND_FAILED ); + + return SUCCESSFUL_RETURN; +} + + + +/* + * end of file + */ diff --git a/phonelibs/qpoases/SRC/Constraints.ipp b/phonelibs/qpoases/SRC/Constraints.ipp new file mode 100644 index 00000000000000..67add20434a1e4 --- /dev/null +++ b/phonelibs/qpoases/SRC/Constraints.ipp @@ -0,0 +1,144 @@ +/* + * This file is part of qpOASES. + * + * qpOASES -- An Implementation of the Online Active Set Strategy. + * Copyright (C) 2007-2008 by Hans Joachim Ferreau 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 SRC/Constraints.ipp + * \author Hans Joachim Ferreau + * \version 1.3embedded + * \date 2007-2008 + * + * Declaration of inlined member functions of the Constraints class designed + * to manage working sets of constraints within a QProblem. + */ + + + +/***************************************************************************** + * P U B L I C * + *****************************************************************************/ + +/* + * g e t N C + */ +inline int Constraints::getNC( ) const +{ + return nC; +} + + +/* + * g e t N E C + */ +inline int Constraints::getNEC( ) const +{ + return nEC; +} + + +/* + * g e t N I C + */ +inline int Constraints::getNIC( ) const +{ + return nIC; +} + + +/* + * g e t N U C + */ +inline int Constraints::getNUC( ) const +{ + return nUC; +} + + +/* + * s e t N E C + */ +inline returnValue Constraints::setNEC( int n ) +{ + nEC = n; + return SUCCESSFUL_RETURN; +} + + +/* + * s e t N I C + */ +inline returnValue Constraints::setNIC( int n ) +{ + nIC = n; + return SUCCESSFUL_RETURN; +} + + +/* + * s e t N U C + */ +inline returnValue Constraints::setNUC( int n ) +{ + nUC = n; + return SUCCESSFUL_RETURN; +} + + +/* + * g e t N A C + */ +inline int Constraints::getNAC( ) +{ + return active.getLength( ); +} + + +/* + * g e t N I A C + */ +inline int Constraints::getNIAC( ) +{ + return inactive.getLength( ); +} + + +/* + * g e t A c t i v e + */ +inline Indexlist* Constraints::getActive( ) +{ + return &active; +} + + +/* + * g e t I n a c t i v e + */ +inline Indexlist* Constraints::getInactive( ) +{ + return &inactive; +} + + +/* + * end of file + */ diff --git a/phonelibs/qpoases/SRC/CyclingManager.cpp b/phonelibs/qpoases/SRC/CyclingManager.cpp new file mode 100644 index 00000000000000..7bbccdac228460 --- /dev/null +++ b/phonelibs/qpoases/SRC/CyclingManager.cpp @@ -0,0 +1,188 @@ +/* + * This file is part of qpOASES. + * + * qpOASES -- An Implementation of the Online Active Set Strategy. + * Copyright (C) 2007-2008 by Hans Joachim Ferreau 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 SRC/CyclingManager.cpp + * \author Hans Joachim Ferreau + * \version 1.3embedded + * \date 2007-2008 + * + * Implementation of the CyclingManager class designed to detect + * and handle possible cycling during QP iterations. + * + */ + + +#include + + +/***************************************************************************** + * P U B L I C * + *****************************************************************************/ + + +/* + * C y c l i n g M a n a g e r + */ +CyclingManager::CyclingManager( ) : nV( 0 ), + nC( 0 ) +{ + cyclingDetected = BT_FALSE; +} + + +/* + * C y c l i n g M a n a g e r + */ +CyclingManager::CyclingManager( const CyclingManager& rhs ) : nV( rhs.nV ), + nC( rhs.nC ), + cyclingDetected( rhs.cyclingDetected ) +{ + int i; + + for( i=0; i= 0 ) && ( number < nV ) ) + { + status[number] = _status; + return SUCCESSFUL_RETURN; + } + else + return THROWERROR( RET_INDEX_OUT_OF_BOUNDS ); + } + else + { + /* Set cycling status of a constraint. */ + if ( ( number >= 0 ) && ( number < nC ) ) + { + status[nV+number] = _status; + return SUCCESSFUL_RETURN; + } + else + return THROWERROR( RET_INDEX_OUT_OF_BOUNDS ); + } +} + + +/* + * g e t C y c l i n g S t a t u s + */ +CyclingStatus CyclingManager::getCyclingStatus( int number, BooleanType isBound ) const +{ + if ( isBound == BT_TRUE ) + { + /* Return cycling status of a bound. */ + if ( ( number >= 0 ) && ( number < nV ) ) + return status[number]; + } + else + { + /* Return cycling status of a constraint. */ + if ( ( number >= 0 ) && ( number < nC ) ) + return status[nV+number]; + } + + return CYC_NOT_INVOLVED; +} + + +/* + * c l e a r C y c l i n g D a t a + */ +returnValue CyclingManager::clearCyclingData( ) +{ + int i; + + /* Reset all status values ... */ + for( i=0; i + +/* + * S o l u t i o n A n a l y s i s + */ +SolutionAnalysis::SolutionAnalysis( ) +{ + +} + +/* + * S o l u t i o n A n a l y s i s + */ +SolutionAnalysis::SolutionAnalysis( const SolutionAnalysis& rhs ) +{ + +} + +/* + * ~ S o l u t i o n A n a l y s i s + */ +SolutionAnalysis::~SolutionAnalysis( ) +{ + +} + +/* + * o p e r a t o r = + */ +SolutionAnalysis& SolutionAnalysis::operator=( const SolutionAnalysis& rhs ) +{ + if ( this != &rhs ) + { + + } + + return *this; +} + +/* + * g e t H e s s i a n I n v e r s e + */ +returnValue SolutionAnalysis::getHessianInverse( QProblem* qp, real_t* hessianInverse ) +{ + returnValue returnvalue; /* the return value */ + BooleanType Delta_bC_isZero = BT_FALSE; /* (just use FALSE here) */ + BooleanType Delta_bB_isZero = BT_FALSE; /* (just use FALSE here) */ + + register int run1, run2, run3; + + register int nFR, nFX; + + /* Ask for the number of free and fixed variables, assumes that active set + * is constant for the covariance evaluation */ + nFR = qp->getNFR( ); + nFX = qp->getNFX( ); + + /* Ask for the corresponding index arrays: */ + if ( qp->bounds.getFree( )->getNumberArray( FR_idx ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_HOTSTART_FAILED ); + + if ( qp->bounds.getFixed( )->getNumberArray( FX_idx ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_HOTSTART_FAILED ); + + if ( qp->constraints.getActive( )->getNumberArray( AC_idx ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_HOTSTART_FAILED ); + + /* Initialization: */ + for( run1 = 0; run1 < NVMAX; run1++ ) + delta_g_cov[ run1 ] = 0.0; + + for( run1 = 0; run1 < NVMAX; run1++ ) + delta_lb_cov[ run1 ] = 0.0; + + for( run1 = 0; run1 < NVMAX; run1++ ) + delta_ub_cov[ run1 ] = 0.0; + + for( run1 = 0; run1 < NCMAX; run1++ ) + delta_lbA_cov[ run1 ] = 0.0; + + for( run1 = 0; run1 < NCMAX; run1++ ) + delta_ubA_cov[ run1 ] = 0.0; + + /* The following loop solves the following: + * + * KKT * x = + * [delta_g_cov', delta_lbA_cov', delta_ubA_cov', delta_lb_cov', delta_ub_cov]' + * + * for the first NVMAX (negative) elementary vectors in order to get + * transposed inverse of the Hessian. Assuming that the Hessian is + * symmetric, the function will return transposed inverse, instead of the + * true inverse. + * + * Note, that we use negative elementary vectors due because internal + * implementation of the function hotstart_determineStepDirection requires + * so. + * + * */ + + for( run3 = 0; run3 < NVMAX; run3++ ) + { + /* Line wise loading of the corresponding (negative) elementary vector: */ + delta_g_cov[ run3 ] = -1.0; + + /* Evaluation of the step: */ + returnvalue = qp->hotstart_determineStepDirection( + FR_idx, FX_idx, AC_idx, + delta_g_cov, delta_lbA_cov, delta_ubA_cov, delta_lb_cov, delta_ub_cov, + Delta_bC_isZero, Delta_bB_isZero, + delta_xFX, delta_xFR, delta_yAC, delta_yFX + ); + if ( returnvalue != SUCCESSFUL_RETURN ) + { + return returnvalue; + } + + /* Line wise storage of the QP reaction: */ + for( run1 = 0; run1 < nFR; run1++ ) + { + run2 = FR_idx[ run1 ]; + + hessianInverse[run3 * NVMAX + run2] = delta_xFR[ run1 ]; + } + + for( run1 = 0; run1 < nFX; run1++ ) + { + run2 = FX_idx[ run1 ]; + + hessianInverse[run3 * NVMAX + run2] = delta_xFX[ run1 ]; + } + + /* Prepare for the next iteration */ + delta_g_cov[ run3 ] = 0.0; + } + + // TODO: Perform the transpose of the inverse of the Hessian matrix + + return SUCCESSFUL_RETURN; +} + +/* + * g e t H e s s i a n I n v e r s e + */ +returnValue SolutionAnalysis::getHessianInverse( QProblemB* qp, real_t* hessianInverse ) +{ + returnValue returnvalue; /* the return value */ + BooleanType Delta_bB_isZero = BT_FALSE; /* (just use FALSE here) */ + + register int run1, run2, run3; + + register int nFR, nFX; + + /* Ask for the number of free and fixed variables, assumes that active set + * is constant for the covariance evaluation */ + nFR = qp->getNFR( ); + nFX = qp->getNFX( ); + + /* Ask for the corresponding index arrays: */ + if ( qp->bounds.getFree( )->getNumberArray( FR_idx ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_HOTSTART_FAILED ); + + if ( qp->bounds.getFixed( )->getNumberArray( FX_idx ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_HOTSTART_FAILED ); + + /* Initialization: */ + for( run1 = 0; run1 < NVMAX; run1++ ) + delta_g_cov[ run1 ] = 0.0; + + for( run1 = 0; run1 < NVMAX; run1++ ) + delta_lb_cov[ run1 ] = 0.0; + + for( run1 = 0; run1 < NVMAX; run1++ ) + delta_ub_cov[ run1 ] = 0.0; + + /* The following loop solves the following: + * + * KKT * x = + * [delta_g_cov', delta_lb_cov', delta_ub_cov']' + * + * for the first NVMAX (negative) elementary vectors in order to get + * transposed inverse of the Hessian. Assuming that the Hessian is + * symmetric, the function will return transposed inverse, instead of the + * true inverse. + * + * Note, that we use negative elementary vectors due because internal + * implementation of the function hotstart_determineStepDirection requires + * so. + * + * */ + + for( run3 = 0; run3 < NVMAX; run3++ ) + { + /* Line wise loading of the corresponding (negative) elementary vector: */ + delta_g_cov[ run3 ] = -1.0; + + /* Evaluation of the step: */ + returnvalue = qp->hotstart_determineStepDirection( + FR_idx, FX_idx, + delta_g_cov, delta_lb_cov, delta_ub_cov, + Delta_bB_isZero, + delta_xFX, delta_xFR, delta_yFX + ); + if ( returnvalue != SUCCESSFUL_RETURN ) + { + return returnvalue; + } + + /* Line wise storage of the QP reaction: */ + for( run1 = 0; run1 < nFR; run1++ ) + { + run2 = FR_idx[ run1 ]; + + hessianInverse[run3 * NVMAX + run2] = delta_xFR[ run1 ]; + } + + for( run1 = 0; run1 < nFX; run1++ ) + { + run2 = FX_idx[ run1 ]; + + hessianInverse[run3 * NVMAX + run2] = delta_xFX[ run1 ]; + } + + /* Prepare for the next iteration */ + delta_g_cov[ run3 ] = 0.0; + } + + // TODO: Perform the transpose of the inverse of the Hessian matrix + + return SUCCESSFUL_RETURN; +} + +/* + * g e t V a r i a n c e C o v a r i a n c e + */ + +#if QPOASES_USE_OLD_VERSION + +returnValue SolutionAnalysis::getVarianceCovariance( QProblem* qp, real_t* g_b_bA_VAR, real_t* Primal_Dual_VAR ) +{ + int run1, run2, run3; /* simple run variables (for loops). */ + + returnValue returnvalue; /* the return value */ + BooleanType Delta_bC_isZero = BT_FALSE; /* (just use FALSE here) */ + BooleanType Delta_bB_isZero = BT_FALSE; /* (just use FALSE here) */ + + /* ASK FOR THE NUMBER OF FREE AND FIXED VARIABLES: + * (ASSUMES THAT ACTIVE SET IS CONSTANT FOR THE + * VARIANCE-COVARIANCE EVALUATION) + * ----------------------------------------------- */ + int nFR, nFX, nAC; + + nFR = qp->getNFR( ); + nFX = qp->getNFX( ); + nAC = qp->getNAC( ); + + if ( qp->bounds.getFree( )->getNumberArray( FR_idx ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_HOTSTART_FAILED ); + + if ( qp->bounds.getFixed( )->getNumberArray( FX_idx ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_HOTSTART_FAILED ); + + if ( qp->constraints.getActive( )->getNumberArray( AC_idx ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_HOTSTART_FAILED ); + + /* SOME INITIALIZATIONS: + * --------------------- */ + for( run1 = 0; run1 < KKT_DIM * KKT_DIM; run1++ ) + { + K [run1] = 0.0; + Primal_Dual_VAR[run1] = 0.0; + } + + /* ================================================================= */ + + /* FIRST MATRIX MULTIPLICATION (OBTAINS THE INTERMEDIATE RESULT + * K := [ ("ACTIVE" KKT-MATRIX OF THE QP)^(-1) * g_b_bA_VAR ]^T ) + * THE EVALUATION OF THE INVERSE OF THE KKT-MATRIX OF THE QP + * WITH RESPECT TO THE CURRENT ACTIVE SET + * USES THE EXISTING CHOLESKY AND TQ-DECOMPOSITIONS. FOR DETAILS + * cf. THE (protected) FUNCTION determineStepDirection. */ + + for( run3 = 0; run3 < KKT_DIM; run3++ ) + { + + for( run1 = 0; run1 < NVMAX; run1++ ) + { + delta_g_cov [run1] = g_b_bA_VAR[run3*KKT_DIM+run1]; + delta_lb_cov [run1] = g_b_bA_VAR[run3*KKT_DIM+NVMAX+run1]; /* LINE-WISE LOADING OF THE INPUT */ + delta_ub_cov [run1] = g_b_bA_VAR[run3*KKT_DIM+NVMAX+run1]; /* VARIANCE-COVARIANCE */ + } + for( run1 = 0; run1 < NCMAX; run1++ ) + { + delta_lbA_cov [run1] = g_b_bA_VAR[run3*KKT_DIM+2*NVMAX+run1]; + delta_ubA_cov [run1] = g_b_bA_VAR[run3*KKT_DIM+2*NVMAX+run1]; + } + + /* EVALUATION OF THE STEP: + * ------------------------------------------------------------------------------ */ + + returnvalue = qp->hotstart_determineStepDirection( + FR_idx, FX_idx, AC_idx, + delta_g_cov, delta_lbA_cov, delta_ubA_cov, delta_lb_cov, delta_ub_cov, + Delta_bC_isZero, Delta_bB_isZero, delta_xFX,delta_xFR, + delta_yAC,delta_yFX ); + + /* ------------------------------------------------------------------------------ */ + + /* STOP THE ALGORITHM IN THE CASE OF NO SUCCESFUL RETURN: + * ------------------------------------------------------ */ + if ( returnvalue != SUCCESSFUL_RETURN ) + { + return returnvalue; + } + + /* LINE WISE */ + /* STORAGE OF THE QP-REACTION */ + /* (uses the index list) */ + + for( run1=0; run1hotstart_determineStepDirection( + FR_idx, FX_idx, AC_idx, + delta_g_cov, delta_lbA_cov, delta_ubA_cov, delta_lb_cov, delta_ub_cov, + Delta_bC_isZero, Delta_bB_isZero, delta_xFX,delta_xFR, + delta_yAC,delta_yFX ); + + /* ------------------------------------------------------------------------------ */ + + /* STOP THE ALGORITHM IN THE CASE OF NO SUCCESFUL RETURN: + * ------------------------------------------------------ */ + if ( returnvalue != SUCCESSFUL_RETURN ) + { + return returnvalue; + } + + /* ROW-WISE STORAGE */ + /* OF THE RESULT. */ + + for( run1=0; run1 + + +/***************************************************************************** + * P U B L I C * + *****************************************************************************/ + + +/* + * I n d e x l i s t + */ +Indexlist::Indexlist( ) : length( 0 ), + first( -1 ), + last( -1 ), + lastusedindex( -1 ), + physicallength( INDEXLISTFACTOR*(NVMAX+NCMAX) ) +{ + int i; + + for( i=0; i= 0 ) && ( number[n] >= 0 ) ) + numberarray[i] = number[n]; + else + return THROWERROR( RET_INDEXLIST_CORRUPTED ); + + n = next[n]; + } + + return SUCCESSFUL_RETURN; +} + + +/* + * g e t I n d e x + */ +int Indexlist::getIndex( int givennumber ) const +{ + int i; + int n = first; + int index = -1; /* return -1 by default */ + + /* Run trough indexlist until number is found, if so return it index. */ + for ( i=0; i length ) ) + return -RET_INDEXLIST_OUTOFBOUNDS; + + return number[physicalindex]; +} + + +/* + * g e t L e n g t h + */ +inline int Indexlist::getLength( ) +{ + return length; +} + + +/* + * g e t L a s t N u m b e r + */ +inline int Indexlist::getLastNumber( ) const +{ + return number[last]; +} + + +/* + * g e t L a s t N u m b e r + */ +inline BooleanType Indexlist::isMember( int _number ) const +{ + if ( getIndex( _number ) >= 0 ) + return BT_TRUE; + else + return BT_FALSE; +} + + +/* + * end of file + */ diff --git a/phonelibs/qpoases/SRC/MessageHandling.cpp b/phonelibs/qpoases/SRC/MessageHandling.cpp new file mode 100644 index 00000000000000..6e68cd8552449e --- /dev/null +++ b/phonelibs/qpoases/SRC/MessageHandling.cpp @@ -0,0 +1,529 @@ +/* + * This file is part of qpOASES. + * + * qpOASES -- An Implementation of the Online Active Set Strategy. + * Copyright (C) 2007-2008 by Hans Joachim Ferreau 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 SRC/MessageHandling.cpp + * \author Hans Joachim Ferreau + * \version 1.3embedded + * \date 2007-2008 + * + * Implementation of the MessageHandling class including global return values. + * + */ + + + +#include +#include + + + + +/** Defines pairs of global return values and messages. */ +MessageHandling::ReturnValueList returnValueList[] = +{ +/* miscellaneous */ +{ SUCCESSFUL_RETURN, "Successful return", VS_VISIBLE }, +{ RET_DIV_BY_ZERO, "Division by zero", VS_VISIBLE }, +{ RET_INDEX_OUT_OF_BOUNDS, "Index out of bounds", VS_VISIBLE }, +{ RET_INVALID_ARGUMENTS, "At least one of the arguments is invalid", VS_VISIBLE }, +{ RET_ERROR_UNDEFINED, "Error number undefined", VS_VISIBLE }, +{ RET_WARNING_UNDEFINED, "Warning number undefined", VS_VISIBLE }, +{ RET_INFO_UNDEFINED, "Info number undefined", VS_VISIBLE }, +{ RET_EWI_UNDEFINED, "Error/warning/info number undefined", VS_VISIBLE }, +{ RET_AVAILABLE_WITH_LINUX_ONLY, "This function is available under Linux only", VS_HIDDEN }, +{ RET_UNKNOWN_BUG, "The error occured is not yet known", VS_VISIBLE }, +{ RET_PRINTLEVEL_CHANGED, "Print level changed", VS_VISIBLE }, +{ RET_NOT_YET_IMPLEMENTED, "Requested function is not yet implemented.", VS_VISIBLE }, +/* Indexlist */ +{ RET_INDEXLIST_MUST_BE_REORDERD, "Index list has to be reordered", VS_VISIBLE }, +{ RET_INDEXLIST_EXCEEDS_MAX_LENGTH, "Index list exceeds its maximal physical length", VS_VISIBLE }, +{ RET_INDEXLIST_CORRUPTED, "Index list corrupted", VS_VISIBLE }, +{ RET_INDEXLIST_OUTOFBOUNDS, "Physical index is out of bounds", VS_VISIBLE }, +{ RET_INDEXLIST_ADD_FAILED, "Adding indices from another index set failed", VS_VISIBLE }, +{ RET_INDEXLIST_INTERSECT_FAILED, "Intersection with another index set failed", VS_VISIBLE }, +/* SubjectTo / Bounds / Constraints */ +{ RET_INDEX_ALREADY_OF_DESIRED_STATUS, "Index is already of desired status", VS_VISIBLE }, +{ RET_SWAPINDEX_FAILED, "Cannot swap between different indexsets", VS_VISIBLE }, +{ RET_ADDINDEX_FAILED, "Adding index to index set failed", VS_VISIBLE }, +{ RET_NOTHING_TO_DO, "Nothing to do", VS_VISIBLE }, +{ RET_SETUP_BOUND_FAILED, "Setting up bound index failed", VS_VISIBLE }, +{ RET_SETUP_CONSTRAINT_FAILED, "Setting up constraint index failed", VS_VISIBLE }, +{ RET_MOVING_BOUND_FAILED, "Moving bound between index sets failed", VS_VISIBLE }, +{ RET_MOVING_CONSTRAINT_FAILED, "Moving constraint between index sets failed", VS_VISIBLE }, +/* QProblem */ +{ RET_QP_ALREADY_INITIALISED, "QProblem has already been initialised", VS_VISIBLE }, +{ RET_NO_INIT_WITH_STANDARD_SOLVER, "Initialisation via extern QP solver is not yet implemented", VS_VISIBLE }, +{ RET_RESET_FAILED, "Reset failed", VS_VISIBLE }, +{ RET_INIT_FAILED, "Initialisation failed", VS_VISIBLE }, +{ RET_INIT_FAILED_TQ, "Initialisation failed due to TQ factorisation", VS_VISIBLE }, +{ RET_INIT_FAILED_CHOLESKY, "Initialisation failed due to Cholesky decomposition", VS_VISIBLE }, +{ RET_INIT_FAILED_HOTSTART, "Initialisation failed! QP could not be solved!", VS_VISIBLE }, +{ RET_INIT_FAILED_INFEASIBILITY, "Initial QP could not be solved due to infeasibility!", VS_VISIBLE }, +{ RET_INIT_FAILED_UNBOUNDEDNESS, "Initial QP could not be solved due to unboundedness!", VS_VISIBLE }, +{ RET_INIT_SUCCESSFUL, "Initialisation done", VS_VISIBLE }, +{ RET_OBTAINING_WORKINGSET_FAILED, "Failed to obtain working set for auxiliary QP", VS_VISIBLE }, +{ RET_SETUP_WORKINGSET_FAILED, "Failed to setup working set for auxiliary QP", VS_VISIBLE }, +{ RET_SETUP_AUXILIARYQP_FAILED, "Failed to setup auxiliary QP for initialised homotopy", VS_VISIBLE }, +{ RET_NO_EXTERN_SOLVER, "No extern QP solver available", VS_VISIBLE }, +{ RET_QP_UNBOUNDED, "QP is unbounded", VS_VISIBLE }, +{ RET_QP_INFEASIBLE, "QP is infeasible", VS_VISIBLE }, +{ RET_QP_NOT_SOLVED, "Problems occured while solving QP with standard solver", VS_VISIBLE }, +{ RET_QP_SOLVED, "QP successfully solved", VS_VISIBLE }, +{ RET_UNABLE_TO_SOLVE_QP, "Problems occured while solving QP", VS_VISIBLE }, +{ RET_INITIALISATION_STARTED, "Starting problem initialisation...", VS_VISIBLE }, +{ RET_HOTSTART_FAILED, "Unable to perform homotopy due to internal error", VS_VISIBLE }, +{ RET_HOTSTART_FAILED_TO_INIT, "Unable to initialise problem", VS_VISIBLE }, +{ RET_HOTSTART_FAILED_AS_QP_NOT_INITIALISED, "Unable to perform homotopy as previous QP is not solved", VS_VISIBLE }, +{ RET_ITERATION_STARTED, "Iteration", VS_VISIBLE }, +{ RET_SHIFT_DETERMINATION_FAILED, "Determination of shift of the QP data failed", VS_VISIBLE }, +{ RET_STEPDIRECTION_DETERMINATION_FAILED, "Determination of step direction failed", VS_VISIBLE }, +{ RET_STEPLENGTH_DETERMINATION_FAILED, "Determination of step direction failed", VS_VISIBLE }, +{ RET_OPTIMAL_SOLUTION_FOUND, "Optimal solution of neighbouring QP found", VS_VISIBLE }, +{ RET_HOMOTOPY_STEP_FAILED, "Unable to perform homotopy step", VS_VISIBLE }, +{ RET_HOTSTART_STOPPED_INFEASIBILITY, "Premature homotopy termination because QP is infeasible", VS_VISIBLE }, +{ RET_HOTSTART_STOPPED_UNBOUNDEDNESS, "Premature homotopy termination because QP is unbounded", VS_VISIBLE }, +{ RET_WORKINGSET_UPDATE_FAILED, "Unable to update working sets according to initial guesses", VS_VISIBLE }, +{ RET_MAX_NWSR_REACHED, "Maximum number of working set recalculations performed", VS_VISIBLE }, +{ RET_CONSTRAINTS_NOT_SPECIFIED, "Problem does comprise constraints! You have to specify new constraints' bounds", VS_VISIBLE }, +{ RET_INVALID_FACTORISATION_FLAG, "Invalid factorisation flag", VS_VISIBLE }, +{ RET_UNABLE_TO_SAVE_QPDATA, "Unable to save QP data", VS_VISIBLE }, +{ RET_STEPDIRECTION_FAILED_TQ, "Abnormal termination due to TQ factorisation", VS_VISIBLE }, +{ RET_STEPDIRECTION_FAILED_CHOLESKY, "Abnormal termination due to Cholesky factorisation", VS_VISIBLE }, +{ RET_CYCLING_DETECTED, "Cycling detected", VS_VISIBLE }, +{ RET_CYCLING_NOT_RESOLVED, "Cycling cannot be resolved, QP is probably infeasible", VS_VISIBLE }, +{ RET_CYCLING_RESOLVED, "Cycling probably resolved", VS_VISIBLE }, +{ RET_STEPSIZE, "", VS_VISIBLE }, +{ RET_STEPSIZE_NONPOSITIVE, "", VS_VISIBLE }, +{ RET_SETUPSUBJECTTOTYPE_FAILED, "Setup of SubjectToTypes failed", VS_VISIBLE }, +{ RET_ADDCONSTRAINT_FAILED, "Addition of constraint to working set failed", VS_VISIBLE }, +{ RET_ADDCONSTRAINT_FAILED_INFEASIBILITY, "Addition of constraint to working set failed", VS_VISIBLE }, +{ RET_ADDBOUND_FAILED, "Addition of bound to working set failed", VS_VISIBLE }, +{ RET_ADDBOUND_FAILED_INFEASIBILITY, "Addition of bound to working set failed", VS_VISIBLE }, +{ RET_REMOVECONSTRAINT_FAILED, "Removal of constraint from working set failed", VS_VISIBLE }, +{ RET_REMOVEBOUND_FAILED, "Removal of bound from working set failed", VS_VISIBLE }, +{ RET_REMOVE_FROM_ACTIVESET, "Removing from active set:", VS_VISIBLE }, +{ RET_ADD_TO_ACTIVESET, "Adding to active set:", VS_VISIBLE }, +{ RET_REMOVE_FROM_ACTIVESET_FAILED, "Removing from active set failed", VS_VISIBLE }, +{ RET_ADD_TO_ACTIVESET_FAILED, "Adding to active set failed", VS_VISIBLE }, +{ RET_CONSTRAINT_ALREADY_ACTIVE, "Constraint is already active", VS_VISIBLE }, +{ RET_ALL_CONSTRAINTS_ACTIVE, "All constraints are active, no further constraint can be added", VS_VISIBLE }, +{ RET_LINEARLY_DEPENDENT, "New bound/constraint is linearly dependent", VS_VISIBLE }, +{ RET_LINEARLY_INDEPENDENT, "New bound/constraint is linearly independent", VS_VISIBLE }, +{ RET_LI_RESOLVED, "Linear independence of active contraint matrix successfully resolved", VS_VISIBLE }, +{ RET_ENSURELI_FAILED, "Failed to ensure linear indepence of active contraint matrix", VS_VISIBLE }, +{ RET_ENSURELI_FAILED_TQ, "Abnormal termination due to TQ factorisation", VS_VISIBLE }, +{ RET_ENSURELI_FAILED_NOINDEX, "No index found, QP is probably infeasible", VS_VISIBLE }, +{ RET_ENSURELI_FAILED_CYCLING, "Cycling detected, QP is probably infeasible", VS_VISIBLE }, +{ RET_BOUND_ALREADY_ACTIVE, "Bound is already active", VS_VISIBLE }, +{ RET_ALL_BOUNDS_ACTIVE, "All bounds are active, no further bound can be added", VS_VISIBLE }, +{ RET_CONSTRAINT_NOT_ACTIVE, "Constraint is not active", VS_VISIBLE }, +{ RET_BOUND_NOT_ACTIVE, "Bound is not active", VS_VISIBLE }, +{ RET_HESSIAN_NOT_SPD, "Projected Hessian matrix not positive definite", VS_VISIBLE }, +{ RET_MATRIX_SHIFT_FAILED, "Unable to update matrices or to transform vectors", VS_VISIBLE }, +{ RET_MATRIX_FACTORISATION_FAILED, "Unable to calculate new matrix factorisations", VS_VISIBLE }, +{ RET_PRINT_ITERATION_FAILED, "Unable to print information on current iteration", VS_VISIBLE }, +{ RET_NO_GLOBAL_MESSAGE_OUTPUTFILE, "No global message output file initialised", VS_VISIBLE }, +/* Utils */ +{ RET_UNABLE_TO_OPEN_FILE, "Unable to open file", VS_VISIBLE }, +{ RET_UNABLE_TO_WRITE_FILE, "Unable to write into file", VS_VISIBLE }, +{ RET_UNABLE_TO_READ_FILE, "Unable to read from file", VS_VISIBLE }, +{ RET_FILEDATA_INCONSISTENT, "File contains inconsistent data", VS_VISIBLE }, +/* SolutionAnalysis */ +{ RET_NO_SOLUTION, "QP solution does not satisfy KKT optimality conditions", VS_VISIBLE }, +{ RET_INACCURATE_SOLUTION, "KKT optimality conditions not satisfied to sufficient accuracy", VS_VISIBLE }, +{ TERMINAL_LIST_ELEMENT, "", VS_HIDDEN } /* IMPORTANT: Terminal list element! */ +}; + + + +/***************************************************************************** + * P U B L I C * + *****************************************************************************/ + + +/* + * M e s s a g e H a n d l i n g + */ +MessageHandling::MessageHandling( ) : errorVisibility( VS_VISIBLE ), + warningVisibility( VS_VISIBLE ), + infoVisibility( VS_VISIBLE ), + outputFile( myStdout ), + errorCount( 0 ) +{ +} + +/* + * M e s s a g e H a n d l i n g + */ +MessageHandling::MessageHandling( myFILE* _outputFile ) : + errorVisibility( VS_VISIBLE ), + warningVisibility( VS_VISIBLE ), + infoVisibility( VS_VISIBLE ), + outputFile( _outputFile ), + errorCount( 0 ) +{ +} + +/* + * M e s s a g e H a n d l i n g + */ +MessageHandling::MessageHandling( VisibilityStatus _errorVisibility, + VisibilityStatus _warningVisibility, + VisibilityStatus _infoVisibility + ) : + errorVisibility( _errorVisibility ), + warningVisibility( _warningVisibility ), + infoVisibility( _infoVisibility ), + outputFile( myStderr ), + errorCount( 0 ) +{ +} + +/* + * M e s s a g e H a n d l i n g + */ +MessageHandling::MessageHandling( myFILE* _outputFile, + VisibilityStatus _errorVisibility, + VisibilityStatus _warningVisibility, + VisibilityStatus _infoVisibility + ) : + errorVisibility( _errorVisibility ), + warningVisibility( _warningVisibility ), + infoVisibility( _infoVisibility ), + outputFile( _outputFile ), + errorCount( 0 ) +{ +} + + + +/* + * M e s s a g e H a n d l i n g + */ +MessageHandling::MessageHandling( const MessageHandling& rhs ) : + errorVisibility( rhs.errorVisibility ), + warningVisibility( rhs.warningVisibility ), + infoVisibility( rhs.infoVisibility ), + outputFile( rhs.outputFile ), + errorCount( rhs.errorCount ) +{ +} + + +/* + * ~ M e s s a g e H a n d l i n g + */ +MessageHandling::~MessageHandling( ) +{ + #ifdef PC_DEBUG + if ( outputFile != 0 ) + fclose( outputFile ); + #endif +} + + +/* + * o p e r a t o r = + */ +MessageHandling& MessageHandling::operator=( const MessageHandling& rhs ) +{ + if ( this != &rhs ) + { + errorVisibility = rhs.errorVisibility; + warningVisibility = rhs.warningVisibility; + infoVisibility = rhs.infoVisibility; + outputFile = rhs.outputFile; + errorCount = rhs.errorCount; + } + + return *this; +} + + +/* + * t h r o w E r r o r + */ +returnValue MessageHandling::throwError( + returnValue Enumber, + const char* additionaltext, + const char* functionname, + const char* filename, + const unsigned long linenumber, + VisibilityStatus localVisibilityStatus + ) +{ + /* consistency check */ + if ( Enumber <= SUCCESSFUL_RETURN ) + return throwError( RET_ERROR_UNDEFINED,0,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE ); + + /* Call to common throwMessage function if error shall be displayed. */ + if ( errorVisibility == VS_VISIBLE ) + return throwMessage( Enumber,additionaltext,functionname,filename,linenumber,localVisibilityStatus,"ERROR" ); + else + return Enumber; +} + + +/* + * t h r o w W a r n i n g + */ +returnValue MessageHandling::throwWarning( + returnValue Wnumber, + const char* additionaltext, + const char* functionname, + const char* filename, + const unsigned long linenumber, + VisibilityStatus localVisibilityStatus + ) +{ + /* consistency check */ + if ( Wnumber <= SUCCESSFUL_RETURN ) + return throwError( RET_WARNING_UNDEFINED,0,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE ); + + /* Call to common throwMessage function if warning shall be displayed. */ + if ( warningVisibility == VS_VISIBLE ) + return throwMessage( Wnumber,additionaltext,functionname,filename,linenumber,localVisibilityStatus,"WARNING" ); + else + return Wnumber; +} + + +/* + * t h r o w I n f o + */ +returnValue MessageHandling::throwInfo( + returnValue Inumber, + const char* additionaltext, + const char* functionname, + const char* filename, + const unsigned long linenumber, + VisibilityStatus localVisibilityStatus + ) +{ + /* consistency check */ + if ( Inumber < SUCCESSFUL_RETURN ) + return throwError( RET_INFO_UNDEFINED,0,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE ); + + /* Call to common throwMessage function if info shall be displayed. */ + if ( infoVisibility == VS_VISIBLE ) + return throwMessage( Inumber,additionaltext,functionname,filename,linenumber,localVisibilityStatus,"INFO" ); + else + return Inumber; +} + + +/* + * r e s e t + */ +returnValue MessageHandling::reset( ) +{ + setErrorVisibilityStatus( VS_VISIBLE ); + setWarningVisibilityStatus( VS_VISIBLE ); + setInfoVisibilityStatus( VS_VISIBLE ); + + setOutputFile( myStderr ); + setErrorCount( 0 ); + + return SUCCESSFUL_RETURN; +} + + +/* + * l i s t A l l M e s s a g e s + */ +returnValue MessageHandling::listAllMessages( ) +{ + #ifdef PC_DEBUG + int keypos = 0; + char myPrintfString[160]; + + /* Run through whole returnValueList and print each item. */ + while ( returnValueList[keypos].key != TERMINAL_LIST_ELEMENT ) + { + sprintf( myPrintfString," %d - %s \n",keypos,returnValueList[keypos].data ); + myPrintf( myPrintfString ); + + ++keypos; + } + #endif + + return SUCCESSFUL_RETURN; +} + + + +/***************************************************************************** + * P R O T E C T E D * + *****************************************************************************/ + + +#ifdef PC_DEBUG /* Re-define throwMessage function for embedded code! */ + +/* + * t h r o w M e s s a g e + */ +returnValue MessageHandling::throwMessage( + returnValue RETnumber, + const char* additionaltext, + const char* functionname, + const char* filename, + const unsigned long linenumber, + VisibilityStatus localVisibilityStatus, + const char* RETstring + ) +{ + int i; + + int keypos = 0; + char myPrintfString[160]; + + /* 1) Determine number of whitespace for output. */ + char whitespaces[41]; + int numberOfWhitespaces = (errorCount-1)*2; + + if ( numberOfWhitespaces < 0 ) + numberOfWhitespaces = 0; + + if ( numberOfWhitespaces > 40 ) + numberOfWhitespaces = 40; + + for( i=0; i 0 ) + { + sprintf( myPrintfString,"%s->", whitespaces ); + myPrintf( myPrintfString ); + } + + if ( additionaltext == 0 ) + { + sprintf( myPrintfString,"%s (%s, %s:%d): \t%s\n", + RETstring,functionname,filename,(int)linenumber,returnValueList[keypos].data + ); + myPrintf( myPrintfString ); + } + else + { + sprintf( myPrintfString,"%s (%s, %s:%d): \t%s %s\n", + RETstring,functionname,filename,(int)linenumber,returnValueList[keypos].data,additionaltext + ); + myPrintf( myPrintfString ); + } + + /* take care of proper indention for subsequent error messages */ + if ( RETstring[0] == 'E' ) + { + ++errorCount; + } + else + { + if ( errorCount > 0 ) + myPrintf( "\n" ); + errorCount = 0; + } + } + + return RETnumber; +} + +#else /* = PC_DEBUG not defined */ + +/* + * t h r o w M e s s a g e + */ +returnValue MessageHandling::throwMessage( + returnValue RETnumber, + const char* additionaltext, + const char* functionname, + const char* filename, + const unsigned long linenumber, + VisibilityStatus localVisibilityStatus, + const char* RETstring + ) +{ + /* DUMMY CODE FOR PRETENDING USE OF ARGUMENTS + * FOR SUPPRESSING COMPILER WARNINGS! */ + int i = 0; + if ( additionaltext == 0 ) i++; + if ( functionname == 0 ) i++; + if ( filename == 0 ) i++; + if ( linenumber == 0 ) i++; + if ( localVisibilityStatus == VS_VISIBLE ) i++; + if ( RETstring == 0 ) i++; + /* END OF DUMMY CODE */ + + return RETnumber; +} + +#endif /* PC_DEBUG */ + + + +/***************************************************************************** + * G L O B A L M E S S A G E H A N D L E R * + *****************************************************************************/ + + +/** Global message handler for all qpOASES modules.*/ +MessageHandling globalMessageHandler( myStderr,VS_VISIBLE,VS_VISIBLE,VS_VISIBLE ); + + +/* + * g e t G l o b a l M e s s a g e H a n d l e r + */ +MessageHandling* getGlobalMessageHandler( ) +{ + return &globalMessageHandler; +} + +const char* MessageHandling::getErrorString(int error) +{ + return returnValueList[ error ].data; +} + + + +/* + * end of file + */ diff --git a/phonelibs/qpoases/SRC/MessageHandling.ipp b/phonelibs/qpoases/SRC/MessageHandling.ipp new file mode 100644 index 00000000000000..ad9624b3d69a62 --- /dev/null +++ b/phonelibs/qpoases/SRC/MessageHandling.ipp @@ -0,0 +1,137 @@ +/* + * This file is part of qpOASES. + * + * qpOASES -- An Implementation of the Online Active Set Strategy. + * Copyright (C) 2007-2008 by Hans Joachim Ferreau 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 SRC/MessageHandling.ipp + * \author Hans Joachim Ferreau + * \version 1.3embedded + * \date 2007-2008 + * + * Implementation of inlined member functions of the MessageHandling class. + */ + + + +/***************************************************************************** + * P U B L I C * + *****************************************************************************/ + +/* + * g e t E r r o r V i s i b i l i t y S t a t u s + */ +inline VisibilityStatus MessageHandling::getErrorVisibilityStatus( ) const +{ + return 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 + */ +inline VisibilityStatus MessageHandling::getWarningVisibilityStatus( ) const +{ + return warningVisibility; +} + + +/* + * g e t I n f o V i s i b i l i t y S t a t u s + */ +inline VisibilityStatus MessageHandling::getInfoVisibilityStatus( ) const +{ + return infoVisibility; +} + + +/* + * g e t O u t p u t F i l e + */ +inline myFILE* MessageHandling::getOutputFile( ) const +{ + return outputFile; +} + + +/* + * g e t E r r o r C o u n t + */ +inline int MessageHandling::getErrorCount( ) const +{ + return 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 + */ +inline void MessageHandling::setErrorVisibilityStatus( VisibilityStatus _errorVisibility ) +{ + 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 + */ +inline void MessageHandling::setWarningVisibilityStatus( VisibilityStatus _warningVisibility ) +{ + 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 + */ +inline void MessageHandling::setInfoVisibilityStatus( VisibilityStatus _infoVisibility ) +{ + infoVisibility = _infoVisibility; +} + + +/* + * s e t O u t p u t F i l e + */ +inline void MessageHandling::setOutputFile( myFILE* _outputFile ) +{ + outputFile = _outputFile; +} + + +/* + * s e t E r r o r C o u n t + */ +inline returnValue MessageHandling::setErrorCount( int _errorCount ) +{ + if ( _errorCount >= 0 ) + { + errorCount = _errorCount; + return SUCCESSFUL_RETURN; + } + else + return RET_INVALID_ARGUMENTS; +} + + +/* + * end of file + */ diff --git a/phonelibs/qpoases/SRC/QProblem.cpp b/phonelibs/qpoases/SRC/QProblem.cpp new file mode 100644 index 00000000000000..68a6a79e534f65 --- /dev/null +++ b/phonelibs/qpoases/SRC/QProblem.cpp @@ -0,0 +1,3867 @@ +/* + * This file is part of qpOASES. + * + * qpOASES -- An Implementation of the Online Active Set Strategy. + * Copyright (C) 2007-2008 by Hans Joachim Ferreau 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 SRC/QProblem.cpp + * \author Hans Joachim Ferreau + * \version 1.3embedded + * \date 2007-2008 + * + * Implementation of the QProblem class which is able to use the newly + * developed online active set strategy for parametric quadratic programming. + */ + + +#include + +#include + +void printmatrix2(char *name, double *A, int m, int n) { + int i, j; + + printf("%s = [...\n", name); + for (i = 0; i < m; i++) { + for (j = 0; j < n; j++) + printf(" % 9.4f", A[i*n+j]); + printf(",\n"); + } + printf("];\n"); +} + +//#define __PERFORM_KKT_TEST__ + + +/***************************************************************************** + * P U B L I C * + *****************************************************************************/ + + +/* + * Q P r o b l e m + */ +QProblem::QProblem( ) : QProblemB( ) +{ + constraints.init( 0 ); + + sizeT = 0; + + cyclingManager.init( 0,0 ); +} + + +/* + * Q P r o b l e m + */ +QProblem::QProblem( int _nV, int _nC ) : QProblemB( _nV ) +{ + /* consistency checks */ + if ( _nV <= 0 ) + _nV = 1; + + if ( _nC < 0 ) + { + _nC = 0; + THROWERROR( RET_INVALID_ARGUMENTS ); + } + + constraints.init( _nC ); + + + sizeT = _nC; + if ( _nC > _nV ) + sizeT = _nV; + + cyclingManager.init( _nV,_nC ); +} + + +/* + * Q P r o b l e m + */ +QProblem::QProblem( const QProblem& rhs ) : QProblemB( rhs ) +{ + int i, j; + + int _nV = rhs.bounds.getNV( ); + int _nC = rhs.constraints.getNC( ); + + for( i=0; i<_nC; ++i ) + for( j=0; j<_nV; ++j ) + A[i*NVMAX + j] = rhs.A[i*NVMAX + j]; + + for( i=0; i<_nC; ++i ) + lbA[i] = rhs.lbA[i]; + + for( i=0; i<_nC; ++i ) + ubA[i] = rhs.ubA[i]; + + constraints = rhs.constraints; + + for( i=0; i<(_nV+_nC); ++i ) + y[i] = rhs.y[i]; + + + sizeT = rhs.sizeT; + + for( i=0; ithrowInfo( RET_ITERATION_STARTED,messageString,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE ); + #endif + } + + /* 1) Setup index arrays. */ + if ( bounds.getFree( )->getNumberArray( FR_idx ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_HOTSTART_FAILED ); + + if ( bounds.getFixed( )->getNumberArray( FX_idx ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_HOTSTART_FAILED ); + + if ( constraints.getActive( )->getNumberArray( AC_idx ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_HOTSTART_FAILED ); + + if ( constraints.getInactive( )->getNumberArray( IAC_idx ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_HOTSTART_FAILED ); + + /* 2) Detemination of shift direction of the gradient and the (constraints') bounds. */ + returnvalue = hotstart_determineDataShift( FX_idx, AC_idx, + g_new,lbA_new,ubA_new,lb_new,ub_new, + delta_g,delta_lbA,delta_ubA,delta_lb,delta_ub, + Delta_bC_isZero, Delta_bB_isZero ); + if ( returnvalue != SUCCESSFUL_RETURN ) + { + nWSR = l; + THROWERROR( RET_SHIFT_DETERMINATION_FAILED ); + return returnvalue; + } + + /* 3) Determination of step direction of X and Y. */ + returnvalue = hotstart_determineStepDirection( FR_idx,FX_idx,AC_idx, + delta_g,delta_lbA,delta_ubA,delta_lb,delta_ub, + Delta_bC_isZero, Delta_bB_isZero, + delta_xFX,delta_xFR,delta_yAC,delta_yFX + ); + if ( returnvalue != SUCCESSFUL_RETURN ) + { + nWSR = l; + THROWERROR( RET_STEPDIRECTION_DETERMINATION_FAILED ); + return returnvalue; + } + + /* 4) Determination of step length TAU. */ + returnvalue = hotstart_determineStepLength( FR_idx,FX_idx,AC_idx,IAC_idx, + delta_lbA,delta_ubA,delta_lb,delta_ub, + delta_xFX,delta_xFR,delta_yAC,delta_yFX,delta_Ax, + BC_idx,BC_status,BC_isBound + ); + if ( returnvalue != SUCCESSFUL_RETURN ) + { + nWSR = l; + THROWERROR( RET_STEPLENGTH_DETERMINATION_FAILED ); + return returnvalue; + } + + /* 5) Realisation of the homotopy step. */ + returnvalue = hotstart_performStep( FR_idx,FX_idx,AC_idx,IAC_idx, + delta_g,delta_lbA,delta_ubA,delta_lb,delta_ub, + delta_xFX,delta_xFR,delta_yAC,delta_yFX,delta_Ax, + BC_idx,BC_status,BC_isBound + ); + + if ( returnvalue != SUCCESSFUL_RETURN ) + { + nWSR = l; + + /* stop runtime measurement */ + if ( cputime != 0 ) + *cputime = getCPUtime( ) - starttime; + + /* optimal solution found? */ + if ( returnvalue == RET_OPTIMAL_SOLUTION_FOUND ) + { + status = QPS_SOLVED; + + if ( printlevel == PL_HIGH ) + THROWINFO( RET_OPTIMAL_SOLUTION_FOUND ); + + #ifdef PC_DEBUG + if ( printIteration( l,BC_idx,BC_status,BC_isBound ) != SUCCESSFUL_RETURN ) + THROWERROR( RET_PRINT_ITERATION_FAILED ); /* do not pass this as return value! */ + #endif + + /* check KKT optimality conditions */ + return checkKKTconditions( ); + } + else + { + /* checks for infeasibility... */ + if ( isInfeasible( ) == BT_TRUE ) + { + status = QPS_HOMOTOPYQPSOLVED; + return THROWERROR( RET_HOTSTART_STOPPED_INFEASIBILITY ); + } + + /* ...unboundedness... */ + if ( unbounded == BT_TRUE ) /* not necessary since objective function convex! */ + return THROWERROR( RET_HOTSTART_STOPPED_UNBOUNDEDNESS ); + + /* ... and throw unspecific error otherwise */ + THROWERROR( RET_HOMOTOPY_STEP_FAILED ); + return returnvalue; + } + } + + /* 6) Output information of successful QP iteration. */ + status = QPS_HOMOTOPYQPSOLVED; + + #ifdef PC_DEBUG + if ( printIteration( l,BC_idx,BC_status,BC_isBound ) != SUCCESSFUL_RETURN ) + THROWERROR( RET_PRINT_ITERATION_FAILED ); /* do not pass this as return value! */ + #endif + } + + + /* stop runtime measurement */ + if ( cputime != 0 ) + *cputime = getCPUtime( ) - starttime; + + + /* if programm gets to here, output information that QP could not be solved + * within the given maximum numbers of working set changes */ + if ( printlevel == PL_HIGH ) + { + #ifdef PC_DEBUG + sprintf( messageString,"(nWSR = %d)",nWSR ); + return getGlobalMessageHandler( )->throwWarning( RET_MAX_NWSR_REACHED,messageString,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE ); + #endif + } + + /* Finally check KKT optimality conditions. */ + returnValue returnvalueKKTcheck = checkKKTconditions( ); + + if ( returnvalueKKTcheck != SUCCESSFUL_RETURN ) + return returnvalueKKTcheck; + else + return RET_MAX_NWSR_REACHED; +} + + +/* + * g e t N Z + */ +int QProblem::getNZ( ) +{ + /* nZ = nFR - nAC */ + return bounds.getFree( )->getLength( ) - constraints.getActive( )->getLength( ); +} + + +/* + * g e t D u a l S o l u t i o n + */ +returnValue QProblem::getDualSolution( real_t* const yOpt ) const +{ + int i; + + /* return optimal dual solution vector + * only if current QP has been solved */ + if ( ( getStatus( ) == QPS_AUXILIARYQPSOLVED ) || + ( getStatus( ) == QPS_HOMOTOPYQPSOLVED ) || + ( getStatus( ) == QPS_SOLVED ) ) + { + for( i=0; i -INFTY ) + { + constraints.setNoLower( BT_FALSE ); + break; + } + } + + /* 2) Check if upper constraints' bounds are present. */ + constraints.setNoUpper( BT_TRUE ); + for( i=0; i INFTY - BOUNDTOL ) ) + { + constraints.setType( i,ST_UNBOUNDED ); + ++nUC; + } + else + { + if ( lbA[i] > ubA[i] - BOUNDTOL ) + { + constraints.setType( i,ST_EQUALITY ); + ++nEC; + } + else + { + constraints.setType( i,ST_BOUNDED ); + } + } + } + + /* 4) Set dimensions of constraints structure. */ + constraints.setNEC( nEC ); + constraints.setNUC( nUC ); + constraints.setNIC( nC - nEC - nUC ); + + return SUCCESSFUL_RETURN; +} + + +/* + * c h o l e s k y D e c o m p o s i t i o n P r o j e c t e d + */ +returnValue QProblem::setupCholeskyDecompositionProjected( ) +{ + int i, j, k, ii, kk; + int nV = getNV( ); + int nFR = getNFR( ); + int nZ = getNZ( ); + + /* 1) Initialises R with all zeros. */ + for( i=0; i 0 ) + { + int FR_idx[NVMAX]; + if ( bounds.getFree( )->getNumberArray( FR_idx ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_INDEXLIST_CORRUPTED ); + +#if 0 + real_t HZ[NVMAX*NVMAX]; + real_t ZHZ[NVMAX*NVMAX]; + + /* calculate H*Z */ + for ( i=0; i=0; --k ) + sum -= R[k*NVMAX + i] * R[k*NVMAX + i]; + + if ( sum > 0.0 ) + { + R[i*NVMAX + i] = sqrt( sum ); + inv = 1.0 / R[i * NVMAX + i]; + } + else + { + hessianType = HST_SEMIDEF; + return THROWERROR( RET_HESSIAN_NOT_SPD ); + } + + for( j=(i+1); j=0; --k ) + sum -= R[k*NVMAX + i] * R[k*NVMAX + j]; + + R[i*NVMAX + j] = sum * inv; + } + } +#else + real_t HZ[NVMAX]; + real_t ZHZ[NVMAX]; + + real_t sum, inv; + for (j = 0; j < nZ; ++j) + { + /* Cache one column of Z. */ + for (i = 0; i < NVMAX; ++i) + ZHZ[i] = Q[i * NVMAX + j]; + + /* Create one column of the product H * Z. */ + for (i = 0; i < nFR; ++i) + { + ii = FR_idx[i]; + + sum = 0.0; + for (k = 0; k < nFR; ++k) + { + kk = FR_idx[k]; + sum += H[ii * NVMAX + kk] * ZHZ[kk]; + } + HZ[ii] = sum; + } + + /* Create one column of the product Z^T * H * Z. */ + for (i = j; i < nZ; ++i) + ZHZ[ i ] = 0.0; + + for (k = 0; k < nFR; ++k) + { + kk = FR_idx[k]; + real_t q = HZ[kk]; + for (i = j; i < nZ; ++i) + { + ZHZ[i] += Q[kk * NVMAX + i] * q; + } + } + + /* Use the computed column to update the factorization. */ + /* j == i */ + sum = ZHZ[j]; + + for (k = (j - 1); k >= 0; --k) + sum -= R[k * NVMAX + j] * R[k * NVMAX + j]; + + if (sum > 0.0) + { + R[j * NVMAX + j] = sqrt(sum); + inv = 1.0 / R[j * NVMAX + j]; + } + else + { + hessianType = HST_SEMIDEF; + return THROWERROR( RET_HESSIAN_NOT_SPD ); + } + + for (i = (j + 1); i < nZ; ++i) + { + sum = ZHZ[i]; + + for (k = (j - 1); k >= 0; --k) + sum -= R[k * NVMAX + j] * R[k * NVMAX + i]; + + R[j * NVMAX + i] = sum * inv; + } + } +#endif + } + } + + return SUCCESSFUL_RETURN; +} + + +/* + * s e t u p T Q f a c t o r i s a t i o n + */ +returnValue QProblem::setupTQfactorisation( ) +{ + int i, j, ii; + int nV = getNV( ); + int nFR = getNFR( ); + + int FR_idx[NVMAX]; + if ( bounds.getFree( )->getNumberArray( FR_idx ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_INDEXLIST_CORRUPTED ); + + /* 1) Set Q to unity matrix. */ + for( i=0; igetStatus( i ); + + if ( constraints.getType( i ) == ST_EQUALITY ) + { + if ( auxiliaryConstraints->setupConstraint( i,ST_LOWER ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED ); + } + else + { + if ( auxiliaryConstraints->setupConstraint( i,guessedStatus ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED ); + } + } + } + else /* No initial working set specified. */ + { + /* Obtain initial working set by "clipping". */ + if ( ( xOpt != 0 ) && ( yOpt == 0 ) ) + { + for( i=0; isetupConstraint( i,ST_LOWER ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED ); + continue; + } + + if ( Ax[i] >= ubA[i] - BOUNDTOL ) + { + if ( auxiliaryConstraints->setupConstraint( i,ST_UPPER ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED ); + continue; + } + + /* Moreover, add all equality constraints if specified. */ + if ( constraints.getType( i ) == ST_EQUALITY ) + { + if ( auxiliaryConstraints->setupConstraint( i,ST_LOWER ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED ); + } + else + { + if ( auxiliaryConstraints->setupConstraint( i,ST_INACTIVE ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED ); + } + } + } + + /* Obtain initial working set in accordance to sign of dual solution vector. */ + if ( ( xOpt == 0 ) && ( yOpt != 0 ) ) + { + for( i=0; i ZERO ) + { + if ( auxiliaryConstraints->setupConstraint( i,ST_LOWER ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED ); + continue; + } + + if ( yOpt[nV+i] < -ZERO ) + { + if ( auxiliaryConstraints->setupConstraint( i,ST_UPPER ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED ); + continue; + } + + /* Moreover, add all equality constraints if specified. */ + if ( constraints.getType( i ) == ST_EQUALITY ) + { + if ( auxiliaryConstraints->setupConstraint( i,ST_LOWER ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED ); + } + else + { + if ( auxiliaryConstraints->setupConstraint( i,ST_INACTIVE ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED ); + } + } + } + + /* If xOpt and yOpt are null pointer and no initial working is specified, + * start with empty working set (or implicitly fixed bounds and equality constraints only) + * for auxiliary QP. */ + if ( ( xOpt == 0 ) && ( yOpt == 0 ) ) + { + for( i=0; isetupConstraint( i,ST_LOWER ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED ); + } + else + { + if ( auxiliaryConstraints->setupConstraint( i,ST_INACTIVE ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED ); + } + } + } + } + + return SUCCESSFUL_RETURN; +} + + + +/* + * s e t u p A u x i l i a r y W o r k i n g S e t + */ +returnValue QProblem::setupAuxiliaryWorkingSet( const Bounds* const auxiliaryBounds, + const Constraints* const auxiliaryConstraints, + BooleanType setupAfresh + ) +{ + int i; + int nV = getNV( ); + int nC = getNC( ); + + /* consistency checks */ + if ( auxiliaryBounds != 0 ) + { + for( i=0; igetStatus( i ) == ST_UNDEFINED ) ) + return THROWERROR( RET_UNKNOWN_BUG ); + } + else + { + return THROWERROR( RET_INVALID_ARGUMENTS ); + } + + if ( auxiliaryConstraints != 0 ) + { + for( i=0; igetStatus( i ) == ST_UNDEFINED ) ) + return THROWERROR( RET_UNKNOWN_BUG ); + } + else + { + return THROWERROR( RET_INVALID_ARGUMENTS ); + } + + + /* I) SETUP CHOLESKY FLAG: + * Cholesky decomposition shall only be updated if working set + * shall be updated (i.e. NOT setup afresh!) */ + BooleanType updateCholesky; + if ( setupAfresh == BT_TRUE ) + updateCholesky = BT_FALSE; + else + updateCholesky = BT_TRUE; + + + /* II) REMOVE FORMERLY ACTIVE (CONSTRAINTS') BOUNDS (IF NECESSARY): */ + if ( setupAfresh == BT_FALSE ) + { + /* 1) Remove all active constraints that shall be inactive AND + * all active constraints that are active at the wrong bound. */ + for( i=0; igetStatus( i ) != ST_LOWER ) ) + if ( removeConstraint( i,updateCholesky ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_SETUP_WORKINGSET_FAILED ); + + if ( ( constraints.getStatus( i ) == ST_UPPER ) && ( auxiliaryConstraints->getStatus( i ) != ST_UPPER ) ) + if ( removeConstraint( i,updateCholesky ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_SETUP_WORKINGSET_FAILED ); + } + + /* 2) Remove all active bounds that shall be inactive AND + * all active bounds that are active at the wrong bound. */ + for( i=0; igetStatus( i ) != ST_LOWER ) ) + if ( removeBound( i,updateCholesky ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_SETUP_WORKINGSET_FAILED ); + + if ( ( bounds.getStatus( i ) == ST_UPPER ) && ( auxiliaryBounds->getStatus( i ) != ST_UPPER ) ) + if ( removeBound( i,updateCholesky ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_SETUP_WORKINGSET_FAILED ); + } + } + + + /* III) ADD NEWLY ACTIVE (CONSTRAINTS') BOUNDS: */ + /* 1) Add all inactive bounds that shall be active AND + * all formerly active bounds that have been active at the wrong bound. */ + for( i=0; igetStatus( i ) != ST_INACTIVE ) ) + { + /* Add bound only if it is linearly independent from the current working set. */ + if ( addBound_checkLI( i ) == RET_LINEARLY_INDEPENDENT ) + { + if ( addBound( i,auxiliaryBounds->getStatus( i ),updateCholesky ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_SETUP_WORKINGSET_FAILED ); + } + } + } + + /* 2) Add all inactive constraints that shall be active AND + * all formerly active constraints that have been active at the wrong bound. */ + for( i=0; igetStatus( i ) == ST_LOWER ) || ( auxiliaryConstraints->getStatus( i ) == ST_UPPER ) ) + { + /* formerly inactive */ + if ( constraints.getStatus( i ) == ST_INACTIVE ) + { + /* Add constraint only if it is linearly independent from the current working set. */ + if ( addConstraint_checkLI( i ) == RET_LINEARLY_INDEPENDENT ) + { + if ( addConstraint( i,auxiliaryConstraints->getStatus( i ),updateCholesky ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_SETUP_WORKINGSET_FAILED ); + } + } + } + } + + return SUCCESSFUL_RETURN; +} + + +/* + * s e t u p A u x i l i a r y Q P s o l u t i o n + */ +returnValue QProblem::setupAuxiliaryQPsolution( const real_t* const xOpt, const real_t* const yOpt + ) +{ + int i, j; + int nV = getNV( ); + int nC = getNC( ); + + + /* Setup primal/dual solution vector for auxiliary initial QP: + * if a null pointer is passed, a zero vector is assigned; + * old solution vector is kept if pointer to internal solution vevtor is passed. */ + if ( xOpt != 0 ) + { + if ( xOpt != x ) + for( i=0; igetStatus( i ) == ST_LOWER ) + lb[i] = x[i]; + else + lb[i] = x[i] - BOUNDRELAXATION; + + if ( auxiliaryBounds->getStatus( i ) == ST_UPPER ) + ub[i] = x[i]; + else + ub[i] = x[i] + BOUNDRELAXATION; + } + } + break; + + case ST_LOWER: + lb[i] = x[i]; + if ( bounds.getType( i ) == ST_EQUALITY ) + { + ub[i] = x[i]; + } + else + { + if ( useRelaxation == BT_TRUE ) + ub[i] = x[i] + BOUNDRELAXATION; + } + break; + + case ST_UPPER: + ub[i] = x[i]; + if ( bounds.getType( i ) == ST_EQUALITY ) + { + lb[i] = x[i]; + } + else + { + if ( useRelaxation == BT_TRUE ) + lb[i] = x[i] - BOUNDRELAXATION; + } + break; + + default: + return THROWERROR( RET_UNKNOWN_BUG ); + } + } + + /* 2) Setup constraints vectors. */ + for ( i=0; igetStatus( i ) == ST_LOWER ) + lbA[i] = Ax[i]; + else + lbA[i] = Ax[i] - BOUNDRELAXATION; + + if ( auxiliaryConstraints->getStatus( i ) == ST_UPPER ) + ubA[i] = Ax[i]; + else + ubA[i] = Ax[i] + BOUNDRELAXATION; + } + } + break; + + case ST_LOWER: + lbA[i] = Ax[i]; + if ( constraints.getType( i ) == ST_EQUALITY ) + { + ubA[i] = Ax[i]; + } + else + { + if ( useRelaxation == BT_TRUE ) + ubA[i] = Ax[i] + BOUNDRELAXATION; + } + break; + + case ST_UPPER: + ubA[i] = Ax[i]; + if ( constraints.getType( i ) == ST_EQUALITY ) + { + lbA[i] = Ax[i]; + } + else + { + if ( useRelaxation == BT_TRUE ) + lbA[i] = Ax[i] - BOUNDRELAXATION; + } + break; + + default: + return THROWERROR( RET_UNKNOWN_BUG ); + } + } + + return SUCCESSFUL_RETURN; +} + + +/* + * a d d C o n s t r a i n t + */ +returnValue QProblem::addConstraint( int number, SubjectToStatus C_status, + BooleanType updateCholesky + ) +{ + int i, j, ii; + + /* consistency checks */ + if ( constraints.getStatus( number ) != ST_INACTIVE ) + return THROWERROR( RET_CONSTRAINT_ALREADY_ACTIVE ); + + if ( ( constraints.getNC( ) - getNAC( ) ) == constraints.getNUC( ) ) + return THROWERROR( RET_ALL_CONSTRAINTS_ACTIVE ); + + if ( ( getStatus( ) == QPS_NOTINITIALISED ) || + ( getStatus( ) == QPS_AUXILIARYQPSOLVED ) || + ( getStatus( ) == QPS_HOMOTOPYQPSOLVED ) || + ( getStatus( ) == QPS_SOLVED ) ) + { + return THROWERROR( RET_UNKNOWN_BUG ); + } + + + /* I) ENSURE LINEAR INDEPENDENCE OF THE WORKING SET, + * i.e. remove a constraint or bound if linear dependence occurs. */ + /* check for LI only if Cholesky decomposition shall be updated! */ + if ( updateCholesky == BT_TRUE ) + { + returnValue ensureLIreturnvalue = addConstraint_ensureLI( number,C_status ); + + switch ( ensureLIreturnvalue ) + { + case SUCCESSFUL_RETURN: + break; + + case RET_LI_RESOLVED: + break; + + case RET_ENSURELI_FAILED_NOINDEX: + return THROWERROR( RET_ADDCONSTRAINT_FAILED_INFEASIBILITY ); + + case RET_ENSURELI_FAILED_CYCLING: + return THROWERROR( RET_ADDCONSTRAINT_FAILED_INFEASIBILITY ); + + default: + return THROWERROR( RET_ENSURELI_FAILED ); + } + } + + /* some definitions */ + int nFR = getNFR( ); + int nAC = getNAC( ); + int nZ = getNZ( ); + + int tcol = sizeT - nAC; + + + int FR_idx[NVMAX]; + if ( bounds.getFree( )->getNumberArray( FR_idx ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_ADDCONSTRAINT_FAILED ); + + real_t aFR[NVMAX]; + real_t wZ[NVMAX]; + for( i=0; i 0 ) + { + for( j=0; j 0 ) + { + /* II) RESTORE TRIANGULAR FORM OF T: */ + /* Use column-wise Givens rotations to restore reverse triangular form + * of T, simultanenous change of Q (i.e. Z) and R. */ + for( j=0; jgetNumberArray( FR_idx ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_INDEXLIST_CORRUPTED ); + + /* Check if constraint is linearly independent from the + the active ones (<=> is element of null space of Afr). */ + real_t sum; + + for( i=0; i 10.0*EPS ) + return RET_LINEARLY_INDEPENDENT; + } + + return RET_LINEARLY_DEPENDENT; +} + + +/* + * a d d C o n s t r a i n t _ e n s u r e L I + */ +returnValue QProblem::addConstraint_ensureLI( int number, SubjectToStatus C_status ) +{ + int i, j, ii, jj; + int nV = getNV( ); + int nFR = getNFR( ); + int nFX = getNFX( ); + int nAC = getNAC( ); + int nZ = getNZ( ); + + + /* I) Check if new constraint is linearly independent from the active ones. */ + returnValue returnvalueCheckLI = addConstraint_checkLI( number ); + + if ( returnvalueCheckLI == RET_INDEXLIST_CORRUPTED ) + return THROWERROR( RET_ENSURELI_FAILED ); + + if ( returnvalueCheckLI == RET_LINEARLY_INDEPENDENT ) + return SUCCESSFUL_RETURN; + + + /* II) NEW CONSTRAINT IS LINEARLY DEPENDENT: */ + /* 1) Determine coefficients of linear combination, + * cf. M.J. Best. Applied Mathematics and Parallel Computing, chapter: + * An Algorithm for the Solution of the Parametric Quadratic Programming + * Problem, pages 57-76. Physica-Verlag, Heidelberg, 1996. */ + int FR_idx[NVMAX]; + if ( bounds.getFree( )->getNumberArray( FR_idx ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_ENSURELI_FAILED ); + + int FX_idx[NVMAX]; + if ( bounds.getFixed( )->getNumberArray( FX_idx ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_ENSURELI_FAILED ); + + real_t xiC[NCMAX_ALLOC]; + real_t xiC_TMP[NCMAX_ALLOC]; + real_t xiB[NVMAX]; + + /* 2) Calculate xiC */ + if ( nAC > 0 ) + { + if ( C_status == ST_LOWER ) + { + for( i=0; igetNumberArray( AC_idx ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_ENSURELI_FAILED ); + + if ( C_status == ST_LOWER ) + { + for( i=0; i ZERO ) && ( y[nV+ii] >= 0.0 ) ) + { + if ( y[nV+ii]/xiC[i] < y_min ) + { + y_min = y[nV+ii]/xiC[i]; + y_min_number = ii; + } + } + } + else + { + if ( ( xiC[i] < -ZERO ) && ( y[nV+ii] <= 0.0 ) ) + { + if ( y[nV+ii]/xiC[i] < y_min ) + { + y_min = y[nV+ii]/xiC[i]; + y_min_number = ii; + } + } + } + } + + /* 2) Bounds. */ + for( i=0; i ZERO ) && ( y[ii] >= 0.0 ) ) + { + if ( y[ii]/xiB[i] < y_min ) + { + y_min = y[ii]/xiB[i]; + y_min_number = ii; + y_min_isBound = BT_TRUE; + } + } + } + else + { + if ( ( xiB[i] < -ZERO ) && ( y[ii] <= 0.0 ) ) + { + if ( y[ii]/xiB[i] < y_min ) + { + y_min = y[ii]/xiB[i]; + y_min_number = ii; + y_min_isBound = BT_TRUE; + } + } + } + } + + /* setup output preferences */ + #ifdef PC_DEBUG + char messageString[80]; + VisibilityStatus visibilityStatus; + + if ( printlevel == PL_HIGH ) + visibilityStatus = VS_VISIBLE; + else + visibilityStatus = VS_HIDDEN; + #endif + + + /* IV) REMOVE CONSTRAINT/BOUND FOR RESOLVING LINEAR DEPENDENCE: */ + if ( y_min_number >= 0 ) + { + /* 1) Check for cycling due to infeasibility. */ + if ( ( cyclingManager.getCyclingStatus( number,BT_FALSE ) == CYC_PREV_REMOVED ) && + ( cyclingManager.getCyclingStatus( y_min_number,y_min_isBound ) == CYC_PREV_ADDED ) ) + { + infeasible = BT_TRUE; + + return THROWERROR( RET_ENSURELI_FAILED_CYCLING ); + } + else + { + /* set cycling data */ + cyclingManager.clearCyclingData( ); + cyclingManager.setCyclingStatus( number,BT_FALSE, CYC_PREV_ADDED ); + cyclingManager.setCyclingStatus( y_min_number,y_min_isBound, CYC_PREV_REMOVED ); + } + + /* 2) Update Lagrange multiplier... */ + for( i=0; ithrowInfo( RET_REMOVE_FROM_ACTIVESET,messageString,__FUNCTION__,__FILE__,__LINE__,visibilityStatus ); + #endif + + if ( removeBound( y_min_number,BT_TRUE ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_REMOVE_FROM_ACTIVESET_FAILED ); + + y[y_min_number] = 0.0; + } + else + { + #ifdef PC_DEBUG + sprintf( messageString,"constraint no. %d.",y_min_number ); + getGlobalMessageHandler( )->throwInfo( RET_REMOVE_FROM_ACTIVESET,messageString,__FUNCTION__,__FILE__,__LINE__,visibilityStatus ); + #endif + + if ( removeConstraint( y_min_number,BT_TRUE ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_REMOVE_FROM_ACTIVESET_FAILED ); + + y[nV+y_min_number] = 0.0; + } + } + else + { + /* no constraint/bound can be removed => QP is infeasible! */ + infeasible = BT_TRUE; + + return THROWERROR( RET_ENSURELI_FAILED_NOINDEX ); + } + + return getGlobalMessageHandler( )->throwInfo( RET_LI_RESOLVED,0,__FUNCTION__,__FILE__,__LINE__,VS_HIDDEN ); +} + + + +/* + * a d d B o u n d + */ +returnValue QProblem::addBound( int number, SubjectToStatus B_status, + BooleanType updateCholesky + ) +{ + int i, j, ii; + + /* consistency checks */ + if ( bounds.getStatus( number ) != ST_INACTIVE ) + return THROWERROR( RET_BOUND_ALREADY_ACTIVE ); + + if ( getNFR( ) == bounds.getNUV( ) ) + return THROWERROR( RET_ALL_BOUNDS_ACTIVE ); + + if ( ( getStatus( ) == QPS_NOTINITIALISED ) || + ( getStatus( ) == QPS_AUXILIARYQPSOLVED ) || + ( getStatus( ) == QPS_HOMOTOPYQPSOLVED ) || + ( getStatus( ) == QPS_SOLVED ) ) + { + return THROWERROR( RET_UNKNOWN_BUG ); + } + + + /* I) ENSURE LINEAR INDEPENDENCE OF THE WORKING SET, + * i.e. remove a constraint or bound if linear dependence occurs. */ + /* check for LI only if Cholesky decomposition shall be updated! */ + if ( updateCholesky == BT_TRUE ) + { + returnValue ensureLIreturnvalue = addBound_ensureLI( number,B_status ); + + switch ( ensureLIreturnvalue ) + { + case SUCCESSFUL_RETURN: + break; + + case RET_LI_RESOLVED: + break; + + case RET_ENSURELI_FAILED_NOINDEX: + return THROWERROR( RET_ADDBOUND_FAILED_INFEASIBILITY ); + + case RET_ENSURELI_FAILED_CYCLING: + return THROWERROR( RET_ADDBOUND_FAILED_INFEASIBILITY ); + + default: + return THROWERROR( RET_ENSURELI_FAILED ); + } + } + + + /* some definitions */ + int nFR = getNFR( ); + int nAC = getNAC( ); + int nZ = getNZ( ); + + int tcol = sizeT - nAC; + + + /* I) SWAP INDEXLIST OF FREE VARIABLES: + * move the variable to be fixed to the end of the list of free variables. */ + int lastfreenumber = bounds.getFree( )->getLastNumber( ); + if ( lastfreenumber != number ) + if ( bounds.swapFree( number,lastfreenumber ) != SUCCESSFUL_RETURN ) + THROWERROR( RET_ADDBOUND_FAILED ); + + + int FR_idx[NVMAX]; + if ( bounds.getFree( )->getNumberArray( FR_idx ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_ADDBOUND_FAILED ); + + real_t w[NVMAX]; + + + /* II) ADD NEW ACTIVE BOUND TO TOP OF MATRIX T: */ + /* 1) add row [wZ wY] = [Z Y](number) at the top of T: assign w */ + for( i=0; i 0 ) /* ( nAC == 0 ) <=> ( nZ == nFR ) <=> Y and T are empty => nothing to do */ + { + /* store new column a in a temporary vector instead of shifting T one column to the left */ + real_t tmp[NCMAX_ALLOC]; + for( i=0; i is linearly independent from the + the active ones (<=> is element of null space of Afr). */ + for( i=0; i EPS ) + return RET_LINEARLY_INDEPENDENT; + } + + return RET_LINEARLY_DEPENDENT; +} + + +/* + * a d d B o u n d _ e n s u r e L I + */ +returnValue QProblem::addBound_ensureLI( int number, SubjectToStatus B_status ) +{ + int i, j, ii, jj; + int nV = getNV( ); + int nFX = getNFX( ); + int nAC = getNAC( ); + int nZ = getNZ( ); + + + /* I) Check if new constraint is linearly independent from the active ones. */ + returnValue returnvalueCheckLI = addBound_checkLI( number ); + + if ( returnvalueCheckLI == RET_LINEARLY_INDEPENDENT ) + return SUCCESSFUL_RETURN; + + + /* II) NEW BOUND IS LINEARLY DEPENDENT: */ + /* 1) Determine coefficients of linear combination, + * cf. M.J. Best. Applied Mathematics and Parallel Computing, chapter: + * An Algorithm for the Solution of the Parametric Quadratic Programming + * Problem, pages 57-76. Physica-Verlag, Heidelberg, 1996. */ + int FR_idx[NVMAX]; + if ( bounds.getFree( )->getNumberArray( FR_idx ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_ENSURELI_FAILED ); + + int FX_idx[NVMAX]; + if ( bounds.getFixed( )->getNumberArray( FX_idx ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_ENSURELI_FAILED ); + + int AC_idx[NCMAX_ALLOC]; + if ( constraints.getActive( )->getNumberArray( AC_idx ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_ENSURELI_FAILED ); + + real_t xiC[NCMAX_ALLOC]; + real_t xiC_TMP[NCMAX_ALLOC]; + real_t xiB[NVMAX]; + + /* 2) Calculate xiC. */ + if ( nAC > 0 ) + { + if ( B_status == ST_LOWER ) + { + for( i=0; i ZERO ) && ( y[nV+ii] >= 0.0 ) ) + { + if ( y[nV+ii]/xiC[i] < y_min ) + { + y_min = y[nV+ii]/xiC[i]; + y_min_number = ii; + } + } + } + else + { + if ( ( xiC[i] < -ZERO ) && ( y[nV+ii] <= 0.0 ) ) + { + if ( y[nV+ii]/xiC[i] < y_min ) + { + y_min = y[nV+ii]/xiC[i]; + y_min_number = ii; + } + } + } + } + + /* 2) Bounds. */ + for( i=0; i ZERO ) && ( y[ii] >= 0.0 ) ) + { + if ( y[ii]/xiB[i] < y_min ) + { + y_min = y[ii]/xiB[i]; + y_min_number = ii; + y_min_isBound = BT_TRUE; + } + } + } + else + { + if ( ( xiB[i] < -ZERO ) && ( y[ii] <= 0.0 ) ) + { + if ( y[ii]/xiB[i] < y_min ) + { + y_min = y[ii]/xiB[i]; + y_min_number = ii; + y_min_isBound = BT_TRUE; + } + } + } + } + + /* setup output preferences */ + #ifdef PC_DEBUG + char messageString[80]; + VisibilityStatus visibilityStatus; + + if ( printlevel == PL_HIGH ) + visibilityStatus = VS_VISIBLE; + else + visibilityStatus = VS_HIDDEN; + #endif + + + /* IV) REMOVE CONSTRAINT/BOUND FOR RESOLVING LINEAR DEPENDENCE: */ + if ( y_min_number >= 0 ) + { + /* 1) Check for cycling due to infeasibility. */ + if ( ( cyclingManager.getCyclingStatus( number,BT_TRUE ) == CYC_PREV_REMOVED ) && + ( cyclingManager.getCyclingStatus( y_min_number,y_min_isBound ) == CYC_PREV_ADDED ) ) + { + infeasible = BT_TRUE; + + return THROWERROR( RET_ENSURELI_FAILED_CYCLING ); + } + else + { + /* set cycling data */ + cyclingManager.clearCyclingData( ); + cyclingManager.setCyclingStatus( number,BT_TRUE, CYC_PREV_ADDED ); + cyclingManager.setCyclingStatus( y_min_number,y_min_isBound, CYC_PREV_REMOVED ); + } + + + /* 2) Update Lagrange multiplier... */ + for( i=0; ithrowInfo( RET_REMOVE_FROM_ACTIVESET,messageString,__FUNCTION__,__FILE__,__LINE__,visibilityStatus ); + #endif + + if ( removeBound( y_min_number,BT_TRUE ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_REMOVE_FROM_ACTIVESET_FAILED ); + + y[y_min_number] = 0.0; + } + else + { + #ifdef PC_DEBUG + sprintf( messageString,"constraint no. %d.",y_min_number ); + getGlobalMessageHandler( )->throwInfo( RET_REMOVE_FROM_ACTIVESET,messageString,__FUNCTION__,__FILE__,__LINE__,visibilityStatus ); + #endif + + if ( removeConstraint( y_min_number,BT_TRUE ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_REMOVE_FROM_ACTIVESET_FAILED ); + + y[nV+y_min_number] = 0.0; + } + } + else + { + /* no constraint/bound can be removed => QP is infeasible! */ + infeasible = BT_TRUE; + + return THROWERROR( RET_ENSURELI_FAILED_NOINDEX ); + } + + return getGlobalMessageHandler( )->throwInfo( RET_LI_RESOLVED,0,__FUNCTION__,__FILE__,__LINE__,VS_HIDDEN ); +} + + + +/* + * r e m o v e C o n s t r a i n t + */ +returnValue QProblem::removeConstraint( int number, + BooleanType updateCholesky + ) +{ + int i, j, ii, jj; + + /* consistency check */ + if ( ( getStatus( ) == QPS_NOTINITIALISED ) || + ( getStatus( ) == QPS_AUXILIARYQPSOLVED ) || + ( getStatus( ) == QPS_HOMOTOPYQPSOLVED ) || + ( getStatus( ) == QPS_SOLVED ) ) + { + return THROWERROR( RET_UNKNOWN_BUG ); + } + + /* some definitions */ + int nFR = getNFR( ); + int nAC = getNAC( ); + int nZ = getNZ( ); + + int tcol = sizeT - nAC; + int number_idx = constraints.getActive( )->getIndex( number ); + + + /* consistency checks */ + if ( constraints.getStatus( number ) == ST_INACTIVE ) + return THROWERROR( RET_CONSTRAINT_NOT_ACTIVE ); + + if ( ( number_idx < 0 ) || ( number_idx >= nAC ) ) + return THROWERROR( RET_CONSTRAINT_NOT_ACTIVE ); + + + int FR_idx[NVMAX]; + if ( bounds.getFree( )->getNumberArray( FR_idx ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_REMOVECONSTRAINT_FAILED ); + + + /* I) REMOVE th ROW FROM T, + * i.e. shift rows number+1 through nAC upwards (instead of the actual + * constraint number its corresponding index within matrix A is used). */ + if ( number_idx < nAC-1 ) + { + for( i=(number_idx+1); i=0; --j ) + { + computeGivens( T[(nAC-2-j)*NVMAX + tcol+1+j],T[(nAC-2-j)*NVMAX + tcol+j], T[(nAC-2-j)*NVMAX + tcol+1+j],T[(nAC-2-j)*NVMAX + tcol+j],c,s ); + + for( i=(nAC-j-1); i<(nAC-1); ++i ) + applyGivens( c,s,T[i*NVMAX + tcol+1+j],T[i*NVMAX + tcol+j], T[i*NVMAX + tcol+1+j],T[i*NVMAX + tcol+j] ); + + for( i=0; i 0 ) + { + real_t ZHz[NVMAX]; + for ( i=0; i 0.0 ) + R[nZ*NVMAX + nZ] = sqrt( rho2 ); + else + { + hessianType = HST_SEMIDEF; + return THROWERROR( RET_HESSIAN_NOT_SPD ); + } + } + + /* IV) UPDATE INDICES */ + if ( constraints.moveActiveToInactive( number ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_REMOVECONSTRAINT_FAILED ); + + + return SUCCESSFUL_RETURN; +} + + +/* + * r e m o v e B o u n d + */ +returnValue QProblem::removeBound( int number, + BooleanType updateCholesky + ) +{ + int i, j, ii, jj; + + /* consistency checks */ + if ( bounds.getStatus( number ) == ST_INACTIVE ) + return THROWERROR( RET_BOUND_NOT_ACTIVE ); + + if ( ( getStatus( ) == QPS_NOTINITIALISED ) || + ( getStatus( ) == QPS_AUXILIARYQPSOLVED ) || + ( getStatus( ) == QPS_HOMOTOPYQPSOLVED ) || + ( getStatus( ) == QPS_SOLVED ) ) + { + return THROWERROR( RET_UNKNOWN_BUG ); + } + + /* some definitions */ + int nFR = getNFR( ); + int nAC = getNAC( ); + int nZ = getNZ( ); + + int tcol = sizeT - nAC; + + + /* I) UPDATE INDICES */ + if ( bounds.moveFixedToFree( number ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_REMOVEBOUND_FAILED ); + + + int FR_idx[NVMAX]; + if ( bounds.getFree( )->getNumberArray( FR_idx ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_REMOVEBOUND_FAILED ); + + /* I) APPEND th UNITY VECOTR TO Q. */ + int nnFRp1 = FR_idx[nFR]; + for( i=0; i 0 ) + { + /* store new column a in a temporary vector instead of shifting T one column to the left and appending a */ + int AC_idx[NCMAX_ALLOC]; + if ( constraints.getActive( )->getNumberArray( AC_idx ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_REMOVEBOUND_FAILED ); + + real_t tmp[NCMAX_ALLOC]; + for( i=0; i=0; --j ) + { + computeGivens( tmp[nAC-1-j],T[(nAC-1-j)*NVMAX + tcol+j],T[(nAC-1-j)*NVMAX + tcol+j],tmp[nAC-1-j],c,s ); + + for( i=(nAC-j); i 0 ) + { + real_t Hz[NVMAX]; + for( i=0; i 0 ) + { + real_t r[NVMAX]; + real_t rhs[NVMAX]; + for( i=0; i 0.0 ) + R[nZ*NVMAX + nZ] = sqrt( rho2 ); + else + { + hessianType = HST_SEMIDEF; + return THROWERROR( RET_HESSIAN_NOT_SPD ); + } + } + + return SUCCESSFUL_RETURN; +} + + +/* + * b a c k s o l v e R (CODE DUPLICATE OF QProblemB CLASS!!!) + */ +returnValue QProblem::backsolveR( const real_t* const b, BooleanType transposed, + real_t* const a + ) +{ + /* Call standard backsolve procedure (i.e. removingBound == BT_FALSE). */ + return backsolveR( b,transposed,BT_FALSE,a ); +} + + +/* + * b a c k s o l v e R (CODE DUPLICATE OF QProblemB CLASS!!!) + */ +returnValue QProblem::backsolveR( const real_t* const b, BooleanType transposed, + BooleanType removingBound, + real_t* const a + ) +{ + int i, j; + int nR = getNZ( ); + + real_t sum; + + /* if backsolve is called while removing a bound, reduce nZ by one. */ + if ( removingBound == BT_TRUE ) + --nR; + + /* nothing to do */ + if ( nR <= 0 ) + return SUCCESSFUL_RETURN; + + + /* Solve Ra = b, where R might be transposed. */ + if ( transposed == BT_FALSE ) + { + /* solve Ra = b */ + for( i=(nR-1); i>=0; --i ) + { + sum = b[i]; + for( j=(i+1); j ZERO ) + a[i] = sum / R[i*NVMAX + i]; + else + return THROWERROR( RET_DIV_BY_ZERO ); + } + } + else + { + /* solve R^T*a = b */ + for( i=0; i ZERO ) + a[i] = sum / R[i*NVMAX + i]; + else + return THROWERROR( RET_DIV_BY_ZERO ); + } + } + + return SUCCESSFUL_RETURN; +} + + + +/* + * b a c k s o l v e T + */ +returnValue QProblem::backsolveT( const real_t* const b, BooleanType transposed, real_t* const a ) +{ + int i, j; + int nT = getNAC( ); + int tcol = sizeT - nT; + + real_t sum; + + /* nothing to do */ + if ( nT <= 0 ) + return SUCCESSFUL_RETURN; + + + /* Solve Ta = b, where T might be transposed. */ + if ( transposed == BT_FALSE ) + { + /* solve Ta = b */ + for( i=0; i ZERO ) + a[nT-1-i] = sum / T[i*NVMAX + sizeT-1-i]; + else + return THROWERROR( RET_DIV_BY_ZERO ); + } + } + else + { + /* solve T^T*a = b */ + for( i=0; i ZERO ) + a[nT-1-i] = sum / T[(nT-1-i)*NVMAX + tcol+i]; + else + return THROWERROR( RET_DIV_BY_ZERO ); + } + } + + + return SUCCESSFUL_RETURN; +} + + +/* + * h o t s t a r t _ d e t e r m i n e D a t a S h i f t + */ +returnValue QProblem::hotstart_determineDataShift( const int* const FX_idx, const int* const AC_idx, + const real_t* const g_new, const real_t* const lbA_new, const real_t* const ubA_new, + const real_t* const lb_new, const real_t* const ub_new, + real_t* const delta_g, real_t* const delta_lbA, real_t* const delta_ubA, + real_t* const delta_lb, real_t* const delta_ub, + BooleanType& Delta_bC_isZero, BooleanType& Delta_bB_isZero + ) +{ + int i, ii; + int nC = getNC( ); + int nAC = getNAC( ); + + + /* I) DETERMINE DATA SHIFT FOR BOUNDS */ + QProblemB::hotstart_determineDataShift( FX_idx,g_new,lb_new,ub_new, delta_g,delta_lb,delta_ub, Delta_bB_isZero ); + + + /* II) DETERMINE DATA SHIFT FOR CONSTRAINTS */ + /* 1) Calculate shift directions. */ + for( i=0; i EPS ) || ( getAbs( delta_ubA[ii] ) > EPS ) ) + { + Delta_bC_isZero = BT_FALSE; + break; + } + } + + return SUCCESSFUL_RETURN; +} + + +/* + * h o t s t a r t _ d e t e r m i n e S t e p D i r e c t i o n + */ +returnValue QProblem::hotstart_determineStepDirection( const int* const FR_idx, const int* const FX_idx, const int* const AC_idx, + const real_t* const delta_g, const real_t* const delta_lbA, const real_t* const delta_ubA, + const real_t* const delta_lb, const real_t* const delta_ub, + BooleanType Delta_bC_isZero, BooleanType Delta_bB_isZero, + real_t* const delta_xFX, real_t* const delta_xFR, + real_t* const delta_yAC, real_t* const delta_yFX + ) +{ + int i, j, ii, jj; + int nFR = getNFR( ); + int nFX = getNFX( ); + int nAC = getNAC( ); + int nZ = getNZ( ); + + /* initialise auxiliary vectors */ + real_t HMX_delta_xFX[NVMAX]; + real_t YFR_delta_xFRy[NVMAX]; + real_t ZFR_delta_xFRz[NVMAX]; + real_t HFR_YFR_delta_xFRy[NVMAX]; + for( i=0; i 0 ) + { + for( i=0; i 0 ) + { + /* 1) Determine delta_xFRy. */ + if ( nAC > 0 ) + { + if ( ( Delta_bC_isZero == BT_TRUE ) && ( Delta_bB_isZero == BT_TRUE ) ) + { + for( i=0; i 0 ) + { + for( i=0; i 0 ) + { + if ( ( Delta_bC_isZero == BT_FALSE ) || ( Delta_bB_isZero == BT_FALSE ) ) + { + for( i=0; i 0 ) + { + /* auxiliary variable */ + real_t delta_xFRz_TMP[NVMAX]; + real_t delta_xFRz_RHS[NVMAX]; + + + if ( ( nAC > 0 ) && ( nFX > 0 ) && ( Delta_bB_isZero == BT_FALSE ) ) + { + for( j=0; j 0 ) /* => Delta_bB_isZero == BT_TRUE, as BT_FALSE would imply nFX>0 */ + { + for( j=0; j 0 ) /* => ( nFR = nZ + nAC > 0 ) */ + { + /* auxiliary variables */ + real_t delta_yAC_TMP[NCMAX_ALLOC]; + for( i=0; i 0 ) + { + for( i=0; i 0 ) + { + if ( Delta_bB_isZero == BT_FALSE ) + { + for( i=0; i 0 ) + { + for( i=0; i 0.0 ) + maxStepLength[nV+ii] = y[nV+ii] / ( -delta_yAC[i] ); + else + maxStepLength[nV+ii] = 0.0; + } + } + else + { + /* active upper constraints' bounds */ + if ( delta_yAC[i] > ZERO ) + { + if ( y[nV+ii] < 0.0 ) + maxStepLength[nV+ii] = y[nV+ii] / ( -delta_yAC[i] ); + else + maxStepLength[nV+ii] = 0.0; + } + } + } + } + + /* 2) Ensure that active dual bounds remain valid + * (ignoring implicitly fixed variables). */ + for( i=0; i 0.0 ) + maxStepLength[ii] = y[ii] / ( -delta_yFX[i] ); + else + maxStepLength[ii] = 0.0; + } + } + else + { + /* active upper bounds */ + if ( delta_yFX[i] > ZERO ) + { + if ( y[ii] < 0.0 ) + maxStepLength[ii] = y[ii] / ( -delta_yFX[i] ); + else + maxStepLength[ii] = 0.0; + } + } + } + } + + + /* II) DETERMINE MAXIMUM PRIMAL STEPLENGTH */ + /* 1) Ensure that inactive constraints' bounds remain valid + * (ignoring unbounded constraints). */ + real_t delta_x[NVMAX]; + for( j=0; j delta_Ax[ii] ) + { + if ( Ax[ii] > lbA[ii] ) + maxStepLength[nV+ii] = ( Ax[ii] - lbA[ii] ) / ( delta_lbA[ii] - delta_Ax[ii] ); + else + maxStepLength[nV+ii] = 0.0; + } + } + + /* inactive upper constraints' bounds */ + if ( constraints.isNoUpper( ) == BT_FALSE ) + { + if ( delta_ubA[ii] < delta_Ax[ii] ) + { + if ( Ax[ii] < ubA[ii] ) + maxStepLength[nV+nC+nV+ii] = ( Ax[ii] - ubA[ii] ) / ( delta_ubA[ii] - delta_Ax[ii] ); + else + maxStepLength[nV+nC+nV+ii] = 0.0; + } + } + } + } + + + /* 2) Ensure that inactive bounds remain valid + * (ignoring unbounded variables). */ + /* inactive lower bounds */ + if ( bounds.isNoLower( ) == BT_FALSE ) + { + for( i=0; i delta_xFR[i] ) + { + if ( x[ii] > lb[ii] ) + maxStepLength[ii] = ( x[ii] - lb[ii] ) / ( delta_lb[ii] - delta_xFR[i] ); + else + maxStepLength[ii] = 0.0; + } + } + } + + /* inactive upper bounds */ + if ( bounds.isNoUpper( ) == BT_FALSE ) + { + for( i=0; i EPS ) + cyclingManager.clearCyclingData( ); + + + /* V) SET MAXIMUM HOMOTOPY STEPLENGTH */ + tau = tau_new; + + #ifdef PC_DEBUG + if ( printlevel == PL_HIGH ) + { + + char messageString[80]; + + if ( BC_status == ST_UNDEFINED ) + sprintf( messageString,"Stepsize is %.6e!",tau ); + else + sprintf( messageString,"Stepsize is %.6e! (BC_idx = %d, BC_isBound = %d, BC_status = %d)",tau,BC_idx,BC_isBound,BC_status ); + + getGlobalMessageHandler( )->throwInfo( RET_STEPSIZE_NONPOSITIVE,messageString,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE ); + } + #endif + + return SUCCESSFUL_RETURN; +} + + +/* + * h o t s t a r t _ p e r f o r m S t e p + */ +returnValue QProblem::hotstart_performStep( const int* const FR_idx, const int* const FX_idx, const int* const AC_idx, const int* const IAC_idx, + const real_t* const delta_g, const real_t* const delta_lbA, const real_t* const delta_ubA, + const real_t* const delta_lb, const real_t* const delta_ub, + const real_t* const delta_xFX, const real_t* const delta_xFR, + const real_t* const delta_yAC, const real_t* const delta_yFX, + const real_t* const delta_Ax, int BC_idx, SubjectToStatus BC_status, BooleanType BC_isBound + ) +{ + int i, j, ii; + int nV = getNV( ); + int nC = getNC( ); + int nFR = getNFR( ); + int nFX = getNFX( ); + int nAC = getNAC( ); + int nIAC = getNIAC( ); + + + /* I) CHECK (CONSTRAINTS') BOUNDS' CONSISTENCY */ + if ( areBoundsConsistent( delta_lb,delta_ub,delta_lbA,delta_ubA ) == BT_FALSE ) + { + infeasible = BT_TRUE; + tau = 0.0; + + return THROWERROR( RET_QP_INFEASIBLE ); + } + + + /* II) GO TO ACTIVE SET CHANGE */ + if ( tau > ZERO ) + { + /* 1) Perform step in primal und dual space... */ + for( i=0; ithrowWarning( RET_STEPSIZE,messageString,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE ); + #endif + } + + + /* setup output preferences */ + #ifdef PC_DEBUG + char messageString[80]; + VisibilityStatus visibilityStatus; + + if ( printlevel == PL_HIGH ) + visibilityStatus = VS_VISIBLE; + else + visibilityStatus = VS_HIDDEN; + #endif + + + /* III) UPDATE ACTIVE SET */ + switch ( BC_status ) + { + /* Optimal solution found as no working set change detected. */ + case ST_UNDEFINED: + return RET_OPTIMAL_SOLUTION_FOUND; + + + /* Remove one variable from active set. */ + case ST_INACTIVE: + if ( BC_isBound == BT_TRUE ) + { + #ifdef PC_DEBUG + sprintf( messageString,"bound no. %d.", BC_idx ); + getGlobalMessageHandler( )->throwInfo( RET_REMOVE_FROM_ACTIVESET,messageString,__FUNCTION__,__FILE__,__LINE__,visibilityStatus ); + #endif + + if ( removeBound( BC_idx,BT_TRUE ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_REMOVE_FROM_ACTIVESET_FAILED ); + + y[BC_idx] = 0.0; + } + else + { + #ifdef PC_DEBUG + sprintf( messageString,"constraint no. %d.", BC_idx ); + getGlobalMessageHandler( )->throwInfo( RET_REMOVE_FROM_ACTIVESET,messageString,__FUNCTION__,__FILE__,__LINE__,visibilityStatus ); + #endif + + if ( removeConstraint( BC_idx,BT_TRUE ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_REMOVE_FROM_ACTIVESET_FAILED ); + + y[nV+BC_idx] = 0.0; + } + break; + + + /* Add one variable to active set. */ + default: + if ( BC_isBound == BT_TRUE ) + { + #ifdef PC_DEBUG + if ( BC_status == ST_LOWER ) + sprintf( messageString,"lower bound no. %d.", BC_idx ); + else + sprintf( messageString,"upper bound no. %d.", BC_idx ); + getGlobalMessageHandler( )->throwInfo( RET_ADD_TO_ACTIVESET,messageString,__FUNCTION__,__FILE__,__LINE__,visibilityStatus ); + #endif + + if ( addBound( BC_idx,BC_status,BT_TRUE ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_ADD_TO_ACTIVESET_FAILED ); + } + else + { + #ifdef PC_DEBUG + if ( BC_status == ST_LOWER ) + sprintf( messageString,"lower constraint's bound no. %d.", BC_idx ); + else + sprintf( messageString,"upper constraint's bound no. %d.", BC_idx ); + getGlobalMessageHandler( )->throwInfo( RET_ADD_TO_ACTIVESET,messageString,__FUNCTION__,__FILE__,__LINE__,visibilityStatus ); + #endif + + if ( addConstraint( BC_idx,BC_status,BT_TRUE ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_ADD_TO_ACTIVESET_FAILED ); + } + break; + } + + return SUCCESSFUL_RETURN; +} + + +/* + * a r e B o u n d s C o n s i s t e n t + */ +BooleanType QProblem::areBoundsConsistent( const real_t* const delta_lb, const real_t* const delta_ub, + const real_t* const delta_lbA, const real_t* const delta_ubA + ) const +{ + int i; + + /* 1) Check bounds' consistency. */ + if ( QProblemB::areBoundsConsistent( delta_lb,delta_ub ) == BT_FALSE ) + return BT_FALSE; + + /* 2) Check constraints' consistency, i.e. + * check if delta_lb[i] is greater than delta_ub[i] + * for a component i whose bounds are already (numerically) equal. */ + for( i=0; i ubA[i] - BOUNDTOL ) && ( delta_lbA[i] > delta_ubA[i] + EPS ) ) + return BT_FALSE; + + return BT_TRUE; +} + + +/* + * s e t u p Q P d a t a + */ +returnValue QProblem::setupQPdata( const real_t* const _H, const real_t* const _R, const real_t* const _g, const real_t* const _A, + const real_t* const _lb, const real_t* const _ub, + const real_t* const _lbA, const real_t* const _ubA + ) +{ + int i, j; + int nV = getNV( ); + int nC = getNC( ); + + + /* 1) Load Hessian matrix as well as lower and upper bounds vectors. */ + if (QProblemB::setupQPdata(_H, _R, _g, _lb, _ub) != SUCCESSFUL_RETURN) + return THROWERROR( RET_INVALID_ARGUMENTS ); + + /* 2) Load constraint matrix. */ + if ( ( nC > 0 ) && ( _A == 0 ) ) + return THROWERROR( RET_INVALID_ARGUMENTS ); + + if ( nC > 0 ) + { + for( i=0; igetNumberArray( AC_idx ); + + /* 1) check for Hx + g - [yFX yAC]*[Id A]' = 0. */ + for( i=0; i maxKKTviolation ) + maxKKTviolation = getAbs( tmp ); + } + + /* 2) Check for [lb lbA] <= [Id A]*x <= [ub ubA]. */ + /* lbA <= Ax <= ubA */ + for( i=0; i maxKKTviolation ) + maxKKTviolation = lbA[i] - Ax[i]; + + if ( Ax[i] - ubA[i] > maxKKTviolation ) + maxKKTviolation = Ax[i] - ubA[i]; + } + + /* lb <= x <= ub */ + for( i=0; i maxKKTviolation ) + maxKKTviolation = lb[i] - x[i]; + + if ( x[i] - ub[i] > maxKKTviolation ) + maxKKTviolation = x[i] - ub[i]; + } + + /* 3) Check for correct sign of y and for complementary slackness. */ + /* bounds */ + for( i=0; i maxKKTviolation ) + maxKKTviolation = -y[i]; + if ( getAbs( x[i] - lb[i] ) > maxKKTviolation ) + maxKKTviolation = getAbs( x[i] - lb[i] ); + break; + + case ST_UPPER: + if ( y[i] > maxKKTviolation ) + maxKKTviolation = y[i]; + if ( getAbs( ub[i] - x[i] ) > maxKKTviolation ) + maxKKTviolation = getAbs( ub[i] - x[i] ); + break; + + default: /* inactive */ + if ( getAbs( y[i] ) > maxKKTviolation ) + maxKKTviolation = getAbs( y[i] ); + break; + } + } + + /* constraints */ + for( i=0; i maxKKTviolation ) + maxKKTviolation = -y[nV+i]; + if ( getAbs( Ax[i] - lbA[i] ) > maxKKTviolation ) + maxKKTviolation = getAbs( Ax[i] - lbA[i] ); + break; + + case ST_UPPER: + if ( y[nV+i] > maxKKTviolation ) + maxKKTviolation = y[nV+i]; + if ( getAbs( ubA[i] - Ax[i] ) > maxKKTviolation ) + maxKKTviolation = getAbs( ubA[i] - Ax[i] ); + break; + + default: /* inactive */ + if ( getAbs( y[nV+i] ) > maxKKTviolation ) + maxKKTviolation = getAbs( y[nV+i] ); + break; + } + } + + if ( maxKKTviolation > CRITICALACCURACY ) + return RET_NO_SOLUTION; + + if ( maxKKTviolation > DESIREDACCURACY ) + return RET_INACCURATE_SOLUTION; + + #endif /* __PERFORM_KKT_TEST__ */ + + return SUCCESSFUL_RETURN; +} + + +/* + * end of file + */ diff --git a/phonelibs/qpoases/SRC/QProblem.ipp b/phonelibs/qpoases/SRC/QProblem.ipp new file mode 100644 index 00000000000000..cec58e291ddeab --- /dev/null +++ b/phonelibs/qpoases/SRC/QProblem.ipp @@ -0,0 +1,299 @@ +/* + * This file is part of qpOASES. + * + * qpOASES -- An Implementation of the Online Active Set Strategy. + * Copyright (C) 2007-2008 by Hans Joachim Ferreau 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 SRC/QProblem.ipp + * \author Hans Joachim Ferreau + * \version 1.3embedded + * \date 2007-2008 + * + * Implementation of inlined member functions of the QProblem class which + * is able to use the newly developed online active set strategy for + * parametric quadratic programming. + */ + + + +/***************************************************************************** + * P U B L I C * + *****************************************************************************/ + +/* + * g e t A + */ +inline returnValue QProblem::getA( real_t* const _A ) const +{ + int i; + + for ( i=0; i= 0 ) && ( number < getNC( ) ) ) + { + for ( int i=0; i= 0 ) && ( number < getNC( ) ) ) + { + value = lbA[number]; + return SUCCESSFUL_RETURN; + } + else + return THROWERROR( RET_INDEX_OUT_OF_BOUNDS ); +} + + +/* + * g e t U B A + */ +inline returnValue QProblem::getUBA( real_t* const _ubA ) const +{ + int i; + + for ( i=0; i= 0 ) && ( number < getNC( ) ) ) + { + value = ubA[number]; + return SUCCESSFUL_RETURN; + } + else + return THROWERROR( RET_INDEX_OUT_OF_BOUNDS ); +} + + +/* + * g e t C o n s t r a i n t s + */ +inline returnValue QProblem::getConstraints( Constraints* const _constraints ) const +{ + *_constraints = constraints; + + return SUCCESSFUL_RETURN; +} + + + +/* + * g e t N C + */ +inline int QProblem::getNC( ) const +{ + return constraints.getNC( ); +} + + +/* + * g e t N E C + */ +inline int QProblem::getNEC( ) const +{ + return constraints.getNEC( ); +} + + +/* + * g e t N A C + */ +inline int QProblem::getNAC( ) +{ + return constraints.getNAC( ); +} + + +/* + * g e t N I A C + */ +inline int QProblem::getNIAC( ) +{ + return constraints.getNIAC( ); +} + + + +/***************************************************************************** + * P R O T E C T E D * + *****************************************************************************/ + + +/* + * s e t A + */ +inline returnValue QProblem::setA( const real_t* const A_new ) +{ + int i, j; + int nV = getNV( ); + int nC = getNC( ); + + /* Set constraint matrix AND update member AX. */ + for( j=0; j= 0 ) && ( number < getNC( ) ) ) + { + Ax[number] = 0.0; + + for( i=0; i= 0 ) && ( number < getNC( ) ) ) + { + lbA[number] = value; + return SUCCESSFUL_RETURN; + } + else + return THROWERROR( RET_INDEX_OUT_OF_BOUNDS ); +} + + +/* + * s e t U B A + */ +inline returnValue QProblem::setUBA( const real_t* const ubA_new ) +{ + int i; + int nC = getNC(); + + for( i=0; i= 0 ) && ( number < getNC( ) ) ) + { + ubA[number] = value; + return SUCCESSFUL_RETURN; + } + else + return THROWERROR( RET_INDEX_OUT_OF_BOUNDS ); +} + + +/* + * end of file + */ diff --git a/phonelibs/qpoases/SRC/QProblemB.cpp b/phonelibs/qpoases/SRC/QProblemB.cpp new file mode 100644 index 00000000000000..f84daabc025d3f --- /dev/null +++ b/phonelibs/qpoases/SRC/QProblemB.cpp @@ -0,0 +1,2151 @@ +/* + * This file is part of qpOASES. + * + * qpOASES -- An Implementation of the Online Active Set Strategy. + * Copyright (C) 2007-2008 by Hans Joachim Ferreau 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 SRC/QProblemB.cpp + * \author Hans Joachim Ferreau + * \version 1.3embedded + * \date 2007-2008 + * + * Implementation of the QProblemB class which is able to use the newly + * developed online active set strategy for parametric quadratic programming. + */ + + +#include + +#include + +void printmatrix(char *name, double *A, int m, int n) { + int i, j; + + printf("%s = [...\n", name); + for (i = 0; i < m; i++) { + for (j = 0; j < n; j++) + printf(" % 9.4f", A[i*n+j]); + printf(",\n"); + } + printf("];\n"); +} + + + +/***************************************************************************** + * P U B L I C * + *****************************************************************************/ + + +/* + * Q P r o b l e m B + */ +QProblemB::QProblemB( ) +{ + /* reset global message handler */ + getGlobalMessageHandler( )->reset( ); + + hasHessian = BT_FALSE; + + bounds.init( 0 ); + + hasCholesky = BT_FALSE; + + tau = 0.0; + + hessianType = HST_POSDEF_NULLSPACE; /* Hessian is assumed to be positive definite by default */ + infeasible = BT_FALSE; + unbounded = BT_FALSE; + + status = QPS_NOTINITIALISED; + + #ifdef PC_DEBUG + printlevel = PL_MEDIUM; + setPrintLevel( PL_MEDIUM ); + #else + printlevel = QPOASES_PRINTLEVEL; + #endif + + count = 0; +} + + +/* + * Q P r o b l e m B + */ +QProblemB::QProblemB( int _nV ) +{ + /* consistency check */ + if ( _nV <= 0 ) + { + _nV = 1; + THROWERROR( RET_INVALID_ARGUMENTS ); + } + + hasHessian = BT_FALSE; + + /* reset global message handler */ + getGlobalMessageHandler( )->reset( ); + + bounds.init( _nV ); + + hasCholesky = BT_FALSE; + + tau = 0.0; + + hessianType = HST_POSDEF_NULLSPACE; /* Hessian is assumed to be positive definite by default */ + infeasible = BT_FALSE; + unbounded = BT_FALSE; + + status = QPS_NOTINITIALISED; + + #ifdef PC_DEBUG + printlevel = PL_MEDIUM; + setPrintLevel( PL_MEDIUM ); + #else + printlevel = QPOASES_PRINTLEVEL; + #endif + + count = 0; +} + + +/* + * Q P r o b l e m B + */ +QProblemB::QProblemB( const QProblemB& rhs ) +{ + int i, j; + + int _nV = rhs.bounds.getNV( ); + + for( i=0; i<_nV; ++i ) + for( j=0; j<_nV; ++j ) + H[i*NVMAX + j] = rhs.H[i*NVMAX + j]; + + hasHessian = rhs.hasHessian; + + for( i=0; i<_nV; ++i ) + g[i] = rhs.g[i]; + + for( i=0; i<_nV; ++i ) + lb[i] = rhs.lb[i]; + + for( i=0; i<_nV; ++i ) + ub[i] = rhs.ub[i]; + + + bounds = rhs.bounds; + + for( i=0; i<_nV; ++i ) + for( j=0; j<_nV; ++j ) + R[i*NVMAX + j] = rhs.R[i*NVMAX + j]; + hasCholesky = rhs.hasCholesky; + + for( i=0; i<_nV; ++i ) + x[i] = rhs.x[i]; + + for( i=0; i<_nV; ++i ) + y[i] = rhs.y[i]; + + tau = rhs.tau; + + hessianType = rhs.hessianType; + infeasible = rhs.infeasible; + unbounded = rhs.unbounded; + + status = rhs.status; + + printlevel = rhs.printlevel; + + count = rhs.count; +} + + +/* + * ~ Q P r o b l e m B + */ +QProblemB::~QProblemB( ) +{ +} + + +/* + * o p e r a t o r = + */ +QProblemB& QProblemB::operator=( const QProblemB& rhs ) +{ + int i, j; + + if ( this != &rhs ) + { + int _nV = rhs.bounds.getNV( ); + + for( i=0; i<_nV; ++i ) + for( j=0; j<_nV; ++j ) + H[i*NVMAX + j] = rhs.H[i*NVMAX + j]; + + hasHessian = rhs.hasHessian; + + for( i=0; i<_nV; ++i ) + g[i] = rhs.g[i]; + + for( i=0; i<_nV; ++i ) + lb[i] = rhs.lb[i]; + + for( i=0; i<_nV; ++i ) + ub[i] = rhs.ub[i]; + + bounds = rhs.bounds; + + for( i=0; i<_nV; ++i ) + for( j=0; j<_nV; ++j ) + R[i*NVMAX + j] = rhs.R[i*NVMAX + j]; + hasCholesky = rhs.hasCholesky; + + + for( i=0; i<_nV; ++i ) + x[i] = rhs.x[i]; + + for( i=0; i<_nV; ++i ) + y[i] = rhs.y[i]; + + tau = rhs.tau; + + hessianType = rhs.hessianType; + infeasible = rhs.infeasible; + unbounded = rhs.unbounded; + + status = rhs.status; + + printlevel = rhs.printlevel; + setPrintLevel( rhs.printlevel ); + + count = rhs.count; + } + + return *this; +} + + +/* + * r e s e t + */ +returnValue QProblemB::reset( ) +{ + int i, j; + int nV = getNV( ); + + /** 0) Reset has Hessian flag. */ + hasHessian = BT_FALSE; + + /* 1) Reset bounds. */ + bounds.init( nV ); + + /* 2) Reset Cholesky decomposition. */ + for( i=0; ithrowInfo( RET_ITERATION_STARTED,messageString,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE ); + #endif + } + + /* 1) Setup index arrays. */ + if ( bounds.getFree( )->getNumberArray( FR_idx ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_HOTSTART_FAILED ); + + if ( bounds.getFixed( )->getNumberArray( FX_idx ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_HOTSTART_FAILED ); + + /* 2) Initialize shift direction of the gradient and the bounds. */ + returnvalue = hotstart_determineDataShift( FX_idx, + g_new,lb_new,ub_new, + delta_g,delta_lb,delta_ub, + Delta_bB_isZero + ); + if ( returnvalue != SUCCESSFUL_RETURN ) + { + nWSR = l; + THROWERROR( RET_SHIFT_DETERMINATION_FAILED ); + return returnvalue; + } + + /* 3) Determination of step direction of X and Y. */ + returnvalue = hotstart_determineStepDirection( FR_idx,FX_idx, + delta_g,delta_lb,delta_ub, + Delta_bB_isZero, + delta_xFX,delta_xFR,delta_yFX + ); + if ( returnvalue != SUCCESSFUL_RETURN ) + { + nWSR = l; + THROWERROR( RET_STEPDIRECTION_DETERMINATION_FAILED ); + return returnvalue; + } + + + /* 4) Determination of step length TAU. */ + returnvalue = hotstart_determineStepLength( FR_idx,FX_idx, + delta_lb,delta_ub, + delta_xFR,delta_yFX, + BC_idx,BC_status ); + if ( returnvalue != SUCCESSFUL_RETURN ) + { + nWSR = l; + THROWERROR( RET_STEPLENGTH_DETERMINATION_FAILED ); + return returnvalue; + } + + /* 5) Realization of the homotopy step. */ + returnvalue = hotstart_performStep( FR_idx,FX_idx, + delta_g,delta_lb,delta_ub, + delta_xFX,delta_xFR,delta_yFX, + BC_idx,BC_status + ); + + + if ( returnvalue != SUCCESSFUL_RETURN ) + { + nWSR = l; + + /* stop runtime measurement */ + if ( cputime != 0 ) + *cputime = getCPUtime( ) - starttime; + + /* optimal solution found? */ + if ( returnvalue == RET_OPTIMAL_SOLUTION_FOUND ) + { + status = QPS_SOLVED; + + if ( printlevel == PL_HIGH ) + THROWINFO( RET_OPTIMAL_SOLUTION_FOUND ); + + #ifdef PC_DEBUG + if ( printIteration( l,BC_idx,BC_status ) != SUCCESSFUL_RETURN ) + THROWERROR( RET_PRINT_ITERATION_FAILED ); /* do not pass this as return value! */ + #endif + + /* check KKT optimality conditions */ + return checkKKTconditions( ); + } + else + { + /* checks for infeasibility... */ + if ( infeasible == BT_TRUE ) + { + status = QPS_HOMOTOPYQPSOLVED; + return THROWERROR( RET_HOTSTART_STOPPED_INFEASIBILITY ); + } + + /* ...unboundedness... */ + if ( unbounded == BT_TRUE ) /* not necessary since objective function convex! */ + return THROWERROR( RET_HOTSTART_STOPPED_UNBOUNDEDNESS ); + + /* ... and throw unspecific error otherwise */ + THROWERROR( RET_HOMOTOPY_STEP_FAILED ); + return returnvalue; + } + } + + /* 6) Output information of successful QP iteration. */ + status = QPS_HOMOTOPYQPSOLVED; + + #ifdef PC_DEBUG + if ( printIteration( l,BC_idx,BC_status ) != SUCCESSFUL_RETURN ) + THROWERROR( RET_PRINT_ITERATION_FAILED ); /* do not pass this as return value! */ + #endif + } + + + /* stop runtime measurement */ + if ( cputime != 0 ) + *cputime = getCPUtime( ) - starttime; + + + /* if programm gets to here, output information that QP could not be solved + * within the given maximum numbers of working set changes */ + if ( printlevel == PL_HIGH ) + { + #ifdef PC_DEBUG + sprintf( messageString,"(nWSR = %d)",nWSR ); + return getGlobalMessageHandler( )->throwWarning( RET_MAX_NWSR_REACHED,messageString,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE ); + #endif + } + + /* Finally check KKT optimality conditions. */ + returnValue returnvalueKKTcheck = checkKKTconditions( ); + + if ( returnvalueKKTcheck != SUCCESSFUL_RETURN ) + return returnvalueKKTcheck; + else + return RET_MAX_NWSR_REACHED; +} + + +/* + * g e t N Z + */ +int QProblemB::getNZ( ) +{ + /* if no constraints are present: nZ=nFR */ + return bounds.getFree( )->getLength( ); +} + + +/* + * g e t O b j V a l + */ +real_t QProblemB::getObjVal( ) const +{ + real_t objVal; + + /* calculated optimal objective function value + * only if current QP has been solved */ + if ( ( getStatus( ) == QPS_AUXILIARYQPSOLVED ) || + ( getStatus( ) == QPS_HOMOTOPYQPSOLVED ) || + ( getStatus( ) == QPS_SOLVED ) ) + { + objVal = getObjVal( x ); + } + else + { + objVal = INFTY; + } + + return objVal; +} + + +/* + * g e t O b j V a l + */ +real_t QProblemB::getObjVal( const real_t* const _x ) const +{ + int i, j; + int nV = getNV( ); + + real_t obj_tmp = 0.0; + + for( i=0; i= PL_MEDIUM ) && ( printlevel != _printlevel ) ) + THROWINFO( RET_PRINTLEVEL_CHANGED ); + #endif + + printlevel = _printlevel; + + /* update message handler preferences */ + switch ( printlevel ) + { + case PL_NONE: + getGlobalMessageHandler( )->setErrorVisibilityStatus( VS_HIDDEN ); + getGlobalMessageHandler( )->setWarningVisibilityStatus( VS_HIDDEN ); + getGlobalMessageHandler( )->setInfoVisibilityStatus( VS_HIDDEN ); + break; + + case PL_LOW: + getGlobalMessageHandler( )->setErrorVisibilityStatus( VS_VISIBLE ); + getGlobalMessageHandler( )->setWarningVisibilityStatus( VS_HIDDEN ); + getGlobalMessageHandler( )->setInfoVisibilityStatus( VS_HIDDEN ); + break; + + default: /* PL_MEDIUM, PL_HIGH */ + getGlobalMessageHandler( )->setErrorVisibilityStatus( VS_VISIBLE ); + getGlobalMessageHandler( )->setWarningVisibilityStatus( VS_VISIBLE ); + getGlobalMessageHandler( )->setInfoVisibilityStatus( VS_VISIBLE ); + break; + } + + return SUCCESSFUL_RETURN; +} + + + +/***************************************************************************** + * P R O T E C T E D * + *****************************************************************************/ + +/* + * c h e c k F o r I d e n t i t y H e s s i a n + */ +returnValue QProblemB::checkForIdentityHessian( ) +{ + int i, j; + int nV = getNV( ); + + /* nothing to do as status flag remains unaltered + * if Hessian differs from identity matrix */ + if ( hessianType == HST_IDENTITY ) + return SUCCESSFUL_RETURN; + + /* 1) If Hessian differs from identity matrix, + * return without changing the internal HessianType. */ + for ( i=0; i EPS ) + return SUCCESSFUL_RETURN; + + for ( i=0; i EPS ) || ( getAbs( H[j*NVMAX + i] ) > EPS ) ) + return SUCCESSFUL_RETURN; + } + + /* 2) If this point is reached, Hessian equals the idetity matrix. */ + hessianType = HST_IDENTITY; + + return SUCCESSFUL_RETURN; +} + + +/* + * s e t u p S u b j e c t T o T y p e + */ +returnValue QProblemB::setupSubjectToType( ) +{ + int i; + int nV = getNV( ); + + + /* 1) Check if lower bounds are present. */ + bounds.setNoLower( BT_TRUE ); + for( i=0; i -INFTY ) + { + bounds.setNoLower( BT_FALSE ); + break; + } + + /* 2) Check if upper bounds are present. */ + bounds.setNoUpper( BT_TRUE ); + for( i=0; i INFTY - BOUNDTOL ) ) + { + bounds.setType( i,ST_UNBOUNDED ); + ++nUV; + } + else + { + if ( lb[i] > ub[i] - BOUNDTOL ) + { + bounds.setType( i,ST_EQUALITY ); + ++nFV; + } + else + { + bounds.setType( i,ST_BOUNDED ); + } + } + + /* 4) Set dimensions of bounds structure. */ + bounds.setNFV( nFV ); + bounds.setNUV( nUV ); + bounds.setNBV( nV - nFV - nUV ); + + return SUCCESSFUL_RETURN; +} + + +/* + * c h o l e s k y D e c o m p o s i t i o n + */ +returnValue QProblemB::setupCholeskyDecomposition( ) +{ + int i, j, k, ii, jj; + int nV = getNV( ); + int nFR = getNFR( ); + + /* If Hessian flag is false, it means that H & R already contain Cholesky + * factorization -- provided from outside. */ + if (hasHessian == BT_FALSE) + return SUCCESSFUL_RETURN; + + /* 1) Initialises R with all zeros. */ + for( i=0; i 0 ) + { + int FR_idx[NVMAX]; + if ( bounds.getFree( )->getNumberArray( FR_idx ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_INDEXLIST_CORRUPTED ); + + /* R'*R = H */ + real_t sum; + real_t inv; + + for( i=0; i=0; --k ) + sum -= R[k*NVMAX + i] * R[k*NVMAX + i]; + + if ( sum > 0.0 ) + { + R[i*NVMAX + i] = sqrt( sum ); + inv = 1.0 / R[i*NVMAX + i]; + } + else + { + hessianType = HST_SEMIDEF; + return THROWERROR( RET_HESSIAN_NOT_SPD ); + } + + /* j > i */ + for( j=(i+1); j=0; --k ) + sum -= R[k*NVMAX + i] * R[k*NVMAX + j]; + + R[i*NVMAX + j] = sum * inv; + } + } + } + } + + return SUCCESSFUL_RETURN; +} + + +/* + * s o l v e I n i t i a l Q P + */ +returnValue QProblemB::solveInitialQP( const real_t* const xOpt, const real_t* const yOpt, + const Bounds* const guessedBounds, + int& nWSR, real_t* const cputime + ) +{ + int i, nFR; + int nV = getNV( ); + + + /* start runtime measurement */ + real_t starttime = 0.0; + if ( cputime != 0 ) + starttime = getCPUtime( ); + + + status = QPS_NOTINITIALISED; + + /* I) ANALYSE QP DATA: */ + /* 1) Check if Hessian happens to be the identity matrix. */ + if ( checkForIdentityHessian( ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_INIT_FAILED ); + + /* 2) Setup type of bounds (i.e. unbounded, implicitly fixed etc.). */ + if ( setupSubjectToType( ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_INIT_FAILED ); + + status = QPS_PREPARINGAUXILIARYQP; + + + /* II) SETUP AUXILIARY QP WITH GIVEN OPTIMAL SOLUTION: */ + /* 1) Setup bounds data structure. */ + if ( bounds.setupAllFree( ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_INIT_FAILED ); + + /* 2) Setup optimal primal/dual solution for auxiliary QP. */ + if ( setupAuxiliaryQPsolution( xOpt,yOpt ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_INIT_FAILED ); + + /* 3) Obtain linear independent working set for auxiliary QP. */ + + static Bounds auxiliaryBounds; + + auxiliaryBounds.init( nV ); + + if ( obtainAuxiliaryWorkingSet( xOpt,yOpt,guessedBounds, &auxiliaryBounds ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_INIT_FAILED ); + + /* 4) Setup working set of auxiliary QP and setup cholesky decomposition. */ + if ( setupAuxiliaryWorkingSet( &auxiliaryBounds,BT_TRUE ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_INIT_FAILED ); + + nFR = getNFR(); + /* At the moment we can only provide a Cholesky of the Hessian if + * the solver is cold-started. */ + if (hasCholesky == BT_FALSE || nFR != nV) + if (setupCholeskyDecomposition() != SUCCESSFUL_RETURN) + return THROWERROR( RET_INIT_FAILED_CHOLESKY ); + + /* 5) Store original QP formulation... */ + real_t g_original[NVMAX]; + real_t lb_original[NVMAX]; + real_t ub_original[NVMAX]; + + for( i=0; isetupBound( i,ST_LOWER ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED ); + } + else + { + if ( auxiliaryBounds->setupBound( i,guessedBounds->getStatus( i ) ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED ); + } + } + } + else /* No initial working set specified. */ + { + if ( ( xOpt != 0 ) && ( yOpt == 0 ) ) + { + /* Obtain initial working set by "clipping". */ + for( i=0; isetupBound( i,ST_LOWER ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED ); + continue; + } + + if ( xOpt[i] >= ub[i] - BOUNDTOL ) + { + if ( auxiliaryBounds->setupBound( i,ST_UPPER ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED ); + continue; + } + + /* Moreover, add all implictly fixed variables if specified. */ + if ( bounds.getType( i ) == ST_EQUALITY ) + { + if ( auxiliaryBounds->setupBound( i,ST_LOWER ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED ); + } + else + { + if ( auxiliaryBounds->setupBound( i,ST_INACTIVE ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED ); + } + } + } + + if ( ( xOpt == 0 ) && ( yOpt != 0 ) ) + { + /* Obtain initial working set in accordance to sign of dual solution vector. */ + for( i=0; i ZERO ) + { + if ( auxiliaryBounds->setupBound( i,ST_LOWER ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED ); + continue; + } + + if ( yOpt[i] < -ZERO ) + { + if ( auxiliaryBounds->setupBound( i,ST_UPPER ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED ); + continue; + } + + /* Moreover, add all implictly fixed variables if specified. */ + if ( bounds.getType( i ) == ST_EQUALITY ) + { + if ( auxiliaryBounds->setupBound( i,ST_LOWER ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED ); + } + else + { + if ( auxiliaryBounds->setupBound( i,ST_INACTIVE ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED ); + } + } + } + + /* If xOpt and yOpt are null pointer and no initial working is specified, + * start with empty working set (or implicitly fixed bounds only) + * for auxiliary QP. */ + if ( ( xOpt == 0 ) && ( yOpt == 0 ) ) + { + for( i=0; isetupBound( i,ST_LOWER ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED ); + } + else + { + if ( auxiliaryBounds->setupBound( i,ST_INACTIVE ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_OBTAINING_WORKINGSET_FAILED ); + } + } + } + } + + return SUCCESSFUL_RETURN; +} + + +/* + * s e t u p A u x i l i a r y W o r k i n g S e t + */ +returnValue QProblemB::setupAuxiliaryWorkingSet( const Bounds* const auxiliaryBounds, + BooleanType setupAfresh + ) +{ + int i; + int nV = getNV( ); + + /* consistency checks */ + if ( auxiliaryBounds != 0 ) + { + for( i=0; igetStatus( i ) == ST_UNDEFINED ) ) + return THROWERROR( RET_UNKNOWN_BUG ); + } + else + { + return THROWERROR( RET_INVALID_ARGUMENTS ); + } + + + /* I) SETUP CHOLESKY FLAG: + * Cholesky decomposition shall only be updated if working set + * shall be updated (i.e. NOT setup afresh!) */ + BooleanType updateCholesky; + if ( setupAfresh == BT_TRUE ) + updateCholesky = BT_FALSE; + else + updateCholesky = BT_TRUE; + + + /* II) REMOVE FORMERLY ACTIVE BOUNDS (IF NECESSARY): */ + if ( setupAfresh == BT_FALSE ) + { + /* Remove all active bounds that shall be inactive AND + * all active bounds that are active at the wrong bound. */ + for( i=0; igetStatus( i ) != ST_LOWER ) ) + if ( removeBound( i,updateCholesky ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_SETUP_WORKINGSET_FAILED ); + + if ( ( bounds.getStatus( i ) == ST_UPPER ) && ( auxiliaryBounds->getStatus( i ) != ST_UPPER ) ) + if ( removeBound( i,updateCholesky ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_SETUP_WORKINGSET_FAILED ); + } + } + + + /* III) ADD NEWLY ACTIVE BOUNDS: */ + /* Add all inactive bounds that shall be active AND + * all formerly active bounds that have been active at the wrong bound. */ + for( i=0; igetStatus( i ) != ST_INACTIVE ) ) + { + if ( addBound( i,auxiliaryBounds->getStatus( i ),updateCholesky ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_SETUP_WORKINGSET_FAILED ); + } + } + + return SUCCESSFUL_RETURN; +} + + +/* + * s e t u p A u x i l i a r y Q P s o l u t i o n + */ +returnValue QProblemB::setupAuxiliaryQPsolution( const real_t* const xOpt, const real_t* const yOpt + ) +{ + int i; + int nV = getNV( ); + + + /* Setup primal/dual solution vectors for auxiliary initial QP: + * if a null pointer is passed, a zero vector is assigned; + * old solution vector is kept if pointer to internal solution vector is passed. */ + if ( xOpt != 0 ) + { + if ( xOpt != x ) + for( i=0; igetIndex( number ); + + real_t c, s; + + /* 2) Use row-wise Givens rotations to restore upper triangular form of R. */ + for( i=number_idx+1; ith column and ... */ + for( i=0; igetNumberArray( FR_idx ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_REMOVEBOUND_FAILED ); + + /* 1) Calculate new column of cholesky decomposition. */ + real_t rhs[NVMAX]; + real_t r[NVMAX]; + real_t r0 = H[number*NVMAX + number]; + + for( i=0; i 0.0 ) + R[nFR*NVMAX + nFR] = sqrt( r0 ); + else + { + hessianType = HST_SEMIDEF; + return THROWERROR( RET_HESSIAN_NOT_SPD ); + } + + + return SUCCESSFUL_RETURN; +} + + +/* + * b a c k s o l v e R (CODE DUPLICATED IN QProblem CLASS!!!) + */ +returnValue QProblemB::backsolveR( const real_t* const b, BooleanType transposed, + real_t* const a + ) +{ + /* Call standard backsolve procedure (i.e. removingBound == BT_FALSE). */ + return backsolveR( b,transposed,BT_FALSE,a ); +} + + +/* + * b a c k s o l v e R (CODE DUPLICATED IN QProblem CLASS!!!) + */ +returnValue QProblemB::backsolveR( const real_t* const b, BooleanType transposed, + BooleanType removingBound, + real_t* const a + ) +{ + int i, j; + int nR = getNZ( ); + + real_t sum; + + /* if backsolve is called while removing a bound, reduce nZ by one. */ + if ( removingBound == BT_TRUE ) + --nR; + + /* nothing to do */ + if ( nR <= 0 ) + return SUCCESSFUL_RETURN; + + + /* Solve Ra = b, where R might be transposed. */ + if ( transposed == BT_FALSE ) + { + /* solve Ra = b */ + for( i=(nR-1); i>=0; --i ) + { + sum = b[i]; + for( j=(i+1); j ZERO ) + a[i] = sum / R[i*NVMAX + i]; + else + return THROWERROR( RET_DIV_BY_ZERO ); + } + } + else + { + /* solve R^T*a = b */ + for( i=0; i ZERO ) + a[i] = sum / R[i*NVMAX + i]; + else + return THROWERROR( RET_DIV_BY_ZERO ); + } + } + + return SUCCESSFUL_RETURN; +} + + +/* + * h o t s t a r t _ d e t e r m i n e D a t a S h i f t + */ +returnValue QProblemB::hotstart_determineDataShift( const int* const FX_idx, + const real_t* const g_new, const real_t* const lb_new, const real_t* const ub_new, + real_t* const delta_g, real_t* const delta_lb, real_t* const delta_ub, + BooleanType& Delta_bB_isZero + ) +{ + int i, ii; + int nV = getNV( ); + int nFX = getNFX( ); + + + /* 1) Calculate shift directions. */ + for( i=0; i EPS ) || ( getAbs( delta_ub[ii] ) > EPS ) ) + { + Delta_bB_isZero = BT_FALSE; + break; + } + } + + return SUCCESSFUL_RETURN; +} + + +/* + * a r e B o u n d s C o n s i s t e n t + */ +BooleanType QProblemB::areBoundsConsistent( const real_t* const delta_lb, const real_t* const delta_ub + ) const +{ + int i; + + /* Check if delta_lb[i] is greater than delta_ub[i] + * for a component i whose bounds are already (numerically) equal. */ + for( i=0; i ub[i] - BOUNDTOL ) && ( delta_lb[i] > delta_ub[i] + EPS ) ) + return BT_FALSE; + + return BT_TRUE; +} + + +/* + * s e t u p Q P d a t a + */ +returnValue QProblemB::setupQPdata( const real_t* const _H, const real_t* const _R, const real_t* const _g, + const real_t* const _lb, const real_t* const _ub + ) +{ + int i, j; + int nV = getNV( ); + + /* 1) Setup Hessian matrix and it's Cholesky factorization. */ + if (_H != 0) + { + for( i=0; i 0 ) + { + for( i=0; i 0 ) + { + /* auxiliary variables */ + real_t delta_xFRz_TMP[NVMAX]; + real_t delta_xFRz_RHS[NVMAX]; + + /* Determine delta_xFRz. */ + if ( Delta_bB_isZero == BT_FALSE ) + { + for( i=0; i 0 ) + { + for( i=0; i= 0.0 ) ) + { + tau_tmp = y[ii] / ( -delta_yFX[i] ); + if ( tau_tmp < tau_new ) + { + if ( tau_tmp >= 0.0 ) + { + tau_new = tau_tmp; + BC_idx = ii; + BC_status = ST_INACTIVE; + } + } + } + } + else + { + /* 2) Active upper bounds. */ + if ( ( delta_yFX[i] > ZERO ) && ( y[ii] <= 0.0 ) ) + { + tau_tmp = y[ii] / ( -delta_yFX[i] ); + if ( tau_tmp < tau_new ) + { + if ( tau_tmp >= 0.0 ) + { + tau_new = tau_tmp; + BC_idx = ii; + BC_status = ST_INACTIVE; + } + } + } + } + } + } + + + /* II) DETERMINE MAXIMUM PRIMAL STEPLENGTH, i.e. ensure that + * inactive bounds remain valid (ignoring unbounded variables). */ + /* 1) Inactive lower bounds. */ + if ( bounds.isNoLower( ) == BT_FALSE ) + { + for( i=0; i delta_xFR[i] ) + { + if ( x[ii] > lb[ii] ) + tau_tmp = ( x[ii] - lb[ii] ) / ( delta_lb[ii] - delta_xFR[i] ); + else + tau_tmp = 0.0; + + if ( tau_tmp < tau_new ) + { + if ( tau_tmp >= 0.0 ) + { + tau_new = tau_tmp; + BC_idx = ii; + BC_status = ST_LOWER; + } + } + } + } + } + } + + /* 2) Inactive upper bounds. */ + if ( bounds.isNoUpper( ) == BT_FALSE ) + { + for( i=0; i= 0.0 ) + { + tau_new = tau_tmp; + BC_idx = ii; + BC_status = ST_UPPER; + } + } + } + } + } + } + + + /* III) SET MAXIMUM HOMOTOPY STEPLENGTH */ + tau = tau_new; + + if ( printlevel == PL_HIGH ) + { + #ifdef PC_DEBUG + char messageString[80]; + + if ( BC_status == ST_UNDEFINED ) + sprintf( messageString,"Stepsize is %.6e!",tau ); + else + sprintf( messageString,"Stepsize is %.6e! (BC_idx = %d, BC_status = %d)",tau,BC_idx,BC_status ); + + getGlobalMessageHandler( )->throwInfo( RET_STEPSIZE_NONPOSITIVE,messageString,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE ); + #endif + } + + return SUCCESSFUL_RETURN; +} + + +/* + * h o t s t a r t _ p e r f o r m S t e p + */ +returnValue QProblemB::hotstart_performStep( const int* const FR_idx, const int* const FX_idx, + const real_t* const delta_g, const real_t* const delta_lb, const real_t* const delta_ub, + const real_t* const delta_xFX, const real_t* const delta_xFR, + const real_t* const delta_yFX, + int BC_idx, SubjectToStatus BC_status + ) +{ + int i, ii; + int nV = getNV( ); + int nFR = getNFR( ); + int nFX = getNFX( ); + + + /* I) CHECK BOUNDS' CONSISTENCY */ + if ( areBoundsConsistent( delta_lb,delta_ub ) == BT_FALSE ) + { + infeasible = BT_TRUE; + tau = 0.0; + + return THROWERROR( RET_QP_INFEASIBLE ); + } + + + /* II) GO TO ACTIVE SET CHANGE */ + if ( tau > ZERO ) + { + /* 1) Perform step in primal und dual space. */ + for( i=0; ithrowWarning( RET_STEPSIZE,messageString,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE ); + #endif + } + + + /* setup output preferences */ + #ifdef PC_DEBUG + char messageString[80]; + VisibilityStatus visibilityStatus; + + if ( printlevel == PL_HIGH ) + visibilityStatus = VS_VISIBLE; + else + visibilityStatus = VS_HIDDEN; + #endif + + + /* III) UPDATE ACTIVE SET */ + switch ( BC_status ) + { + /* Optimal solution found as no working set change detected. */ + case ST_UNDEFINED: + return RET_OPTIMAL_SOLUTION_FOUND; + + + /* Remove one variable from active set. */ + case ST_INACTIVE: + #ifdef PC_DEBUG + sprintf( messageString,"bound no. %d.", BC_idx ); + getGlobalMessageHandler( )->throwInfo( RET_REMOVE_FROM_ACTIVESET,messageString,__FUNCTION__,__FILE__,__LINE__,visibilityStatus ); + #endif + + if ( removeBound( BC_idx,BT_TRUE ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_REMOVE_FROM_ACTIVESET_FAILED ); + + y[BC_idx] = 0.0; + break; + + + /* Add one variable to active set. */ + default: + #ifdef PC_DEBUG + if ( BC_status == ST_LOWER ) + sprintf( messageString,"lower bound no. %d.", BC_idx ); + else + sprintf( messageString,"upper bound no. %d.", BC_idx ); + getGlobalMessageHandler( )->throwInfo( RET_ADD_TO_ACTIVESET,messageString,__FUNCTION__,__FILE__,__LINE__,visibilityStatus ); + #endif + + if ( addBound( BC_idx,BC_status,BT_TRUE ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_ADD_TO_ACTIVESET_FAILED ); + break; + } + + return SUCCESSFUL_RETURN; +} + + +#ifdef PC_DEBUG /* Define print functions only for debugging! */ + +/* + * p r i n t I t e r a t i o n + */ +returnValue QProblemB::printIteration( int iteration, + int BC_idx, SubjectToStatus BC_status + ) +{ + char myPrintfString[160]; + + /* consistency check */ + if ( iteration < 0 ) + return THROWERROR( RET_INVALID_ARGUMENTS ); + + /* nothing to do */ + if ( printlevel != PL_MEDIUM ) + return SUCCESSFUL_RETURN; + + + /* 1) Print header at first iteration. */ + if ( iteration == 0 ) + { + sprintf( myPrintfString,"\n############## qpOASES -- QP NO.%4.1d ###############\n", count ); + myPrintf( myPrintfString ); + + sprintf( myPrintfString," Iter | StepLength | Info | nFX \n" ); + myPrintf( myPrintfString ); + } + + /* 2) Print iteration line. */ + if ( BC_status == ST_UNDEFINED ) + { + sprintf( myPrintfString," %4.1d | %1.5e | QP SOLVED | %4.1d \n", iteration,tau,getNFX( ) ); + myPrintf( myPrintfString ); + } + else + { + char info[8]; + + if ( BC_status == ST_INACTIVE ) + sprintf( info,"REM BND" ); + else + sprintf( info,"ADD BND" ); + + sprintf( myPrintfString," %4.1d | %1.5e | %s%4.1d | %4.1d \n", iteration,tau,info,BC_idx,getNFX( ) ); + myPrintf( myPrintfString ); + } + + return SUCCESSFUL_RETURN; +} + +#endif /* PC_DEBUG */ + + + +/* + * c h e c k K K T c o n d i t i o n s + */ +returnValue QProblemB::checkKKTconditions( ) +{ + #ifdef __PERFORM_KKT_TEST__ + + int i, j; + int nV = getNV( ); + + real_t tmp; + real_t maxKKTviolation = 0.0; + + + /* 1) Check for Hx + g - y*A' = 0 (here: A = Id). */ + for( i=0; i maxKKTviolation ) + maxKKTviolation = getAbs( tmp ); + } + + /* 2) Check for lb <= x <= ub. */ + for( i=0; i maxKKTviolation ) + maxKKTviolation = lb[i] - x[i]; + + if ( x[i] - ub[i] > maxKKTviolation ) + maxKKTviolation = x[i] - ub[i]; + } + + /* 3) Check for correct sign of y and for complementary slackness. */ + for( i=0; i maxKKTviolation ) + maxKKTviolation = -y[i]; + if ( getAbs( ( x[i] - lb[i] ) * y[i] ) > maxKKTviolation ) + maxKKTviolation = getAbs( ( x[i] - lb[i] ) * y[i] ); + break; + + case ST_UPPER: + if ( y[i] > maxKKTviolation ) + maxKKTviolation = y[i]; + if ( getAbs( ( ub[i] - x[i] ) * y[i] ) > maxKKTviolation ) + maxKKTviolation = getAbs( ( ub[i] - x[i] ) * y[i] ); + break; + + default: /* inactive */ + if ( getAbs( y[i] ) > maxKKTviolation ) + maxKKTviolation = getAbs( y[i] ); + break; + } + } + + if ( maxKKTviolation > CRITICALACCURACY ) + return RET_NO_SOLUTION; + + if ( maxKKTviolation > DESIREDACCURACY ) + return RET_INACCURATE_SOLUTION; + + #endif /* __PERFORM_KKT_TEST__ */ + + return SUCCESSFUL_RETURN; +} + + + +/* + * end of file + */ diff --git a/phonelibs/qpoases/SRC/QProblemB.ipp b/phonelibs/qpoases/SRC/QProblemB.ipp new file mode 100644 index 00000000000000..0c1c8b231147b5 --- /dev/null +++ b/phonelibs/qpoases/SRC/QProblemB.ipp @@ -0,0 +1,425 @@ +/* + * This file is part of qpOASES. + * + * qpOASES -- An Implementation of the Online Active Set Strategy. + * Copyright (C) 2007-2008 by Hans Joachim Ferreau 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 SRC/QProblemB.ipp + * \author Hans Joachim Ferreau + * \version 1.3embedded + * \date 2007-2008 + * + * Implementation of inlined member functions of the QProblemB class which + * is able to use the newly developed online active set strategy for + * parametric quadratic programming. + */ + + + +#include + + + +/***************************************************************************** + * P U B L I C * + *****************************************************************************/ + +/* + * g e t H + */ +inline returnValue QProblemB::getH( real_t* const _H ) const +{ + int i; + + for ( i=0; i= 0 ) && ( number < getNV( ) ) ) + { + value = lb[number]; + return SUCCESSFUL_RETURN; + } + else + { + return THROWERROR( RET_INDEX_OUT_OF_BOUNDS ); + } +} + + +/* + * g e t U B + */ +inline returnValue QProblemB::getUB( real_t* const _ub ) const +{ + int i; + + for ( i=0; i= 0 ) && ( number < getNV( ) ) ) + { + value = ub[number]; + return SUCCESSFUL_RETURN; + } + else + { + return THROWERROR( RET_INDEX_OUT_OF_BOUNDS ); + } +} + + +/* + * g e t B o u n d s + */ +inline returnValue QProblemB::getBounds( Bounds* const _bounds ) const +{ + *_bounds = bounds; + + return SUCCESSFUL_RETURN; +} + + +/* + * g e t N V + */ +inline int QProblemB::getNV( ) const +{ + return bounds.getNV( ); +} + + +/* + * g e t N F R + */ +inline int QProblemB::getNFR( ) +{ + return bounds.getNFR( ); +} + + +/* + * g e t N F X + */ +inline int QProblemB::getNFX( ) +{ + return bounds.getNFX( ); +} + + +/* + * g e t N F V + */ +inline int QProblemB::getNFV( ) const +{ + return bounds.getNFV( ); +} + + +/* + * g e t S t a t u s + */ +inline QProblemStatus QProblemB::getStatus( ) const +{ + return status; +} + + +/* + * i s I n i t i a l i s e d + */ +inline BooleanType QProblemB::isInitialised( ) const +{ + if ( status == QPS_NOTINITIALISED ) + return BT_FALSE; + else + return BT_TRUE; +} + + +/* + * i s S o l v e d + */ +inline BooleanType QProblemB::isSolved( ) const +{ + if ( status == QPS_SOLVED ) + return BT_TRUE; + else + return BT_FALSE; +} + + +/* + * i s I n f e a s i b l e + */ +inline BooleanType QProblemB::isInfeasible( ) const +{ + return infeasible; +} + + +/* + * i s U n b o u n d e d + */ +inline BooleanType QProblemB::isUnbounded( ) const +{ + return unbounded; +} + + +/* + * g e t P r i n t L e v e l + */ +inline PrintLevel QProblemB::getPrintLevel( ) const +{ + return printlevel; +} + + +/* + * g e t H e s s i a n T y p e + */ +inline HessianType QProblemB::getHessianType( ) const +{ + return hessianType; +} + + +/* + * s e t H e s s i a n T y p e + */ +inline returnValue QProblemB::setHessianType( HessianType _hessianType ) +{ + hessianType = _hessianType; + return SUCCESSFUL_RETURN; +} + + + +/***************************************************************************** + * P R O T E C T E D * + *****************************************************************************/ + +/* + * s e t H + */ +inline returnValue QProblemB::setH( const real_t* const H_new ) +{ + int i, j; + + int nV = getNV(); + + for( i=0; i= 0 ) && ( number < getNV( ) ) ) + { + lb[number] = value; + return SUCCESSFUL_RETURN; + } + else + { + return THROWERROR( RET_INDEX_OUT_OF_BOUNDS ); + } +} + + +/* + * s e t U B + */ +inline returnValue QProblemB::setUB( const real_t* const ub_new ) +{ + int i; + + int nV = getNV(); + + for( i=0; i= 0 ) && ( number < getNV( ) ) ) + { + 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 + */ +inline void QProblemB::computeGivens( real_t xold, real_t yold, real_t& xnew, real_t& ynew, + real_t& c, real_t& s + ) const +{ + if ( getAbs( yold ) <= ZERO ) + { + c = 1.0; + s = 0.0; + + xnew = xold; + ynew = yold; + } + else + { + real_t t, mu; + + mu = getAbs( xold ); + if ( getAbs( yold ) > mu ) + mu = getAbs( 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 + */ +inline void QProblemB::applyGivens( real_t c, real_t s, real_t xold, real_t yold, + real_t& xnew, real_t& ynew + ) const +{ + /* Usual Givens plane rotation requiring four multiplications. */ + xnew = c*xold + s*yold; + ynew = -s*xold + c*yold; +// double nu = s/(1.0+c); +// +// xnew = xold*c + yold*s; +// ynew = (xnew+xold)*nu - yold; + + return; +} + + +/* + * end of file + */ diff --git a/phonelibs/qpoases/SRC/SubjectTo.cpp b/phonelibs/qpoases/SRC/SubjectTo.cpp new file mode 100644 index 00000000000000..5dbf707c9d1f21 --- /dev/null +++ b/phonelibs/qpoases/SRC/SubjectTo.cpp @@ -0,0 +1,200 @@ +/* + * This file is part of qpOASES. + * + * qpOASES -- An Implementation of the Online Active Set Strategy. + * Copyright (C) 2007-2008 by Hans Joachim Ferreau 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 SRC/SubjectTo.cpp + * \author Hans Joachim Ferreau + * \version 1.3embedded + * \date 2007-2008 + * + * Implementation of the SubjectTo class designed to manage working sets of + * constraints and bounds within a QProblem. + */ + + +#include + + +/***************************************************************************** + * P U B L I C * + *****************************************************************************/ + + +/* + * S u b j e c t T o + */ +SubjectTo::SubjectTo( ) : noLower( BT_TRUE ), + noUpper( BT_TRUE ), + size( 0 ) +{ + int i; + + for( i=0; iaddNumber( newnumber ) == RET_INDEXLIST_EXCEEDS_MAX_LENGTH ) + return THROWERROR( RET_ADDINDEX_FAILED ); + + return SUCCESSFUL_RETURN; +} + + +/* + * r e m o v e I n d e x + */ +returnValue SubjectTo::removeIndex( Indexlist* const indexlist, + int removenumber + ) +{ + status[removenumber] = ST_UNDEFINED; + + if ( indexlist->removeNumber( removenumber ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_UNKNOWN_BUG ); + + return SUCCESSFUL_RETURN; +} + + +/* + * s w a p I n d e x + */ +returnValue SubjectTo::swapIndex( Indexlist* const indexlist, + int number1, int number2 + ) +{ + /* consistency checks */ + if ( status[number1] != status[number2] ) + return THROWERROR( RET_SWAPINDEX_FAILED ); + + if ( number1 == number2 ) + { + THROWWARNING( RET_NOTHING_TO_DO ); + return SUCCESSFUL_RETURN; + } + + if ( indexlist->swapNumbers( number1,number2 ) != SUCCESSFUL_RETURN ) + return THROWERROR( RET_SWAPINDEX_FAILED ); + + return SUCCESSFUL_RETURN; +} + + +/* + * end of file + */ diff --git a/phonelibs/qpoases/SRC/SubjectTo.ipp b/phonelibs/qpoases/SRC/SubjectTo.ipp new file mode 100644 index 00000000000000..7cd6dc69fe9bd7 --- /dev/null +++ b/phonelibs/qpoases/SRC/SubjectTo.ipp @@ -0,0 +1,132 @@ +/* + * This file is part of qpOASES. + * + * qpOASES -- An Implementation of the Online Active Set Strategy. + * Copyright (C) 2007-2008 by Hans Joachim Ferreau 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 SRC/SubjectTo.ipp + * \author Hans Joachim Ferreau + * \version 1.3embedded + * \date 2007-2008 + * + * Implementation of the inlined member functions of the SubjectTo class + * designed to manage working sets of constraints and bounds within a QProblem. + */ + + +/***************************************************************************** + * P U B L I C * + *****************************************************************************/ + + +/* + * g e t T y p e + */ +inline SubjectToType SubjectTo::getType( int i ) const +{ + if ( ( i >= 0 ) && ( i < size ) ) + return type[i]; + else + return ST_UNKNOWN; +} + + +/* + * g e t S t a t u s + */ +inline SubjectToStatus SubjectTo::getStatus( int i ) const +{ + if ( ( i >= 0 ) && ( i < size ) ) + return status[i]; + else + return ST_UNDEFINED; +} + + +/* + * s e t T y p e + */ +inline returnValue SubjectTo::setType( int i, SubjectToType value ) +{ + if ( ( i >= 0 ) && ( i < size ) ) + { + type[i] = value; + return SUCCESSFUL_RETURN; + } + else + return THROWERROR( RET_INDEX_OUT_OF_BOUNDS ); +} + + +/* + * s e t S t a t u s + */ +inline returnValue SubjectTo::setStatus( int i, SubjectToStatus value ) +{ + if ( ( i >= 0 ) && ( i < size ) ) + { + status[i] = value; + return SUCCESSFUL_RETURN; + } + else + return THROWERROR( RET_INDEX_OUT_OF_BOUNDS ); +} + + +/* + * s e t N o L o w e r + */ +inline void SubjectTo::setNoLower( BooleanType _status ) +{ + noLower = _status; +} + + +/* + * s e t N o U p p e r + */ +inline void SubjectTo::setNoUpper( BooleanType _status ) +{ + noUpper = _status; +} + + +/* + * i s N o L o w e r + */ +inline BooleanType SubjectTo::isNoLower( ) const +{ + return noLower; +} + + +/* + * i s N o L o w e r + */ +inline BooleanType SubjectTo::isNoUpper( ) const +{ + return noUpper; +} + + +/* + * end of file + */ diff --git a/phonelibs/qpoases/SRC/Utils.cpp b/phonelibs/qpoases/SRC/Utils.cpp new file mode 100644 index 00000000000000..7a3d0a5226203b --- /dev/null +++ b/phonelibs/qpoases/SRC/Utils.cpp @@ -0,0 +1,471 @@ +/* + * This file is part of qpOASES. + * + * qpOASES -- An Implementation of the Online Active Set Strategy. + * Copyright (C) 2007-2008 by Hans Joachim Ferreau 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 SRC/Utils.cpp + * \author Hans Joachim Ferreau, Eckhard Arnold + * \version 1.3embedded + * \date 2007-2008 + * + * Implementation of some inlined utilities for working with the different QProblem + * classes. + */ + + +#include + +#if defined(__WIN32__) || defined(WIN32) + #include +#elif defined(LINUX) + #include + #include +#endif + +#ifdef __MATLAB__ + #include +#endif + + +#include + + + +#ifdef PC_DEBUG /* Define print functions only for debugging! */ +/* + * p r i n t + */ +returnValue print( const real_t* const v, int n ) +{ + int i; + char myPrintfString[160]; + + /* Print a vector. */ + myPrintf( "[\t" ); + for( i=0; ithrowError( RET_UNABLE_TO_OPEN_FILE,errstr,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE ); + } + + /* 2) Read data from file. */ + for( i=0; ithrowError( RET_UNABLE_TO_READ_FILE,errstr,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE ); + } + data[i*ncol + j] = ( (real_t) float_data ); + } + } + + /* 3) Close file. */ + fclose( datafile ); + + return SUCCESSFUL_RETURN; +} + + +/* + * r e a d F r o m F i l e + */ +returnValue readFromFile( real_t* data, int n, + const char* datafilename + ) +{ + return readFromFile( data, n, 1, datafilename ); +} + + + +/* + * r e a d F r o m F i l e + */ +returnValue readFromFile( int* data, int n, + const char* datafilename + ) +{ + int i; + myFILE* datafile; + + /* 1) Open file. */ + if ( ( datafile = fopen( datafilename, "r" ) ) == 0 ) + { + char errstr[80]; + sprintf( errstr,"(%s)",datafilename ); + return getGlobalMessageHandler( )->throwError( RET_UNABLE_TO_OPEN_FILE,errstr,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE ); + } + + /* 2) Read data from file. */ + for( i=0; ithrowError( RET_UNABLE_TO_READ_FILE,errstr,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE ); + } + } + + /* 3) Close file. */ + fclose( datafile ); + + return SUCCESSFUL_RETURN; +} + + +/* + * w r i t e I n t o F i l e + */ +returnValue writeIntoFile( const real_t* const data, int nrow, int ncol, + const char* datafilename, BooleanType append + ) +{ + int i, j; + myFILE* datafile; + + /* 1) Open file. */ + if ( append == BT_TRUE ) + { + /* append data */ + if ( ( datafile = fopen( datafilename, "a" ) ) == 0 ) + { + char errstr[80]; + sprintf( errstr,"(%s)",datafilename ); + return getGlobalMessageHandler( )->throwError( RET_UNABLE_TO_OPEN_FILE,errstr,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE ); + } + } + else + { + /* do not append data */ + if ( ( datafile = fopen( datafilename, "w" ) ) == 0 ) + { + char errstr[80]; + sprintf( errstr,"(%s)",datafilename ); + return getGlobalMessageHandler( )->throwError( RET_UNABLE_TO_OPEN_FILE,errstr,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE ); + } + } + + /* 2) Write data into file. */ + for( i=0; ithrowError( RET_UNABLE_TO_OPEN_FILE,errstr,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE ); + } + } + else + { + /* do not append data */ + if ( ( datafile = fopen( datafilename, "w" ) ) == 0 ) + { + char errstr[80]; + sprintf( errstr,"(%s)",datafilename ); + return getGlobalMessageHandler( )->throwError( RET_UNABLE_TO_OPEN_FILE,errstr,__FUNCTION__,__FILE__,__LINE__,VS_VISIBLE ); + } + } + + /* 2) Write data into file. */ + for( i=0; i + +#include "DiagLog/Options.hpp" +#include "DlSystem/String.hpp" + +namespace zdl +{ +namespace DiagLog +{ + +/** @addtogroup c_plus_plus_apis C++ +@{ */ + +/// @brief . +/// +/// Interface for controlling logging for zdl components. + +class ZDL_LOGGING_EXPORT IDiagLog +{ +public: + + /// @brief . + /// + /// Sets the options after initialization occurs. + /// + /// @param[in] loggingOptions The options to set up diagnostic logging. + /// + /// @return False if the options could not be set. Ensure logging is not started. + virtual bool setOptions(const Options& loggingOptions) = 0; + + /// @brief . + /// + /// Gets the curent options for the diag logger. + /// + /// @return Diag log options object. + virtual Options getOptions() = 0; + + /// @brief . + /// + /// Allows for setting the log mask once diag logging has started + /// + /// @return True if the level was set successfully, false if a failure occurred. + virtual bool setDiagLogMask(const std::string& mask) = 0; + + /// @brief . + /// + /// Allows for setting the log mask once diag logging has started + /// + /// @return True if the level was set successfully, false if a failure occurred. + virtual bool setDiagLogMask(const zdl::DlSystem::String& mask) = 0; + + /// @brief . + /// + /// Enables logging for zdl components. + /// + /// Logging should be started prior to the instantiation of zdl components + /// to ensure all events are captured. + /// + /// @return False if diagnostic logging could not be started. + virtual bool start(void) = 0; + + /// @brief Disables logging for zdl components. + virtual bool stop(void) = 0; + + virtual ~IDiagLog() {}; +}; + +} // DiagLog namespace +} // zdl namespace + +/** @} */ /* end_addtogroup c_plus_plus_apis C++ */ + +#endif diff --git a/phonelibs/snpe/include/DiagLog/Options.hpp b/phonelibs/snpe/include/DiagLog/Options.hpp new file mode 100644 index 00000000000000..ba0c82119bfebb --- /dev/null +++ b/phonelibs/snpe/include/DiagLog/Options.hpp @@ -0,0 +1,75 @@ +//============================================================================= +// +// Copyright (c) 2015 Qualcomm Technologies, Inc. +// All Rights Reserved. +// Confidential and Proprietary - Qualcomm Technologies, Inc. +// +//============================================================================= +#ifndef __DIAGLOG_OPTIONS_HPP_ +#define __DIAGLOG_OPTIONS_HPP_ + +#ifndef ZDL_LOGGING_EXPORT +#define ZDL_LOGGING_EXPORT __attribute__((visibility("default"))) +#endif + +#include +#include + +namespace zdl +{ +namespace DiagLog +{ +/** @addtogroup c_plus_plus_apis C++ +@{ */ + +/// @brief . +/// +/// Options for setting up diagnostic logging for zdl components. +class ZDL_LOGGING_EXPORT Options +{ +public: + Options() : + DiagLogMask(""), + LogFileDirectory("diaglogs"), + LogFileName("DiagLog"), + LogFileRotateCount(20) + { + // Solves the empty string problem with multiple std libs + DiagLogMask.reserve(1); + } + + /// @brief . + /// + /// Enables diag logging only on the specified area mask (DNN_RUNTIME=ON | OFF) + std::string DiagLogMask; + + /// @brief . + /// + /// The path to the directory where log files will be written. + /// The path may be relative or absolute. Relative paths are interpreted + /// from the current working directory. + /// Default value is "diaglogs" + std::string LogFileDirectory; + + /// @brief . + /// + //// The name used for log files. If this value is empty then BaseName will be + /// used as the default file name. + /// Default value is "DiagLog" + std::string LogFileName; + + /// @brief . + /// + /// The maximum number of log files to create. If set to 0 no log rotation + /// will be used and the log file name specified will be used each time, overwriting + /// any existing log file that may exist. + /// Default value is 20 + uint32_t LogFileRotateCount; +}; +/** @} */ /* end_addtogroup c_plus_plus_apis C++ */ + +} // DiagLog namespace +} // zdl namespace + + +#endif diff --git a/phonelibs/snpe/include/DlContainer/IDlContainer.hpp b/phonelibs/snpe/include/DlContainer/IDlContainer.hpp new file mode 100644 index 00000000000000..c4b465fd04bbe6 --- /dev/null +++ b/phonelibs/snpe/include/DlContainer/IDlContainer.hpp @@ -0,0 +1,156 @@ +//============================================================================= +// +// Copyright (c) 2015 Qualcomm Technologies, Inc. +// All Rights Reserved. +// Confidential and Proprietary - Qualcomm Technologies, Inc. +// +//============================================================================= + +#ifndef ZEROTH_IDNC_CONTAINER_HPP +#define ZEROTH_IDNC_CONTAINER_HPP + +#include +#include +#include +#include +#include +#include + +#include "DlSystem/ZdlExportDefine.hpp" +#include "DlSystem/String.hpp" + +namespace zdl { +namespace DlContainer { + +/** @addtogroup c_plus_plus_apis C++ +@{ */ + +class IDlContainer; +class dlc_error; + +/** + * The structure of a record in a DL container. + */ +struct ZDL_EXPORT DlcRecord +{ + /// Name of the record. + std::string name; + /// Byte blob holding the data for the record. + std::vector data; + + DlcRecord(); + DlcRecord( DlcRecord&& other ) + : name(std::move(other.name)) + , data(std::move(other.data)) + {} + + DlcRecord(const DlcRecord&) = delete; +}; + +// The maximum length of any record name. +extern const uint32_t RECORD_NAME_MAX_SIZE; +// The maximum size of the record payload (bytes). +extern const uint32_t RECORD_DATA_MAX_SIZE; +// The maximum number of records in an archive at one time. +extern const uint32_t ARCHIVE_MAX_RECORDS; + +/** + * Represents a container for a neural network model which can + * be used to load the model into the SNPE runtime. + */ +class ZDL_EXPORT IDlContainer +{ +public: + /** + * Initializes a container from a container archive file. + * + * @param[in] filename Container archive file path. + * + * @return A pointer to the initialized container + */ + ZDL_EXPORT static std::unique_ptr + open(const std::string &filename) noexcept; + + /** + * Initializes a container from a container archive file. + * + * @param[in] filename Container archive file path. + * + * @return A pointer to the initialized container + */ + ZDL_EXPORT static std::unique_ptr + open(const zdl::DlSystem::String &filename) noexcept; + + /** + * Initializes a container from a byte buffer. + * + * @param[in] buffer Byte buffer holding the contents of an archive + * file. + * + * @return A pointer to the initialized container + */ + ZDL_EXPORT static std::unique_ptr + open(const std::vector &buffer) noexcept; + + /** + * Initializes a container from a byte buffer. + * + * @param[in] buffer Byte buffer holding the contents of an archive + * file. + * + * @param[in] size Size of the byte buffer. + * + * @return A pointer to the initialized container + */ + ZDL_EXPORT static std::unique_ptr + open(const uint8_t* buffer, const size_t size) noexcept; + + +/** @} */ /* end_addtogroup c_plus_plus_apis C++ */ + + /** + * Get the record catalog for a container. + * + * @param[out] catalog Buffer that will hold the record names on + * return. + */ + virtual void getCatalog(std::set &catalog) const = 0; + + /** + * Get the record catalog for a container. + * + * @param[out] catalog Buffer that will hold the record names on + * return. + */ + virtual void getCatalog(std::set &catalog) const = 0; + + /** + * Get a record from a container by name. + * + * @param[in] name Name of the record to fetch. + * @param[out] record The passed in record will be populated with the + * record data on return. Note that the caller + * will own the data in the record and is + * responsible for freeing it if needed. + */ + virtual void getRecord(const std::string &name, DlcRecord &record) const = 0; + + /** + * Get a record from a container by name. + * + * @param[in] name Name of the record to fetch. + * @param[out] record The passed in record will be populated with the + * record data on return. Note that the caller + * will own the data in the record and is + * responsible for freeing it if needed. + */ + virtual void getRecord(const zdl::DlSystem::String &name, DlcRecord &record) const = 0; + + virtual ~IDlContainer() {} +}; + +} // ns DlContainer +} // ns zdl + + +#endif diff --git a/phonelibs/snpe/include/DlSystem/DlEnums.hpp b/phonelibs/snpe/include/DlSystem/DlEnums.hpp new file mode 100644 index 00000000000000..fde252ca7f6742 --- /dev/null +++ b/phonelibs/snpe/include/DlSystem/DlEnums.hpp @@ -0,0 +1,146 @@ +//============================================================================== +// +// Copyright (c) 2014-2018 Qualcomm Technologies, Inc. +// All Rights Reserved. +// Confidential and Proprietary - Qualcomm Technologies, Inc. +// +//============================================================================== + +#ifndef _DL_ENUMS_HPP_ +#define _DL_ENUMS_HPP_ + +#include "DlSystem/ZdlExportDefine.hpp" + + +namespace zdl { +namespace DlSystem +{ +/** @addtogroup c_plus_plus_apis C++ +@{ */ + +/** + * Enumeration of supported target runtimes. + */ +enum class Runtime_t +{ + /// Run the processing on Snapdragon CPU. + /// Data: float 32bit + /// Math: float 32bit + CPU_FLOAT32 = 0, + + /// Run the processing on the Adreno GPU. + /// Data: float 16bit + /// Math: float 32bit + GPU_FLOAT32_16_HYBRID = 1, + + /// Run the processing on the Hexagon DSP. + /// Data: 8bit fixed point Tensorflow style format + /// Math: 8bit fixed point Tensorflow style format + DSP_FIXED8_TF = 2, + + /// Run the processing on the Adreno GPU. + /// Data: float 16bit + /// Math: float 16bit + GPU_FLOAT16 = 3, + + /// Default legacy enum to retain backward compatibility. + /// CPU = CPU_FLOAT32 + CPU = CPU_FLOAT32, + + /// Default legacy enum to retain backward compatibility. + /// GPU = GPU_FLOAT32_16_HYBRID + GPU = GPU_FLOAT32_16_HYBRID, + + /// Default legacy enum to retain backward compatibility. + /// DSP = DSP_FIXED8_TF + DSP = DSP_FIXED8_TF +}; + +/** + * Enumeration of various performance profiles that can be requested. + */ +enum class PerformanceProfile_t +{ + /// Run in a standard mode. + /// This mode will be deprecated in the future and replaced with BALANCED. + DEFAULT = 0, + /// Run in a balanced mode. + BALANCED = 0, + + /// Run in high performance mode + HIGH_PERFORMANCE, + + /// Run in a power sensitive mode, at the expense of performance. + POWER_SAVER, + + /// Use system settings. SNPE makes no calls to any performance related APIs. + SYSTEM_SETTINGS, + + /// Run in sustained high performance mode + SUSTAINED_HIGH_PERFORMANCE + +}; + +/** + * Enumeration of various execution priority hints. + */ +enum class ExecutionPriorityHint_t +{ + /// Normal priority + NORMAL = 0, + + /// Higher than normal priority + HIGH, + + /// Lower priority + LOW + +}; + +/** @} */ /* end_addtogroup c_plus_plus_apis C++*/ + +/** + * Enumeration that lists the supported image encoding formats. + */ +enum class ImageEncoding_t +{ + /// For unknown image type. Also used as a default value for ImageEncoding_t. + UNKNOWN = 0, + + /// The RGB format consists of 3 bytes per pixel: one byte for + /// Red, one for Green, and one for Blue. The byte ordering is + /// endian independent and is always in RGB byte order. + RGB, + + /// The ARGB32 format consists of 4 bytes per pixel: one byte for + /// Red, one for Green, one for Blue, and one for the alpha channel. + /// The alpha channel is ignored. The byte ordering depends on the + /// underlying CPU. For little endian CPUs, the byte order is BGRA. + /// For big endian CPUs, the byte order is ARGB. + ARGB32, + + /// The RGBA format consists of 4 bytes per pixel: one byte for + /// Red, one for Green, one for Blue, and one for the alpha channel. + /// The alpha channel is ignored. The byte ordering is endian independent + /// and is always in RGBA byte order. + RGBA, + + /// The GRAYSCALE format is for 8-bit grayscale. + GRAYSCALE, + + /// NV21 is the Android version of YUV. The Chrominance is down + /// sampled and has a subsampling ratio of 4:2:0. Note that this + /// image format has 3 channels, but the U and V channels + /// are subsampled. For every four Y pixels there is one U and one V pixel. @newpage + NV21, + + /// The BGR format consists of 3 bytes per pixel: one byte for + /// Red, one for Green and one for Blue. The byte ordering is + /// endian independent and is always BGR byte order. + BGR +}; + +}} // namespaces end + + +#endif diff --git a/phonelibs/snpe/include/DlSystem/DlError.hpp b/phonelibs/snpe/include/DlSystem/DlError.hpp new file mode 100644 index 00000000000000..383403b5418a26 --- /dev/null +++ b/phonelibs/snpe/include/DlSystem/DlError.hpp @@ -0,0 +1,205 @@ +//============================================================================== +// +// Copyright (c) 2016-18 Qualcomm Technologies, Inc. +// All Rights Reserved. +// Confidential and Proprietary - Qualcomm Technologies, Inc. +// +//============================================================================== + +#ifndef _DL_ERROR_HPP_ +#define _DL_ERROR_HPP_ + +#include +#include // numeric_limits + +#include "DlSystem/ZdlExportDefine.hpp" + +namespace zdl { +namespace DlSystem { + +// clang and arm gcc different in how ZDL_EXPORT is used with enum class +#if !defined (__clang__) +enum class ErrorCode : uint32_t ZDL_EXPORT { +#else +enum class ZDL_EXPORT ErrorCode : uint32_t { +#endif // ARM64V8A + NONE = 0, + + // System config errors + SNPE_CONFIG_MISSING_PARAM = 100, + SNPE_CONFIG_INVALID_PARAM = 101, + SNPE_CONFIG_MISSING_FILE = 102, + SNPE_CONFIG_NNCONFIG_NOT_SET = 103, + SNPE_CONFIG_NNCONFIG_INVALID = 104, + SNPE_CONFIG_WRONG_INPUT_NAME = 105, + SNPE_CONFIG_INCORRECT_INPUT_DIMENSIONS = 106, + SNPE_CONFIG_DIMENSIONS_MODIFICATION_NOT_SUPPORTED = 107, + + SNPE_CONFIG_NNCONFIG_ONLY_TENSOR_SUPPORTED = 120, + SNPE_CONFIG_NNCONFIG_ONLY_USER_BUFFER_SUPPORTED = 121, + + // DlSystem errors + SNPE_DLSYSTEM_MISSING_BUFFER = 200, + SNPE_DLSYSTEM_TENSOR_CAST_FAILED = 201, + SNPE_DLSYSTEM_FIXED_POINT_PARAM_INVALID = 202, + SNPE_DLSYSTEM_SIZE_MISMATCH = 203, + SNPE_DLSYSTEM_NAME_NOT_FOUND = 204, + SNPE_DLSYSTEM_VALUE_MISMATCH = 205, + SNPE_DLSYSTEM_INSERT_FAILED = 206, + SNPE_DLSYSTEM_TENSOR_FILE_READ_FAILED = 207, + SNPE_DLSYSTEM_DIAGLOG_FAILURE = 208, + SNPE_DLSYSTEM_LAYER_NOT_SET = 209, + SNPE_DLSYSTEM_WRONG_NUMBER_INPUT_BUFFERS = 210, + SNPE_DLSYSTEM_RUNTIME_TENSOR_SHAPE_MISMATCH = 211, + SNPE_DLSYSTEM_TENSOR_MISSING = 212, + SNPE_DLSYSTEM_TENSOR_ITERATION_UNSUPPORTED = 213, + SNPE_DLSYSTEM_BUFFER_MANAGER_MISSING = 214, + SNPE_DLSYSTEM_RUNTIME_BUFFER_SOURCE_UNSUPPORTED = 215, + SNPE_DLSYSTEM_BUFFER_CAST_FAILED = 216, + + SNPE_DLSYSTEM_BUFFERENCODING_UNKNOWN = 240, + + // DlContainer errors + SNPE_DLCONTAINER_MODEL_PARSING_FAILED = 300, + SNPE_DLCONTAINER_UNKNOWN_LAYER_CODE = 301, + SNPE_DLCONTAINER_MISSING_LAYER_PARAM = 302, + SNPE_DLCONTAINER_LAYER_PARAM_NOT_SUPPORTED = 303, + SNPE_DLCONTAINER_LAYER_PARAM_INVALID = 304, + SNPE_DLCONTAINER_TENSOR_DATA_MISSING = 305, + SNPE_DLCONTAINER_MODEL_LOAD_FAILED = 306, + SNPE_DLCONTAINER_MISSING_RECORDS = 307, + SNPE_DLCONTAINER_INVALID_RECORD = 308, + SNPE_DLCONTAINER_WRITE_FAILURE = 309, + SNPE_DLCONTAINER_READ_FAILURE = 310, + SNPE_DLCONTAINER_BAD_CONTAINER = 311, + SNPE_DLCONTAINER_BAD_DNN_FORMAT_VERSION = 312, + SNPE_DLCONTAINER_UNKNOWN_AXIS_ANNOTATION = 313, + SNPE_DLCONTAINER_UNKNOWN_SHUFFLE_TYPE = 314, + + // Network errors + SNPE_NETWORK_EMPTY_NETWORK = 400, + SNPE_NETWORK_CREATION_FAILED = 401, + SNPE_NETWORK_PARTITION_FAILED = 402, + SNPE_NETWORK_NO_OUTPUT_DEFINED = 403, + SNPE_NETWORK_MISMATCH_BETWEEN_NAMES_AND_DIMS = 404, + SNPE_NETWORK_MISSING_INPUT_NAMES = 405, + SNPE_NETWORK_MISSING_OUTPUT_NAMES = 406, + + // Host runtime errors + SNPE_HOST_RUNTIME_TARGET_UNAVAILABLE = 500, + + // CPU runtime errors + SNPE_CPU_LAYER_NOT_SUPPORTED = 600, + SNPE_CPU_LAYER_PARAM_NOT_SUPPORTED = 601, + SNPE_CPU_LAYER_PARAM_INVALID = 602, + SNPE_CPU_LAYER_PARAM_COMBINATION_INVALID = 603, + SNPE_CPU_BUFFER_NOT_FOUND = 604, + SNPE_CPU_NETWORK_NOT_SUPPORTED = 605, + + // CPU fixed-point runtime errors + SNPE_CPU_FXP_LAYER_NOT_SUPPORTED = 700, + SNPE_CPU_FXP_LAYER_PARAM_NOT_SUPPORTED = 701, + SNPE_CPU_FXP_LAYER_PARAM_INVALID = 702, + + // GPU runtime errors + SNPE_GPU_LAYER_NOT_SUPPORTED = 800, + SNPE_GPU_LAYER_PARAM_NOT_SUPPORTED = 801, + SNPE_GPU_LAYER_PARAM_INVALID = 802, + SNPE_GPU_LAYER_PARAM_COMBINATION_INVALID = 803, + SNPE_GPU_KERNEL_COMPILATION_FAILED = 804, + SNPE_GPU_CONTEXT_NOT_SET = 805, + SNPE_GPU_KERNEL_NOT_SET = 806, + SNPE_GPU_KERNEL_PARAM_INVALID = 807, + SNPE_GPU_OPENCL_CHECK_FAILED = 808, + SNPE_GPU_OPENCL_FUNCTION_ERROR = 809, + SNPE_GPU_BUFFER_NOT_FOUND = 810, + SNPE_GPU_TENSOR_DIM_INVALID = 811, + SNPE_GPU_MEMORY_FLAGS_INVALID = 812, + SNPE_GPU_UNEXPECTED_NUMBER_OF_IO = 813, + SNPE_GPU_LAYER_PROXY_ERROR = 814, + SNPE_GPU_BUFFER_IN_USE = 815, + SNPE_GPU_BUFFER_MODIFICATION_ERROR = 816, + + // DSP runtime errors + SNPE_DSP_LAYER_NOT_SUPPORTED = 900, + SNPE_DSP_LAYER_PARAM_NOT_SUPPORTED = 901, + SNPE_DSP_LAYER_PARAM_INVALID = 902, + SNPE_DSP_LAYER_PARAM_COMBINATION_INVALID = 903, + SNPE_DSP_STUB_NOT_PRESENT = 904, + SNPE_DSP_LAYER_NAME_TRUNCATED = 905, + SNPE_DSP_LAYER_INPUT_BUFFER_NAME_TRUNCATED = 906, + SNPE_DSP_LAYER_OUTPUT_BUFFER_NAME_TRUNCATED = 907, + SNPE_DSP_RUNTIME_COMMUNICATION_ERROR = 908, + SNPE_DSP_RUNTIME_INVALID_PARAM_ERROR = 909, + SNPE_DSP_RUNTIME_SYSTEM_ERROR = 910, + + // Model validataion errors + SNPE_MODEL_VALIDATION_LAYER_NOT_SUPPORTED = 1000, + SNPE_MODEL_VALIDATION_LAYER_PARAM_NOT_SUPPORTED = 1001, + SNPE_MODEL_VALIDATION_LAYER_PARAM_INVALID = 1002, + SNPE_MODEL_VALIDATION_LAYER_PARAM_MISSING = 1003, + SNPE_MODEL_VALIDATION_LAYER_PARAM_COMBINATION_INVALID = 1004, + SNPE_MODEL_VALIDATION_LAYER_ORDERING_INVALID = 1005, + SNPE_MODEL_VALIDATION_INVALID_CONSTRAINT = 1006, + SNPE_MODEL_VALIDATION_MISSING_BUFFER = 1007, + SNPE_MODEL_VALIDATION_BUFFER_REUSE_NOT_SUPPORTED = 1008, + + // UDL errors + SNPE_UDL_LAYER_EMPTY_UDL_NETWORK = 1100, + SNPE_UDL_LAYER_PARAM_INVALID = 1101, + SNPE_UDL_LAYER_INSTANCE_MISSING = 1102, + SNPE_UDL_LAYER_SETUP_FAILED = 1103, + SNPE_UDL_EXECUTE_FAILED = 1104, + SNPE_UDL_BUNDLE_INVALID = 1105, + + // Dependent library errors + SNPE_STD_LIBRARY_ERROR = 1200, + + // Unknown exception (catch (...)), Has no component attached to this + SNPE_UNKNOWN_EXCEPTION = 1210, + + // Storage Errors + SNPE_STORAGE_INVALID_KERNEL_REPO = 1300, + +}; + + +/** @addtogroup c_plus_plus_apis C++ +@{ */ + +/** + * Returns the error code of the last error encountered. + * + * @return The error code. + * + * @note The returned error code is significant only when the return + * value of the call indicated an error. + */ +ZDL_EXPORT ErrorCode getLastErrorCode(); + +/** + * Returns the error string of the last error encountered. + * + * @return The error string. + * + * @note The returned error string is significant only when the return + * value of the call indicated an error. + */ +ZDL_EXPORT const char* getLastErrorString(); + +/** + * Returns the uint32_t representation of the error code enum. + * + * @param[in] code The error code to be converted. + * + * @return uint32_t representation of the error code. + */ +ZDL_EXPORT uint32_t enumToUInt32(zdl::DlSystem::ErrorCode code); + +/** @} */ /* end_addtogroup c_plus_plus_apis C++ */ + +} // DlSystem +} // zdl + +#endif // _DL_ERROR_HPP_ + diff --git a/phonelibs/snpe/include/DlSystem/DlOptional.hpp b/phonelibs/snpe/include/DlSystem/DlOptional.hpp new file mode 100644 index 00000000000000..2c41b6b6894ee4 --- /dev/null +++ b/phonelibs/snpe/include/DlSystem/DlOptional.hpp @@ -0,0 +1,224 @@ +//============================================================================== +// +// Copyright (c) 2016 Qualcomm Technologies, Inc. +// All Rights Reserved. +// Confidential and Proprietary - Qualcomm Technologies, Inc. +// +//============================================================================== + +#ifndef _DL_SYSTEM_OPTIONAL_HPP_ +#define _DL_SYSTEM_OPTIONAL_HPP_ + +#include +#include + +#include "DlSystem/ZdlExportDefine.hpp" + +namespace zdl { +namespace DlSystem { + +template + +/** @addtogroup c_plus_plus_apis C++ +@{ */ + +/** + * @brief . + * + * Class to manage a value that may or may not exist. The boolean value + * of the Optional class is true if the object contains a value and false + * if it does not contain a value. + * + * The class must be evaluated and confirmed as true (containing a value) + * before being dereferenced. + */ +class ZDL_EXPORT Optional final { +public: + enum class LIFECYCLE { + NONE, + REFERENCE_OWNED, + POINTER_OWNED, + POINTER_NOT_OWNED + }; + + struct ReferenceCount { + size_t count = 0; + + void increment() { count++; } + + size_t decrement() { + if (count > 0) { + count--; + } + return count; + } + }; + + using U = typename std::remove_pointer::type; + + /** + * The default constructor is set to not have any value, and is + * therefore evaluated as false. + */ + // Do not explicit it so we can return {} + Optional() { + m_Type = LIFECYCLE::NONE; + } + + /** + * Construct an Optional class using an object. + * @param[in] Reference to an object v + * @param[out] Optional instance of object v + */ + template + Optional (const T& v, typename std::enable_if::value>::type* = 0) + : m_Type(LIFECYCLE::REFERENCE_OWNED) { + try { + m_StoragePtr = new T(v); + } catch (...) { + m_StoragePtr = nullptr; + m_Type = LIFECYCLE::NONE; + } + } + + template + Optional(U* v, LIFECYCLE type, typename std::enable_if::value>::type* = 0) + : m_Type(type) { + switch (m_Type) { + case LIFECYCLE::POINTER_OWNED: + m_StoragePtr = v; + m_Count = new ReferenceCount(); + m_Count->increment(); + break; + case LIFECYCLE::POINTER_NOT_OWNED: + m_StoragePtr = v; + break; + case LIFECYCLE::REFERENCE_OWNED: + throw std::bad_exception(); + case LIFECYCLE::NONE: + break; + } + } + + Optional(const Optional &other) : m_Type(other.m_Type), m_Count(other.m_Count) { + if (isReference()) { + m_StoragePtr = new U(*other.m_StoragePtr); + } else if (isPointer()) { + m_StoragePtr = other.m_StoragePtr; + if (isOwned()) { + m_Count->increment(); + } + } + } + + Optional& operator=(const Optional& other) noexcept { + Optional tmp(other); + swap(std::move(tmp)); + return *this; + } + + Optional(Optional&& other) noexcept { + swap(std::move(other)); + } + + Optional& operator=(Optional&& other) noexcept { + swap(std::move(other)); + return *this; + } + + ~Optional() { + if (isOwned()) { + if (isReference() || (isPointer() && m_Count->decrement() == 0)) { + delete m_StoragePtr; + delete m_Count; + } + } + } + + /** + * Boolean value of Optional class is only true when there exists a value. + */ + operator bool() const noexcept { return isValid(); } + + bool operator!() const noexcept { return !isValid(); } + + /** + * Get reference of Optional object + * @warning User must validate Optional has value before. + */ + const T& operator*() { return this->GetReference(); } + + /** + * Get reference of Optional object + * @warning User must validate Optional has value before. + */ + const T& operator*() const { return this->GetReference(); } + + operator T&() { return this->GetReference(); } + + T operator->() { + T self = this->GetReference(); + return self; + } +private: + void swap(Optional&& other) { + m_Type = other.m_Type; + m_StoragePtr = other.m_StoragePtr; + m_Count = other.m_Count; + + other.m_Type = LIFECYCLE::NONE; + other.m_StoragePtr = nullptr; + other.m_Count = nullptr; + } + + template + typename std::enable_if::value, const Q&>::type GetReference() const noexcept { + if (!isReference()) throw std::bad_exception(); + return *static_cast(m_StoragePtr); + } + + template + typename std::enable_if::value, const Q&>::type GetReference() const noexcept { + if (!isPointer()) throw std::bad_exception(); + return static_cast(m_StoragePtr); + } + + template + typename std::enable_if::value, Q&>::type GetReference() noexcept { + if (!isReference()) throw std::bad_exception(); + return *m_StoragePtr; + } + + template + typename std::enable_if::value, Q&>::type GetReference() noexcept { + if (!isPointer()) throw std::bad_exception(); + return m_StoragePtr; + } + + bool isPointer() const { + return m_Type == LIFECYCLE::POINTER_OWNED || m_Type == LIFECYCLE::POINTER_NOT_OWNED; + } + + bool isOwned() const { + return m_Type == LIFECYCLE::REFERENCE_OWNED || m_Type == LIFECYCLE::POINTER_OWNED; + } + + bool isReference() const { + return m_Type == LIFECYCLE::REFERENCE_OWNED; + } + + bool isValid() const { + return m_Type != LIFECYCLE::NONE; + } + + U* m_StoragePtr = nullptr; + LIFECYCLE m_Type; + ReferenceCount *m_Count = nullptr; +}; + +} // ns DlSystem +} // ns zdl + +/** @} */ /* end_addtogroup c_plus_plus_apis C++ */ + +#endif // _DL_SYSTEM_OPTIONAL_HPP_ diff --git a/phonelibs/snpe/include/DlSystem/DlVersion.hpp b/phonelibs/snpe/include/DlSystem/DlVersion.hpp new file mode 100644 index 00000000000000..beb8d75f218caf --- /dev/null +++ b/phonelibs/snpe/include/DlSystem/DlVersion.hpp @@ -0,0 +1,78 @@ +//============================================================================== +// +// Copyright (c) 2014-2015 Qualcomm Technologies, Inc. +// All Rights Reserved. +// Confidential and Proprietary - Qualcomm Technologies, Inc. +// +//============================================================================== + + +#ifndef _DL_VERSION_HPP_ +#define _DL_VERSION_HPP_ + +#include "ZdlExportDefine.hpp" +#include +#include +#include "DlSystem/String.hpp" + + +namespace zdl { +namespace DlSystem +{ + class Version_t; +}} + + +namespace zdl { namespace DlSystem +{ +/** @addtogroup c_plus_plus_apis C++ +@{ */ + +/** + * A class that contains the different portions of a version number. + */ +class ZDL_EXPORT Version_t +{ +public: + /// Holds the major version number. Changes in this value indicate + /// major changes that break backward compatibility. + int32_t Major; + + /// Holds the minor version number. Changes in this value indicate + /// minor changes made to library that are backwards compatible + /// (such as additions to the interface). + int32_t Minor; + + /// Holds the teeny version number. Changes in this value indicate + /// changes such as bug fixes and patches made to the library that + /// do not affect the interface. + int32_t Teeny; + + /// This string holds information about the build version. + /// + std::string Build; + + static zdl::DlSystem::Version_t fromString(const std::string &stringValue); + + static zdl::DlSystem::Version_t fromString(const zdl::DlSystem::String &stringValue); + + /** + * @brief Returns a string in the form Major.Minor.Teeny.Build + * + * @return A formatted string holding the version information. + */ + const std::string toString() const; + + /** + * @brief Returns a string in the form Major.Minor.Teeny.Build + * + * @return A formatted string holding the version information. + */ + const zdl::DlSystem::String asString() const; +}; + +}} + +/** @} */ /* end_addtogroup c_plus_plus_apis */ + +#endif diff --git a/phonelibs/snpe/include/DlSystem/IBufferAttributes.hpp b/phonelibs/snpe/include/DlSystem/IBufferAttributes.hpp new file mode 100644 index 00000000000000..e80f6c134c9ab4 --- /dev/null +++ b/phonelibs/snpe/include/DlSystem/IBufferAttributes.hpp @@ -0,0 +1,78 @@ +//============================================================================== +// +// Copyright (c) 2017 Qualcomm Technologies, Inc. +// All Rights Reserved. +// Confidential and Proprietary - Qualcomm Technologies, Inc. +// +//============================================================================== + +#ifndef _IBUFFER_ATTRIBUTES_HPP +#define _IBUFFER_ATTRIBUTES_HPP +#include "IUserBuffer.hpp" +#include "TensorShape.hpp" +#include "ZdlExportDefine.hpp" + +namespace zdl { + namespace DlSystem { + class UserBufferEncoding; + } +} + +namespace zdl { +namespace DlSystem { + + +/** + * @brief IBufferAttributes returns a buffer's dimension and alignment + * requirements, along with info on its encoding type + */ +class ZDL_EXPORT IBufferAttributes { +public: + + /** + * @brief Gets the buffer's element size, in bytes + * + * This can be used to compute the memory size required + * to back this buffer. + * + * @return Element size, in bytes + */ + virtual size_t getElementSize() const noexcept = 0; + + /** + * @brief Gets the element's encoding type + * + * @return encoding type + */ + virtual zdl::DlSystem::UserBufferEncoding::ElementType_t getEncodingType() const noexcept = 0; + + /** + * @brief Gets the number of elements in each dimension + * + * @return Dimension size, in terms of number of elements + */ + virtual const TensorShape getDims() const noexcept = 0; + + /** + * @brief Gets the alignment requirement of each dimension + * + * Alignment per each dimension is expressed as an multiple, for + * example, if one particular dimension can accept multiples of 8, + * the alignment will be 8. + * + * @return Alignment in each dimension, in terms of multiple of + * number of elements + */ + virtual const TensorShape getAlignments() const noexcept = 0; + + virtual ~IBufferAttributes() {} +}; + + + +/** @} */ /* end_addtogroup c_plus_plus_apis C++ */ + +} +} + +#endif diff --git a/phonelibs/snpe/include/DlSystem/ITensor.hpp b/phonelibs/snpe/include/DlSystem/ITensor.hpp new file mode 100644 index 00000000000000..ed6d5f1072e888 --- /dev/null +++ b/phonelibs/snpe/include/DlSystem/ITensor.hpp @@ -0,0 +1,147 @@ +//============================================================================= +// +// Copyright (c) 2015-2018 Qualcomm Technologies, Inc. +// All Rights Reserved. +// Confidential and Proprietary - Qualcomm Technologies, Inc. +// +//============================================================================= + +#ifndef _ITENSOR_HPP_ +#define _ITENSOR_HPP_ + +#include "ITensorItr.hpp" +#include "ITensorItrImpl.hpp" +#include "TensorShape.hpp" +#include "ZdlExportDefine.hpp" +#include +#include +#include +#include + +namespace zdl { +namespace DlSystem +{ + class ITensor; +}} + +namespace zdl { namespace DlSystem +{ +/** @addtogroup c_plus_plus_apis C++ +@{ */ + +/** + * Represents a tensor which holds n-dimensional data. It is important to + * understand how the tensor data is represented in memory + * relative to the tensor dimensions. Tensors store data in + * memory in row-major order (i.e. the last tensor dimension is + * the fastest varying one). For example, if you have a two + * dimensional tensor with 3 rows and 2 columns (i.e. the tensor + * dimensions are 3,2 as returned in tensor dimension vectors) + * with the following data in terms rows and columns: + * + * | 1 2 |
+ * | 3 4 |
+ * | 5 6 |
+ * + * This data would be stored in memory as 1,2,3,4,5,6. + */ +class ZDL_EXPORT ITensor +{ +public: + + typedef zdl::DlSystem::ITensorItr iterator; + typedef zdl::DlSystem::ITensorItr const_iterator; + + virtual ~ITensor() {} + + /** + * Returns a tensor iterator pointing to the beginning + * of the data in the tensor. + * + * @return A tensor iterator that points to the first data + * element in the tensor. + */ + virtual iterator begin() = 0; + + /** + * Returns the const version of a tensor iterator + * pointing to the beginning of the data in the tensor. + * + * @return A tensor const iterator that points to the first data + * element in the tensor. + */ + virtual const_iterator cbegin() const = 0; + + /** + * Returns a tensor iterator pointing to the end of the + * data in the tensor. This tensor should not be + * dereferenced. + * + * @return A tensor iterator that points to the end of the data + * (one past the last element) in the tensor. + */ + virtual iterator end() = 0; + + /** + * Returns the const version of a tensor iterator + * pointing to the end of the data in the tensor. This + * tensor should not be dereferenced. + * + * @return A tensor const iterator that points to the end of the + * data (one past the last element) in the tensor. + */ + virtual const_iterator cend() const = 0; + + /** + * @brief Gets the shape of this tensor. + * + * The last element of the vector represents the fastest varying + * dimension and the zeroth element represents the slowest + * varying dimension, etc. + * + * @return A shape class holding the tensor dimensions. + */ + virtual TensorShape getShape() const = 0; + + /** + * Returns the element size of the data in the tensor + * (discounting strides). This is how big a buffer would + * need to be to hold the tensor data contiguously in + * memory. + * + * @return The size of the tensor (in elements). + */ + virtual size_t getSize() const = 0; + + /** + * @brief Serializes the tensor to an output stream. + * + * @param[in] output The output stream to which to write the tensor + * + * @throw std::runtime_error If the stream is ever in a bad + * state before the tensor is fully serialized. + */ + virtual void serialize(std::ostream &output) const = 0; + + friend iterator; + friend const_iterator; + + virtual bool isQuantized() {return false;} + virtual float GetDelta() {return NAN;}; + virtual float GetOffset() {return NAN;}; + +protected: + + /** + * Returns the tensor iterator implementation. + * + * @return A pointer to the tensor iterator implementation. + */ + virtual std::unique_ptr<::DlSystem::ITensorItrImpl> getItrImpl() const = 0; +}; + +}} + +/** @} */ /* end_addtogroup c_plus_plus_apis C++ */ + +#endif diff --git a/phonelibs/snpe/include/DlSystem/ITensorFactory.hpp b/phonelibs/snpe/include/DlSystem/ITensorFactory.hpp new file mode 100644 index 00000000000000..57d2c8ea992375 --- /dev/null +++ b/phonelibs/snpe/include/DlSystem/ITensorFactory.hpp @@ -0,0 +1,92 @@ +//============================================================================= +// +// Copyright (c) 2015-2016 Qualcomm Technologies, Inc. +// All Rights Reserved. +// Confidential and Proprietary - Qualcomm Technologies, Inc. +// +//============================================================================= + +#ifndef _ITENSOR_FACTORY_HPP +#define _ITENSOR_FACTORY_HPP + +#include "ITensor.hpp" +#include "TensorShape.hpp" +#include "ZdlExportDefine.hpp" +#include + +namespace zdl { + namespace DlSystem + { + class ITensor; + class TensorShape; + } +} + +namespace zdl { namespace DlSystem +{ + +/** @addtogroup c_plus_plus_apis C++ +@{ */ + +/** + * Factory interface class to create ITensor objects. + */ +class ZDL_EXPORT ITensorFactory +{ +public: + virtual ~ITensorFactory() = default; + + /** + * Creates a new ITensor with uninitialized data. + * + * The strides for the tensor will match the tensor dimensions + * (i.e., the tensor data is contiguous in memory). + * + * @param[in] shape The dimensions for the tensor in which the last + * element of the vector represents the fastest varying + * dimension and the zeroth element represents the slowest + * varying, etc. + * + * @return A pointer to the created tensor or nullptr if creating failed. + */ + virtual std::unique_ptr + createTensor(const TensorShape &shape) noexcept = 0; + + /** + * Creates a new ITensor by loading it from a file. + * + * @param[in] input The input stream from which to read the tensor + * data. + * + * @return A pointer to the created tensor or nullptr if creating failed. + * + */ + virtual std::unique_ptr createTensor(std::istream &input) noexcept = 0; + + /** + * Create a new ITensor with specific data. + * (i.e. the tensor data is contiguous in memory). This tensor is + * primarily used to create a tensor where tensor size can't be + * computed directly from dimension. One such example is + * NV21-formatted image, or any YUV formatted image + * + * @param[in] shape The dimensions for the tensor in which the last + * element of the vector represents the fastest varying + * dimension and the zeroth element represents the slowest + * varying, etc. + * + * @param[in] data The actual data with which the Tensor object is filled. + * + * @param[in] dataSize The size of data + * + * @return A pointer to the created tensor + */ + virtual std::unique_ptr + createTensor(const TensorShape &shape, const unsigned char *data, size_t dataSize) noexcept = 0; +}; + +}} + +/** @} */ /* end_addtogroup c_plus_plus_apis C++ */ + +#endif diff --git a/phonelibs/snpe/include/DlSystem/ITensorItr.hpp b/phonelibs/snpe/include/DlSystem/ITensorItr.hpp new file mode 100644 index 00000000000000..4ce12a9f113acb --- /dev/null +++ b/phonelibs/snpe/include/DlSystem/ITensorItr.hpp @@ -0,0 +1,182 @@ +//============================================================================= +// +// Copyright (c) 2015 Qualcomm Technologies, Inc. +// All Rights Reserved. +// Confidential and Proprietary - Qualcomm Technologies, Inc. +// +//============================================================================= + +#ifndef _ITENSOR_ITR_HPP_ +#define _ITENSOR_ITR_HPP_ + +#include "ZdlExportDefine.hpp" +#include "ITensorItrImpl.hpp" + +#include +#include +#include + +namespace zdl { +namespace DlSystem +{ + template class ITensorItr; + class ITensor; + void ZDL_EXPORT fill(ITensorItr first, ITensorItr end, float val); + template OutItr ZDL_EXPORT copy(InItr first, InItr last, OutItr result) + { + return std::copy(first, last, result); + } +}} +namespace DlSystem +{ + class ITensorItrImpl; +} + +namespace zdl { namespace DlSystem +{ + +/** @addtogroup c_plus_plus_apis C++ +@{ */ + +/** + * A bidirectional iterator (with limited random access + * capabilities) for the zdl::DlSystem::ITensor class. + * + * This is a standard bidrectional iterator and is compatible + * with standard algorithm functions that operate on bidirectional + * access iterators (e.g., std::copy, std::fill, etc.). It uses a + * template parameter to create const and non-const iterators + * from the same code. Iterators are easiest to declare via the + * typedefs iterator and const_iterator in the ITensor class + * (e.g., zdl::DlSystem::ITensor::iterator). + * + * Note that if the tensor the iterator is traversing was + * created with nondefault (i.e., nontrivial) strides, the + * iterator will obey the strides when traversing the tensor + * data. + * + * Also note that nontrivial strides dramatically affect the + * performance of the iterator (on the order of 20x slower). + */ +template +class ZDL_EXPORT ITensorItr : public std::iterator +{ +public: + + typedef typename std::conditional::type VALUE_REF; + + ITensorItr() = delete; + virtual ~ITensorItr() {} + + ITensorItr(std::unique_ptr<::DlSystem::ITensorItrImpl> impl, + bool isTrivial = false, + float* data = nullptr) + : m_Impl(impl->clone()) + , m_IsTrivial(isTrivial) + , m_Data(data) + , m_DataStart(data) {} + + ITensorItr(const ITensorItr& itr) + : m_Impl(itr.m_Impl->clone()), + m_IsTrivial(itr.m_IsTrivial), + m_Data(itr.m_Data), + m_DataStart(itr.m_DataStart) {} + + zdl::DlSystem::ITensorItr& operator=(const ITensorItr& other) + { + if (this == &other) return *this; + m_Impl = std::move(other.m_Impl->clone()); + m_IsTrivial = other.m_IsTrivial; + m_Data = other.m_Data; + m_DataStart = other.m_DataStart; + return *this; + } + + inline zdl::DlSystem::ITensorItr& operator++() + { + if (m_IsTrivial) m_Data++; else m_Impl->increment(); + return *this; + } + inline zdl::DlSystem::ITensorItr operator++(int) + { + ITensorItr tmp(*this); + operator++(); + return tmp; + } + inline zdl::DlSystem::ITensorItr& operator--() + { + if (m_IsTrivial) m_Data--; else m_Impl->decrement(); + return *this; + } + inline zdl::DlSystem::ITensorItr operator--(int) + { + ITensorItr tmp(*this); + operator--(); + return tmp; + } + inline zdl::DlSystem::ITensorItr& operator+=(int rhs) + { + if (m_IsTrivial) m_Data += rhs; else m_Impl->increment(rhs); + return *this; + } + inline friend zdl::DlSystem::ITensorItr operator+(zdl::DlSystem::ITensorItr lhs, int rhs) + { lhs += rhs; return lhs; } + inline zdl::DlSystem::ITensorItr& operator-=(int rhs) + { + if (m_IsTrivial) m_Data -= rhs; else m_Impl->decrement(rhs); + return *this; + } + inline friend zdl::DlSystem::ITensorItr operator-(zdl::DlSystem::ITensorItr lhs, int rhs) + { lhs -= rhs; return lhs; } + + inline size_t operator-(const zdl::DlSystem::ITensorItr& rhs) + { + if (m_IsTrivial) return (m_Data - m_DataStart) - (rhs.m_Data - rhs.m_DataStart); + return m_Impl->getPosition() - rhs.m_Impl->getPosition(); + } + + inline friend bool operator<(const ITensorItr& lhs, const ITensorItr& rhs) + { + if (lhs.m_IsTrivial) return lhs.m_Data < rhs.m_Data; + return lhs.m_Impl->dataPointer() < rhs.m_Impl->dataPointer(); + } + inline friend bool operator>(const ITensorItr& lhs, const ITensorItr& rhs) + { return rhs < lhs; } + inline friend bool operator<=(const ITensorItr& lhs, const ITensorItr& rhs) + { return !(lhs > rhs); } + inline friend bool operator>=(const ITensorItr& lhs, const ITensorItr& rhs) + { return !(lhs < rhs); } + + inline bool operator==(const ITensorItr& rhs) const + { + if (m_IsTrivial) return m_Data == rhs.m_Data; + return m_Impl->dataPointer() == rhs.m_Impl->dataPointer(); + } + inline bool operator!=(const ITensorItr& rhs) const + { return !operator==(rhs); } + + inline VALUE_REF operator[](size_t idx) + { + if (m_IsTrivial) return *(m_DataStart + idx); + return m_Impl->getReferenceAt(idx); + } + inline VALUE_REF operator*() + { if (m_IsTrivial) return *m_Data; else return m_Impl->getReference(); } + inline VALUE_REF operator->() + { return *(*this); } + inline float* dataPointer() const + { if (m_IsTrivial) return m_Data; else return m_Impl->dataPointer(); } + + +protected: + std::unique_ptr<::DlSystem::ITensorItrImpl> m_Impl; + bool m_IsTrivial = false; + float* m_Data = nullptr; + float* m_DataStart = nullptr; +}; + +}} + +/** @} */ /* end_addtogroup c_plus_plus_apis C++ */ + +#endif diff --git a/phonelibs/snpe/include/DlSystem/ITensorItrImpl.hpp b/phonelibs/snpe/include/DlSystem/ITensorItrImpl.hpp new file mode 100644 index 00000000000000..7923c160b95b0d --- /dev/null +++ b/phonelibs/snpe/include/DlSystem/ITensorItrImpl.hpp @@ -0,0 +1,43 @@ +//============================================================================= +// +// Copyright (c) 2015 Qualcomm Technologies, Inc. +// All Rights Reserved. +// Confidential and Proprietary - Qualcomm Technologies, Inc. +// +//============================================================================= + +#ifndef _ITENSOR_ITR_IMPL_HPP_ +#define _ITENSOR_ITR_IMPL_HPP_ + +#include "ZdlExportDefine.hpp" + +#include +#include +#include + +namespace DlSystem +{ + class ITensorItrImpl; +} + +class ZDL_EXPORT DlSystem::ITensorItrImpl +{ +public: + ITensorItrImpl() {} + virtual ~ITensorItrImpl() {} + + virtual float getValue() const = 0; + virtual float& getReference() = 0; + virtual float& getReferenceAt(size_t idx) = 0; + virtual float* dataPointer() const = 0; + virtual void increment(int incVal = 1) = 0; + virtual void decrement(int decVal = 1) = 0; + virtual size_t getPosition() = 0; + virtual std::unique_ptr clone() = 0; + +private: + ITensorItrImpl& operator=(const ITensorItrImpl& other) = delete; + ITensorItrImpl(const ITensorItrImpl& other) = delete; +}; + +#endif diff --git a/phonelibs/snpe/include/DlSystem/IUDL.hpp b/phonelibs/snpe/include/DlSystem/IUDL.hpp new file mode 100644 index 00000000000000..2e9dddc48f53c4 --- /dev/null +++ b/phonelibs/snpe/include/DlSystem/IUDL.hpp @@ -0,0 +1,98 @@ +//============================================================================= +// +// Copyright (c) 2016-2017 Qualcomm Technologies, Inc. +// All Rights Reserved. +// Confidential and Proprietary - Qualcomm Technologies, Inc. +// +//============================================================================= + +#ifndef _DL_SYSTEM_IUDL_HPP_ +#define _DL_SYSTEM_IUDL_HPP_ + +#include "ZdlExportDefine.hpp" + +namespace zdl { +namespace DlSystem { +/** @addtogroup c_plus_plus_apis C++ +@{ */ + +/** + * @brief . + * + * Base class user concrete UDL implementation. + * + * All functions are marked as: + * + * - virtual + * - noexcept + * + * User should make sure no exceptions are propagated outside of + * their module. Errors can be communicated via return values. + */ +class ZDL_EXPORT IUDL { +public: + /** + * @brief . + * + * Destructor + */ + virtual ~IUDL() = default; + + /** + * @brief Sets up the user's environment. + * This is called by the SNPE framework to allow the user the + * opportunity to setup anything which is needed for running + * user defined layers. + * + * @param cookie User provided opaque data returned by the SNPE + * runtime + * + * @param insz How many elements in input size array + * @param indim Pointer to a buffer that holds input dimension + * array + * @param indimsz Input dimension size array of the buffer + * 'indim'. Corresponds to indim + * + * @param outsz How many elements in output size array + * @param outdim Pointer to a buffer that holds output + * dimension array + * @param outdimsz Output dimension size of the buffer 'oudim'. + * Corresponds to indim + * + * @return true on success, false otherwise + */ + virtual bool setup(void *cookie, + size_t insz, const size_t **indim, const size_t *indimsz, + size_t outsz, const size_t **outdim, const size_t *outdimsz) = 0; + + /** + * @brief Close the instance. Invoked by the SNPE + * framework to allow the user the opportunity to release any resources + * allocated during setup. + * + * @param cookie - User provided opaque data returned by the SNPE runtime + */ + virtual void close(void *cookie) noexcept = 0; + + /** + * @brief Execute the user defined layer + * + * @param cookie User provided opaque data returned by the SNPE + * runtime + * + * @param input Const pointer to a float buffer that contains + * the input + * + * @param output Float pointer to a buffer that would hold + * the user defined layer's output. This buffer + * is allocated and owned by SNPE runtime. + */ + virtual bool execute(void *cookie, const float **input, float **output) = 0; +}; +/** @} */ /* end_addtogroup c_plus_plus_apis C++ */ + +} // ns DlSystem + +} // ns zdl + +#endif // _DL_SYSTEM_IUDL_HPP_ diff --git a/phonelibs/snpe/include/DlSystem/IUserBuffer.hpp b/phonelibs/snpe/include/DlSystem/IUserBuffer.hpp new file mode 100644 index 00000000000000..70f6b33cbba1a9 --- /dev/null +++ b/phonelibs/snpe/include/DlSystem/IUserBuffer.hpp @@ -0,0 +1,289 @@ +//============================================================================== +// +// Copyright (c) 2017-2018 Qualcomm Technologies, Inc. +// All Rights Reserved. +// Confidential and Proprietary - Qualcomm Technologies, Inc. +// +//============================================================================== + +#ifndef _IUSER_BUFFER_HPP +#define _IUSER_BUFFER_HPP + +#include "TensorShape.hpp" +#include "ZdlExportDefine.hpp" + +namespace zdl { +namespace DlSystem { + +/** @addtogroup c_plus_plus_apis C++ +@{ */ + + +/** + * @brief . + * + * A base class buffer encoding type + */ +class ZDL_EXPORT UserBufferEncoding { +public: + + /** + * @brief . + * + * An enum class of all supported element types in a IUserBuffer + */ + enum class ElementType_t + { + /// Unknown element type. + UNKNOWN = 0, + + /// Each element is presented by float. + FLOAT = 1, + + /// Each element is presented by an unsigned int. + UNSIGNED8BIT = 2, + + /// Each element is presented by an 8-bit quantized value. + TF8 = 10 + }; + + /** + * @brief Retrieves the size of the element, in bytes. + * + * @return Size of the element, in bytes. + */ + virtual size_t getElementSize() const noexcept = 0; + + /** + * @brief Retrieves the element type + * + * @return Element type + */ + ElementType_t getElementType() const noexcept {return m_ElementType;}; + + virtual ~UserBufferEncoding() {} + +protected: + UserBufferEncoding(ElementType_t elementType) : m_ElementType(elementType) {}; +private: + const ElementType_t m_ElementType; +}; + +/** + * @brief . + * + * A base class buffer source type + * + * @note User buffer from CPU support all kinds of runtimes; + * User buffer from GLBUFFER support only GPU runtime. + */ +class ZDL_EXPORT UserBufferSource { +public: + enum class SourceType_t + { + /// Unknown buffer source type. + UNKNOWN = 0, + + /// The network inputs are from CPU buffer. + CPU = 1, + + /// The network inputs are from OpenGL buffer. + GLBUFFER = 2 + }; + + /** + * @brief Retrieves the source type + * + * @return Source type + */ + SourceType_t getSourceType() const noexcept {return m_SourceType;}; + +protected: + UserBufferSource(SourceType_t sourceType): m_SourceType(sourceType) {}; +private: + const SourceType_t m_SourceType; +}; + +/** + * @brief . + * + * An source type where input data is delivered from OpenGL buffer + */ +class ZDL_EXPORT UserBufferSourceGLBuffer : public UserBufferSource{ +public: + UserBufferSourceGLBuffer() : UserBufferSource(SourceType_t::GLBUFFER) {}; +}; + +/** + * @brief . + * + * An encoding type where each element is represented by an unsigned int + */ +class ZDL_EXPORT UserBufferEncodingUnsigned8Bit : public UserBufferEncoding { +public: + UserBufferEncodingUnsigned8Bit() : UserBufferEncoding(ElementType_t::UNSIGNED8BIT) {}; + size_t getElementSize() const noexcept override; + +protected: + UserBufferEncodingUnsigned8Bit(ElementType_t elementType) : UserBufferEncoding(elementType) {}; + +}; + +/** + * @brief . + * + * An encoding type where each element is represented by a float + */ +class ZDL_EXPORT UserBufferEncodingFloat : public UserBufferEncoding { +public: + UserBufferEncodingFloat() : UserBufferEncoding(ElementType_t::FLOAT) {}; + size_t getElementSize() const noexcept override; + +}; + +/** + * @brief . + * + * An encoding type where each element is represented by tf8, which is an + * 8-bit quantizd value, which has an exact representation of 0.0 + */ +class ZDL_EXPORT UserBufferEncodingTf8 : public UserBufferEncodingUnsigned8Bit { +public: + UserBufferEncodingTf8() = delete; + UserBufferEncodingTf8(unsigned char stepFor0, float stepSize) : + UserBufferEncodingUnsigned8Bit(ElementType_t::TF8), + m_StepExactly0(stepFor0), + m_QuantizedStepSize(stepSize) {}; + + /** + * @brief Sets the step value that represents 0 + * + * @param[in] stepExactly0 The step value that represents 0 + * + */ + void setStepExactly0(const unsigned char stepExactly0) { + m_StepExactly0 = stepExactly0; + } + + /** + * @brief Sets the float value that each step represents + * + * @param[in] quantizedStepSize The float value of each step size + * + */ + void setQuantizedStepSize(const float quantizedStepSize) { + m_QuantizedStepSize = quantizedStepSize; + } + + /** + * @brief Retrieves the step that represents 0.0 + * + * @return Step value + */ + unsigned char getStepExactly0() const { + return m_StepExactly0; + } + + /** + * Calculates the minimum floating point value that + * can be represented with this encoding. + * + * @return Minimum representable floating point value + */ + float getMin() const { + return m_QuantizedStepSize * (0 - m_StepExactly0); + } + + /** + * Calculates the maximum floating point value that + * can be represented with this encoding. + * + * @return Maximum representable floating point value + */ + float getMax() const { + return m_QuantizedStepSize * (255 - m_StepExactly0); + } + + /** + * @brief Retrieves the step size + * + * @return Step size + */ + float getQuantizedStepSize() const { + return m_QuantizedStepSize; + } + +private: + unsigned char m_StepExactly0; + + float m_QuantizedStepSize; +}; + +/** + * @brief UserBuffer contains a pointer and info on how to walk it and interpret its content. + */ +class ZDL_EXPORT IUserBuffer { +public: + virtual ~IUserBuffer() = default; + + /** + * @brief Retrieves the total number of bytes between elements in each dimension if + * the buffer were to be interpreted as a multi-dimensional array. + * + * @return Number of bytes between elements in each dimension. + * e.g. A tightly packed tensor of floats with dimensions [4, 3, 2] would + * return strides of [24, 8, 4]. + */ + virtual const TensorShape& getStrides() const = 0; + + /** + * @brief Retrieves the size of the buffer, in bytes. + * + * @return Size of the underlying buffer, in bytes. + */ + virtual size_t getSize() const = 0; + + /** + * @brief Changes the underlying memory that backs the UserBuffer. + * + * This can be used to avoid creating multiple UserBuffer objects + * when the only thing that differs is the memory location. + * + * @param[in] buffer Pointer to the memory location + * + * @return Whether the set succeeds. + */ + virtual bool setBufferAddress(void *buffer) noexcept = 0; + + /** + * @brief Gets a const reference to the data encoding object of + * the underlying buffer + * + * This is necessary when the UserBuffer is filled by SNPE with + * data types such as TF8, where the caller needs to know the quantization + * parameters in order to interpret the data properly + * + * @return A read-only encoding object + */ + virtual const UserBufferEncoding& getEncoding() const noexcept = 0; + + /** + * @brief Gets a reference to the data encoding object of + * the underlying buffer + * + * This is necessary when the UserBuffer is re-used, and the encoding + * parameters can change. For example, each input can be quantized with + * different step sizes. + * + * @return Data encoding meta-data + */ + virtual UserBufferEncoding& getEncoding() noexcept = 0; + +}; + +/** @} */ /* end_addtogroup c_plus_plus_apis C++ */ + +} +} + +#endif diff --git a/phonelibs/snpe/include/DlSystem/IUserBufferFactory.hpp b/phonelibs/snpe/include/DlSystem/IUserBufferFactory.hpp new file mode 100644 index 00000000000000..59803fbd8f8772 --- /dev/null +++ b/phonelibs/snpe/include/DlSystem/IUserBufferFactory.hpp @@ -0,0 +1,81 @@ +//============================================================================= +// +// Copyright (c) 2017 Qualcomm Technologies, Inc. +// All Rights Reserved. +// Confidential and Proprietary - Qualcomm Technologies, Inc. +// +//============================================================================= + +#ifndef _IUSERBUFFER_FACTORY_HPP +#define _IUSERBUFFER_FACTORY_HPP + +#include "IUserBuffer.hpp" +#include "TensorShape.hpp" +#include "ZdlExportDefine.hpp" +#include "DlEnums.hpp" +namespace zdl { + namespace DlSystem { + class IUserBuffer; + + class TensorShape; + } +} + +namespace zdl { +namespace DlSystem { + +/** @addtogroup c_plus_plus_apis C++ +@{ */ + +/** +* Factory interface class to create IUserBuffer objects. +*/ +class ZDL_EXPORT IUserBufferFactory { +public: + virtual ~IUserBufferFactory() = default; + + /** + * @brief Creates a UserBuffer + * + * @param[in] buffer Pointer to the buffer that the caller supplies + * + * @param[in] bufSize Buffer size, in bytes + * + * @param[in] strides Total number of bytes between elements in each dimension. + * E.g. A tightly packed tensor of floats with dimensions [4, 3, 2] would have strides of [24, 8, 4]. + * + * @param[in] userBufferEncoding Reference to an UserBufferEncoding object + * + * @note Caller has to ensure that memory pointed to by buffer stays accessible + * for the lifetime of the object created + */ + virtual std::unique_ptr + createUserBuffer(void *buffer, size_t bufSize, const zdl::DlSystem::TensorShape &strides, zdl::DlSystem::UserBufferEncoding* userBufferEncoding) noexcept = 0; + + /** + * @brief Creates a UserBuffer + * + * @param[in] buffer Pointer to the buffer that the caller supplies + * + * @param[in] bufSize Buffer size, in bytes + * + * @param[in] strides Total number of bytes between elements in each dimension. + * E.g. A tightly packed tensor of floats with dimensions [4, 3, 2] would have strides of [24, 8, 4]. + * + * @param[in] userBufferEncoding Reference to an UserBufferEncoding object + * + * @param[in] userBufferSource Reference to an UserBufferSource object + * + * @note Caller has to ensure that memory pointed to by buffer stays accessible + * for the lifetime of the object created + */ + virtual std::unique_ptr + createUserBuffer(void *buffer, size_t bufSize, const zdl::DlSystem::TensorShape &strides, zdl::DlSystem::UserBufferEncoding* userBufferEncoding, zdl::DlSystem::UserBufferSource* userBufferSource) noexcept = 0; +}; +/** @} */ /* end_addtogroup c_plus_plus_apis C++ */ + +} +} + + +#endif diff --git a/phonelibs/snpe/include/DlSystem/PlatformConfig.hpp b/phonelibs/snpe/include/DlSystem/PlatformConfig.hpp new file mode 100644 index 00000000000000..df452dc46970bf --- /dev/null +++ b/phonelibs/snpe/include/DlSystem/PlatformConfig.hpp @@ -0,0 +1,168 @@ +//============================================================================= +// +// Copyright (c) 2017-2018 Qualcomm Technologies, Inc. +// All Rights Reserved. +// Confidential and Proprietary - Qualcomm Technologies, Inc. +// +//============================================================================= + +#ifndef _DL_SYSTEM_PLATFORM_CONFIG_HPP_ +#define _DL_SYSTEM_PLATFORM_CONFIG_HPP_ + +#include "DlSystem/ZdlExportDefine.hpp" + +namespace zdl{ +namespace DlSystem +{ + +/** @addtogroup c_plus_plus_apis C++ +@{ */ + + +/** + * @brief . + * + * A structure OpenGL configuration + * + * @note When certain OpenGL context and display are provided to UserGLConfig for using + * GPU buffer as input directly, the user MUST ensure the particular OpenGL + * context and display remain vaild throughout the execution of neural network models. + */ +struct ZDL_EXPORT UserGLConfig +{ + /// Holds user EGL context. + /// + void* userGLContext = nullptr; + + /// Holds user EGL display. + void* userGLDisplay = nullptr; +}; + +/** + * @brief . + * + * A structure Gpu configuration + */ +struct ZDL_EXPORT UserGpuConfig{ + /// Holds user OpenGL configuration. + /// + UserGLConfig userGLConfig; +}; + +/** + * @brief . + * + * A class user platform configuration + */ +class ZDL_EXPORT PlatformConfig +{ +public: + + /** + * @brief . + * + * An enum class of all supported platform types + */ + enum class PlatformType_t + { + /// Unknown platform type. + UNKNOWN = 0, + + /// Snapdragon CPU. + CPU = 1, + + /// Adreno GPU. + GPU = 2, + + /// Hexagon DSP. + DSP = 3 + }; + + /** + * @brief . + * + * A union class user platform configuration information + */ + union PlatformConfigInfo + { + /// Holds user GPU Configuration. + /// + UserGpuConfig userGpuConfig; + + PlatformConfigInfo(){}; + }; + + PlatformConfig() : m_PlatformType(PlatformType_t::UNKNOWN) {}; + + /** + * @brief Retrieves the platform type + * + * @return Platform type + */ + PlatformType_t getPlatformType() const {return m_PlatformType;}; + + /** + * @brief Indicates whther the plaform configuration is valid. + * + * @return True if the platform configuration is valid; false otherwise. + */ + bool isValid() const {return (PlatformType_t::UNKNOWN != m_PlatformType);}; + + /** + * @brief Retrieves the Gpu configuration + * + * @param[out] userGpuConfig The passed in userGpuConfig populated with the Gpu configuration on return. + * + * @return True if Gpu configuration was retrieved; false otherwise. + */ + bool getUserGpuConfig(UserGpuConfig& userGpuConfig) const + { + if(m_PlatformType == PlatformType_t::GPU) + { + userGpuConfig = m_PlatformConfigInfo.userGpuConfig; + return true; + } + else + { + return false; + } + } + + /** + * @brief Sets the Gpu configuration + * + * @param[in] userGpuConfig Gpu Configuration + * + * @return True if Gpu configuration was successfully set; false otherwise. + */ + bool setUserGpuConfig(UserGpuConfig& userGpuConfig) + { + if((userGpuConfig.userGLConfig.userGLContext != nullptr) && (userGpuConfig.userGLConfig.userGLDisplay != nullptr)) + { + switch (m_PlatformType) + { + case PlatformType_t::GPU: + m_PlatformConfigInfo.userGpuConfig = userGpuConfig; + return true; + case PlatformType_t::UNKNOWN: + m_PlatformType = PlatformType_t::GPU; + m_PlatformConfigInfo.userGpuConfig = userGpuConfig; + return true; + default: + return false; + } + } + else + return false; + } + +private: + PlatformType_t m_PlatformType; + PlatformConfigInfo m_PlatformConfigInfo; +}; + +/** @} */ /* end_addtogroup c_plus_plus_apis C++ */ + +}} //namespace end + +#endif diff --git a/phonelibs/snpe/include/DlSystem/String.hpp b/phonelibs/snpe/include/DlSystem/String.hpp new file mode 100644 index 00000000000000..97b07726c72bc7 --- /dev/null +++ b/phonelibs/snpe/include/DlSystem/String.hpp @@ -0,0 +1,108 @@ +//============================================================================= +// +// Copyright (c) 2017 Qualcomm Technologies, Inc. +// All Rights Reserved. +// Confidential and Proprietary - Qualcomm Technologies, Inc. +// +//============================================================================= + +#ifndef PLATFORM_STANDARD_STRING_HPP +#define PLATFORM_STANDARD_STRING_HPP + +#include +#include +#include + +#ifndef ZDL_EXPORT +#define ZDL_EXPORT __attribute__((visibility("default"))) +#endif + +namespace zdl +{ +namespace DlSystem +{ +/** @addtogroup c_plus_plus_apis C++ +@{ */ + +/** + * @brief . + * + * Class for wrapping char * as a really stripped down std::string replacement. + */ +class ZDL_EXPORT String final +{ +public: + String() = delete; + + /** + * Construct a string from std::string reference. + * @param str Reference to a std::string + */ + explicit String(const std::string& str); + + /** + * Construct a string from char* reference. + * @param a char* + */ + explicit String(const char* str); + + /** + * move constructor. + */ + String(String&& other) noexcept; + + /** + * copy constructor. + */ + String(const String& other) = delete; + + /** + * assignment operator. + */ + String& operator=(const String&) = delete; + + /** + * move assignment operator. + */ + String& operator=(String&&) = delete; + + /** + * class comparators + */ + bool operator<(const String& rhs) const noexcept; + bool operator>(const String& rhs) const noexcept; + bool operator<=(const String& rhs) const noexcept; + bool operator>=(const String& rhs) const noexcept; + bool operator==(const String& rhs) const noexcept; + bool operator!=(const String& rhs) const noexcept; + + /** + * class comparators against std::string + */ + bool operator<(const std::string& rhs) const noexcept; + bool operator>(const std::string& rhs) const noexcept; + bool operator<=(const std::string& rhs) const noexcept; + bool operator>=(const std::string& rhs) const noexcept; + bool operator==(const std::string& rhs) const noexcept; + bool operator!=(const std::string& rhs) const noexcept; + + const char* c_str() const noexcept; + + ~String(); +private: + + char* m_string; +}; + +/** + * overloaded << operator + */ +ZDL_EXPORT std::ostream& operator<<(std::ostream& os, const String& str) noexcept; + +} // DlSystem namespace +} // zdl namespace + +/** @} */ /* end_addtogroup c_plus_plus_apis C++ */ + +#endif // PLATFORM_STANDARD_STRING_HPP + diff --git a/phonelibs/snpe/include/DlSystem/StringList.hpp b/phonelibs/snpe/include/DlSystem/StringList.hpp new file mode 100644 index 00000000000000..a9a7d5ed89674c --- /dev/null +++ b/phonelibs/snpe/include/DlSystem/StringList.hpp @@ -0,0 +1,107 @@ +//============================================================================= +// +// Copyright (c) 2016 Qualcomm Technologies, Inc. +// All Rights Reserved. +// Confidential and Proprietary - Qualcomm Technologies, Inc. +// +//============================================================================= +#include +#include "ZdlExportDefine.hpp" + +#ifndef DL_SYSTEM_STRINGLIST_HPP +#define DL_SYSTEM_STRINGLIST_HPP + +namespace zdl +{ +namespace DlSystem +{ +/** @addtogroup c_plus_plus_apis C++ +@{ */ + +/** + * @brief . + * + * Class for holding an order list of null-terminated ASCII strings. + */ +class ZDL_EXPORT StringList final +{ +public: + StringList() {} + + /** + * Construct a string list with some pre-allocated memory. + * @warning Contents of the list will be uninitialized + * @param[in] length Number of elements for which to pre-allocate space. + */ + explicit StringList(size_t length); + + /** + * Append a string to the list. + * @param[in] str Null-terminated ASCII string to append to the list. + */ + void append(const char* str); + + /** + * Returns the string at the indicated position, + * or an empty string if the positions is greater than the size + * of the list. + * @param[in] idx Position in the list of the desired string + */ + const char* at(size_t idx) const noexcept; + + /** + * Pointer to the first string in the list. + * Can be used to iterate through the list. + */ + const char** begin() const noexcept; + + /** + * Pointer to one after the last string in the list. + * Can be used to iterate through the list. + */ + const char** end() const noexcept; + + /** + * Return the number of valid string pointers held by this list. + */ + size_t size() const noexcept; + + + /** + * assignment operator. + */ + StringList& operator=(const StringList&) noexcept; + + /** + * copy constructor. + * @param[in] other object to copy. + */ + StringList(const StringList& other); + + /** + * move constructor. + * @param[in] other object to move. + */ + StringList(StringList&& other) noexcept; + + ~StringList(); +private: + void copy(const StringList& other); + + void resize(size_t length); + + void clear(); + + static const char* s_Empty; + const char** m_Strings = nullptr; + const char** m_End = nullptr; + size_t m_Size = 0; +}; + +} // DlSystem namespace +} // zdl namespace + +/** @} */ /* end_addtogroup c_plus_plus_apis C++ */ + +#endif // DL_SYSTEM_STRINGLIST_HPP + diff --git a/phonelibs/snpe/include/DlSystem/TensorMap.hpp b/phonelibs/snpe/include/DlSystem/TensorMap.hpp new file mode 100644 index 00000000000000..feecec666729ad --- /dev/null +++ b/phonelibs/snpe/include/DlSystem/TensorMap.hpp @@ -0,0 +1,120 @@ +//============================================================================= +// +// Copyright (c) 2016 Qualcomm Technologies, Inc. +// All Rights Reserved. +// Confidential and Proprietary - Qualcomm Technologies, Inc. +// +//============================================================================= +#include +#include "ZdlExportDefine.hpp" +#include "ITensor.hpp" +#include "StringList.hpp" + +#ifndef DL_SYSTEM_TENSOR_MAP_HPP +#define DL_SYSTEM_TENSOR_MAP_HPP + +namespace DlSystem +{ + // Forward declaration of tensor map implementation. + class TensorMapImpl; +} + +namespace zdl +{ +namespace DlSystem +{ + +/** @addtogroup c_plus_plus_apis C++ +@{ */ + +/** + * @brief . + * + * A class representing the map of tensor. + */ +class ZDL_EXPORT TensorMap final +{ +public: + + /** + * @brief . + * + * Creates a new empty tensor map + */ + TensorMap(); + + /** + * copy constructor. + * @param[in] other object to copy. + */ + TensorMap(const TensorMap& other); + + /** + * assignment operator. + */ + TensorMap& operator=(const TensorMap& other); + + /** + * @brief Adds a name and the corresponding tensor pointer + * to the map + * + * @param[in] name The name of the tensor + * @param[out] tensor The pointer to the tensor + * + * @note If a tensor with the same name already exists, the + * tensor is replaced with the existing tensor. + */ + void add(const char *name, zdl::DlSystem::ITensor *tensor); + + /** + * @brief Removes a mapping of tensor and its name by its name + * + * @param[in] name The name of tensor to be removed + * + * @note If no tensor with the specified name is found, nothing + * is done. + */ + void remove(const char *name) noexcept; + + /** + * @brief Returns the number of tensors in the map + */ + size_t size() const noexcept; + + /** + * @brief . + * + * Removes all tensors from the map + */ + void clear() noexcept; + + /** + * @brief Returns the tensor given its name. + * + * @param[in] name The name of the tensor to get. + * + * @return nullptr if no tensor with the specified name is + * found; otherwise, a valid pointer to the tensor. + */ + zdl::DlSystem::ITensor* getTensor(const char *name) const noexcept; + + /** + * @brief . + * + * Returns the names of all tensors + */ + zdl::DlSystem::StringList getTensorNames() const; + + ~TensorMap(); +private: + void swap(const TensorMap &other); + std::unique_ptr<::DlSystem::TensorMapImpl> m_TensorMapImpl; +}; + +} // DlSystem namespace +} // zdl namespace + +/** @} */ /* end_addtogroup c_plus_plus_apis C++ */ + +#endif // DL_SYSTEM_TENSOR_MAP_HPP + diff --git a/phonelibs/snpe/include/DlSystem/TensorShape.hpp b/phonelibs/snpe/include/DlSystem/TensorShape.hpp new file mode 100644 index 00000000000000..99583dccb40bac --- /dev/null +++ b/phonelibs/snpe/include/DlSystem/TensorShape.hpp @@ -0,0 +1,203 @@ +//============================================================================= +// +// Copyright (c) 2016 Qualcomm Technologies, Inc. +// All Rights Reserved. +// Confidential and Proprietary - Qualcomm Technologies, Inc. +// +//============================================================================= +#include +#include +#include +#include +#include "ZdlExportDefine.hpp" + +#ifndef DL_SYSTEM_TENSOR_SHAPE_HPP +#define DL_SYSTEM_TENSOR_SHAPE_HPP + +namespace DlSystem +{ + // Forward declaration of tensor shape implementation. + class TensorShapeImpl; +} + +namespace zdl +{ +namespace DlSystem +{ + +/** @addtogroup c_plus_plus_apis C++ +@{ */ + +/** + * @brief . + * + * Convenient typedef to represent dimension + */ +using Dimension = size_t; + +/** + * @brief . + * + * A class representing the shape of tensor. It is used at the + * time of creation of tensor. + */ +class ZDL_EXPORT TensorShape final +{ +public: + + /** + * @brief . + * + * Creates a new shape with a list of dims specified in + * initializer list fashion. + * + * @param[in] dims The dimensions are specified in which the last + * element of the vector represents the fastest varying + * dimension and the zeroth element represents the slowest + * varying, etc. + * + */ + TensorShape(std::initializer_list dims); + + /** + * @brief . + * + * Creates a new shape with a list of dims specified in array + * + * @param[in] dims The dimensions are specified in which the last + * element of the vector represents the fastest varying + * dimension and the zeroth element represents the slowest + * varying, etc. + * + * @param[in] size Size of the array. + * + */ + TensorShape(const Dimension *dims, size_t size); + + /** + * @brief . + * + * Creates a new shape with a vector of dims specified in + * vector fashion. + * + * @param[in] dims The dimensions are specified in which the last + * element of the vector represents the fastest varying + * dimension and the zeroth element represents the slowest + * varying, etc. + * + */ + TensorShape(std::vector dims); + + /** + * @brief . + * + * copy constructor. + * @param[in] other object to copy. + */ + TensorShape(const TensorShape& other); + + /** + * @brief . + * + * assignment operator. + */ + TensorShape& operator=(const TensorShape& other); + + /** + * @brief . + * + * Creates a new shape with no dims. It can be extended later + * by invoking concatenate. + */ + TensorShape(); + + /** + * @brief . + * + * Concatenates additional dimensions specified in + * initializer list fashion to the existing dimensions. + * + * @param[in] dims The dimensions are specified in which the last + * element of the vector represents the fastest varying + * dimension and the zeroth element represents the slowest + * varying, etc. + * + */ + void concatenate(std::initializer_list dims); + + /** + * @brief . + * + * Concatenates additional dimensions specified in + * the array to the existing dimensions. + * + * @param[in] dims The dimensions are specified in which the last + * element of the vector represents the fastest varying + * dimension and the zeroth element represents the slowest + * varying, etc. + * + * @param[in] size Size of the array. + * + */ + void concatenate(const Dimension *dims, size_t size); + + /** + * @brief . + * + * Concatenates an additional dimension to the existing + * dimensions. + * + * @param[in] dim The dimensions are specified in which the last element + * of the vector represents the fastest varying dimension and the + * zeroth element represents the slowest varying, etc. + * + */ + void concatenate(const Dimension &dim); + + /** + * @brief . + * + * Retrieves a single dimension, based on its index. + * + * @return The value of dimension + * + * @throws std::out_of_range if the index is >= the number of + * dimensions (or rank). + */ + Dimension& operator[](size_t index); + Dimension& operator[](size_t index) const; + + /** + * @brief . + * + * Retrieves the rank i.e. number of dimensions. + * + * @return The rank + */ + size_t rank() const; + + /** + * @brief . + * + * Retrieves a pointer to the first dimension of shape + * + * @return nullptr if no dimension exists; otherwise, points to + * the first dimension. + * + */ + const Dimension* getDimensions() const; + + ~TensorShape(); + +private: + void swap(const TensorShape &other); + std::unique_ptr<::DlSystem::TensorShapeImpl> m_TensorShapeImpl; +}; + +} // DlSystem namespace +} // zdl namespace + +/** @} */ /* end_addtogroup c_plus_plus_apis C++ */ + +#endif // DL_SYSTEM_TENSOR_SHAPE_HPP + diff --git a/phonelibs/snpe/include/DlSystem/TensorShapeMap.hpp b/phonelibs/snpe/include/DlSystem/TensorShapeMap.hpp new file mode 100644 index 00000000000000..00dc41a113160d --- /dev/null +++ b/phonelibs/snpe/include/DlSystem/TensorShapeMap.hpp @@ -0,0 +1,128 @@ +//============================================================================= +// +// Copyright (c) 2017 Qualcomm Technologies, Inc. +// All Rights Reserved. +// Confidential and Proprietary - Qualcomm Technologies, Inc. +// +//============================================================================= +#include +#include +#include +#include +#include "ZdlExportDefine.hpp" +#include "DlSystem/TensorShape.hpp" +#include "DlSystem/StringList.hpp" + +#ifndef DL_SYSTEM_TENSOR_SHAPE_MAP_HPP +#define DL_SYSTEM_TENSOR_SHAPE_MAP_HPP + +namespace DlSystem +{ + // Forward declaration of tensor shape map implementation. + class TensorShapeMapImpl; +} + +namespace zdl +{ +namespace DlSystem +{ + +/** @addtogroup c_plus_plus_apis C++ +@{ */ + +/** + * @brief . + * + * A class representing the map of names and tensorshapes. + */ +class ZDL_EXPORT TensorShapeMap final +{ +public: + + /** + * @brief . + * + * Creates a new tensor shape map + * + */ + TensorShapeMap(); + + /** + * @brief . + * + * copy constructor. + * @param[in] other object to copy. + */ + TensorShapeMap(const TensorShapeMap& other); + + /** + * @brief . + * + * assignment operator. + */ + TensorShapeMap& operator=(const TensorShapeMap& other); + + /** + * @brief Adds a name and the corresponding tensor pointer + * to the map + * + * @param[in] name The name of the tensor + * @param[out] tensor The pointer to the tensor + * + * @note If a tensor with the same name already exists, no new + * tensor is added. + */ + void add(const char *name, const zdl::DlSystem::TensorShape& tensorShape); + + /** + * @brief Removes a mapping of tensor and its name by its name + * + * @param[in] name The name of tensor to be removed + * + * @note If no tensor with the specified name is found, nothing + * is done. + */ + void remove(const char *name) noexcept; + + /** + * @brief Returns the number of tensors in the map + */ + size_t size() const noexcept; + + /** + * @brief . + * + * Removes all tensors from the map + */ + void clear() noexcept; + + /** + * @brief Returns the tensor given its name. + * + * @param[in] name The name of the tensor to get. + * + * @return nullptr if no tensor with the specified name is + * found; otherwise, a valid pointer to the tensor. + */ + zdl::DlSystem::TensorShape getTensorShape(const char *name) const noexcept; + + /** + * @brief . + * + * Returns the names of all tensor shapes + */ + zdl::DlSystem::StringList getTensorShapeNames() const; + + ~TensorShapeMap(); +private: + void swap(const TensorShapeMap &other); + std::unique_ptr<::DlSystem::TensorShapeMapImpl> m_TensorShapeMapImpl; +}; + +} // DlSystem namespace +} // zdl namespace + +/** @} */ /* end_addtogroup c_plus_plus_apis C++ */ + +#endif // DL_SYSTEM_TENSOR_SHAPE_MAP_HPP + diff --git a/phonelibs/snpe/include/DlSystem/UDLContext.hpp b/phonelibs/snpe/include/DlSystem/UDLContext.hpp new file mode 100644 index 00000000000000..6b7c07d3ebf182 --- /dev/null +++ b/phonelibs/snpe/include/DlSystem/UDLContext.hpp @@ -0,0 +1,244 @@ +//============================================================================== +// +// Copyright (c) 2016 Qualcomm Technologies, Inc. +// All Rights Reserved. +// Confidential and Proprietary - Qualcomm Technologies, Inc. +// +//============================================================================== + +#ifndef UDL_CONTEXT_HPP +#define UDL_CONTEXT_HPP + +#include // memset +#include + +#include "ZdlExportDefine.hpp" + +namespace zdl { namespace DlSystem { +/** @addtogroup c_plus_plus_apis C++ +@{ */ + +/** + * @brief . + * + * UDLContext holds the user defined layer context which + * consists of a layer name, layer ID, blob and blob size. + * + * An instance of UDLContext is passed as an argument to the + * UDLFactoryFunc provided by the user every time the SNPE + * runtime encounters an unknown layer descriptor. The instance + * of a UDLContext is created by the SNPE runtime and is + * consumed by the user's factory function. The user should + * obtain a copy of this class and should not assume any + * prolonged object lifetime beyond the UDLFactoryFunction. + */ +class ZDL_EXPORT UDLContext final { +public: + /** + * @brief Constructor + * + * @param[in] name name of the layer + * + * @param[in] type layer type + * + * @param[in] id identifier for the layer + * + * @param[in] id Blob/bytes as packed by the user code as part of + * the Python converter script + */ + UDLContext(const std::string& name, + const std::string& type, + int32_t id, + const std::string& blob) : + m_Name(name), m_Type(type), m_Size(blob.size()), m_Id(id) { + // FIXME not dealing with alloc error + m_Buffer = new uint8_t[m_Size]; + std::memcpy(m_Buffer, blob.data(), m_Size); + } + + /** + * @brief . + * + * Empty constructor is useful for + * creating an empty UDLContext and then run copy constructor + * from a fully initialized one. + */ + explicit UDLContext() {} + + /** + * @brief . + * + * destructor Deallocates any internal allocated memory + */ + ~UDLContext() { release(); } + + /** + * @brief . + * + * Deallocate any internally allocated memory + */ + void release() { + if (m_Buffer && m_Size) + std::memset(m_Buffer, 0, m_Size); + delete []m_Buffer; + m_Buffer = nullptr; + m_Size = 0; + } + + /** + * @brief . + * + * Copy Constructor - makes a copy from ctx + * + * @param[in] ctx Source UDLContext to copy from + */ + UDLContext(const UDLContext& ctx) : m_Name(ctx.m_Name), + m_Type(ctx.m_Type), + m_Id(ctx.m_Id) { + std::tuple cpy = ctx.getCopy(); + // current compiler does not support get + m_Buffer = std::get<0>(cpy); + m_Size = std::get<1>(cpy); + } + + /** + * @brief + * + * Assignment operator - makes a copy from ctx + * + * @param[in] ctx Source UDLContext to copy from + * + * @return this + */ + UDLContext& operator=(const UDLContext& ctx) { + UDLContext c (ctx); + this->swap(c); // non throwing swap + return *this; + } + + /** + * @brief . + * + * Move Constructor - Move internals from ctx into this + * + * @param[in] ctx Source UDLContext to move from + */ + UDLContext(UDLContext&& ctx) : + m_Name(std::move(ctx.m_Name)), + m_Type(std::move(ctx.m_Type)), + m_Buffer(ctx.m_Buffer), + m_Size(ctx.m_Size), + m_Id(ctx.m_Id) { + ctx.clear(); + } + + /** + * @brief . + * + * Assignment move - Move assignment operator from ctx + * + * @param[in] ctx Source UDLContext to move from + * + * @return this + */ + UDLContext& operator=(UDLContext&& ctx) { + m_Name = std::move(ctx.m_Name); + m_Type = std::move(ctx.m_Type); + m_Buffer = ctx.m_Buffer; + m_Size = ctx.m_Size; + m_Id = ctx.m_Id; + ctx.clear(); + return *this; + } + + /** + * @brief . + * + * Obtain the name of the layer + * + * @return const reference to the name of the layer + */ + const std::string& getName() const noexcept { return m_Name; } + + /** + * @brief . + * + * Obtain the type of the layer + * + * @return const reference to the type of the layer + */ + const std::string& getType() const noexcept { return m_Type; } + + /** + * @brief . + * + * Obtain the Id of the layer + * + * @return The id of the layer + */ + int32_t getId() const noexcept { return m_Id; } + + /** + * @brief . + * + * Obtain the size of the blob + * + * @return Size of the internal blob + */ + size_t getSize() const noexcept { return m_Size; } + + /** + * @brief . + * + * Get a const pointer to the internal blob + * + * @return Const pointer to the internal blob + */ + const uint8_t* getBlob() const noexcept { return m_Buffer; } + + /** + * @brief . + * + * Get a copy of the blob/size into a tuple + * + * @return A tuple with a pointer to a copy of the blob and a + * size + */ + std::tuple getCopy() const { + uint8_t* buf = new uint8_t[m_Size]; + // FIXME missing memcpy + std::memcpy(buf, m_Buffer, m_Size); + return std::make_tuple(buf, m_Size); + } + + /** + * @brief . + * + * Set zeros in the internals members + */ + void clear() { + m_Name.clear(); + m_Type.clear(); + m_Buffer = 0; + m_Size = 0; + m_Id = -1; + } +private: + void swap(UDLContext& c) noexcept { + std::swap(m_Name, c.m_Name); + std::swap(m_Type, c.m_Type); + std::swap(m_Id, c.m_Id); + std::swap(m_Buffer, c.m_Buffer); + std::swap(m_Size, c.m_Size); + } + std::string m_Name; // name of the layer instance + std::string m_Type; // The actual layer type + uint8_t* m_Buffer = nullptr; + size_t m_Size = 0; + int32_t m_Id = -1; +}; +/** @} */ /* end_addtogroup c_plus_plus_apis C++ */ + +}} + +#endif /* UDL_CONTEXT_HPP */ diff --git a/phonelibs/snpe/include/DlSystem/UDLFunc.hpp b/phonelibs/snpe/include/DlSystem/UDLFunc.hpp new file mode 100644 index 00000000000000..633ce985bf006b --- /dev/null +++ b/phonelibs/snpe/include/DlSystem/UDLFunc.hpp @@ -0,0 +1,84 @@ +//============================================================================== +// +// Copyright (c) 2015 Qualcomm Technologies, Inc. +// All Rights Reserved. +// Confidential and Proprietary - Qualcomm Technologies, Inc. +// +//============================================================================== + +#ifndef _UDL_FUNC_HPP_ +#define _UDL_FUNC_HPP_ + +#include + +#include "ZdlExportDefine.hpp" +#include + +namespace zdl { + namespace DlSystem { + class UDLContext; + } +} + +namespace zdl { namespace DlSystem { +/** @addtogroup c_plus_plus_apis C++ +@{ */ +/** + * @brief . + * + * Definition of UDLFactoyFunc, using/typedef and default FactoryFunction + * UDLBundle - a simple way to bundle func and cookie into one type + */ + + +/** + * @brief . + * + * Convenient typedef for user defined layer creation factory + * + * @param[out] void* Cookie - a user opaque data that was passed during SNPE's runtime's + * CreateInstance. SNPE's runtime is passing this back to the user. + * + * @param[out] DlSystem::UDLContext* - The specific Layer Description context what is passe + * SNPE runtime. + * + * @return IUDL* - a Concrete instance of IUDL derivative + */ +using UDLFactoryFunc = std::function; + +/** + * @brief . + * + * default UDL factory implementation + * + * @param[out] DlSystem::UDLContext* - The specific Layer Description context what is passe + * SNPE runtime. + * + * @param[out] void* Cookie - a user opaque data that was passed during SNPE's runtime's + * CreateInstance. SNPE's runtime is passing this back to the user. + * + * @return IUDL* - nullptr to indicate SNPE's runtime that there is no specific + * implementation for UDL. When SNPE's runtime sees nullptr as a return + * value from the factory, it will halt execution if model has an unknown layer + * + */ +inline ZDL_EXPORT zdl::DlSystem::IUDL* DefaultUDLFunc(void*, const zdl::DlSystem::UDLContext*) { return nullptr; } + +/** + * @brief . + * + * Simple struct to bundle 2 elements. + * A user defined cookie that would be returned for each + * IUDL call. The user can place anything there and the + * SNPE runtime will provide it back + */ +struct ZDL_EXPORT UDLBundle { + void *cookie = nullptr; + UDLFactoryFunc func = DefaultUDLFunc; +}; + +/** @} */ /* end_addtogroup c_plus_plus_apis C++ */ +}} + + +#endif // _UDL_FUNC_HPP_ diff --git a/phonelibs/snpe/include/DlSystem/UserBufferMap.hpp b/phonelibs/snpe/include/DlSystem/UserBufferMap.hpp new file mode 100644 index 00000000000000..a03ddfe1d11ad8 --- /dev/null +++ b/phonelibs/snpe/include/DlSystem/UserBufferMap.hpp @@ -0,0 +1,122 @@ +//============================================================================= +// +// Copyright (c) 2017 Qualcomm Technologies, Inc. +// All Rights Reserved. +// Confidential and Proprietary - Qualcomm Technologies, Inc. +// +//============================================================================= +#include +#include "ZdlExportDefine.hpp" +#include "StringList.hpp" + +#ifndef DL_SYSTEM_USER_BUFFER_MAP_HPP +#define DL_SYSTEM_USER_BUFFER_MAP_HPP + +namespace DlSystem +{ + // Forward declaration of UserBuffer map implementation. + class UserBufferMapImpl; +} + +namespace zdl +{ +namespace DlSystem +{ +class IUserBuffer; + +/** @addtogroup c_plus_plus_apis C++ +@{ */ + +/** + * @brief . + * + * A class representing the map of UserBuffer. + */ +class ZDL_EXPORT UserBufferMap final +{ +public: + + /** + * @brief . + * + * Creates a new empty UserBuffer map + */ + UserBufferMap(); + + /** + * copy constructor. + * @param[in] other object to copy. + */ + UserBufferMap(const UserBufferMap& other); + + /** + * assignment operator. + */ + UserBufferMap& operator=(const UserBufferMap& other); + + /** + * @brief Adds a name and the corresponding UserBuffer pointer + * to the map + * + * @param[in] name The name of the UserBuffer + * @param[in] userBuffer The pointer to the UserBuffer + * + * @note If a UserBuffer with the same name already exists, the new + * UserBuffer pointer would be updated. + */ + void add(const char *name, zdl::DlSystem::IUserBuffer *buffer); + + /** + * @brief Removes a mapping of one UserBuffer and its name by its name + * + * @param[in] name The name of UserBuffer to be removed + * + * @note If no UserBuffer with the specified name is found, nothing + * is done. + */ + void remove(const char *name) noexcept; + + /** + * @brief Returns the number of UserBuffers in the map + */ + size_t size() const noexcept; + + /** + * @brief . + * + * Removes all UserBuffers from the map + */ + void clear() noexcept; + + /** + * @brief Returns the UserBuffer given its name. + * + * @param[in] name The name of the UserBuffer to get. + * + * @return nullptr if no UserBuffer with the specified name is + * found; otherwise, a valid pointer to the UserBuffer. + */ + zdl::DlSystem::IUserBuffer* getUserBuffer(const char *name) const noexcept; + + /** + * @brief . + * + * Returns the names of all UserBuffers + * + * @return A list of UserBuffer names. + */ + zdl::DlSystem::StringList getUserBufferNames() const; + + ~UserBufferMap(); +private: + void swap(const UserBufferMap &other); + std::unique_ptr<::DlSystem::UserBufferMapImpl> m_UserBufferMapImpl; +}; +/** @} */ /* end_addtogroup c_plus_plus_apis C++ */ + +} // DlSystem namespace +} // zdl namespace + + +#endif // DL_SYSTEM_TENSOR_MAP_HPP + diff --git a/phonelibs/snpe/include/DlSystem/ZdlExportDefine.hpp b/phonelibs/snpe/include/DlSystem/ZdlExportDefine.hpp new file mode 100644 index 00000000000000..dd0704dd8c996d --- /dev/null +++ b/phonelibs/snpe/include/DlSystem/ZdlExportDefine.hpp @@ -0,0 +1,16 @@ +//============================================================================= +// +// Copyright (c) 2015 Qualcomm Technologies, Inc. +// All Rights Reserved. +// Confidential and Proprietary - Qualcomm Technologies, Inc. +// +//============================================================================= + +#ifndef _ZDL_EXPORT_DEFINE_HPP_ +#define _ZDL_EXPORT_DEFINE_HPP_ + +#ifndef ZDL_EXPORT +#define ZDL_EXPORT __attribute__((visibility("default"))) +#endif + +#endif diff --git a/phonelibs/snpe/include/SNPE/SNPE.hpp b/phonelibs/snpe/include/SNPE/SNPE.hpp new file mode 100644 index 00000000000000..ba84265b9663f8 --- /dev/null +++ b/phonelibs/snpe/include/SNPE/SNPE.hpp @@ -0,0 +1,239 @@ +//============================================================================== +// +// Copyright (c) 2015-2017 Qualcomm Technologies, Inc. +// All Rights Reserved. +// Confidential and Proprietary - Qualcomm Technologies, Inc. +// +//============================================================================== + +#ifndef _SNPE_SNPE_HPP_ +#define _SNPE_SNPE_HPP_ + +#include +#include + +#include "DlSystem/DlOptional.hpp" +#include "DlSystem/DlVersion.hpp" +#include "DlSystem/IBufferAttributes.hpp" +#include "DlSystem/ITensor.hpp" +#include "DlSystem/TensorShape.hpp" +#include "DlSystem/TensorMap.hpp" +#include "DlSystem/String.hpp" +#include "DlSystem/StringList.hpp" +#include "DlSystem/IUserBuffer.hpp" +#include "DlSystem/UserBufferMap.hpp" +#include "DlSystem/ZdlExportDefine.hpp" + +namespace zdl { + namespace SNPE + { + class SnpeRuntime; + } +} +namespace zdl { + namespace DiagLog + { + class IDiagLog; + } +} + +namespace zdl { namespace SNPE { +/** @addtogroup c_plus_plus_apis C++ +@{ */ + +/** + * @brief . + * + * The SNPE interface class definition + */ +class ZDL_EXPORT SNPE final +{ +public: + + // keep this undocumented to be hidden in doxygen using HIDE_UNDOC_MEMBERS + explicit SNPE(std::unique_ptr&& runtime) noexcept; + ~SNPE(); + + /** + * @brief Gets the names of input tensors to the network + * + * To support multiple input scenarios, where multiple tensors are + * passed through execute() in a TensorMap, each tensor needs to + * be uniquely named. The names of tensors can be retrieved + * through this function. + * + * In the case of a single input, one name will be returned. + * + * @note Note that because the returned value is an Optional list, + * the list must be verified as boolean true value before being + * dereferenced. + * + * @return An Optional List of input tensor names. + * + * @see zdl::DlSystem::Optional + */ + zdl::DlSystem::Optional + getInputTensorNames() const noexcept; + + /** + * @brief Gets the names of output tensors to the network + * + * @return List of output tensor names. + */ + zdl::DlSystem::Optional + getOutputTensorNames() const noexcept; + + /** + * @brief Processes the input data and returns the output + * + * @param[in] A map of tensors that contains the input data for + * each input. The names of tensors needs to be + * matched with names retrieved through + * getInputTensorNames() + * + * @param[in,out] An empty map of tensors that will contain the output + * data of potentially multiple layers (the key + * in the map is the layer name) upon return + * + * @note output tensormap has to be empty. To forward propagate + * and get results in user-supplied tensors, use + * executeWithSuppliedOutputTensors. + */ + bool execute(const zdl::DlSystem::TensorMap &input, + zdl::DlSystem::TensorMap &output) noexcept; + + /** + * @brief Processes the input data and returns the output + * + * @param[in] A single tensor contains the input data. + * + * @param[in,out] An empty map of tensors that will contain the output + * data of potentially multiple layers (the key + * in the map is the layer name) upon return + * + * @note output tensormap has to be empty. + */ + bool execute(const zdl::DlSystem::ITensor *input, + zdl::DlSystem::TensorMap &output) noexcept; + + /** + * @brief Processes the input data and returns the output, using + * user-supplied buffers + * + * @param[in] A map of UserBuffers that contains the input data for + * each input. The names of UserBuffers needs to be + * matched with names retrieved through + * getInputTensorNames() + * + * @param[in,out] A map of UserBuffers that will hold the output + * data of potentially multiple layers (the key + * in the map is the UserBuffer name) + * + * @note input and output UserBuffer maps must be fully pre-populated. with + * dimensions matching what the network expects. + * For example, if there are 5 output UserBuffers they all have to be + * present in map. + * + * Caller must guarantee that for the duration of execute(), the buffer + * stored in UserBuffer would remain valid. For more detail on buffer + * ownership and lifetime requirements, please refer to zdl::DlSystem::UserBuffer + * documentation. + */ + bool execute(const zdl::DlSystem::UserBufferMap &input, + const zdl::DlSystem::UserBufferMap &output) noexcept; + + /** + * @brief Returns the version string embedded at model conversion + * time. + * + * @return Model version string, which is a free-form string + * supplied at the time of the conversion + * + */ + zdl::DlSystem::String getModelVersion() const noexcept; + + /** + * @brief Returns the dimensions of the input data to the model in the + * form of TensorShape. The dimensions in TensorShape corresponds to + * what the tensor dimensions would need to be for an input tensor to + * the model. + * + * @param[in] layer input name. + * + * @note Note that this function only makes sense for networks + * that have a fixed input size. For networks in which the + * input size varies with each call of Execute(), this + * function should not be used. + * + * @note Because the returned type is an Optional instance, it must + * be verified as a boolean true value before being dereferenced. + * + * @return An Optional instance of TensorShape that maintains dimensions, + * matching the tensor dimensions for input to the model, + * where the last entry is the fastest varying dimension, etc. + * + * @see zdl::DlSystem::ITensor + * @see zdl::DlSystem::TensorShape + * @see zdl::DlSystem::Optional + */ + zdl::DlSystem::Optional + getInputDimensions() const noexcept; + zdl::DlSystem::Optional + getInputDimensions(const char *name) const noexcept; + + /** + * @brief Gets the output layer(s) for the network. + * + * Note that the output layers returned by this function may be + * different than those specified when the network was created + * via the zdl::SNPE::SNPEBuilder. For example, if the + * network was created in debug mode with no explicit output + * layers specified, this will contain all layers. + * + * @note Note that because the returned value is an Optional StringList, + * the list must be verified as a boolean true value before being + * dereferenced. + * + * @return A List of output layer names. + * + * @see zdl::DlSystem::Optional + */ + zdl::DlSystem::Optional + getOutputLayerNames() const noexcept; + + /** + * @brief Returns attributes of buffers used to feed input tensors and receive result from output tensors. + * + * @param[in] Tensor name. + * + * @return BufferAttributes of input/output tensor named + */ + zdl::DlSystem::Optional getInputOutputBufferAttributes(const char *name) const noexcept; + + zdl::DlSystem::Optional getInputOutputBufferAttributesTf8(const char *name) const noexcept; + + /** + * @brief . + * + * Get the diagnostic logging interface + * + * @note Note that because the returned type is an Optional instance, + * it must be verified as a boolean true value before being + * dereferenced. + * + * @see zdl::DlSystem::Optional + */ + zdl::DlSystem::Optional + getDiagLogInterface() noexcept; + +private: + SNPE(const SNPE&) = delete; + SNPE& operator=(const SNPE&) = delete; + + std::unique_ptr m_Runtime; +}; + +/** @} */ /* end_addtogroup c_plus_plus_apis C++ */ +}} + +#endif diff --git a/phonelibs/snpe/include/SNPE/SNPEBuilder.hpp b/phonelibs/snpe/include/SNPE/SNPEBuilder.hpp new file mode 100644 index 00000000000000..13e80e8c1a703d --- /dev/null +++ b/phonelibs/snpe/include/SNPE/SNPEBuilder.hpp @@ -0,0 +1,210 @@ +//============================================================================== +// +// Copyright (c) 2017 Qualcomm Technologies, Inc. +// All Rights Reserved. +// Confidential and Proprietary - Qualcomm Technologies, Inc. +// +//============================================================================== + +#ifndef _SNPE_BUILDER_HPP_ +#define _SNPE_BUILDER_HPP_ + +#include "SNPE/SNPE.hpp" +#include "DlSystem/DlEnums.hpp" +#include "DlSystem/UDLFunc.hpp" +#include "DlSystem/DlOptional.hpp" +#include "DlSystem/TensorShapeMap.hpp" +#include "DlSystem/PlatformConfig.hpp" + +namespace zdl { + namespace DlContainer + { + class IDlContainer; + } +} + +struct SNPEBuilderImpl; + + +namespace zdl { namespace SNPE { +/** @addtogroup c_plus_plus_apis C++ +@{ */ + +/** + * The builder class for creating SNPE objects. + * Not meant to be extended. + */ +class ZDL_EXPORT SNPEBuilder final +{ +private: + std::unique_ptr<::SNPEBuilderImpl> m_Impl; +public: + + /** + * @brief Constructor of NeuralNetwork Builder with a supplied model. + * + * @param[in] container A container holding the model. + * + * @return A new instance of a SNPEBuilder object + * that can be used to configure and build + * an instance of SNPE. + * + */ + explicit SNPEBuilder( + zdl::DlContainer::IDlContainer* container); + ~SNPEBuilder(); + + /** + * @brief Sets the runtime processor. + * + * @param[in] targetRuntimeProcessor The target runtime. + * + * @return The current instance of SNPEBuilder. + */ + SNPEBuilder& setRuntimeProcessor( + zdl::DlSystem::Runtime_t targetRuntimeProcessor); + + /** + * @brief Requests a performance profile. + * + * @param[in] targetRuntimeProfile The target performance profile. + * + * @return The current instance of SNPEBuilder. + */ + SNPEBuilder& setPerformanceProfile( + zdl::DlSystem::PerformanceProfile_t performanceProfile); + + /** + * @brief Sets a preference for execution priority. + * + * This allows the caller to give coarse hint to SNPE runtime + * about the priority of the network. SNPE runtime is free to use + * this information to co-ordinate between different workloads + * that may or may not extend beyond SNPE. + * + * @param[in] ExecutionPriorityHint_t The target performance profile. + * + * @return The current instance of SNPEBuilder. + */ + SNPEBuilder& setExecutionPriorityHint( + zdl::DlSystem::ExecutionPriorityHint_t priority); + + /** + * @brief Sets the layers that will generate output. + * + * @param[in] outputLayerNames List of layer names to + * output. An empty list will + * result in only the final + * layer of the model being + * the output layer. The list + * will be copied. + * + * @return The current instance of SNPEBuilder. + */ + SNPEBuilder& setOutputLayers( + const zdl::DlSystem::StringList& outputLayerNames); + + /** + * @brief Passes in a User-defined layer. + * + * @param udlBundle Bundle of udl factory function and a cookie + * + * @return The current instance of SNPEBuilder. + */ + SNPEBuilder& setUdlBundle( + zdl::DlSystem::UDLBundle udlBundle); + + /** + * @brief Sets whether this neural network will perform inference with + * input from user-supplied buffers, and write output to user-supplied + * buffers. Default behaviour is to use tensors created by + * ITensorFactory. + * + * @param[in] bufferMode Whether to use user-supplied buffer or not. + * + * @return The current instance of SNPEBuilder. + */ + SNPEBuilder& setUseUserSuppliedBuffers( + bool bufferMode); + + /** + * @brief Sets the debug mode of the runtime. + * + * @param[in] debugMode This enables debug mode for the runtime. It + * does two things. For an empty + * outputLayerNames list, all layers will be + * output. It might also disable some internal + * runtime optimizations (e.g., some networks + * might be optimized by combining layers, + * etc.). + * + * @return The current instance of SNPEBuilder. + */ + SNPEBuilder& setDebugMode( + bool debugMode); + + /** + * @brief Sets the mode of CPU fallback functionality. + * + * @param[in] mode This flag enables/disables the functionality + * of CPU fallback. When the CPU fallback + * functionality is enabled, layers in model that + * violates runtime constraints will run on CPU + * while the rest of non-violating layers will + * run on the chosen runtime processor. In + * disabled mode, models with layers violating + * runtime constraints will NOT run on the chosen + * runtime processor and will result in runtime + * exception. By default, the functionality is + * enabled. + * + * @return The current instance of SNPEBuilder. + */ + SNPEBuilder& setCPUFallbackMode( + bool mode); + + + /** + * @brief Sets network's input dimensions to enable resizing of + * the spatial dimensions of each layer for fully convolutional networks, + * and the batch dimension for all networks. + * + * @param[in] tensorShapeMap The map of input names and their new dimensions. + * The new dimensions overwrite the input dimensions + * embedded in the model and then resize each layer + * of the model. If the model contains + * layers whose dimensions cannot be resized e.g FullyConnected, + * exception will be thrown when SNPE instance is actually built. + * In general the batch dimension is always resizable. + * After resizing of layers' dimensions in model based + * on new input dimensions, the new model is revalidated + * against all runtime constraints, whose failures may + * result in cpu fallback situation. + * + * @return The current instance of SNPEBuilder. + */ + SNPEBuilder& setInputDimensions(const zdl::DlSystem::TensorShapeMap& inputDimensionsMap); + + /** + * @brief Returns an instance of SNPE based on the current parameters. + * + * @return A new instance of a SNPE object that can be used + * to execute models or null if any errors occur. + */ + std::unique_ptr build() noexcept; + + /** + * @brief Sets the platform configuration. + * + * @param[in] platformConfig The platform configuration. + * + * @return The current instance of SNPEBuilder. + */ + SNPEBuilder& setPlatformConfig(const zdl::DlSystem::PlatformConfig& platformConfig); + +}; +/** @} */ /* end_addtogroup c_plus_plus_apis C++ */ + +}} + +#endif diff --git a/phonelibs/snpe/include/SNPE/SNPEFactory.hpp b/phonelibs/snpe/include/SNPE/SNPEFactory.hpp new file mode 100644 index 00000000000000..bb9921afe10591 --- /dev/null +++ b/phonelibs/snpe/include/SNPE/SNPEFactory.hpp @@ -0,0 +1,104 @@ +//============================================================================== +// +// Copyright (c) 2015-2016 Qualcomm Technologies, Inc. +// All Rights Reserved. +// Confidential and Proprietary - Qualcomm Technologies, Inc. +// +//============================================================================== + +#ifndef _SNPE_FACTORY_HPP_ +#define _SNPE_FACTORY_HPP_ + +#include "SNPE/SNPE.hpp" +#include "DlSystem/DlEnums.hpp" +#include "DlSystem/UDLFunc.hpp" +#include "DlSystem/ZdlExportDefine.hpp" +#include "DlSystem/DlOptional.hpp" + +namespace zdl { + namespace DlSystem + { + class ITensorFactory; + class IUserBufferFactory; + } + namespace DlContainer + { + class IDlContainer; + } +} + + + +namespace zdl { namespace SNPE { +/** @addtogroup c_plus_plus_apis C++ +@{ */ + +/** + * The factory class for creating SNPE objects. + * + */ +class ZDL_EXPORT SNPEFactory +{ +public: + + /** + * Indicates whether the supplied runtime is available on the + * current platform. + * + * @param[in] runtime The target runtime to check. + * + * @return True if the supplied runtime is available; false, + * otherwise. + */ + static bool isRuntimeAvailable(zdl::DlSystem::Runtime_t runtime); + + /** + * Gets a reference to the tensor factory. + * + * @return A reference to the tensor factory. + */ + static zdl::DlSystem::ITensorFactory& getTensorFactory(); + + /** + * Gets a reference to the UserBuffer factory. + * + * @return A reference to the UserBuffer factory. + */ + static zdl::DlSystem::IUserBufferFactory& getUserBufferFactory(); + + /** + * Gets the version of the SNPE library. + * + * @return Version of the SNPE library. + * + */ + static zdl::DlSystem::Version_t getLibraryVersion(); + + /** + * Set the SNPE storage location for all SNPE instances in this + * process. Note that this may only be called once, and if so + * must be called before creating any SNPE instances. + * + * @param[in] storagePath Absolute path to a directory which SNPE may + * use for caching and other storage purposes. + * + * @return True if the supplied path was succesfully set as + * the SNPE storage location, false otherwise. + */ + static bool setSNPEStorageLocation(const char* storagePath); + + /** + * Indicates whether the OpenGL and OpenCL interoperability is supported + * on GPU platform. + * + * @return True if the OpenGL and OpenCl interop is supported; false, + * otherwise. + */ + static bool isGLCLInteropSupported(); +}; + +/** @} */ /* end_addtogroup c_plus_plus_apis C++ */ +}} + + +#endif diff --git a/phonelibs/snpe/lib/.gitattributes b/phonelibs/snpe/lib/.gitattributes new file mode 100644 index 00000000000000..72b93e3219e1ce --- /dev/null +++ b/phonelibs/snpe/lib/.gitattributes @@ -0,0 +1,9 @@ +libc++_shared.so filter=lfs diff=lfs merge=lfs -text +libsnpe_adsp.so filter=lfs diff=lfs merge=lfs -text +libsnpe_dsp_domains.so filter=lfs diff=lfs merge=lfs -text +libsnpe_dsp_domains_system.so filter=lfs diff=lfs merge=lfs -text +libsnpe_dsp_domains_v2.so filter=lfs diff=lfs merge=lfs -text +libSNPE_G.so filter=lfs diff=lfs merge=lfs -text +libSNPE.so filter=lfs diff=lfs merge=lfs -text +libsymphony-cpu.so filter=lfs diff=lfs merge=lfs -text +libsymphonypower.so filter=lfs diff=lfs merge=lfs -text diff --git a/phonelibs/snpe/lib/libSNPE.so b/phonelibs/snpe/lib/libSNPE.so new file mode 100644 index 00000000000000..5cee2145e2d1db --- /dev/null +++ b/phonelibs/snpe/lib/libSNPE.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:2df46d2204a3883ba2d3f4481d5d813982033a267ee69f239d146434ac0543a8 +size 5227664 diff --git a/phonelibs/snpe/lib/libSNPE_G.so b/phonelibs/snpe/lib/libSNPE_G.so new file mode 100644 index 00000000000000..dc2dc388de1000 --- /dev/null +++ b/phonelibs/snpe/lib/libSNPE_G.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:1901c3f88ae18db1c10ee327c0060974a7b2e3b84b98bb4ddec2ffa89290da81 +size 4179504 diff --git a/phonelibs/snpe/lib/libc++_shared.so b/phonelibs/snpe/lib/libc++_shared.so new file mode 100644 index 00000000000000..ee7fea00e03671 --- /dev/null +++ b/phonelibs/snpe/lib/libc++_shared.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:e689b38c7e47b309a04b8850e93d68545eb7813498680e68a9ea20bae47efb89 +size 6624168 diff --git a/phonelibs/snpe/lib/libsnpe_adsp.so b/phonelibs/snpe/lib/libsnpe_adsp.so new file mode 100644 index 00000000000000..5a9794c7717d6f --- /dev/null +++ b/phonelibs/snpe/lib/libsnpe_adsp.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:aa79ec0b7f1d286b642a29468e93db82e343d2c62f0aae2594390c31a0a01548 +size 17720 diff --git a/phonelibs/snpe/lib/libsnpe_dsp_domains.so b/phonelibs/snpe/lib/libsnpe_dsp_domains.so new file mode 100644 index 00000000000000..f005705a5288c0 --- /dev/null +++ b/phonelibs/snpe/lib/libsnpe_dsp_domains.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:bb3a6baf73d5977e4a30cf60429f4feb765b9bd8d3efebd29ff82ba73ff34201 +size 17640 diff --git a/phonelibs/snpe/lib/libsnpe_dsp_domains_system.so b/phonelibs/snpe/lib/libsnpe_dsp_domains_system.so new file mode 100644 index 00000000000000..734638007c22fc --- /dev/null +++ b/phonelibs/snpe/lib/libsnpe_dsp_domains_system.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:47d0916a6b322330620be184c36bae7681678287408c96360d70d40f90d6b41e +size 17640 diff --git a/phonelibs/snpe/lib/libsnpe_dsp_domains_v2.so b/phonelibs/snpe/lib/libsnpe_dsp_domains_v2.so new file mode 100644 index 00000000000000..74736813ebbea3 --- /dev/null +++ b/phonelibs/snpe/lib/libsnpe_dsp_domains_v2.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:c64301531edbb3471b70df6dc31901a5de9d907649db4948577d0cfc9b4016bd +size 17648 diff --git a/phonelibs/snpe/lib/libsymphony-cpu.so b/phonelibs/snpe/lib/libsymphony-cpu.so new file mode 100755 index 00000000000000..0d45f2f603d13e --- /dev/null +++ b/phonelibs/snpe/lib/libsymphony-cpu.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:40990fbd09c217301cb5a89c20e401e1dcb9a86b99a7d9436cf2c995ad15952e +size 518000 diff --git a/phonelibs/snpe/lib/libsymphonypower.so b/phonelibs/snpe/lib/libsymphonypower.so new file mode 100755 index 00000000000000..f8a6771749162c --- /dev/null +++ b/phonelibs/snpe/lib/libsymphonypower.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:cf93a6e8ab2a1df4ab3fcac92b277489be8258682b7e15884b55f2b21bfacb29 +size 54960 diff --git a/phonelibs/zlib/build.txt b/phonelibs/zlib/build.txt new file mode 100644 index 00000000000000..b67f9cd57ac853 --- /dev/null +++ b/phonelibs/zlib/build.txt @@ -0,0 +1,5 @@ +# with neos tree +cd ~/android/system +mka libz + +cp ~/android/system/out/target/product/oneplus3/obj/STATIC_LIBRARIES/libz_intermediates/libz.a lib/ diff --git a/phonelibs/zlib/lib/libz.a b/phonelibs/zlib/lib/libz.a new file mode 100644 index 00000000000000..d2170d8b87eb3b Binary files /dev/null and b/phonelibs/zlib/lib/libz.a differ diff --git a/phonelibs/zmq/aarch64-linux/bin/curve_keygen b/phonelibs/zmq/aarch64-linux/bin/curve_keygen new file mode 100755 index 00000000000000..3d76817f73c7f9 Binary files /dev/null and b/phonelibs/zmq/aarch64-linux/bin/curve_keygen differ diff --git a/phonelibs/zmq/aarch64-linux/include/czmq.h b/phonelibs/zmq/aarch64-linux/include/czmq.h new file mode 100644 index 00000000000000..dbf1fe5e40a517 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/include/czmq.h @@ -0,0 +1,39 @@ +/* ========================================================================= + CZMQ - a high-level binding in C for ZeroMQ + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= + + "Tell them I was a writer. + A maker of software. + A humanist. A father. + And many things. + But above all, a writer. + Thank You. :) + - Pieter Hintjens +*/ + +#ifndef __CZMQ_H_INCLUDED__ +#define __CZMQ_H_INCLUDED__ + +// These are signatures for handler functions that customize the +// behavior of CZMQ containers. These are shared between all CZMQ +// container types. + +// -- destroy an item +typedef void (czmq_destructor) (void **item); +// -- duplicate an item +typedef void *(czmq_duplicator) (const void *item); +// - compare two items, for sorting +typedef int (czmq_comparator) (const void *item1, const void *item2); + +// Include the project library file +#include "czmq_library.h" + +#endif diff --git a/phonelibs/zmq/aarch64-linux/include/czmq_library.h b/phonelibs/zmq/aarch64-linux/include/czmq_library.h new file mode 100644 index 00000000000000..89dc4eb9179dd6 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/include/czmq_library.h @@ -0,0 +1,178 @@ +/* ========================================================================= + czmq - generated layer of public API + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + +################################################################################ +# THIS FILE IS 100% GENERATED BY ZPROJECT; DO NOT EDIT EXCEPT EXPERIMENTALLY # +# Read the zproject/README.md for information about making permanent changes. # +################################################################################ + ========================================================================= +*/ + +#ifndef CZMQ_LIBRARY_H_INCLUDED +#define CZMQ_LIBRARY_H_INCLUDED + +// Set up environment for the application +#include "czmq_prelude.h" + +// External dependencies +#include + +// CZMQ version macros for compile-time API detection +#define CZMQ_VERSION_MAJOR 4 +#define CZMQ_VERSION_MINOR 0 +#define CZMQ_VERSION_PATCH 2 + +#define CZMQ_MAKE_VERSION(major, minor, patch) \ + ((major) * 10000 + (minor) * 100 + (patch)) +#define CZMQ_VERSION \ + CZMQ_MAKE_VERSION(CZMQ_VERSION_MAJOR, CZMQ_VERSION_MINOR, CZMQ_VERSION_PATCH) + +#if defined (__WINDOWS__) +# if defined CZMQ_STATIC +# define CZMQ_EXPORT +# elif defined CZMQ_INTERNAL_BUILD +# if defined DLL_EXPORT +# define CZMQ_EXPORT __declspec(dllexport) +# else +# define CZMQ_EXPORT +# endif +# elif defined CZMQ_EXPORTS +# define CZMQ_EXPORT __declspec(dllexport) +# else +# define CZMQ_EXPORT __declspec(dllimport) +# endif +# define CZMQ_PRIVATE +#else +# define CZMQ_EXPORT +# if (defined __GNUC__ && __GNUC__ >= 4) || defined __INTEL_COMPILER +# define CZMQ_PRIVATE __attribute__ ((visibility ("hidden"))) +# else +# define CZMQ_PRIVATE +# endif +#endif + +// Opaque class structures to allow forward references +// These classes are stable or legacy and built in all releases +typedef struct _zactor_t zactor_t; +#define ZACTOR_T_DEFINED +typedef struct _zarmour_t zarmour_t; +#define ZARMOUR_T_DEFINED +typedef struct _zcert_t zcert_t; +#define ZCERT_T_DEFINED +typedef struct _zcertstore_t zcertstore_t; +#define ZCERTSTORE_T_DEFINED +typedef struct _zchunk_t zchunk_t; +#define ZCHUNK_T_DEFINED +typedef struct _zclock_t zclock_t; +#define ZCLOCK_T_DEFINED +typedef struct _zconfig_t zconfig_t; +#define ZCONFIG_T_DEFINED +typedef struct _zdigest_t zdigest_t; +#define ZDIGEST_T_DEFINED +typedef struct _zdir_t zdir_t; +#define ZDIR_T_DEFINED +typedef struct _zdir_patch_t zdir_patch_t; +#define ZDIR_PATCH_T_DEFINED +typedef struct _zfile_t zfile_t; +#define ZFILE_T_DEFINED +typedef struct _zframe_t zframe_t; +#define ZFRAME_T_DEFINED +typedef struct _zhash_t zhash_t; +#define ZHASH_T_DEFINED +typedef struct _zhashx_t zhashx_t; +#define ZHASHX_T_DEFINED +typedef struct _ziflist_t ziflist_t; +#define ZIFLIST_T_DEFINED +typedef struct _zlist_t zlist_t; +#define ZLIST_T_DEFINED +typedef struct _zlistx_t zlistx_t; +#define ZLISTX_T_DEFINED +typedef struct _zloop_t zloop_t; +#define ZLOOP_T_DEFINED +typedef struct _zmsg_t zmsg_t; +#define ZMSG_T_DEFINED +typedef struct _zpoller_t zpoller_t; +#define ZPOLLER_T_DEFINED +typedef struct _zsock_t zsock_t; +#define ZSOCK_T_DEFINED +typedef struct _zstr_t zstr_t; +#define ZSTR_T_DEFINED +typedef struct _zuuid_t zuuid_t; +#define ZUUID_T_DEFINED +typedef struct _zauth_t zauth_t; +#define ZAUTH_T_DEFINED +typedef struct _zbeacon_t zbeacon_t; +#define ZBEACON_T_DEFINED +typedef struct _zgossip_t zgossip_t; +#define ZGOSSIP_T_DEFINED +typedef struct _zmonitor_t zmonitor_t; +#define ZMONITOR_T_DEFINED +typedef struct _zproxy_t zproxy_t; +#define ZPROXY_T_DEFINED +typedef struct _zrex_t zrex_t; +#define ZREX_T_DEFINED +typedef struct _zsys_t zsys_t; +#define ZSYS_T_DEFINED +// Draft classes are by default not built in stable releases +#ifdef CZMQ_BUILD_DRAFT_API +typedef struct _zproc_t zproc_t; +#define ZPROC_T_DEFINED +typedef struct _ztimerset_t ztimerset_t; +#define ZTIMERSET_T_DEFINED +typedef struct _ztrie_t ztrie_t; +#define ZTRIE_T_DEFINED +#endif // CZMQ_BUILD_DRAFT_API + + +// Public classes, each with its own header file +#include "zactor.h" +#include "zarmour.h" +#include "zcert.h" +#include "zcertstore.h" +#include "zchunk.h" +#include "zclock.h" +#include "zconfig.h" +#include "zdigest.h" +#include "zdir.h" +#include "zdir_patch.h" +#include "zfile.h" +#include "zframe.h" +#include "zhash.h" +#include "zhashx.h" +#include "ziflist.h" +#include "zlist.h" +#include "zlistx.h" +#include "zloop.h" +#include "zmsg.h" +#include "zpoller.h" +#include "zsock.h" +#include "zstr.h" +#include "zuuid.h" +#include "zauth.h" +#include "zbeacon.h" +#include "zgossip.h" +#include "zmonitor.h" +#include "zproxy.h" +#include "zrex.h" +#include "zsys.h" +#ifdef CZMQ_BUILD_DRAFT_API +#include "zproc.h" +#include "ztimerset.h" +#include "ztrie.h" +#endif // CZMQ_BUILD_DRAFT_API + +#endif +/* +################################################################################ +# THIS FILE IS 100% GENERATED BY ZPROJECT; DO NOT EDIT EXCEPT EXPERIMENTALLY # +# Read the zproject/README.md for information about making permanent changes. # +################################################################################ +*/ diff --git a/phonelibs/zmq/aarch64-linux/include/czmq_prelude.h b/phonelibs/zmq/aarch64-linux/include/czmq_prelude.h new file mode 100644 index 00000000000000..534f47023cc756 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/include/czmq_prelude.h @@ -0,0 +1,647 @@ +/* ========================================================================= + czmq_prelude.h - CZMQ environment + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __CZMQ_PRELUDE_H_INCLUDED__ +#define __CZMQ_PRELUDE_H_INCLUDED__ + +//- Establish the compiler and computer system ------------------------------ +/* + * Defines zero or more of these symbols, for use in any non-portable + * code: + * + * __WINDOWS__ Microsoft C/C++ with Windows calls + * __MSDOS__ System is MS-DOS (set if __WINDOWS__ set) + * __VMS__ System is VAX/VMS or Alpha/OpenVMS + * __UNIX__ System is UNIX + * __OS2__ System is OS/2 + * + * __IS_32BIT__ OS/compiler is 32 bits + * __IS_64BIT__ OS/compiler is 64 bits + * + * When __UNIX__ is defined, we also define exactly one of these: + * + * __UTYPE_AUX Apple AUX + * __UTYPE_BEOS BeOS + * __UTYPE_BSDOS BSD/OS + * __UTYPE_DECALPHA Digital UNIX (Alpha) + * __UTYPE_IBMAIX IBM RS/6000 AIX + * __UTYPE_FREEBSD FreeBSD + * __UTYPE_HPUX HP/UX + * __UTYPE_ANDROID Android + * __UTYPE_LINUX Linux + * __UTYPE_GNU GNU/Hurd + * __UTYPE_MIPS MIPS (BSD 4.3/System V mixture) + * __UTYPE_NETBSD NetBSD + * __UTYPE_NEXT NeXT + * __UTYPE_OPENBSD OpenBSD + * __UTYPE_OSX Apple Macintosh OS X + * __UTYPE_IOS Apple iOS + * __UTYPE_QNX QNX + * __UTYPE_IRIX Silicon Graphics IRIX + * __UTYPE_SINIX SINIX-N (Siemens-Nixdorf Unix) + * __UTYPE_SUNOS SunOS + * __UTYPE_SUNSOLARIS Sun Solaris + * __UTYPE_UNIXWARE SCO UnixWare + * ... these are the ones I know about so far. + * __UTYPE_GENERIC Any other UNIX + * + * When __VMS__ is defined, we may define one or more of these: + * + * __VMS_XOPEN Supports XOPEN functions + */ + +#if (defined (__64BIT__) || defined (__x86_64__)) +# define __IS_64BIT__ // May have 64-bit OS/compiler +#else +# define __IS_32BIT__ // Else assume 32-bit OS/compiler +#endif + +#if (defined WIN32 || defined _WIN32) +# undef __WINDOWS__ +# define __WINDOWS__ +# undef __MSDOS__ +# define __MSDOS__ +#endif + +#if (defined WINDOWS || defined _WINDOWS || defined __WINDOWS__) +# undef __WINDOWS__ +# define __WINDOWS__ +# undef __MSDOS__ +# define __MSDOS__ +// Stop cheeky warnings about "deprecated" functions like fopen +# if _MSC_VER >= 1500 +# undef _CRT_SECURE_NO_DEPRECATE +# define _CRT_SECURE_NO_DEPRECATE +# pragma warning(disable: 4996) +# endif +#endif + +// MSDOS Microsoft C +// _MSC_VER Microsoft C +#if (defined (MSDOS) || defined (_MSC_VER)) +# undef __MSDOS__ +# define __MSDOS__ +# if (defined (_DEBUG) && !defined (DEBUG)) +# define DEBUG +# endif +#endif + +#if (defined (__EMX__) && defined (__i386__)) +# undef __OS2__ +# define __OS2__ +#endif + +// VMS VAX C (VAX/VMS) +// __VMS Dec C (Alpha/OpenVMS) +// __vax__ gcc +#if (defined (VMS) || defined (__VMS) || defined (__vax__)) +# undef __VMS__ +# define __VMS__ +# if (__VMS_VER >= 70000000) +# define __VMS_XOPEN +# endif +#endif + +// Try to define a __UTYPE_xxx symbol... +// unix SunOS at least +// __unix__ gcc +// _POSIX_SOURCE is various UNIX systems, maybe also VAX/VMS +#if (defined (unix) || defined (__unix__) || defined (_POSIX_SOURCE)) +# if (!defined (__VMS__)) +# undef __UNIX__ +# define __UNIX__ +# if (defined (__alpha)) // Digital UNIX is 64-bit +# undef __IS_32BIT__ +# define __IS_64BIT__ +# define __UTYPE_DECALPHA +# endif +# endif +#endif + +#if (defined (_AUX)) +# define __UTYPE_AUX +# define __UNIX__ +#elif (defined (__BEOS__)) +# define __UTYPE_BEOS +# define __UNIX__ +#elif (defined (__hpux)) +# define __UTYPE_HPUX +# define __UNIX__ +# define _INCLUDE_HPUX_SOURCE +# define _INCLUDE_XOPEN_SOURCE +# define _INCLUDE_POSIX_SOURCE +#elif (defined (_AIX) || defined (AIX)) +# define __UTYPE_IBMAIX +# define __UNIX__ +#elif (defined (BSD) || defined (bsd)) +# define __UTYPE_BSDOS +# define __UNIX__ +#elif (defined (__ANDROID__)) +# define __UTYPE_ANDROID +# define __UNIX__ +#elif (defined (LINUX) || defined (linux) || defined (__linux__)) +# define __UTYPE_LINUX +# define __UNIX__ +# ifndef __NO_CTYPE +# define __NO_CTYPE // Suppress warnings on tolower() +# endif +# ifndef _DEFAULT_SOURCE +# define _DEFAULT_SOURCE // Include stuff from 4.3 BSD Unix +# endif +#elif (defined (__GNU__)) +# define __UTYPE_GNU +# define __UNIX__ +#elif (defined (Mips)) +# define __UTYPE_MIPS +# define __UNIX__ +#elif (defined (FreeBSD) || defined (__FreeBSD__)) +# define __UTYPE_FREEBSD +# define __UNIX__ +#elif (defined (NetBSD) || defined (__NetBSD__)) +# define __UTYPE_NETBSD +# define __UNIX__ +#elif (defined (OpenBSD) || defined (__OpenBSD__)) +# define __UTYPE_OPENBSD +# define __UNIX__ +#elif (defined (APPLE) || defined (__APPLE__)) +# include +# define __UNIX__ +# if TARGET_OS_IPHONE || TARGET_IPHONE_SIMULATOR +# define __UTYPE_IOS +# else +# define __UTYPE_OSX +# endif +#elif (defined (NeXT)) +# define __UTYPE_NEXT +# define __UNIX__ +#elif (defined (__QNX__)) +# define __UTYPE_QNX +# define __UNIX__ +#elif (defined (sgi)) +# define __UTYPE_IRIX +# define __UNIX__ +#elif (defined (sinix)) +# define __UTYPE_SINIX +# define __UNIX__ +#elif (defined (SOLARIS) || defined (__SVR4)) || defined (SVR4) +# define __UTYPE_SUNSOLARIS +# define __UNIX__ +#elif (defined (SUNOS) || defined (SUN) || defined (sun)) +# define __UTYPE_SUNOS +# define __UNIX__ +#elif (defined (__USLC__) || defined (UnixWare)) +# define __UTYPE_UNIXWARE +# define __UNIX__ +#elif (defined (__CYGWIN__)) +# define __UTYPE_CYGWIN +# define __UNIX__ +#elif (defined (__UNIX__)) +# define __UTYPE_GENERIC +#endif + +//- Always include ZeroMQ headers ------------------------------------------- + +#include "zmq.h" +#if (ZMQ_VERSION < ZMQ_MAKE_VERSION (4, 2, 0)) +# include "zmq_utils.h" +#endif + +//- Standard ANSI include files --------------------------------------------- + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +//- System-specific include files ------------------------------------------- + +#if (defined (__MSDOS__)) +# if (defined (__WINDOWS__)) +# if (_WIN32_WINNT < 0x0600) +# undef _WIN32_WINNT +# define _WIN32_WINNT 0x0600 +# endif +# if (!defined (FD_SETSIZE)) +# define FD_SETSIZE 1024 // Max. filehandles/sockets +# endif +# include +# include +# include +# include +# include // For getnameinfo () +# include // For GetAdaptersAddresses () +# endif +# include +# include +# include +# include +# include +# include +# include +# include +#endif + +#if (defined (__UNIX__)) +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include // Let CZMQ build with libzmq/3.x +# include // Must come before arpa/inet.h +# if (!defined (__UTYPE_ANDROID)) && (!defined (__UTYPE_IBMAIX)) \ + && (!defined (__UTYPE_HPUX)) +# include +# endif +# if defined (__UTYPE_SUNSOLARIS) || defined (__UTYPE_SUNOS) +# include +# endif +# if (!defined (__UTYPE_BEOS)) +# include +# if (!defined (TCP_NODELAY)) +# include +# endif +# endif +# if (defined (__UTYPE_IBMAIX) || defined(__UTYPE_QNX)) +# include +# endif +# if (defined (__UTYPE_BEOS)) +# include +# endif +# if ((defined (_XOPEN_REALTIME) && (_XOPEN_REALTIME >= 1)) \ + || (defined (_POSIX_VERSION) && (_POSIX_VERSION >= 199309L))) +# include +# endif +# if (defined (__UTYPE_OSX) || defined (__UTYPE_IOS)) +# include +# include // For monotonic clocks +# endif +# if (defined (__UTYPE_OSX)) +# include // For _NSGetEnviron() +# endif +# if (defined (__UTYPE_ANDROID)) +# include +# endif +# if (defined (__UTYPE_LINUX) && defined (HAVE_LIBSYSTEMD)) +# include +# endif +#endif + +#if (defined (__VMS__)) +# if (!defined (vaxc)) +# include // Not provided by Vax C +# endif +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +#endif + +#if (defined (__OS2__)) +# include // Required near top +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include // Must come before arpa/inet.h +# include +# include +# if (!defined (TCP_NODELAY)) +# include +# endif +#endif + +// Add missing defines for non-POSIX systems +#ifndef S_IRUSR +# define S_IRUSR S_IREAD +#endif +#ifndef S_IWUSR +# define S_IWUSR S_IWRITE +#endif +#ifndef S_ISDIR +# define S_ISDIR(m) (((m) & S_IFDIR) != 0) +#endif +#ifndef S_ISREG +# define S_ISREG(m) (((m) & S_IFREG) != 0) +#endif + + +//- Check compiler data type sizes ------------------------------------------ + +#if (UCHAR_MAX != 0xFF) +# error "Cannot compile: must change definition of 'byte'." +#endif +#if (USHRT_MAX != 0xFFFFU) +# error "Cannot compile: must change definition of 'dbyte'." +#endif +#if (UINT_MAX != 0xFFFFFFFFU) +# error "Cannot compile: must change definition of 'qbyte'." +#endif + +//- Data types -------------------------------------------------------------- + +typedef unsigned char byte; // Single unsigned byte = 8 bits +typedef unsigned short dbyte; // Double byte = 16 bits +typedef unsigned int qbyte; // Quad byte = 32 bits +typedef struct sockaddr_in inaddr_t; // Internet socket address structure +typedef struct sockaddr_in6 in6addr_t; // Internet 6 socket address structure + +// Common structure to hold inaddr_t and in6addr_t with length +typedef struct { + union { + inaddr_t __addr; // IPv4 address + in6addr_t __addr6; // IPv6 address + } __inaddr_u; +#define ipv4addr __inaddr_u.__addr +#define ipv6addr __inaddr_u.__addr6 + int inaddrlen; +} inaddr_storage_t; + +//- Inevitable macros ------------------------------------------------------- + +#define streq(s1,s2) (!strcmp ((s1), (s2))) +#define strneq(s1,s2) (strcmp ((s1), (s2))) + +// Provide random number from 0..(num-1) +// Note that (at least in Solaris) while rand() returns an int limited by +// RAND_MAX, random() returns a 32-bit value all filled with random bits. +#if (defined (__WINDOWS__)) || (defined (__UTYPE_IBMAIX)) \ + || (defined (__UTYPE_HPUX)) || (defined (__UTYPE_SUNOS)) || (defined (__UTYPE_SOLARIS)) +# define randof(num) (int) ((float) (num) * rand () / (RAND_MAX + 1.0)) +#else +# if defined(RAND_MAX) +# define randof(num) (int) ((float) (num) * (random () % RAND_MAX) / (RAND_MAX + 1.0)) +# else +# define randof(num) (int) ((float) (num) * (uint32_t)random () / (UINT32_MAX + 1.0)) +# endif +#endif + +// Windows MSVS doesn't have stdbool +#if (defined (_MSC_VER)) +# if (!defined (__cplusplus) && (!defined (true))) +# define true 1 +# define false 0 + typedef char bool; +# endif +#else +# include +#endif + +//- A number of POSIX and C99 keywords and data types ----------------------- +// CZMQ uses uint for array indices; equivalent to unsigned int, but more +// convenient in code. We define it in czmq_prelude.h on systems that do +// not define it by default. + +#if (defined (__WINDOWS__)) +# if (!defined (__cplusplus) && (!defined (inline))) +# define inline __inline +# endif +# define strtoull _strtoui64 +# define atoll _atoi64 +# define srandom srand +# define TIMEZONE _timezone +# if (!defined (__MINGW32__)) +# define snprintf _snprintf +# define vsnprintf _vsnprintf +# endif + typedef unsigned long ulong; + typedef unsigned int uint; +# if (!defined (__MINGW32__)) + typedef int mode_t; +# if !defined (_SSIZE_T_DEFINED) +typedef intptr_t ssize_t; +# define _SSIZE_T_DEFINED +# endif +# endif +# if ((!defined (__MINGW32__) \ + || (defined (__MINGW32__) && defined (__IS_64BIT__))) \ + && !defined (ZMQ_DEFINED_STDINT)) + typedef __int8 int8_t; + typedef __int16 int16_t; + typedef __int32 int32_t; + typedef __int64 int64_t; + typedef unsigned __int8 uint8_t; + typedef unsigned __int16 uint16_t; + typedef unsigned __int32 uint32_t; + typedef unsigned __int64 uint64_t; +# endif + typedef uint32_t in_addr_t; +# if (!defined (PRId8)) +# define PRId8 "d" +# endif +# if (!defined (PRId16)) +# define PRId16 "d" +# endif +# if (!defined (PRId32)) +# define PRId32 "d" +# endif +# if (!defined (PRId64)) +# define PRId64 "I64d" +# endif +# if (!defined (PRIu8)) +# define PRIu8 "u" +# endif +# if (!defined (PRIu16)) +# define PRIu16 "u" +# endif +# if (!defined (PRIu32)) +# define PRIu32 "u" +# endif +# if (!defined (PRIu64)) +# define PRIu64 "I64u" +# endif +# if (!defined (va_copy)) + // MSVC does not support C99's va_copy so we use a regular assignment +# define va_copy(dest,src) (dest) = (src) +# endif +#elif (defined (__UTYPE_OSX)) + typedef unsigned long ulong; + typedef unsigned int uint; + // This fixes header-order dependence problem with some Linux versions +#elif (defined (__UTYPE_LINUX)) +# if (__STDC_VERSION__ >= 199901L && !defined (__USE_MISC)) + typedef unsigned int uint; +# endif +#endif + +//- Non-portable declaration specifiers ------------------------------------- + +// For thread-local storage +#if defined (__WINDOWS__) +# define CZMQ_THREADLS __declspec(thread) +#else +# define CZMQ_THREADLS __thread +#endif + +// Replacement for malloc() which asserts if we run out of heap, and +// which zeroes the allocated block. +static inline void * +safe_malloc (size_t size, const char *file, unsigned line) +{ +// printf ("%s:%u %08d\n", file, line, (int) size); + void *mem = calloc (1, size); + if (mem == NULL) { + fprintf (stderr, "FATAL ERROR at %s:%u\n", file, line); + fprintf (stderr, "OUT OF MEMORY (malloc returned NULL)\n"); + fflush (stderr); + abort (); + } + return mem; +} + +// Define _ZMALLOC_DEBUG if you need to trace memory leaks using e.g. mtrace, +// otherwise all allocations will claim to come from czmq_prelude.h. For best +// results, compile all classes so you see dangling object allocations. +// _ZMALLOC_PEDANTIC does the same thing, but its intention is to propagate +// out of memory condition back up the call stack. +#if defined (_ZMALLOC_DEBUG) || defined (_ZMALLOC_PEDANTIC) +# define zmalloc(size) calloc(1,(size)) +#else +# define zmalloc(size) safe_malloc((size), __FILE__, __LINE__) +#endif + +// GCC supports validating format strings for functions that act like printf +#if defined (__GNUC__) && (__GNUC__ >= 2) +# define CHECK_PRINTF(a) __attribute__((format (printf, a, a + 1))) +#else +# define CHECK_PRINTF(a) +#endif + +// Lets us write code that compiles both on Windows and normal platforms +#if !defined (__WINDOWS__) +typedef int SOCKET; +# define closesocket close +# define INVALID_SOCKET -1 +# define SOCKET_ERROR -1 +# define O_BINARY 0 +#endif + +//- Include non-portable header files based on platform.h ------------------- + +#if defined (HAVE_LINUX_WIRELESS_H) +# include +// This would normally come from net/if.h +unsigned int if_nametoindex (const char *ifname); +#else +# if defined (HAVE_NET_IF_H) +# include +# endif +# if defined (HAVE_NET_IF_MEDIA_H) +# include +# endif +#endif + +#if defined (__WINDOWS__) && !defined (HAVE_UUID) +# define HAVE_UUID 1 +#endif +#if defined (__UTYPE_OSX) && !defined (HAVE_UUID) +# define HAVE_UUID 1 +#endif +#if defined (HAVE_UUID) +# if defined (__UTYPE_FREEBSD) || defined (__UTYPE_NETBSD) +# include +# elif defined __UTYPE_HPUX +# include +# elif defined (__UNIX__) +# include +# endif +#endif + +// ZMQ compatibility macros + +#if ZMQ_VERSION_MAJOR == 4 +# define ZMQ_POLL_MSEC 1 // zmq_poll is msec + +#elif ZMQ_VERSION_MAJOR == 3 +# define ZMQ_POLL_MSEC 1 // zmq_poll is msec +# if ZMQ_VERSION_MINOR < 2 +# define zmq_ctx_new zmq_init +# endif +# define zmq_ctx_term zmq_term + +#elif ZMQ_VERSION_MAJOR == 2 +# define ZMQ_POLL_MSEC 1000 // zmq_poll is usec +# define zmq_sendmsg zmq_send // Smooth out 2.x changes +# define zmq_recvmsg zmq_recv +# define zmq_ctx_new zmq_init +# define zmq_ctx_term zmq_term +# define zmq_msg_send(m,s,f) zmq_sendmsg ((s),(m),(f)) +# define zmq_msg_recv(m,s,f) zmq_recvmsg ((s),(m),(f)) + // Older libzmq APIs may be missing some aspects of libzmq v3.0 +# ifndef ZMQ_ROUTER +# define ZMQ_ROUTER ZMQ_XREP +# endif +# ifndef ZMQ_DEALER +# define ZMQ_DEALER ZMQ_XREQ +# endif +# ifndef ZMQ_DONTWAIT +# define ZMQ_DONTWAIT ZMQ_NOBLOCK +# endif +# ifndef ZMQ_XSUB +# error "please upgrade your libzmq from http://zeromq.org" +# endif +# if ZMQ_VERSION_MINOR == 0 \ + || (ZMQ_VERSION_MINOR == 1 && ZMQ_VERSION_PATCH < 7) +# error "CZMQ requires at least libzmq/2.1.7 stable" +# endif +#endif + +#endif diff --git a/phonelibs/zmq/aarch64-linux/include/zactor.h b/phonelibs/zmq/aarch64-linux/include/zactor.h new file mode 100644 index 00000000000000..c865c65daf1efa --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/include/zactor.h @@ -0,0 +1,76 @@ +/* ========================================================================= + zactor - actor + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZACTOR_H_INCLUDED__ +#define __ZACTOR_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/zactor.api" to make changes. +// @interface +// This is a stable class, and may not change except for emergencies. It +// is provided in stable builds. +// Actors get a pipe and arguments from caller +typedef void (zactor_fn) ( + zsock_t *pipe, void *args); + +// Create a new actor passing arbitrary arguments reference. +CZMQ_EXPORT zactor_t * + zactor_new (zactor_fn task, void *args); + +// Destroy an actor. +CZMQ_EXPORT void + zactor_destroy (zactor_t **self_p); + +// Send a zmsg message to the actor, take ownership of the message +// and destroy when it has been sent. +CZMQ_EXPORT int + zactor_send (zactor_t *self, zmsg_t **msg_p); + +// Receive a zmsg message from the actor. Returns NULL if the actor +// was interrupted before the message could be received, or if there +// was a timeout on the actor. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zmsg_t * + zactor_recv (zactor_t *self); + +// Probe the supplied object, and report if it looks like a zactor_t. +CZMQ_EXPORT bool + zactor_is (void *self); + +// Probe the supplied reference. If it looks like a zactor_t instance, +// return the underlying libzmq actor handle; else if it looks like +// a libzmq actor handle, return the supplied value. +CZMQ_EXPORT void * + zactor_resolve (void *self); + +// Return the actor's zsock handle. Use this when you absolutely need +// to work with the zsock instance rather than the actor. +CZMQ_EXPORT zsock_t * + zactor_sock (zactor_t *self); + +// Self test of this class. +CZMQ_EXPORT void + zactor_test (bool verbose); + +// @end + + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/aarch64-linux/include/zarmour.h b/phonelibs/zmq/aarch64-linux/include/zarmour.h new file mode 100644 index 00000000000000..c7f299f7afe989 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/include/zarmour.h @@ -0,0 +1,114 @@ +/* ========================================================================= + zarmour - armoured text encoding and decoding + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZARMOUR_H_INCLUDED__ +#define __ZARMOUR_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/zarmour.api" to make changes. +// @interface +// This is a stable class, and may not change except for emergencies. It +// is provided in stable builds. +#define ZARMOUR_MODE_BASE64_STD 0 // Standard base 64 +#define ZARMOUR_MODE_BASE64_URL 1 // URL and filename friendly base 64 +#define ZARMOUR_MODE_BASE32_STD 2 // Standard base 32 +#define ZARMOUR_MODE_BASE32_HEX 3 // Extended hex base 32 +#define ZARMOUR_MODE_BASE16 4 // Standard base 16 +#define ZARMOUR_MODE_Z85 5 // Z85 from ZeroMQ RFC 32 + +// Create a new zarmour +CZMQ_EXPORT zarmour_t * + zarmour_new (void); + +// Destroy the zarmour +CZMQ_EXPORT void + zarmour_destroy (zarmour_t **self_p); + +// Encode a stream of bytes into an armoured string. Returns the armoured +// string, or NULL if there was insufficient memory available to allocate +// a new string. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT char * + zarmour_encode (zarmour_t *self, const byte *data, size_t size); + +// Decode an armoured string into a chunk. The decoded output is +// null-terminated, so it may be treated as a string, if that's what +// it was prior to encoding. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zchunk_t * + zarmour_decode (zarmour_t *self, const char *data); + +// Get the mode property. +CZMQ_EXPORT int + zarmour_mode (zarmour_t *self); + +// Get printable string for mode. +CZMQ_EXPORT const char * + zarmour_mode_str (zarmour_t *self); + +// Set the mode property. +CZMQ_EXPORT void + zarmour_set_mode (zarmour_t *self, int mode); + +// Return true if padding is turned on. +CZMQ_EXPORT bool + zarmour_pad (zarmour_t *self); + +// Turn padding on or off. Default is on. +CZMQ_EXPORT void + zarmour_set_pad (zarmour_t *self, bool pad); + +// Get the padding character. +CZMQ_EXPORT char + zarmour_pad_char (zarmour_t *self); + +// Set the padding character. +CZMQ_EXPORT void + zarmour_set_pad_char (zarmour_t *self, char pad_char); + +// Return if splitting output into lines is turned on. Default is off. +CZMQ_EXPORT bool + zarmour_line_breaks (zarmour_t *self); + +// Turn splitting output into lines on or off. +CZMQ_EXPORT void + zarmour_set_line_breaks (zarmour_t *self, bool line_breaks); + +// Get the line length used for splitting lines. +CZMQ_EXPORT size_t + zarmour_line_length (zarmour_t *self); + +// Set the line length used for splitting lines. +CZMQ_EXPORT void + zarmour_set_line_length (zarmour_t *self, size_t line_length); + +// Print properties of object +CZMQ_EXPORT void + zarmour_print (zarmour_t *self); + +// Self test of this class. +CZMQ_EXPORT void + zarmour_test (bool verbose); + +// @end + + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/aarch64-linux/include/zauth.h b/phonelibs/zmq/aarch64-linux/include/zauth.h new file mode 100644 index 00000000000000..3e0e59ecabf544 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/include/zauth.h @@ -0,0 +1,100 @@ +/* ========================================================================= + zauth - authentication for ZeroMQ security mechanisms + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZAUTH_H_INCLUDED__ +#define __ZAUTH_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @interface +#define CURVE_ALLOW_ANY "*" + +// CZMQ v3 API (for use with zsock, not zsocket, which is deprecated). +// +// Create new zauth actor instance. This installs authentication on all +// zsock sockets. Until you add policies, all incoming NULL connections are +// allowed (classic ZeroMQ behaviour), and all PLAIN and CURVE connections +// are denied: +// +// zactor_t *auth = zactor_new (zauth, NULL); +// +// Destroy zauth instance. This removes authentication and allows all +// connections to pass, without authentication: +// +// zactor_destroy (&auth); +// +// Note that all zauth commands are synchronous, so your application always +// waits for a signal from the actor after each command. +// +// Enable verbose logging of commands and activity. Verbose logging can help +// debug non-trivial authentication policies: +// +// zstr_send (auth, "VERBOSE"); +// zsock_wait (auth); +// +// Allow (whitelist) a list of IP addresses. For NULL, all clients from +// these addresses will be accepted. For PLAIN and CURVE, they will be +// allowed to continue with authentication. You can call this method +// multiple times to whitelist more IP addresses. If you whitelist one +// or more addresses, any non-whitelisted addresses are treated as +// blacklisted: +// +// zstr_sendx (auth, "ALLOW", "127.0.0.1", "127.0.0.2", NULL); +// zsock_wait (auth); +// +// Deny (blacklist) a list of IP addresses. For all security mechanisms, +// this rejects the connection without any further authentication. Use +// either a whitelist, or a blacklist, not not both. If you define both +// a whitelist and a blacklist, only the whitelist takes effect: +// +// zstr_sendx (auth, "DENY", "192.168.0.1", "192.168.0.2", NULL); +// zsock_wait (auth); +// +// Configure PLAIN authentication using a plain-text password file. You can +// modify the password file at any time; zauth will reload it automatically +// if modified externally: +// +// zstr_sendx (auth, "PLAIN", filename, NULL); +// zsock_wait (auth); +// +// Configure CURVE authentication, using a directory that holds all public +// client certificates, i.e. their public keys. The certificates must be in +// zcert_save format. You can add and remove certificates in that directory +// at any time. To allow all client keys without checking, specify +// CURVE_ALLOW_ANY for the directory name: +// +// zstr_sendx (auth, "CURVE", directory, NULL); +// zsock_wait (auth); +// +// Configure GSSAPI authentication, using an underlying mechanism (usually +// Kerberos) to establish a secure context and perform mutual authentication: +// +// zstr_sendx (auth, "GSSAPI", NULL); +// zsock_wait (auth); +// +// This is the zauth constructor as a zactor_fn: +CZMQ_EXPORT void + zauth (zsock_t *pipe, void *certstore); + +// Selftest +CZMQ_EXPORT void + zauth_test (bool verbose); +// @end + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/aarch64-linux/include/zbeacon.h b/phonelibs/zmq/aarch64-linux/include/zbeacon.h new file mode 100644 index 00000000000000..78917e9577e40f --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/include/zbeacon.h @@ -0,0 +1,86 @@ +/* ========================================================================= + zbeacon - LAN discovery and presence + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZBEACON_H_INCLUDED__ +#define __ZBEACON_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @interface +// Create new zbeacon actor instance: +// +// zactor_t *beacon = zactor_new (zbeacon, NULL); +// +// Destroy zbeacon instance: +// +// zactor_destroy (&beacon); +// +// Enable verbose logging of commands and activity: +// +// zstr_send (beacon, "VERBOSE"); +// +// Configure beacon to run on specified UDP port, and return the name of +// the host, which can be used as endpoint for incoming connections. To +// force the beacon to operate on a given interface, set the environment +// variable ZSYS_INTERFACE, or call zsys_set_interface() before creating +// the beacon. If the system does not support UDP broadcasts (lacking a +// workable interface), returns an empty hostname: +// +// // Pictures: 's' = C string, 'i' = int +// zsock_send (beacon, "si", "CONFIGURE", port_number); +// char *hostname = zstr_recv (beacon); +// +// Start broadcasting a beacon at a specified interval in msec. The beacon +// data can be at most UDP_FRAME_MAX bytes; this constant is defined in +// zsys.h to be 255: +// +// // Pictures: 'b' = byte * data + size_t size +// zsock_send (beacon, "sbi", "PUBLISH", data, size, interval); +// +// Stop broadcasting the beacon: +// +// zstr_sendx (beacon, "SILENCE", NULL); +// +// Start listening to beacons from peers. The filter is used to do a prefix +// match on received beacons, to remove junk. Note that any received data +// that is identical to our broadcast beacon_data is discarded in any case. +// If the filter size is zero, we get all peer beacons: +// +// zsock_send (beacon, "sb", "SUBSCRIBE", filter_data, filter_size); +// +// Stop listening to other peers +// +// zstr_sendx (beacon, "UNSUBSCRIBE", NULL); +// +// Receive next beacon from a peer. Received beacons are always a 2-frame +// message containing the ipaddress of the sender, and then the binary +// beacon data as published by the sender: +// +// zmsg_t *msg = zmsg_recv (beacon); +// +// This is the zbeacon constructor as a zactor_fn: +CZMQ_EXPORT void + zbeacon (zsock_t *pipe, void *unused); + +// Self test of this class +CZMQ_EXPORT void + zbeacon_test (bool verbose); +// @end + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/aarch64-linux/include/zcert.h b/phonelibs/zmq/aarch64-linux/include/zcert.h new file mode 100644 index 00000000000000..3161bc0596b51b --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/include/zcert.h @@ -0,0 +1,128 @@ +/* ========================================================================= + zcert - work with CURVE security certificates + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZCERT_H_INCLUDED__ +#define __ZCERT_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/zcert.api" to make changes. +// @interface +// This is a stable class, and may not change except for emergencies. It +// is provided in stable builds. +// This class has draft methods, which may change over time. They are not +// in stable releases, by default. Use --enable-drafts to enable. +// Create and initialize a new certificate in memory +CZMQ_EXPORT zcert_t * + zcert_new (void); + +// Accepts public/secret key pair from caller +CZMQ_EXPORT zcert_t * + zcert_new_from (const byte *public_key, const byte *secret_key); + +// Load certificate from file +CZMQ_EXPORT zcert_t * + zcert_load (const char *filename); + +// Destroy a certificate in memory +CZMQ_EXPORT void + zcert_destroy (zcert_t **self_p); + +// Return public part of key pair as 32-byte binary string +CZMQ_EXPORT const byte * + zcert_public_key (zcert_t *self); + +// Return secret part of key pair as 32-byte binary string +CZMQ_EXPORT const byte * + zcert_secret_key (zcert_t *self); + +// Return public part of key pair as Z85 armored string +CZMQ_EXPORT const char * + zcert_public_txt (zcert_t *self); + +// Return secret part of key pair as Z85 armored string +CZMQ_EXPORT const char * + zcert_secret_txt (zcert_t *self); + +// Set certificate metadata from formatted string. +CZMQ_EXPORT void + zcert_set_meta (zcert_t *self, const char *name, const char *format, ...) CHECK_PRINTF (3); + +// Get metadata value from certificate; if the metadata value doesn't +// exist, returns NULL. +CZMQ_EXPORT const char * + zcert_meta (zcert_t *self, const char *name); + +// Get list of metadata fields from certificate. Caller is responsible for +// destroying list. Caller should not modify the values of list items. +CZMQ_EXPORT zlist_t * + zcert_meta_keys (zcert_t *self); + +// Save full certificate (public + secret) to file for persistent storage +// This creates one public file and one secret file (filename + "_secret"). +CZMQ_EXPORT int + zcert_save (zcert_t *self, const char *filename); + +// Save public certificate only to file for persistent storage +CZMQ_EXPORT int + zcert_save_public (zcert_t *self, const char *filename); + +// Save secret certificate only to file for persistent storage +CZMQ_EXPORT int + zcert_save_secret (zcert_t *self, const char *filename); + +// Apply certificate to socket, i.e. use for CURVE security on socket. +// If certificate was loaded from public file, the secret key will be +// undefined, and this certificate will not work successfully. +CZMQ_EXPORT void + zcert_apply (zcert_t *self, void *socket); + +// Return copy of certificate; if certificate is NULL or we exhausted +// heap memory, returns NULL. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zcert_t * + zcert_dup (zcert_t *self); + +// Return true if two certificates have the same keys +CZMQ_EXPORT bool + zcert_eq (zcert_t *self, zcert_t *compare); + +// Print certificate contents to stdout +CZMQ_EXPORT void + zcert_print (zcert_t *self); + +// Self test of this class +CZMQ_EXPORT void + zcert_test (bool verbose); + +#ifdef CZMQ_BUILD_DRAFT_API +// *** Draft method, for development use, may change without warning *** +// Unset certificate metadata. +CZMQ_EXPORT void + zcert_unset_meta (zcert_t *self, const char *name); + +#endif // CZMQ_BUILD_DRAFT_API +// @end + + +#ifdef __cplusplus +} +#endif + +// Deprecated method aliases +#define zcert_dump(s) zcert_print(s) + +#endif diff --git a/phonelibs/zmq/aarch64-linux/include/zcertstore.h b/phonelibs/zmq/aarch64-linux/include/zcertstore.h new file mode 100644 index 00000000000000..689b228ac1ed17 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/include/zcertstore.h @@ -0,0 +1,92 @@ +/* ========================================================================= + zcertstore - work with CURVE security certificate stores + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZCERTSTORE_H_INCLUDED__ +#define __ZCERTSTORE_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/zcertstore.api" to make changes. +// @interface +// This is a stable class, and may not change except for emergencies. It +// is provided in stable builds. +// This class has draft methods, which may change over time. They are not +// in stable releases, by default. Use --enable-drafts to enable. +// Create a new certificate store from a disk directory, loading and +// indexing all certificates in that location. The directory itself may be +// absent, and created later, or modified at any time. The certificate store +// is automatically refreshed on any zcertstore_lookup() call. If the +// location is specified as NULL, creates a pure-memory store, which you +// can work with by inserting certificates at runtime. +CZMQ_EXPORT zcertstore_t * + zcertstore_new (const char *location); + +// Destroy a certificate store object in memory. Does not affect anything +// stored on disk. +CZMQ_EXPORT void + zcertstore_destroy (zcertstore_t **self_p); + +// Look up certificate by public key, returns zcert_t object if found, +// else returns NULL. The public key is provided in Z85 text format. +CZMQ_EXPORT zcert_t * + zcertstore_lookup (zcertstore_t *self, const char *public_key); + +// Insert certificate into certificate store in memory. Note that this +// does not save the certificate to disk. To do that, use zcert_save() +// directly on the certificate. Takes ownership of zcert_t object. +CZMQ_EXPORT void + zcertstore_insert (zcertstore_t *self, zcert_t **cert_p); + +// Print list of certificates in store to logging facility +CZMQ_EXPORT void + zcertstore_print (zcertstore_t *self); + +// Self test of this class +CZMQ_EXPORT void + zcertstore_test (bool verbose); + +#ifdef CZMQ_BUILD_DRAFT_API +// Loaders retrieve certificates from an arbitrary source. +typedef void (zcertstore_loader) ( + zcertstore_t *self); + +// Destructor for loader state. +typedef void (zcertstore_destructor) ( + void **self_p); + +// *** Draft method, for development use, may change without warning *** +// Override the default disk loader with a custom loader fn. +CZMQ_EXPORT void + zcertstore_set_loader (zcertstore_t *self, zcertstore_loader loader, zcertstore_destructor destructor, void *state); + +// *** Draft method, for development use, may change without warning *** +// Empty certificate hashtable. This wrapper exists to be friendly to bindings, +// which don't usually have access to struct internals. +CZMQ_EXPORT void + zcertstore_empty (zcertstore_t *self); + +#endif // CZMQ_BUILD_DRAFT_API +// @end + + +#ifdef __cplusplus +} +#endif + +// Deprecated method aliases +#define zcertstore_dump(s) zcertstore_print(s) + +#endif diff --git a/phonelibs/zmq/aarch64-linux/include/zchunk.h b/phonelibs/zmq/aarch64-linux/include/zchunk.h new file mode 100644 index 00000000000000..56f29b161a37e5 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/include/zchunk.h @@ -0,0 +1,163 @@ +/* ========================================================================= + zchunk - work with memory chunks + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZCHUNK_H_INCLUDED__ +#define __ZCHUNK_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/zchunk.api" to make changes. +// @interface +// This is a stable class, and may not change except for emergencies. It +// is provided in stable builds. +// Create a new chunk of the specified size. If you specify the data, it +// is copied into the chunk. If you do not specify the data, the chunk is +// allocated and left empty, and you can then add data using zchunk_append. +CZMQ_EXPORT zchunk_t * + zchunk_new (const void *data, size_t size); + +// Destroy a chunk +CZMQ_EXPORT void + zchunk_destroy (zchunk_t **self_p); + +// Resizes chunk max_size as requested; chunk_cur size is set to zero +CZMQ_EXPORT void + zchunk_resize (zchunk_t *self, size_t size); + +// Return chunk cur size +CZMQ_EXPORT size_t + zchunk_size (zchunk_t *self); + +// Return chunk max size +CZMQ_EXPORT size_t + zchunk_max_size (zchunk_t *self); + +// Return chunk data +CZMQ_EXPORT byte * + zchunk_data (zchunk_t *self); + +// Set chunk data from user-supplied data; truncate if too large. Data may +// be null. Returns actual size of chunk +CZMQ_EXPORT size_t + zchunk_set (zchunk_t *self, const void *data, size_t size); + +// Fill chunk data from user-supplied octet +CZMQ_EXPORT size_t + zchunk_fill (zchunk_t *self, byte filler, size_t size); + +// Append user-supplied data to chunk, return resulting chunk size. If the +// data would exceeded the available space, it is truncated. If you want to +// grow the chunk to accommodate new data, use the zchunk_extend method. +CZMQ_EXPORT size_t + zchunk_append (zchunk_t *self, const void *data, size_t size); + +// Append user-supplied data to chunk, return resulting chunk size. If the +// data would exceeded the available space, the chunk grows in size. +CZMQ_EXPORT size_t + zchunk_extend (zchunk_t *self, const void *data, size_t size); + +// Copy as much data from 'source' into the chunk as possible; returns the +// new size of chunk. If all data from 'source' is used, returns exhausted +// on the source chunk. Source can be consumed as many times as needed until +// it is exhausted. If source was already exhausted, does not change chunk. +CZMQ_EXPORT size_t + zchunk_consume (zchunk_t *self, zchunk_t *source); + +// Returns true if the chunk was exhausted by consume methods, or if the +// chunk has a size of zero. +CZMQ_EXPORT bool + zchunk_exhausted (zchunk_t *self); + +// Read chunk from an open file descriptor +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zchunk_t * + zchunk_read (FILE *handle, size_t bytes); + +// Write chunk to an open file descriptor +CZMQ_EXPORT int + zchunk_write (zchunk_t *self, FILE *handle); + +// Try to slurp an entire file into a chunk. Will read up to maxsize of +// the file. If maxsize is 0, will attempt to read the entire file and +// fail with an assertion if that cannot fit into memory. Returns a new +// chunk containing the file data, or NULL if the file could not be read. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zchunk_t * + zchunk_slurp (const char *filename, size_t maxsize); + +// Create copy of chunk, as new chunk object. Returns a fresh zchunk_t +// object, or null if there was not enough heap memory. If chunk is null, +// returns null. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zchunk_t * + zchunk_dup (zchunk_t *self); + +// Return chunk data encoded as printable hex string. Caller must free +// string when finished with it. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT char * + zchunk_strhex (zchunk_t *self); + +// Return chunk data copied into freshly allocated string +// Caller must free string when finished with it. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT char * + zchunk_strdup (zchunk_t *self); + +// Return TRUE if chunk body is equal to string, excluding terminator +CZMQ_EXPORT bool + zchunk_streq (zchunk_t *self, const char *string); + +// Transform zchunk into a zframe that can be sent in a message. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zframe_t * + zchunk_pack (zchunk_t *self); + +// Transform a zframe into a zchunk. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zchunk_t * + zchunk_unpack (zframe_t *frame); + +// Calculate SHA1 digest for chunk, using zdigest class. +CZMQ_EXPORT const char * + zchunk_digest (zchunk_t *self); + +// Dump chunk to FILE stream, for debugging and tracing. +CZMQ_EXPORT void + zchunk_fprint (zchunk_t *self, FILE *file); + +// Dump message to stderr, for debugging and tracing. +// See zchunk_fprint for details +CZMQ_EXPORT void + zchunk_print (zchunk_t *self); + +// Probe the supplied object, and report if it looks like a zchunk_t. +CZMQ_EXPORT bool + zchunk_is (void *self); + +// Self test of this class. +CZMQ_EXPORT void + zchunk_test (bool verbose); + +// @end + + +#ifdef __cplusplus +} +#endif + +#endif + diff --git a/phonelibs/zmq/aarch64-linux/include/zclock.h b/phonelibs/zmq/aarch64-linux/include/zclock.h new file mode 100644 index 00000000000000..eb064162c4722a --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/include/zclock.h @@ -0,0 +1,73 @@ +/* ========================================================================= + zclock - millisecond clocks and delays + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZCLOCK_H_INCLUDED__ +#define __ZCLOCK_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/zclock.api" to make changes. +// @interface +// This is a stable class, and may not change except for emergencies. It +// is provided in stable builds. +// Sleep for a number of milliseconds +CZMQ_EXPORT void + zclock_sleep (int msecs); + +// Return current system clock as milliseconds. Note that this clock can +// jump backwards (if the system clock is changed) so is unsafe to use for +// timers and time offsets. Use zclock_mono for that instead. +CZMQ_EXPORT int64_t + zclock_time (void); + +// Return current monotonic clock in milliseconds. Use this when you compute +// time offsets. The monotonic clock is not affected by system changes and +// so will never be reset backwards, unlike a system clock. +CZMQ_EXPORT int64_t + zclock_mono (void); + +// Return current monotonic clock in microseconds. Use this when you compute +// time offsets. The monotonic clock is not affected by system changes and +// so will never be reset backwards, unlike a system clock. +CZMQ_EXPORT int64_t + zclock_usecs (void); + +// Return formatted date/time as fresh string. Free using zstr_free(). +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT char * + zclock_timestr (void); + +// Self test of this class. +CZMQ_EXPORT void + zclock_test (bool verbose); + +// @end + + +// DEPRECATED in favor of zsys logging, see issue #519 +// Print formatted string to stdout, prefixed by date/time and +// terminated with a newline. +CZMQ_EXPORT void + zclock_log (const char *format, ...); + +// Compiler hints +CZMQ_EXPORT void zclock_log (const char *format, ...) CHECK_PRINTF (1); + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/aarch64-linux/include/zconfig.h b/phonelibs/zmq/aarch64-linux/include/zconfig.h new file mode 100644 index 00000000000000..df0c708493f512 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/include/zconfig.h @@ -0,0 +1,185 @@ +/* ========================================================================= + zconfig - work with config files written in rfc.zeromq.org/spec:4/ZPL. + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZCONFIG_H_INCLUDED__ +#define __ZCONFIG_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/zconfig.api" to make changes. +// @interface +// This is a stable class, and may not change except for emergencies. It +// is provided in stable builds. +// +typedef int (zconfig_fct) ( + zconfig_t *self, void *arg, int level); + +// Create new config item +CZMQ_EXPORT zconfig_t * + zconfig_new (const char *name, zconfig_t *parent); + +// Load a config tree from a specified ZPL text file; returns a zconfig_t +// reference for the root, if the file exists and is readable. Returns NULL +// if the file does not exist. +CZMQ_EXPORT zconfig_t * + zconfig_load (const char *filename); + +// Equivalent to zconfig_load, taking a format string instead of a fixed +// filename. +CZMQ_EXPORT zconfig_t * + zconfig_loadf (const char *format, ...) CHECK_PRINTF (1); + +// Destroy a config item and all its children +CZMQ_EXPORT void + zconfig_destroy (zconfig_t **self_p); + +// Return name of config item +CZMQ_EXPORT char * + zconfig_name (zconfig_t *self); + +// Return value of config item +CZMQ_EXPORT char * + zconfig_value (zconfig_t *self); + +// Insert or update configuration key with value +CZMQ_EXPORT void + zconfig_put (zconfig_t *self, const char *path, const char *value); + +// Equivalent to zconfig_put, accepting a format specifier and variable +// argument list, instead of a single string value. +CZMQ_EXPORT void + zconfig_putf (zconfig_t *self, const char *path, const char *format, ...) CHECK_PRINTF (3); + +// Get value for config item into a string value; leading slash is optional +// and ignored. +CZMQ_EXPORT char * + zconfig_get (zconfig_t *self, const char *path, const char *default_value); + +// Set config item name, name may be NULL +CZMQ_EXPORT void + zconfig_set_name (zconfig_t *self, const char *name); + +// Set new value for config item. The new value may be a string, a printf +// format, or NULL. Note that if string may possibly contain '%', or if it +// comes from an insecure source, you must use '%s' as the format, followed +// by the string. +CZMQ_EXPORT void + zconfig_set_value (zconfig_t *self, const char *format, ...) CHECK_PRINTF (2); + +// Find our first child, if any +CZMQ_EXPORT zconfig_t * + zconfig_child (zconfig_t *self); + +// Find our first sibling, if any +CZMQ_EXPORT zconfig_t * + zconfig_next (zconfig_t *self); + +// Find a config item along a path; leading slash is optional and ignored. +CZMQ_EXPORT zconfig_t * + zconfig_locate (zconfig_t *self, const char *path); + +// Locate the last config item at a specified depth +CZMQ_EXPORT zconfig_t * + zconfig_at_depth (zconfig_t *self, int level); + +// Execute a callback for each config item in the tree; returns zero if +// successful, else -1. +CZMQ_EXPORT int + zconfig_execute (zconfig_t *self, zconfig_fct handler, void *arg); + +// Add comment to config item before saving to disk. You can add as many +// comment lines as you like. If you use a null format, all comments are +// deleted. +CZMQ_EXPORT void + zconfig_set_comment (zconfig_t *self, const char *format, ...) CHECK_PRINTF (2); + +// Return comments of config item, as zlist. +CZMQ_EXPORT zlist_t * + zconfig_comments (zconfig_t *self); + +// Save a config tree to a specified ZPL text file, where a filename +// "-" means dump to standard output. +CZMQ_EXPORT int + zconfig_save (zconfig_t *self, const char *filename); + +// Equivalent to zconfig_save, taking a format string instead of a fixed +// filename. +CZMQ_EXPORT int + zconfig_savef (zconfig_t *self, const char *format, ...) CHECK_PRINTF (2); + +// Report filename used during zconfig_load, or NULL if none +CZMQ_EXPORT const char * + zconfig_filename (zconfig_t *self); + +// Reload config tree from same file that it was previously loaded from. +// Returns 0 if OK, -1 if there was an error (and then does not change +// existing data). +CZMQ_EXPORT int + zconfig_reload (zconfig_t **self_p); + +// Load a config tree from a memory chunk +CZMQ_EXPORT zconfig_t * + zconfig_chunk_load (zchunk_t *chunk); + +// Save a config tree to a new memory chunk +CZMQ_EXPORT zchunk_t * + zconfig_chunk_save (zconfig_t *self); + +// Load a config tree from a null-terminated string +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zconfig_t * + zconfig_str_load (const char *string); + +// Save a config tree to a new null terminated string +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT char * + zconfig_str_save (zconfig_t *self); + +// Return true if a configuration tree was loaded from a file and that +// file has changed in since the tree was loaded. +CZMQ_EXPORT bool + zconfig_has_changed (zconfig_t *self); + +// Print the config file to open stream +CZMQ_EXPORT void + zconfig_fprint (zconfig_t *self, FILE *file); + +// Print properties of object +CZMQ_EXPORT void + zconfig_print (zconfig_t *self); + +// Self test of this class +CZMQ_EXPORT void + zconfig_test (bool verbose); + +// @end + +// Self test of this class +CZMQ_EXPORT void + zconfig_test (bool verbose); + +// Compiler hints +CZMQ_EXPORT void zconfig_set_value (zconfig_t *self, const char *format, ...) CHECK_PRINTF (2); + +#ifdef __cplusplus +} +#endif + +// Deprecated method aliases +#define zconfig_dump(s) zconfig_print(s) +#define zconfig_resolve(s,p,d) zconfig_get((s),(p),(d)) + +#endif diff --git a/phonelibs/zmq/aarch64-linux/include/zdigest.h b/phonelibs/zmq/aarch64-linux/include/zdigest.h new file mode 100644 index 00000000000000..def9e860537094 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/include/zdigest.h @@ -0,0 +1,65 @@ +/* ========================================================================= + zdigest - provides hashing functions (SHA-1 at present) + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZDIGEST_H_INCLUDED__ +#define __ZDIGEST_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/zdigest.api" to make changes. +// @interface +// This is a stable class, and may not change except for emergencies. It +// is provided in stable builds. +// Constructor - creates new digest object, which you use to build up a +// digest by repeatedly calling zdigest_update() on chunks of data. +CZMQ_EXPORT zdigest_t * + zdigest_new (void); + +// Destroy a digest object +CZMQ_EXPORT void + zdigest_destroy (zdigest_t **self_p); + +// Add buffer into digest calculation +CZMQ_EXPORT void + zdigest_update (zdigest_t *self, const byte *buffer, size_t length); + +// Return final digest hash data. If built without crypto support, +// returns NULL. +CZMQ_EXPORT const byte * + zdigest_data (zdigest_t *self); + +// Return final digest hash size +CZMQ_EXPORT size_t + zdigest_size (zdigest_t *self); + +// Return digest as printable hex string; caller should not modify nor +// free this string. After calling this, you may not use zdigest_update() +// on the same digest. If built without crypto support, returns NULL. +CZMQ_EXPORT char * + zdigest_string (zdigest_t *self); + +// Self test of this class. +CZMQ_EXPORT void + zdigest_test (bool verbose); + +// @end + + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/aarch64-linux/include/zdir.h b/phonelibs/zmq/aarch64-linux/include/zdir.h new file mode 100644 index 00000000000000..6c5551b57eead4 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/include/zdir.h @@ -0,0 +1,149 @@ +/* ========================================================================= + zdir - work with file-system directories + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZDIR_H_INCLUDED__ +#define __ZDIR_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/zdir.api" to make changes. +// @interface +// This is a stable class, and may not change except for emergencies. It +// is provided in stable builds. +// Create a new directory item that loads in the full tree of the specified +// path, optionally located under some parent path. If parent is "-", then +// loads only the top-level directory, and does not use parent as a path. +CZMQ_EXPORT zdir_t * + zdir_new (const char *path, const char *parent); + +// Destroy a directory tree and all children it contains. +CZMQ_EXPORT void + zdir_destroy (zdir_t **self_p); + +// Return directory path +CZMQ_EXPORT const char * + zdir_path (zdir_t *self); + +// Return last modification time for directory. +CZMQ_EXPORT time_t + zdir_modified (zdir_t *self); + +// Return total hierarchy size, in bytes of data contained in all files +// in the directory tree. +CZMQ_EXPORT off_t + zdir_cursize (zdir_t *self); + +// Return directory count +CZMQ_EXPORT size_t + zdir_count (zdir_t *self); + +// Returns a sorted list of zfile objects; Each entry in the list is a pointer +// to a zfile_t item already allocated in the zdir tree. Do not destroy the +// original zdir tree until you are done with this list. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zlist_t * + zdir_list (zdir_t *self); + +// Remove directory, optionally including all files that it contains, at +// all levels. If force is false, will only remove the directory if empty. +// If force is true, will remove all files and all subdirectories. +CZMQ_EXPORT void + zdir_remove (zdir_t *self, bool force); + +// Calculate differences between two versions of a directory tree. +// Returns a list of zdir_patch_t patches. Either older or newer may +// be null, indicating the directory is empty/absent. If alias is set, +// generates virtual filename (minus path, plus alias). +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zlist_t * + zdir_diff (zdir_t *older, zdir_t *newer, const char *alias); + +// Return full contents of directory as a zdir_patch list. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zlist_t * + zdir_resync (zdir_t *self, const char *alias); + +// Load directory cache; returns a hash table containing the SHA-1 digests +// of every file in the tree. The cache is saved between runs in .cache. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zhash_t * + zdir_cache (zdir_t *self); + +// Print contents of directory to open stream +CZMQ_EXPORT void + zdir_fprint (zdir_t *self, FILE *file, int indent); + +// Print contents of directory to stdout +CZMQ_EXPORT void + zdir_print (zdir_t *self, int indent); + +// Create a new zdir_watch actor instance: +// +// zactor_t *watch = zactor_new (zdir_watch, NULL); +// +// Destroy zdir_watch instance: +// +// zactor_destroy (&watch); +// +// Enable verbose logging of commands and activity: +// +// zstr_send (watch, "VERBOSE"); +// +// Subscribe to changes to a directory path: +// +// zsock_send (watch, "ss", "SUBSCRIBE", "directory_path"); +// +// Unsubscribe from changes to a directory path: +// +// zsock_send (watch, "ss", "UNSUBSCRIBE", "directory_path"); +// +// Receive directory changes: +// zsock_recv (watch, "sp", &path, &patches); +// +// // Delete the received data. +// free (path); +// zlist_destroy (&patches); +CZMQ_EXPORT void + zdir_watch (zsock_t *pipe, void *unused); + +// Self test of this class. +CZMQ_EXPORT void + zdir_test (bool verbose); + +// @end + + +// Returns a sorted array of zfile objects; returns a single block of memory, +// that you destroy by calling zstr_free(). Each entry in the array is a pointer +// to a zfile_t item already allocated in the zdir tree. The array ends with +// a null pointer. Do not destroy the original zdir tree until you are done +// with this array. +CZMQ_EXPORT zfile_t ** + zdir_flatten (zdir_t *self); + +// Free a provided string, and nullify the parent pointer. Safe to call on +// a null pointer. +CZMQ_EXPORT void + zdir_flatten_free (zfile_t ***files_p); + +#ifdef __cplusplus +} +#endif + +// Deprecated method aliases +#define zdir_dump(s,i) zdir_print(s,i) + +#endif diff --git a/phonelibs/zmq/aarch64-linux/include/zdir_patch.h b/phonelibs/zmq/aarch64-linux/include/zdir_patch.h new file mode 100644 index 00000000000000..8d15b9aeb40c42 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/include/zdir_patch.h @@ -0,0 +1,82 @@ +/* ========================================================================= + zdir_patch - work with directory patches + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZDIR_PATCH_H_INCLUDED__ +#define __ZDIR_PATCH_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// un-namespaced enumeration values +#define patch_create ZDIR_PATCH_CREATE +#define patch_delete ZDIR_PATCH_DELETE + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/zdir_patch.api" to make changes. +// @interface +// This is a stable class, and may not change except for emergencies. It +// is provided in stable builds. +#define ZDIR_PATCH_CREATE 1 // Creates a new file +#define ZDIR_PATCH_DELETE 2 // Delete a file + +// Create new patch +CZMQ_EXPORT zdir_patch_t * + zdir_patch_new (const char *path, zfile_t *file, int op, const char *alias); + +// Destroy a patch +CZMQ_EXPORT void + zdir_patch_destroy (zdir_patch_t **self_p); + +// Create copy of a patch. If the patch is null, or memory was exhausted, +// returns null. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zdir_patch_t * + zdir_patch_dup (zdir_patch_t *self); + +// Return patch file directory path +CZMQ_EXPORT const char * + zdir_patch_path (zdir_patch_t *self); + +// Return patch file item +CZMQ_EXPORT zfile_t * + zdir_patch_file (zdir_patch_t *self); + +// Return operation +CZMQ_EXPORT int + zdir_patch_op (zdir_patch_t *self); + +// Return patch virtual file path +CZMQ_EXPORT const char * + zdir_patch_vpath (zdir_patch_t *self); + +// Calculate hash digest for file (create only) +CZMQ_EXPORT void + zdir_patch_digest_set (zdir_patch_t *self); + +// Return hash digest for patch file +CZMQ_EXPORT const char * + zdir_patch_digest (zdir_patch_t *self); + +// Self test of this class. +CZMQ_EXPORT void + zdir_patch_test (bool verbose); + +// @end + + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/aarch64-linux/include/zfile.h b/phonelibs/zmq/aarch64-linux/include/zfile.h new file mode 100644 index 00000000000000..75c35774b97fd1 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/include/zfile.h @@ -0,0 +1,177 @@ +/* ========================================================================= + zfile - helper functions for working with files. + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZFILE_H_INCLUDED__ +#define __ZFILE_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/zfile.api" to make changes. +// @interface +// This is a stable class, and may not change except for emergencies. It +// is provided in stable builds. +// If file exists, populates properties. CZMQ supports portable symbolic +// links, which are files with the extension ".ln". A symbolic link is a +// text file containing one line, the filename of a target file. Reading +// data from the symbolic link actually reads from the target file. Path +// may be NULL, in which case it is not used. +CZMQ_EXPORT zfile_t * + zfile_new (const char *path, const char *name); + +// Destroy a file item +CZMQ_EXPORT void + zfile_destroy (zfile_t **self_p); + +// Duplicate a file item, returns a newly constructed item. If the file +// is null, or memory was exhausted, returns null. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zfile_t * + zfile_dup (zfile_t *self); + +// Return file name, remove path if provided +CZMQ_EXPORT const char * + zfile_filename (zfile_t *self, const char *path); + +// Refresh file properties from disk; this is not done automatically +// on access methods, otherwise it is not possible to compare directory +// snapshots. +CZMQ_EXPORT void + zfile_restat (zfile_t *self); + +// Return when the file was last modified. If you want this to reflect the +// current situation, call zfile_restat before checking this property. +CZMQ_EXPORT time_t + zfile_modified (zfile_t *self); + +// Return the last-known size of the file. If you want this to reflect the +// current situation, call zfile_restat before checking this property. +CZMQ_EXPORT off_t + zfile_cursize (zfile_t *self); + +// Return true if the file is a directory. If you want this to reflect +// any external changes, call zfile_restat before checking this property. +CZMQ_EXPORT bool + zfile_is_directory (zfile_t *self); + +// Return true if the file is a regular file. If you want this to reflect +// any external changes, call zfile_restat before checking this property. +CZMQ_EXPORT bool + zfile_is_regular (zfile_t *self); + +// Return true if the file is readable by this process. If you want this to +// reflect any external changes, call zfile_restat before checking this +// property. +CZMQ_EXPORT bool + zfile_is_readable (zfile_t *self); + +// Return true if the file is writeable by this process. If you want this +// to reflect any external changes, call zfile_restat before checking this +// property. +CZMQ_EXPORT bool + zfile_is_writeable (zfile_t *self); + +// Check if file has stopped changing and can be safely processed. +// Updates the file statistics from disk at every call. +CZMQ_EXPORT bool + zfile_is_stable (zfile_t *self); + +// Return true if the file was changed on disk since the zfile_t object +// was created, or the last zfile_restat() call made on it. +CZMQ_EXPORT bool + zfile_has_changed (zfile_t *self); + +// Remove the file from disk +CZMQ_EXPORT void + zfile_remove (zfile_t *self); + +// Open file for reading +// Returns 0 if OK, -1 if not found or not accessible +CZMQ_EXPORT int + zfile_input (zfile_t *self); + +// Open file for writing, creating directory if needed +// File is created if necessary; chunks can be written to file at any +// location. Returns 0 if OK, -1 if error. +CZMQ_EXPORT int + zfile_output (zfile_t *self); + +// Read chunk from file at specified position. If this was the last chunk, +// sets the eof property. Returns a null chunk in case of error. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zchunk_t * + zfile_read (zfile_t *self, size_t bytes, off_t offset); + +// Returns true if zfile_read() just read the last chunk in the file. +CZMQ_EXPORT bool + zfile_eof (zfile_t *self); + +// Write chunk to file at specified position +// Return 0 if OK, else -1 +CZMQ_EXPORT int + zfile_write (zfile_t *self, zchunk_t *chunk, off_t offset); + +// Read next line of text from file. Returns a pointer to the text line, +// or NULL if there was nothing more to read from the file. +CZMQ_EXPORT const char * + zfile_readln (zfile_t *self); + +// Close file, if open +CZMQ_EXPORT void + zfile_close (zfile_t *self); + +// Return file handle, if opened +CZMQ_EXPORT FILE * + zfile_handle (zfile_t *self); + +// Calculate SHA1 digest for file, using zdigest class. +CZMQ_EXPORT const char * + zfile_digest (zfile_t *self); + +// Self test of this class. +CZMQ_EXPORT void + zfile_test (bool verbose); + +// @end + + +// @interface +// These methods are deprecated, and now moved to zsys class. +CZMQ_EXPORT bool + zfile_exists (const char *filename); +CZMQ_EXPORT ssize_t + zfile_size (const char *filename); +CZMQ_EXPORT mode_t + zfile_mode (const char *filename); +CZMQ_EXPORT int + zfile_delete (const char *filename); +CZMQ_EXPORT bool + zfile_stable (const char *filename); +CZMQ_EXPORT int + zfile_mkdir (const char *pathname); +CZMQ_EXPORT int + zfile_rmdir (const char *pathname); +CZMQ_EXPORT void + zfile_mode_private (void); +CZMQ_EXPORT void + zfile_mode_default (void); +// @end + +#ifdef __cplusplus +} +#endif + + +#endif // __ZFILE_H_INCLUDED__ diff --git a/phonelibs/zmq/aarch64-linux/include/zframe.h b/phonelibs/zmq/aarch64-linux/include/zframe.h new file mode 100644 index 00000000000000..728093c36ce117 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/include/zframe.h @@ -0,0 +1,176 @@ +/* ========================================================================= + zframe - working with single message frames + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZFRAME_H_INCLUDED__ +#define __ZFRAME_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/zframe.api" to make changes. +// @interface +// This is a stable class, and may not change except for emergencies. It +// is provided in stable builds. +// This class has draft methods, which may change over time. They are not +// in stable releases, by default. Use --enable-drafts to enable. +#define ZFRAME_MORE 1 // +#define ZFRAME_REUSE 2 // +#define ZFRAME_DONTWAIT 4 // + +// Create a new frame. If size is not null, allocates the frame data +// to the specified size. If additionally, data is not null, copies +// size octets from the specified data into the frame body. +CZMQ_EXPORT zframe_t * + zframe_new (const void *data, size_t size); + +// Create an empty (zero-sized) frame +CZMQ_EXPORT zframe_t * + zframe_new_empty (void); + +// Create a frame with a specified string content. +CZMQ_EXPORT zframe_t * + zframe_from (const char *string); + +// Receive frame from socket, returns zframe_t object or NULL if the recv +// was interrupted. Does a blocking recv, if you want to not block then use +// zpoller or zloop. +CZMQ_EXPORT zframe_t * + zframe_recv (void *source); + +// Destroy a frame +CZMQ_EXPORT void + zframe_destroy (zframe_t **self_p); + +// Send a frame to a socket, destroy frame after sending. +// Return -1 on error, 0 on success. +CZMQ_EXPORT int + zframe_send (zframe_t **self_p, void *dest, int flags); + +// Return number of bytes in frame data +CZMQ_EXPORT size_t + zframe_size (zframe_t *self); + +// Return address of frame data +CZMQ_EXPORT byte * + zframe_data (zframe_t *self); + +// Return meta data property for frame +// Caller must free string when finished with it. +CZMQ_EXPORT const char * + zframe_meta (zframe_t *self, const char *property); + +// Create a new frame that duplicates an existing frame. If frame is null, +// or memory was exhausted, returns null. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zframe_t * + zframe_dup (zframe_t *self); + +// Return frame data encoded as printable hex string, useful for 0MQ UUIDs. +// Caller must free string when finished with it. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT char * + zframe_strhex (zframe_t *self); + +// Return frame data copied into freshly allocated string +// Caller must free string when finished with it. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT char * + zframe_strdup (zframe_t *self); + +// Return TRUE if frame body is equal to string, excluding terminator +CZMQ_EXPORT bool + zframe_streq (zframe_t *self, const char *string); + +// Return frame MORE indicator (1 or 0), set when reading frame from socket +// or by the zframe_set_more() method +CZMQ_EXPORT int + zframe_more (zframe_t *self); + +// Set frame MORE indicator (1 or 0). Note this is NOT used when sending +// frame to socket, you have to specify flag explicitly. +CZMQ_EXPORT void + zframe_set_more (zframe_t *self, int more); + +// Return TRUE if two frames have identical size and data +// If either frame is NULL, equality is always false. +CZMQ_EXPORT bool + zframe_eq (zframe_t *self, zframe_t *other); + +// Set new contents for frame +CZMQ_EXPORT void + zframe_reset (zframe_t *self, const void *data, size_t size); + +// Send message to zsys log sink (may be stdout, or system facility as +// configured by zsys_set_logstream). Prefix shows before frame, if not null. +CZMQ_EXPORT void + zframe_print (zframe_t *self, const char *prefix); + +// Probe the supplied object, and report if it looks like a zframe_t. +CZMQ_EXPORT bool + zframe_is (void *self); + +// Self test of this class. +CZMQ_EXPORT void + zframe_test (bool verbose); + +#ifdef CZMQ_BUILD_DRAFT_API +// *** Draft method, for development use, may change without warning *** +// Return frame routing ID, if the frame came from a ZMQ_SERVER socket. +// Else returns zero. +CZMQ_EXPORT uint32_t + zframe_routing_id (zframe_t *self); + +// *** Draft method, for development use, may change without warning *** +// Set routing ID on frame. This is used if/when the frame is sent to a +// ZMQ_SERVER socket. +CZMQ_EXPORT void + zframe_set_routing_id (zframe_t *self, uint32_t routing_id); + +// *** Draft method, for development use, may change without warning *** +// Return frame group of radio-dish pattern. +CZMQ_EXPORT const char * + zframe_group (zframe_t *self); + +// *** Draft method, for development use, may change without warning *** +// Set group on frame. This is used if/when the frame is sent to a +// ZMQ_RADIO socket. +// Return -1 on error, 0 on success. +CZMQ_EXPORT int + zframe_set_group (zframe_t *self, const char *group); + +#endif // CZMQ_BUILD_DRAFT_API +// @end + + +// DEPRECATED as poor style -- callers should use zloop or zpoller +// Receive a new frame off the socket. Returns newly allocated frame, or +// NULL if there was no input waiting, or if the read was interrupted. +CZMQ_EXPORT zframe_t * + zframe_recv_nowait (void *source); + +// DEPRECATED as inconsistent; breaks principle that logging should all go +// to a single destination. +// Print contents of the frame to FILE stream. +CZMQ_EXPORT void + zframe_fprint (zframe_t *self, const char *prefix, FILE *file); + +// Deprecated method aliases +#define zframe_print_to_stream(s,p,F) zframe_fprint(s,p,F) + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/aarch64-linux/include/zgossip.h b/phonelibs/zmq/aarch64-linux/include/zgossip.h new file mode 100644 index 00000000000000..647cb28c080731 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/include/zgossip.h @@ -0,0 +1,95 @@ +/* ========================================================================= + zgossip - zgossip server + + ** WARNING ************************************************************* + THIS SOURCE FILE IS 100% GENERATED. If you edit this file, you will lose + your changes at the next build cycle. This is great for temporary printf + statements. DO NOT MAKE ANY CHANGES YOU WISH TO KEEP. The correct places + for commits are: + + * The XML model used for this code generation: zgossip.xml, or + * The code generation script that built this file: zproto_server_c + ************************************************************************ + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef ZGOSSIP_H_INCLUDED +#define ZGOSSIP_H_INCLUDED + +#include "czmq.h" + +#ifdef __cplusplus +extern "C" { +#endif + +// @interface +// To work with zgossip, use the CZMQ zactor API: +// +// Create new zgossip instance, passing logging prefix: +// +// zactor_t *zgossip = zactor_new (zgossip, "myname"); +// +// Destroy zgossip instance +// +// zactor_destroy (&zgossip); +// +// Enable verbose logging of commands and activity: +// +// zstr_send (zgossip, "VERBOSE"); +// +// Bind zgossip to specified endpoint. TCP endpoints may specify +// the port number as "*" to aquire an ephemeral port: +// +// zstr_sendx (zgossip, "BIND", endpoint, NULL); +// +// Return assigned port number, specifically when BIND was done using an +// an ephemeral port: +// +// zstr_sendx (zgossip, "PORT", NULL); +// char *command, *port_str; +// zstr_recvx (zgossip, &command, &port_str, NULL); +// assert (streq (command, "PORT")); +// +// Specify configuration file to load, overwriting any previous loaded +// configuration file or options: +// +// zstr_sendx (zgossip, "LOAD", filename, NULL); +// +// Set configuration path value: +// +// zstr_sendx (zgossip, "SET", path, value, NULL); +// +// Save configuration data to config file on disk: +// +// zstr_sendx (zgossip, "SAVE", filename, NULL); +// +// Send zmsg_t instance to zgossip: +// +// zactor_send (zgossip, &msg); +// +// Receive zmsg_t instance from zgossip: +// +// zmsg_t *msg = zactor_recv (zgossip); +// +// This is the zgossip constructor as a zactor_fn: +// +CZMQ_EXPORT void + zgossip (zsock_t *pipe, void *args); + +// Self test of this class +CZMQ_EXPORT void + zgossip_test (bool verbose); +// @end + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/aarch64-linux/include/zhash.h b/phonelibs/zmq/aarch64-linux/include/zhash.h new file mode 100644 index 00000000000000..138adf63ac00e9 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/include/zhash.h @@ -0,0 +1,182 @@ +/* ========================================================================= + zhash - generic type-free hash container (simple) + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZHASH_H_INCLUDED__ +#define __ZHASH_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/zhash.api" to make changes. +// @interface +// This is a stable class, and may not change except for emergencies. It +// is provided in stable builds. +// Callback function for zhash_freefn method +typedef void (zhash_free_fn) ( + void *data); + +// Create a new, empty hash container +CZMQ_EXPORT zhash_t * + zhash_new (void); + +// Unpack binary frame into a new hash table. Packed data must follow format +// defined by zhash_pack. Hash table is set to autofree. An empty frame +// unpacks to an empty hash table. +CZMQ_EXPORT zhash_t * + zhash_unpack (zframe_t *frame); + +// Destroy a hash container and all items in it +CZMQ_EXPORT void + zhash_destroy (zhash_t **self_p); + +// Insert item into hash table with specified key and item. +// If key is already present returns -1 and leaves existing item unchanged +// Returns 0 on success. +CZMQ_EXPORT int + zhash_insert (zhash_t *self, const char *key, void *item); + +// Update item into hash table with specified key and item. +// If key is already present, destroys old item and inserts new one. +// Use free_fn method to ensure deallocator is properly called on item. +CZMQ_EXPORT void + zhash_update (zhash_t *self, const char *key, void *item); + +// Remove an item specified by key from the hash table. If there was no such +// item, this function does nothing. +CZMQ_EXPORT void + zhash_delete (zhash_t *self, const char *key); + +// Return the item at the specified key, or null +CZMQ_EXPORT void * + zhash_lookup (zhash_t *self, const char *key); + +// Reindexes an item from an old key to a new key. If there was no such +// item, does nothing. Returns 0 if successful, else -1. +CZMQ_EXPORT int + zhash_rename (zhash_t *self, const char *old_key, const char *new_key); + +// Set a free function for the specified hash table item. When the item is +// destroyed, the free function, if any, is called on that item. +// Use this when hash items are dynamically allocated, to ensure that +// you don't have memory leaks. You can pass 'free' or NULL as a free_fn. +// Returns the item, or NULL if there is no such item. +CZMQ_EXPORT void * + zhash_freefn (zhash_t *self, const char *key, zhash_free_fn free_fn); + +// Return the number of keys/items in the hash table +CZMQ_EXPORT size_t + zhash_size (zhash_t *self); + +// Make copy of hash table; if supplied table is null, returns null. +// Does not copy items themselves. Rebuilds new table so may be slow on +// very large tables. NOTE: only works with item values that are strings +// since there's no other way to know how to duplicate the item value. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zhash_t * + zhash_dup (zhash_t *self); + +// Return keys for items in table +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zlist_t * + zhash_keys (zhash_t *self); + +// Simple iterator; returns first item in hash table, in no given order, +// or NULL if the table is empty. This method is simpler to use than the +// foreach() method, which is deprecated. To access the key for this item +// use zhash_cursor(). NOTE: do NOT modify the table while iterating. +CZMQ_EXPORT void * + zhash_first (zhash_t *self); + +// Simple iterator; returns next item in hash table, in no given order, +// or NULL if the last item was already returned. Use this together with +// zhash_first() to process all items in a hash table. If you need the +// items in sorted order, use zhash_keys() and then zlist_sort(). To +// access the key for this item use zhash_cursor(). NOTE: do NOT modify +// the table while iterating. +CZMQ_EXPORT void * + zhash_next (zhash_t *self); + +// After a successful first/next method, returns the key for the item that +// was returned. This is a constant string that you may not modify or +// deallocate, and which lasts as long as the item in the hash. After an +// unsuccessful first/next, returns NULL. +CZMQ_EXPORT const char * + zhash_cursor (zhash_t *self); + +// Add a comment to hash table before saving to disk. You can add as many +// comment lines as you like. These comment lines are discarded when loading +// the file. If you use a null format, all comments are deleted. +CZMQ_EXPORT void + zhash_comment (zhash_t *self, const char *format, ...) CHECK_PRINTF (2); + +// Serialize hash table to a binary frame that can be sent in a message. +// The packed format is compatible with the 'dictionary' type defined in +// http://rfc.zeromq.org/spec:35/FILEMQ, and implemented by zproto: +// +// ; A list of name/value pairs +// dictionary = dict-count *( dict-name dict-value ) +// dict-count = number-4 +// dict-value = longstr +// dict-name = string +// +// ; Strings are always length + text contents +// longstr = number-4 *VCHAR +// string = number-1 *VCHAR +// +// ; Numbers are unsigned integers in network byte order +// number-1 = 1OCTET +// number-4 = 4OCTET +// +// Comments are not included in the packed data. Item values MUST be +// strings. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zframe_t * + zhash_pack (zhash_t *self); + +// Save hash table to a text file in name=value format. Hash values must be +// printable strings; keys may not contain '=' character. Returns 0 if OK, +// else -1 if a file error occurred. +CZMQ_EXPORT int + zhash_save (zhash_t *self, const char *filename); + +// Load hash table from a text file in name=value format; hash table must +// already exist. Hash values must printable strings; keys may not contain +// '=' character. Returns 0 if OK, else -1 if a file was not readable. +CZMQ_EXPORT int + zhash_load (zhash_t *self, const char *filename); + +// When a hash table was loaded from a file by zhash_load, this method will +// reload the file if it has been modified since, and is "stable", i.e. not +// still changing. Returns 0 if OK, -1 if there was an error reloading the +// file. +CZMQ_EXPORT int + zhash_refresh (zhash_t *self); + +// Set hash for automatic value destruction +CZMQ_EXPORT void + zhash_autofree (zhash_t *self); + +// Self test of this class. +CZMQ_EXPORT void + zhash_test (bool verbose); + +// @end + + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/aarch64-linux/include/zhashx.h b/phonelibs/zmq/aarch64-linux/include/zhashx.h new file mode 100644 index 00000000000000..360a773ee88ec1 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/include/zhashx.h @@ -0,0 +1,277 @@ +/* ========================================================================= + zhashx - extended generic type-free hash container + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZHASHX_H_INCLUDED__ +#define __ZHASHX_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/zhashx.api" to make changes. +// @interface +// This is a stable class, and may not change except for emergencies. It +// is provided in stable builds. +// This class has draft methods, which may change over time. They are not +// in stable releases, by default. Use --enable-drafts to enable. +// Destroy an item +typedef void (zhashx_destructor_fn) ( + void **item); + +// Duplicate an item +typedef void * (zhashx_duplicator_fn) ( + const void *item); + +// Compare two items, for sorting +typedef int (zhashx_comparator_fn) ( + const void *item1, const void *item2); + +// compare two items, for sorting +typedef void (zhashx_free_fn) ( + void *data); + +// compare two items, for sorting +typedef size_t (zhashx_hash_fn) ( + const void *key); + +// Serializes an item to a longstr. +// The caller takes ownership of the newly created object. +typedef char * (zhashx_serializer_fn) ( + const void *item); + +// Deserializes a longstr into an item. +// The caller takes ownership of the newly created object. +typedef void * (zhashx_deserializer_fn) ( + const char *item_str); + +// Create a new, empty hash container +CZMQ_EXPORT zhashx_t * + zhashx_new (void); + +// Unpack binary frame into a new hash table. Packed data must follow format +// defined by zhashx_pack. Hash table is set to autofree. An empty frame +// unpacks to an empty hash table. +CZMQ_EXPORT zhashx_t * + zhashx_unpack (zframe_t *frame); + +// Destroy a hash container and all items in it +CZMQ_EXPORT void + zhashx_destroy (zhashx_t **self_p); + +// Insert item into hash table with specified key and item. +// If key is already present returns -1 and leaves existing item unchanged +// Returns 0 on success. +CZMQ_EXPORT int + zhashx_insert (zhashx_t *self, const void *key, void *item); + +// Update or insert item into hash table with specified key and item. If the +// key is already present, destroys old item and inserts new one. If you set +// a container item destructor, this is called on the old value. If the key +// was not already present, inserts a new item. Sets the hash cursor to the +// new item. +CZMQ_EXPORT void + zhashx_update (zhashx_t *self, const void *key, void *item); + +// Remove an item specified by key from the hash table. If there was no such +// item, this function does nothing. +CZMQ_EXPORT void + zhashx_delete (zhashx_t *self, const void *key); + +// Delete all items from the hash table. If the key destructor is +// set, calls it on every key. If the item destructor is set, calls +// it on every item. +CZMQ_EXPORT void + zhashx_purge (zhashx_t *self); + +// Return the item at the specified key, or null +CZMQ_EXPORT void * + zhashx_lookup (zhashx_t *self, const void *key); + +// Reindexes an item from an old key to a new key. If there was no such +// item, does nothing. Returns 0 if successful, else -1. +CZMQ_EXPORT int + zhashx_rename (zhashx_t *self, const void *old_key, const void *new_key); + +// Set a free function for the specified hash table item. When the item is +// destroyed, the free function, if any, is called on that item. +// Use this when hash items are dynamically allocated, to ensure that +// you don't have memory leaks. You can pass 'free' or NULL as a free_fn. +// Returns the item, or NULL if there is no such item. +CZMQ_EXPORT void * + zhashx_freefn (zhashx_t *self, const void *key, zhashx_free_fn free_fn); + +// Return the number of keys/items in the hash table +CZMQ_EXPORT size_t + zhashx_size (zhashx_t *self); + +// Return a zlistx_t containing the keys for the items in the +// table. Uses the key_duplicator to duplicate all keys and sets the +// key_destructor as destructor for the list. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zlistx_t * + zhashx_keys (zhashx_t *self); + +// Return a zlistx_t containing the values for the items in the +// table. Uses the duplicator to duplicate all items and sets the +// destructor as destructor for the list. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zlistx_t * + zhashx_values (zhashx_t *self); + +// Simple iterator; returns first item in hash table, in no given order, +// or NULL if the table is empty. This method is simpler to use than the +// foreach() method, which is deprecated. To access the key for this item +// use zhashx_cursor(). NOTE: do NOT modify the table while iterating. +CZMQ_EXPORT void * + zhashx_first (zhashx_t *self); + +// Simple iterator; returns next item in hash table, in no given order, +// or NULL if the last item was already returned. Use this together with +// zhashx_first() to process all items in a hash table. If you need the +// items in sorted order, use zhashx_keys() and then zlistx_sort(). To +// access the key for this item use zhashx_cursor(). NOTE: do NOT modify +// the table while iterating. +CZMQ_EXPORT void * + zhashx_next (zhashx_t *self); + +// After a successful first/next method, returns the key for the item that +// was returned. This is a constant string that you may not modify or +// deallocate, and which lasts as long as the item in the hash. After an +// unsuccessful first/next, returns NULL. +CZMQ_EXPORT const void * + zhashx_cursor (zhashx_t *self); + +// Add a comment to hash table before saving to disk. You can add as many +// comment lines as you like. These comment lines are discarded when loading +// the file. If you use a null format, all comments are deleted. +CZMQ_EXPORT void + zhashx_comment (zhashx_t *self, const char *format, ...) CHECK_PRINTF (2); + +// Save hash table to a text file in name=value format. Hash values must be +// printable strings; keys may not contain '=' character. Returns 0 if OK, +// else -1 if a file error occurred. +CZMQ_EXPORT int + zhashx_save (zhashx_t *self, const char *filename); + +// Load hash table from a text file in name=value format; hash table must +// already exist. Hash values must printable strings; keys may not contain +// '=' character. Returns 0 if OK, else -1 if a file was not readable. +CZMQ_EXPORT int + zhashx_load (zhashx_t *self, const char *filename); + +// When a hash table was loaded from a file by zhashx_load, this method will +// reload the file if it has been modified since, and is "stable", i.e. not +// still changing. Returns 0 if OK, -1 if there was an error reloading the +// file. +CZMQ_EXPORT int + zhashx_refresh (zhashx_t *self); + +// Serialize hash table to a binary frame that can be sent in a message. +// The packed format is compatible with the 'dictionary' type defined in +// http://rfc.zeromq.org/spec:35/FILEMQ, and implemented by zproto: +// +// ; A list of name/value pairs +// dictionary = dict-count *( dict-name dict-value ) +// dict-count = number-4 +// dict-value = longstr +// dict-name = string +// +// ; Strings are always length + text contents +// longstr = number-4 *VCHAR +// string = number-1 *VCHAR +// +// ; Numbers are unsigned integers in network byte order +// number-1 = 1OCTET +// number-4 = 4OCTET +// +// Comments are not included in the packed data. Item values MUST be +// strings. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zframe_t * + zhashx_pack (zhashx_t *self); + +// Make a copy of the list; items are duplicated if you set a duplicator +// for the list, otherwise not. Copying a null reference returns a null +// reference. Note that this method's behavior changed slightly for CZMQ +// v3.x, as it does not set nor respect autofree. It does however let you +// duplicate any hash table safely. The old behavior is in zhashx_dup_v2. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zhashx_t * + zhashx_dup (zhashx_t *self); + +// Set a user-defined deallocator for hash items; by default items are not +// freed when the hash is destroyed. +CZMQ_EXPORT void + zhashx_set_destructor (zhashx_t *self, zhashx_destructor_fn destructor); + +// Set a user-defined duplicator for hash items; by default items are not +// copied when the hash is duplicated. +CZMQ_EXPORT void + zhashx_set_duplicator (zhashx_t *self, zhashx_duplicator_fn duplicator); + +// Set a user-defined deallocator for keys; by default keys are freed +// when the hash is destroyed using free(). +CZMQ_EXPORT void + zhashx_set_key_destructor (zhashx_t *self, zhashx_destructor_fn destructor); + +// Set a user-defined duplicator for keys; by default keys are duplicated +// using strdup. +CZMQ_EXPORT void + zhashx_set_key_duplicator (zhashx_t *self, zhashx_duplicator_fn duplicator); + +// Set a user-defined comparator for keys; by default keys are +// compared using strcmp. +CZMQ_EXPORT void + zhashx_set_key_comparator (zhashx_t *self, zhashx_comparator_fn comparator); + +// Set a user-defined comparator for keys; by default keys are +// compared using strcmp. +CZMQ_EXPORT void + zhashx_set_key_hasher (zhashx_t *self, zhashx_hash_fn hasher); + +// Make copy of hash table; if supplied table is null, returns null. +// Does not copy items themselves. Rebuilds new table so may be slow on +// very large tables. NOTE: only works with item values that are strings +// since there's no other way to know how to duplicate the item value. +CZMQ_EXPORT zhashx_t * + zhashx_dup_v2 (zhashx_t *self); + +// Self test of this class. +CZMQ_EXPORT void + zhashx_test (bool verbose); + +#ifdef CZMQ_BUILD_DRAFT_API +// *** Draft method, for development use, may change without warning *** +// Same as unpack but uses a user-defined deserializer function to convert +// a longstr back into item format. +CZMQ_EXPORT zhashx_t * + zhashx_unpack_own (zframe_t *frame, zhashx_deserializer_fn deserializer); + +// *** Draft method, for development use, may change without warning *** +// Same as pack but uses a user-defined serializer function to convert items +// into longstr. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zframe_t * + zhashx_pack_own (zhashx_t *self, zhashx_serializer_fn serializer); + +#endif // CZMQ_BUILD_DRAFT_API +// @end + + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/aarch64-linux/include/ziflist.h b/phonelibs/zmq/aarch64-linux/include/ziflist.h new file mode 100644 index 00000000000000..cb2b1448025f89 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/include/ziflist.h @@ -0,0 +1,77 @@ +/* ========================================================================= + ziflist - List of network interfaces available on system + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZIFLIST_H_INCLUDED__ +#define __ZIFLIST_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/ziflist.api" to make changes. +// @interface +// This is a stable class, and may not change except for emergencies. It +// is provided in stable builds. +// Get a list of network interfaces currently defined on the system +CZMQ_EXPORT ziflist_t * + ziflist_new (void); + +// Destroy a ziflist instance +CZMQ_EXPORT void + ziflist_destroy (ziflist_t **self_p); + +// Reload network interfaces from system +CZMQ_EXPORT void + ziflist_reload (ziflist_t *self); + +// Return the number of network interfaces on system +CZMQ_EXPORT size_t + ziflist_size (ziflist_t *self); + +// Get first network interface, return NULL if there are none +CZMQ_EXPORT const char * + ziflist_first (ziflist_t *self); + +// Get next network interface, return NULL if we hit the last one +CZMQ_EXPORT const char * + ziflist_next (ziflist_t *self); + +// Return the current interface IP address as a printable string +CZMQ_EXPORT const char * + ziflist_address (ziflist_t *self); + +// Return the current interface broadcast address as a printable string +CZMQ_EXPORT const char * + ziflist_broadcast (ziflist_t *self); + +// Return the current interface network mask as a printable string +CZMQ_EXPORT const char * + ziflist_netmask (ziflist_t *self); + +// Return the list of interfaces. +CZMQ_EXPORT void + ziflist_print (ziflist_t *self); + +// Self test of this class. +CZMQ_EXPORT void + ziflist_test (bool verbose); + +// @end + + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/aarch64-linux/include/zlist.h b/phonelibs/zmq/aarch64-linux/include/zlist.h new file mode 100644 index 00000000000000..1dcd39b9955c9e --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/include/zlist.h @@ -0,0 +1,158 @@ +/* ========================================================================= + zlist - simple generic list container + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZLIST_H_INCLUDED__ +#define __ZLIST_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/zlist.api" to make changes. +// @interface +// This is a stable class, and may not change except for emergencies. It +// is provided in stable builds. +// Comparison function e.g. for sorting and removing. +typedef int (zlist_compare_fn) ( + void *item1, void *item2); + +// Callback function for zlist_freefn method +typedef void (zlist_free_fn) ( + void *data); + +// Create a new list container +CZMQ_EXPORT zlist_t * + zlist_new (void); + +// Destroy a list container +CZMQ_EXPORT void + zlist_destroy (zlist_t **self_p); + +// Return the item at the head of list. If the list is empty, returns NULL. +// Leaves cursor pointing at the head item, or NULL if the list is empty. +CZMQ_EXPORT void * + zlist_first (zlist_t *self); + +// Return the next item. If the list is empty, returns NULL. To move to +// the start of the list call zlist_first (). Advances the cursor. +CZMQ_EXPORT void * + zlist_next (zlist_t *self); + +// Return the item at the tail of list. If the list is empty, returns NULL. +// Leaves cursor pointing at the tail item, or NULL if the list is empty. +CZMQ_EXPORT void * + zlist_last (zlist_t *self); + +// Return first item in the list, or null, leaves the cursor +CZMQ_EXPORT void * + zlist_head (zlist_t *self); + +// Return last item in the list, or null, leaves the cursor +CZMQ_EXPORT void * + zlist_tail (zlist_t *self); + +// Return the current item of list. If the list is empty, returns NULL. +// Leaves cursor pointing at the current item, or NULL if the list is empty. +CZMQ_EXPORT void * + zlist_item (zlist_t *self); + +// Append an item to the end of the list, return 0 if OK or -1 if this +// failed for some reason (out of memory). Note that if a duplicator has +// been set, this method will also duplicate the item. +CZMQ_EXPORT int + zlist_append (zlist_t *self, void *item); + +// Push an item to the start of the list, return 0 if OK or -1 if this +// failed for some reason (out of memory). Note that if a duplicator has +// been set, this method will also duplicate the item. +CZMQ_EXPORT int + zlist_push (zlist_t *self, void *item); + +// Pop the item off the start of the list, if any +CZMQ_EXPORT void * + zlist_pop (zlist_t *self); + +// Checks if an item already is present. Uses compare method to determine if +// items are equal. If the compare method is NULL the check will only compare +// pointers. Returns true if item is present else false. +CZMQ_EXPORT bool + zlist_exists (zlist_t *self, void *item); + +// Remove the specified item from the list if present +CZMQ_EXPORT void + zlist_remove (zlist_t *self, void *item); + +// Make a copy of list. If the list has autofree set, the copied list will +// duplicate all items, which must be strings. Otherwise, the list will hold +// pointers back to the items in the original list. If list is null, returns +// NULL. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zlist_t * + zlist_dup (zlist_t *self); + +// Purge all items from list +CZMQ_EXPORT void + zlist_purge (zlist_t *self); + +// Return number of items in the list +CZMQ_EXPORT size_t + zlist_size (zlist_t *self); + +// Sort the list. If the compare function is null, sorts the list by +// ascending key value using a straight ASCII comparison. If you specify +// a compare function, this decides how items are sorted. The sort is not +// stable, so may reorder items with the same keys. The algorithm used is +// combsort, a compromise between performance and simplicity. +CZMQ_EXPORT void + zlist_sort (zlist_t *self, zlist_compare_fn compare); + +// Set list for automatic item destruction; item values MUST be strings. +// By default a list item refers to a value held elsewhere. When you set +// this, each time you append or push a list item, zlist will take a copy +// of the string value. Then, when you destroy the list, it will free all +// item values automatically. If you use any other technique to allocate +// list values, you must free them explicitly before destroying the list. +// The usual technique is to pop list items and destroy them, until the +// list is empty. +CZMQ_EXPORT void + zlist_autofree (zlist_t *self); + +// Sets a compare function for this list. The function compares two items. +// It returns an integer less than, equal to, or greater than zero if the +// first item is found, respectively, to be less than, to match, or be +// greater than the second item. +// This function is used for sorting, removal and exists checking. +CZMQ_EXPORT void + zlist_comparefn (zlist_t *self, zlist_compare_fn fn); + +// Set a free function for the specified list item. When the item is +// destroyed, the free function, if any, is called on that item. +// Use this when list items are dynamically allocated, to ensure that +// you don't have memory leaks. You can pass 'free' or NULL as a free_fn. +// Returns the item, or NULL if there is no such item. +CZMQ_EXPORT void * + zlist_freefn (zlist_t *self, void *item, zlist_free_fn fn, bool at_tail); + +// Self test of this class. +CZMQ_EXPORT void + zlist_test (bool verbose); + +// @end + + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/aarch64-linux/include/zlistx.h b/phonelibs/zmq/aarch64-linux/include/zlistx.h new file mode 100644 index 00000000000000..512637cef3bff5 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/include/zlistx.h @@ -0,0 +1,205 @@ +/* ========================================================================= + zlistx - extended generic list container + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZLISTX_H_INCLUDED__ +#define __ZLISTX_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/zlistx.api" to make changes. +// @interface +// This is a stable class, and may not change except for emergencies. It +// is provided in stable builds. +// Destroy an item +typedef void (zlistx_destructor_fn) ( + void **item); + +// Duplicate an item +typedef void * (zlistx_duplicator_fn) ( + const void *item); + +// Compare two items, for sorting +typedef int (zlistx_comparator_fn) ( + const void *item1, const void *item2); + +// Create a new, empty list. +CZMQ_EXPORT zlistx_t * + zlistx_new (void); + +// Destroy a list. If an item destructor was specified, all items in the +// list are automatically destroyed as well. +CZMQ_EXPORT void + zlistx_destroy (zlistx_t **self_p); + +// Add an item to the head of the list. Calls the item duplicator, if any, +// on the item. Resets cursor to list head. Returns an item handle on +// success, NULL if memory was exhausted. +CZMQ_EXPORT void * + zlistx_add_start (zlistx_t *self, void *item); + +// Add an item to the tail of the list. Calls the item duplicator, if any, +// on the item. Resets cursor to list head. Returns an item handle on +// success, NULL if memory was exhausted. +CZMQ_EXPORT void * + zlistx_add_end (zlistx_t *self, void *item); + +// Return the number of items in the list +CZMQ_EXPORT size_t + zlistx_size (zlistx_t *self); + +// Return first item in the list, or null, leaves the cursor +CZMQ_EXPORT void * + zlistx_head (zlistx_t *self); + +// Return last item in the list, or null, leaves the cursor +CZMQ_EXPORT void * + zlistx_tail (zlistx_t *self); + +// Return the item at the head of list. If the list is empty, returns NULL. +// Leaves cursor pointing at the head item, or NULL if the list is empty. +CZMQ_EXPORT void * + zlistx_first (zlistx_t *self); + +// Return the next item. At the end of the list (or in an empty list), +// returns NULL. Use repeated zlistx_next () calls to work through the list +// from zlistx_first (). First time, acts as zlistx_first(). +CZMQ_EXPORT void * + zlistx_next (zlistx_t *self); + +// Return the previous item. At the start of the list (or in an empty list), +// returns NULL. Use repeated zlistx_prev () calls to work through the list +// backwards from zlistx_last (). First time, acts as zlistx_last(). +CZMQ_EXPORT void * + zlistx_prev (zlistx_t *self); + +// Return the item at the tail of list. If the list is empty, returns NULL. +// Leaves cursor pointing at the tail item, or NULL if the list is empty. +CZMQ_EXPORT void * + zlistx_last (zlistx_t *self); + +// Returns the value of the item at the cursor, or NULL if the cursor is +// not pointing to an item. +CZMQ_EXPORT void * + zlistx_item (zlistx_t *self); + +// Returns the handle of the item at the cursor, or NULL if the cursor is +// not pointing to an item. +CZMQ_EXPORT void * + zlistx_cursor (zlistx_t *self); + +// Returns the item associated with the given list handle, or NULL if passed +// in handle is NULL. Asserts that the passed in handle points to a list element. +CZMQ_EXPORT void * + zlistx_handle_item (void *handle); + +// Find an item in the list, searching from the start. Uses the item +// comparator, if any, else compares item values directly. Returns the +// item handle found, or NULL. Sets the cursor to the found item, if any. +CZMQ_EXPORT void * + zlistx_find (zlistx_t *self, void *item); + +// Detach an item from the list, using its handle. The item is not modified, +// and the caller is responsible for destroying it if necessary. If handle is +// null, detaches the first item on the list. Returns item that was detached, +// or null if none was. If cursor was at item, moves cursor to previous item, +// so you can detach items while iterating forwards through a list. +CZMQ_EXPORT void * + zlistx_detach (zlistx_t *self, void *handle); + +// Detach item at the cursor, if any, from the list. The item is not modified, +// and the caller is responsible for destroying it as necessary. Returns item +// that was detached, or null if none was. Moves cursor to previous item, so +// you can detach items while iterating forwards through a list. +CZMQ_EXPORT void * + zlistx_detach_cur (zlistx_t *self); + +// Delete an item, using its handle. Calls the item destructor is any is +// set. If handle is null, deletes the first item on the list. Returns 0 +// if an item was deleted, -1 if not. If cursor was at item, moves cursor +// to previous item, so you can delete items while iterating forwards +// through a list. +CZMQ_EXPORT int + zlistx_delete (zlistx_t *self, void *handle); + +// Move an item to the start of the list, via its handle. +CZMQ_EXPORT void + zlistx_move_start (zlistx_t *self, void *handle); + +// Move an item to the end of the list, via its handle. +CZMQ_EXPORT void + zlistx_move_end (zlistx_t *self, void *handle); + +// Remove all items from the list, and destroy them if the item destructor +// is set. +CZMQ_EXPORT void + zlistx_purge (zlistx_t *self); + +// Sort the list. If an item comparator was set, calls that to compare +// items, otherwise compares on item value. The sort is not stable, so may +// reorder equal items. +CZMQ_EXPORT void + zlistx_sort (zlistx_t *self); + +// Create a new node and insert it into a sorted list. Calls the item +// duplicator, if any, on the item. If low_value is true, starts searching +// from the start of the list, otherwise searches from the end. Use the item +// comparator, if any, to find where to place the new node. Returns a handle +// to the new node, or NULL if memory was exhausted. Resets the cursor to the +// list head. +CZMQ_EXPORT void * + zlistx_insert (zlistx_t *self, void *item, bool low_value); + +// Move an item, specified by handle, into position in a sorted list. Uses +// the item comparator, if any, to determine the new location. If low_value +// is true, starts searching from the start of the list, otherwise searches +// from the end. +CZMQ_EXPORT void + zlistx_reorder (zlistx_t *self, void *handle, bool low_value); + +// Make a copy of the list; items are duplicated if you set a duplicator +// for the list, otherwise not. Copying a null reference returns a null +// reference. +CZMQ_EXPORT zlistx_t * + zlistx_dup (zlistx_t *self); + +// Set a user-defined deallocator for list items; by default items are not +// freed when the list is destroyed. +CZMQ_EXPORT void + zlistx_set_destructor (zlistx_t *self, zlistx_destructor_fn destructor); + +// Set a user-defined duplicator for list items; by default items are not +// copied when the list is duplicated. +CZMQ_EXPORT void + zlistx_set_duplicator (zlistx_t *self, zlistx_duplicator_fn duplicator); + +// Set a user-defined comparator for zlistx_find and zlistx_sort; the method +// must return -1, 0, or 1 depending on whether item1 is less than, equal to, +// or greater than, item2. +CZMQ_EXPORT void + zlistx_set_comparator (zlistx_t *self, zlistx_comparator_fn comparator); + +// Self test of this class. +CZMQ_EXPORT void + zlistx_test (bool verbose); + +// @end + + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/aarch64-linux/include/zloop.h b/phonelibs/zmq/aarch64-linux/include/zloop.h new file mode 100644 index 00000000000000..83f46f282aa2ec --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/include/zloop.h @@ -0,0 +1,163 @@ +/* ========================================================================= + zloop - event-driven reactor + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZLOOP_H_INCLUDED__ +#define __ZLOOP_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/zloop.api" to make changes. +// @interface +// This is a stable class, and may not change except for emergencies. It +// is provided in stable builds. +// Callback function for reactor socket activity +typedef int (zloop_reader_fn) ( + zloop_t *loop, zsock_t *reader, void *arg); + +// Callback function for reactor events (low-level) +typedef int (zloop_fn) ( + zloop_t *loop, zmq_pollitem_t *item, void *arg); + +// Callback for reactor timer events +typedef int (zloop_timer_fn) ( + zloop_t *loop, int timer_id, void *arg); + +// Create a new zloop reactor +CZMQ_EXPORT zloop_t * + zloop_new (void); + +// Destroy a reactor +CZMQ_EXPORT void + zloop_destroy (zloop_t **self_p); + +// Register socket reader with the reactor. When the reader has messages, +// the reactor will call the handler, passing the arg. Returns 0 if OK, -1 +// if there was an error. If you register the same socket more than once, +// each instance will invoke its corresponding handler. +CZMQ_EXPORT int + zloop_reader (zloop_t *self, zsock_t *sock, zloop_reader_fn handler, void *arg); + +// Cancel a socket reader from the reactor. If multiple readers exist for +// same socket, cancels ALL of them. +CZMQ_EXPORT void + zloop_reader_end (zloop_t *self, zsock_t *sock); + +// Configure a registered reader to ignore errors. If you do not set this, +// then readers that have errors are removed from the reactor silently. +CZMQ_EXPORT void + zloop_reader_set_tolerant (zloop_t *self, zsock_t *sock); + +// Register low-level libzmq pollitem with the reactor. When the pollitem +// is ready, will call the handler, passing the arg. Returns 0 if OK, -1 +// if there was an error. If you register the pollitem more than once, each +// instance will invoke its corresponding handler. A pollitem with +// socket=NULL and fd=0 means 'poll on FD zero'. +CZMQ_EXPORT int + zloop_poller (zloop_t *self, zmq_pollitem_t *item, zloop_fn handler, void *arg); + +// Cancel a pollitem from the reactor, specified by socket or FD. If both +// are specified, uses only socket. If multiple poll items exist for same +// socket/FD, cancels ALL of them. +CZMQ_EXPORT void + zloop_poller_end (zloop_t *self, zmq_pollitem_t *item); + +// Configure a registered poller to ignore errors. If you do not set this, +// then poller that have errors are removed from the reactor silently. +CZMQ_EXPORT void + zloop_poller_set_tolerant (zloop_t *self, zmq_pollitem_t *item); + +// Register a timer that expires after some delay and repeats some number of +// times. At each expiry, will call the handler, passing the arg. To run a +// timer forever, use 0 times. Returns a timer_id that is used to cancel the +// timer in the future. Returns -1 if there was an error. +CZMQ_EXPORT int + zloop_timer (zloop_t *self, size_t delay, size_t times, zloop_timer_fn handler, void *arg); + +// Cancel a specific timer identified by a specific timer_id (as returned by +// zloop_timer). +CZMQ_EXPORT int + zloop_timer_end (zloop_t *self, int timer_id); + +// Register a ticket timer. Ticket timers are very fast in the case where +// you use a lot of timers (thousands), and frequently remove and add them. +// The main use case is expiry timers for servers that handle many clients, +// and which reset the expiry timer for each message received from a client. +// Whereas normal timers perform poorly as the number of clients grows, the +// cost of ticket timers is constant, no matter the number of clients. You +// must set the ticket delay using zloop_set_ticket_delay before creating a +// ticket. Returns a handle to the timer that you should use in +// zloop_ticket_reset and zloop_ticket_delete. +CZMQ_EXPORT void * + zloop_ticket (zloop_t *self, zloop_timer_fn handler, void *arg); + +// Reset a ticket timer, which moves it to the end of the ticket list and +// resets its execution time. This is a very fast operation. +CZMQ_EXPORT void + zloop_ticket_reset (zloop_t *self, void *handle); + +// Delete a ticket timer. We do not actually delete the ticket here, as +// other code may still refer to the ticket. We mark as deleted, and remove +// later and safely. +CZMQ_EXPORT void + zloop_ticket_delete (zloop_t *self, void *handle); + +// Set the ticket delay, which applies to all tickets. If you lower the +// delay and there are already tickets created, the results are undefined. +CZMQ_EXPORT void + zloop_set_ticket_delay (zloop_t *self, size_t ticket_delay); + +// Set hard limit on number of timers allowed. Setting more than a small +// number of timers (10-100) can have a dramatic impact on the performance +// of the reactor. For high-volume cases, use ticket timers. If the hard +// limit is reached, the reactor stops creating new timers and logs an +// error. +CZMQ_EXPORT void + zloop_set_max_timers (zloop_t *self, size_t max_timers); + +// Set verbose tracing of reactor on/off. The default verbose setting is +// off (false). +CZMQ_EXPORT void + zloop_set_verbose (zloop_t *self, bool verbose); + +// By default the reactor stops if the process receives a SIGINT or SIGTERM +// signal. This makes it impossible to shut-down message based architectures +// like zactors. This method lets you switch off break handling. The default +// nonstop setting is off (false). +CZMQ_EXPORT void + zloop_set_nonstop (zloop_t *self, bool nonstop); + +// Start the reactor. Takes control of the thread and returns when the 0MQ +// context is terminated or the process is interrupted, or any event handler +// returns -1. Event handlers may register new sockets and timers, and +// cancel sockets. Returns 0 if interrupted, -1 if canceled by a handler. +CZMQ_EXPORT int + zloop_start (zloop_t *self); + +// Self test of this class. +CZMQ_EXPORT void + zloop_test (bool verbose); + +// @end + + +// Deprecated method aliases +#define zloop_set_tolerant(s,i) zloop_poller_set_tolerant(s,i) + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/aarch64-linux/include/zmonitor.h b/phonelibs/zmq/aarch64-linux/include/zmonitor.h new file mode 100644 index 00000000000000..b490bcb1a0dfbc --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/include/zmonitor.h @@ -0,0 +1,73 @@ +/* ========================================================================= + zmonitor - socket event monitor + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZMONITOR_H_INCLUDED__ +#define __ZMONITOR_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @interface +// Create new zmonitor actor instance to monitor a zsock_t socket: +// +// zactor_t *monitor = zactor_new (zmonitor, mysocket); +// +// Destroy zmonitor instance. +// +// zactor_destroy (&monitor); +// +// Enable verbose logging of commands and activity. +// +// zstr_send (monitor, "VERBOSE"); +// +// Listen to monitor event type (zero or types, ending in NULL): +// zstr_sendx (monitor, "LISTEN", type, ..., NULL); +// +// Events: +// CONNECTED +// CONNECT_DELAYED +// CONNECT_RETRIED +// LISTENING +// BIND_FAILED +// ACCEPTED +// ACCEPT_FAILED +// CLOSED +// CLOSE_FAILED +// DISCONNECTED +// MONITOR_STOPPED +// ALL +// +// Start monitor; after this, any further LISTEN commands are ignored. +// +// zstr_send (monitor, "START"); +// zsock_wait (monitor); +// +// Receive next monitor event: +// +// zmsg_t *msg = zmsg_recv (monitor); +// +// This is the zmonitor constructor as a zactor_fn; the argument can be +// a zactor_t, zsock_t, or libzmq void * socket: +CZMQ_EXPORT void + zmonitor (zsock_t *pipe, void *sock); + +// Selftest +CZMQ_EXPORT void + zmonitor_test (bool verbose); +// @end +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/aarch64-linux/include/zmq.h b/phonelibs/zmq/aarch64-linux/include/zmq.h new file mode 100644 index 00000000000000..21a78eb6576be2 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/include/zmq.h @@ -0,0 +1,643 @@ +/* + Copyright (c) 2007-2016 Contributors as noted in the AUTHORS file + + This file is part of libzmq, the ZeroMQ core engine in C++. + + libzmq is free software; you can redistribute it and/or modify it under + the terms of the GNU Lesser General Public License (LGPL) as published + by the Free Software Foundation; either version 3 of the License, or + (at your option) any later version. + + As a special exception, the Contributors give you permission to link + this library with independent modules to produce an executable, + regardless of the license terms of these independent modules, and to + copy and distribute the resulting executable under terms of your choice, + provided that you also meet, for each linked independent module, the + terms and conditions of the license of that module. An independent + module is a module which is not derived from or based on this library. + If you modify this library, you must extend this exception to your + version of the library. + + libzmq 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 this program. If not, see . + + ************************************************************************* + NOTE to contributors. This file comprises the principal public contract + for ZeroMQ API users. Any change to this file supplied in a stable + release SHOULD not break existing applications. + In practice this means that the value of constants must not change, and + that old values may not be reused for new constants. + ************************************************************************* +*/ + +#ifndef __ZMQ_H_INCLUDED__ +#define __ZMQ_H_INCLUDED__ + +/* Version macros for compile-time API version detection */ +#define ZMQ_VERSION_MAJOR 4 +#define ZMQ_VERSION_MINOR 2 +#define ZMQ_VERSION_PATCH 2 + +#define ZMQ_MAKE_VERSION(major, minor, patch) \ + ((major) * 10000 + (minor) * 100 + (patch)) +#define ZMQ_VERSION \ + ZMQ_MAKE_VERSION(ZMQ_VERSION_MAJOR, ZMQ_VERSION_MINOR, ZMQ_VERSION_PATCH) + +#ifdef __cplusplus +extern "C" { +#endif + +#if !defined _WIN32_WCE +#include +#endif +#include +#include +#if defined _WIN32 +// Set target version to Windows Server 2008, Windows Vista or higher. +// Windows XP (0x0501) is supported but without client & server socket types. +#ifndef _WIN32_WINNT +#define _WIN32_WINNT 0x0600 +#endif + +#ifdef __MINGW32__ +// Require Windows XP or higher with MinGW for getaddrinfo(). +#if(_WIN32_WINNT >= 0x0600) +#else +#undef _WIN32_WINNT +#define _WIN32_WINNT 0x0600 +#endif +#endif +#include +#endif + +/* Handle DSO symbol visibility */ +#if defined _WIN32 +# if defined ZMQ_STATIC +# define ZMQ_EXPORT +# elif defined DLL_EXPORT +# define ZMQ_EXPORT __declspec(dllexport) +# else +# define ZMQ_EXPORT __declspec(dllimport) +# endif +#else +# if defined __SUNPRO_C || defined __SUNPRO_CC +# define ZMQ_EXPORT __global +# elif (defined __GNUC__ && __GNUC__ >= 4) || defined __INTEL_COMPILER +# define ZMQ_EXPORT __attribute__ ((visibility("default"))) +# else +# define ZMQ_EXPORT +# endif +#endif + +/* Define integer types needed for event interface */ +#define ZMQ_DEFINED_STDINT 1 +#if defined ZMQ_HAVE_SOLARIS || defined ZMQ_HAVE_OPENVMS +# include +#elif defined _MSC_VER && _MSC_VER < 1600 +# ifndef int32_t + typedef __int32 int32_t; +# endif +# ifndef uint16_t + typedef unsigned __int16 uint16_t; +# endif +# ifndef uint8_t + typedef unsigned __int8 uint8_t; +# endif +#else +# include +#endif + +// 32-bit AIX's pollfd struct members are called reqevents and rtnevents so it +// defines compatibility macros for them. Need to include that header first to +// stop build failures since zmq_pollset_t defines them as events and revents. +#ifdef ZMQ_HAVE_AIX + #include +#endif + + +/******************************************************************************/ +/* 0MQ errors. */ +/******************************************************************************/ + +/* A number random enough not to collide with different errno ranges on */ +/* different OSes. The assumption is that error_t is at least 32-bit type. */ +#define ZMQ_HAUSNUMERO 156384712 + +/* On Windows platform some of the standard POSIX errnos are not defined. */ +#ifndef ENOTSUP +#define ENOTSUP (ZMQ_HAUSNUMERO + 1) +#endif +#ifndef EPROTONOSUPPORT +#define EPROTONOSUPPORT (ZMQ_HAUSNUMERO + 2) +#endif +#ifndef ENOBUFS +#define ENOBUFS (ZMQ_HAUSNUMERO + 3) +#endif +#ifndef ENETDOWN +#define ENETDOWN (ZMQ_HAUSNUMERO + 4) +#endif +#ifndef EADDRINUSE +#define EADDRINUSE (ZMQ_HAUSNUMERO + 5) +#endif +#ifndef EADDRNOTAVAIL +#define EADDRNOTAVAIL (ZMQ_HAUSNUMERO + 6) +#endif +#ifndef ECONNREFUSED +#define ECONNREFUSED (ZMQ_HAUSNUMERO + 7) +#endif +#ifndef EINPROGRESS +#define EINPROGRESS (ZMQ_HAUSNUMERO + 8) +#endif +#ifndef ENOTSOCK +#define ENOTSOCK (ZMQ_HAUSNUMERO + 9) +#endif +#ifndef EMSGSIZE +#define EMSGSIZE (ZMQ_HAUSNUMERO + 10) +#endif +#ifndef EAFNOSUPPORT +#define EAFNOSUPPORT (ZMQ_HAUSNUMERO + 11) +#endif +#ifndef ENETUNREACH +#define ENETUNREACH (ZMQ_HAUSNUMERO + 12) +#endif +#ifndef ECONNABORTED +#define ECONNABORTED (ZMQ_HAUSNUMERO + 13) +#endif +#ifndef ECONNRESET +#define ECONNRESET (ZMQ_HAUSNUMERO + 14) +#endif +#ifndef ENOTCONN +#define ENOTCONN (ZMQ_HAUSNUMERO + 15) +#endif +#ifndef ETIMEDOUT +#define ETIMEDOUT (ZMQ_HAUSNUMERO + 16) +#endif +#ifndef EHOSTUNREACH +#define EHOSTUNREACH (ZMQ_HAUSNUMERO + 17) +#endif +#ifndef ENETRESET +#define ENETRESET (ZMQ_HAUSNUMERO + 18) +#endif + +/* Native 0MQ error codes. */ +#define EFSM (ZMQ_HAUSNUMERO + 51) +#define ENOCOMPATPROTO (ZMQ_HAUSNUMERO + 52) +#define ETERM (ZMQ_HAUSNUMERO + 53) +#define EMTHREAD (ZMQ_HAUSNUMERO + 54) + +/* This function retrieves the errno as it is known to 0MQ library. The goal */ +/* of this function is to make the code 100% portable, including where 0MQ */ +/* compiled with certain CRT library (on Windows) is linked to an */ +/* application that uses different CRT library. */ +ZMQ_EXPORT int zmq_errno (void); + +/* Resolves system errors and 0MQ errors to human-readable string. */ +ZMQ_EXPORT const char *zmq_strerror (int errnum); + +/* Run-time API version detection */ +ZMQ_EXPORT void zmq_version (int *major, int *minor, int *patch); + +/******************************************************************************/ +/* 0MQ infrastructure (a.k.a. context) initialisation & termination. */ +/******************************************************************************/ + +/* Context options */ +#define ZMQ_IO_THREADS 1 +#define ZMQ_MAX_SOCKETS 2 +#define ZMQ_SOCKET_LIMIT 3 +#define ZMQ_THREAD_PRIORITY 3 +#define ZMQ_THREAD_SCHED_POLICY 4 +#define ZMQ_MAX_MSGSZ 5 + +/* Default for new contexts */ +#define ZMQ_IO_THREADS_DFLT 1 +#define ZMQ_MAX_SOCKETS_DFLT 1023 +#define ZMQ_THREAD_PRIORITY_DFLT -1 +#define ZMQ_THREAD_SCHED_POLICY_DFLT -1 + +ZMQ_EXPORT void *zmq_ctx_new (void); +ZMQ_EXPORT int zmq_ctx_term (void *context); +ZMQ_EXPORT int zmq_ctx_shutdown (void *context); +ZMQ_EXPORT int zmq_ctx_set (void *context, int option, int optval); +ZMQ_EXPORT int zmq_ctx_get (void *context, int option); + +/* Old (legacy) API */ +ZMQ_EXPORT void *zmq_init (int io_threads); +ZMQ_EXPORT int zmq_term (void *context); +ZMQ_EXPORT int zmq_ctx_destroy (void *context); + + +/******************************************************************************/ +/* 0MQ message definition. */ +/******************************************************************************/ + +/* Some architectures, like sparc64 and some variants of aarch64, enforce pointer + * alignment and raise sigbus on violations. Make sure applications allocate + * zmq_msg_t on addresses aligned on a pointer-size boundary to avoid this issue. + */ +typedef struct zmq_msg_t { +#if defined (__GNUC__) || defined ( __INTEL_COMPILER) || \ + (defined (__SUNPRO_C) && __SUNPRO_C >= 0x590) || \ + (defined (__SUNPRO_CC) && __SUNPRO_CC >= 0x590) + unsigned char _ [64] __attribute__ ((aligned (sizeof (void *)))); +#elif defined (_MSC_VER) && (defined (_M_X64) || defined (_M_ARM64)) + __declspec (align (8)) unsigned char _ [64]; +#elif defined (_MSC_VER) && (defined (_M_IX86) || defined (_M_ARM_ARMV7VE)) + __declspec (align (4)) unsigned char _ [64]; +#else + unsigned char _ [64]; +#endif +} zmq_msg_t; + +typedef void (zmq_free_fn) (void *data, void *hint); + +ZMQ_EXPORT int zmq_msg_init (zmq_msg_t *msg); +ZMQ_EXPORT int zmq_msg_init_size (zmq_msg_t *msg, size_t size); +ZMQ_EXPORT int zmq_msg_init_data (zmq_msg_t *msg, void *data, + size_t size, zmq_free_fn *ffn, void *hint); +ZMQ_EXPORT int zmq_msg_send (zmq_msg_t *msg, void *s, int flags); +ZMQ_EXPORT int zmq_msg_recv (zmq_msg_t *msg, void *s, int flags); +ZMQ_EXPORT int zmq_msg_close (zmq_msg_t *msg); +ZMQ_EXPORT int zmq_msg_move (zmq_msg_t *dest, zmq_msg_t *src); +ZMQ_EXPORT int zmq_msg_copy (zmq_msg_t *dest, zmq_msg_t *src); +ZMQ_EXPORT void *zmq_msg_data (zmq_msg_t *msg); +ZMQ_EXPORT size_t zmq_msg_size (zmq_msg_t *msg); +ZMQ_EXPORT int zmq_msg_more (zmq_msg_t *msg); +ZMQ_EXPORT int zmq_msg_get (zmq_msg_t *msg, int property); +ZMQ_EXPORT int zmq_msg_set (zmq_msg_t *msg, int property, int optval); +ZMQ_EXPORT const char *zmq_msg_gets (zmq_msg_t *msg, const char *property); + +/******************************************************************************/ +/* 0MQ socket definition. */ +/******************************************************************************/ + +/* Socket types. */ +#define ZMQ_PAIR 0 +#define ZMQ_PUB 1 +#define ZMQ_SUB 2 +#define ZMQ_REQ 3 +#define ZMQ_REP 4 +#define ZMQ_DEALER 5 +#define ZMQ_ROUTER 6 +#define ZMQ_PULL 7 +#define ZMQ_PUSH 8 +#define ZMQ_XPUB 9 +#define ZMQ_XSUB 10 +#define ZMQ_STREAM 11 + +/* Deprecated aliases */ +#define ZMQ_XREQ ZMQ_DEALER +#define ZMQ_XREP ZMQ_ROUTER + +/* Socket options. */ +#define ZMQ_AFFINITY 4 +#define ZMQ_IDENTITY 5 +#define ZMQ_SUBSCRIBE 6 +#define ZMQ_UNSUBSCRIBE 7 +#define ZMQ_RATE 8 +#define ZMQ_RECOVERY_IVL 9 +#define ZMQ_SNDBUF 11 +#define ZMQ_RCVBUF 12 +#define ZMQ_RCVMORE 13 +#define ZMQ_FD 14 +#define ZMQ_EVENTS 15 +#define ZMQ_TYPE 16 +#define ZMQ_LINGER 17 +#define ZMQ_RECONNECT_IVL 18 +#define ZMQ_BACKLOG 19 +#define ZMQ_RECONNECT_IVL_MAX 21 +#define ZMQ_MAXMSGSIZE 22 +#define ZMQ_SNDHWM 23 +#define ZMQ_RCVHWM 24 +#define ZMQ_MULTICAST_HOPS 25 +#define ZMQ_RCVTIMEO 27 +#define ZMQ_SNDTIMEO 28 +#define ZMQ_LAST_ENDPOINT 32 +#define ZMQ_ROUTER_MANDATORY 33 +#define ZMQ_TCP_KEEPALIVE 34 +#define ZMQ_TCP_KEEPALIVE_CNT 35 +#define ZMQ_TCP_KEEPALIVE_IDLE 36 +#define ZMQ_TCP_KEEPALIVE_INTVL 37 +#define ZMQ_IMMEDIATE 39 +#define ZMQ_XPUB_VERBOSE 40 +#define ZMQ_ROUTER_RAW 41 +#define ZMQ_IPV6 42 +#define ZMQ_MECHANISM 43 +#define ZMQ_PLAIN_SERVER 44 +#define ZMQ_PLAIN_USERNAME 45 +#define ZMQ_PLAIN_PASSWORD 46 +#define ZMQ_CURVE_SERVER 47 +#define ZMQ_CURVE_PUBLICKEY 48 +#define ZMQ_CURVE_SECRETKEY 49 +#define ZMQ_CURVE_SERVERKEY 50 +#define ZMQ_PROBE_ROUTER 51 +#define ZMQ_REQ_CORRELATE 52 +#define ZMQ_REQ_RELAXED 53 +#define ZMQ_CONFLATE 54 +#define ZMQ_ZAP_DOMAIN 55 +#define ZMQ_ROUTER_HANDOVER 56 +#define ZMQ_TOS 57 +#define ZMQ_CONNECT_RID 61 +#define ZMQ_GSSAPI_SERVER 62 +#define ZMQ_GSSAPI_PRINCIPAL 63 +#define ZMQ_GSSAPI_SERVICE_PRINCIPAL 64 +#define ZMQ_GSSAPI_PLAINTEXT 65 +#define ZMQ_HANDSHAKE_IVL 66 +#define ZMQ_SOCKS_PROXY 68 +#define ZMQ_XPUB_NODROP 69 +#define ZMQ_BLOCKY 70 +#define ZMQ_XPUB_MANUAL 71 +#define ZMQ_XPUB_WELCOME_MSG 72 +#define ZMQ_STREAM_NOTIFY 73 +#define ZMQ_INVERT_MATCHING 74 +#define ZMQ_HEARTBEAT_IVL 75 +#define ZMQ_HEARTBEAT_TTL 76 +#define ZMQ_HEARTBEAT_TIMEOUT 77 +#define ZMQ_XPUB_VERBOSER 78 +#define ZMQ_CONNECT_TIMEOUT 79 +#define ZMQ_TCP_MAXRT 80 +#define ZMQ_THREAD_SAFE 81 +#define ZMQ_MULTICAST_MAXTPDU 84 +#define ZMQ_VMCI_BUFFER_SIZE 85 +#define ZMQ_VMCI_BUFFER_MIN_SIZE 86 +#define ZMQ_VMCI_BUFFER_MAX_SIZE 87 +#define ZMQ_VMCI_CONNECT_TIMEOUT 88 +#define ZMQ_USE_FD 89 + +/* Message options */ +#define ZMQ_MORE 1 +#define ZMQ_SHARED 3 + +/* Send/recv options. */ +#define ZMQ_DONTWAIT 1 +#define ZMQ_SNDMORE 2 + +/* Security mechanisms */ +#define ZMQ_NULL 0 +#define ZMQ_PLAIN 1 +#define ZMQ_CURVE 2 +#define ZMQ_GSSAPI 3 + +/* RADIO-DISH protocol */ +#define ZMQ_GROUP_MAX_LENGTH 15 + +/* Deprecated options and aliases */ +#define ZMQ_TCP_ACCEPT_FILTER 38 +#define ZMQ_IPC_FILTER_PID 58 +#define ZMQ_IPC_FILTER_UID 59 +#define ZMQ_IPC_FILTER_GID 60 +#define ZMQ_IPV4ONLY 31 +#define ZMQ_DELAY_ATTACH_ON_CONNECT ZMQ_IMMEDIATE +#define ZMQ_NOBLOCK ZMQ_DONTWAIT +#define ZMQ_FAIL_UNROUTABLE ZMQ_ROUTER_MANDATORY +#define ZMQ_ROUTER_BEHAVIOR ZMQ_ROUTER_MANDATORY + +/* Deprecated Message options */ +#define ZMQ_SRCFD 2 + +/******************************************************************************/ +/* 0MQ socket events and monitoring */ +/******************************************************************************/ + +/* Socket transport events (TCP, IPC and TIPC only) */ + +#define ZMQ_EVENT_CONNECTED 0x0001 +#define ZMQ_EVENT_CONNECT_DELAYED 0x0002 +#define ZMQ_EVENT_CONNECT_RETRIED 0x0004 +#define ZMQ_EVENT_LISTENING 0x0008 +#define ZMQ_EVENT_BIND_FAILED 0x0010 +#define ZMQ_EVENT_ACCEPTED 0x0020 +#define ZMQ_EVENT_ACCEPT_FAILED 0x0040 +#define ZMQ_EVENT_CLOSED 0x0080 +#define ZMQ_EVENT_CLOSE_FAILED 0x0100 +#define ZMQ_EVENT_DISCONNECTED 0x0200 +#define ZMQ_EVENT_MONITOR_STOPPED 0x0400 +#define ZMQ_EVENT_ALL 0xFFFF + +ZMQ_EXPORT void *zmq_socket (void *, int type); +ZMQ_EXPORT int zmq_close (void *s); +ZMQ_EXPORT int zmq_setsockopt (void *s, int option, const void *optval, + size_t optvallen); +ZMQ_EXPORT int zmq_getsockopt (void *s, int option, void *optval, + size_t *optvallen); +ZMQ_EXPORT int zmq_bind (void *s, const char *addr); +ZMQ_EXPORT int zmq_connect (void *s, const char *addr); +ZMQ_EXPORT int zmq_unbind (void *s, const char *addr); +ZMQ_EXPORT int zmq_disconnect (void *s, const char *addr); +ZMQ_EXPORT int zmq_send (void *s, const void *buf, size_t len, int flags); +ZMQ_EXPORT int zmq_send_const (void *s, const void *buf, size_t len, int flags); +ZMQ_EXPORT int zmq_recv (void *s, void *buf, size_t len, int flags); +ZMQ_EXPORT int zmq_socket_monitor (void *s, const char *addr, int events); + + +/******************************************************************************/ +/* I/O multiplexing. */ +/******************************************************************************/ + +#define ZMQ_POLLIN 1 +#define ZMQ_POLLOUT 2 +#define ZMQ_POLLERR 4 +#define ZMQ_POLLPRI 8 + +typedef struct zmq_pollitem_t +{ + void *socket; +#if defined _WIN32 + SOCKET fd; +#else + int fd; +#endif + short events; + short revents; +} zmq_pollitem_t; + +#define ZMQ_POLLITEMS_DFLT 16 + +ZMQ_EXPORT int zmq_poll (zmq_pollitem_t *items, int nitems, long timeout); + +/******************************************************************************/ +/* Message proxying */ +/******************************************************************************/ + +ZMQ_EXPORT int zmq_proxy (void *frontend, void *backend, void *capture); +ZMQ_EXPORT int zmq_proxy_steerable (void *frontend, void *backend, void *capture, void *control); + +/******************************************************************************/ +/* Probe library capabilities */ +/******************************************************************************/ + +#define ZMQ_HAS_CAPABILITIES 1 +ZMQ_EXPORT int zmq_has (const char *capability); + +/* Deprecated aliases */ +#define ZMQ_STREAMER 1 +#define ZMQ_FORWARDER 2 +#define ZMQ_QUEUE 3 + +/* Deprecated methods */ +ZMQ_EXPORT int zmq_device (int type, void *frontend, void *backend); +ZMQ_EXPORT int zmq_sendmsg (void *s, zmq_msg_t *msg, int flags); +ZMQ_EXPORT int zmq_recvmsg (void *s, zmq_msg_t *msg, int flags); +struct iovec; +ZMQ_EXPORT int zmq_sendiov (void *s, struct iovec *iov, size_t count, int flags); +ZMQ_EXPORT int zmq_recviov (void *s, struct iovec *iov, size_t *count, int flags); + +/******************************************************************************/ +/* Encryption functions */ +/******************************************************************************/ + +/* Encode data with Z85 encoding. Returns encoded data */ +ZMQ_EXPORT char *zmq_z85_encode (char *dest, const uint8_t *data, size_t size); + +/* Decode data with Z85 encoding. Returns decoded data */ +ZMQ_EXPORT uint8_t *zmq_z85_decode (uint8_t *dest, const char *string); + +/* Generate z85-encoded public and private keypair with tweetnacl/libsodium. */ +/* Returns 0 on success. */ +ZMQ_EXPORT int zmq_curve_keypair (char *z85_public_key, char *z85_secret_key); + +/* Derive the z85-encoded public key from the z85-encoded secret key. */ +/* Returns 0 on success. */ +ZMQ_EXPORT int zmq_curve_public (char *z85_public_key, const char *z85_secret_key); + +/******************************************************************************/ +/* Atomic utility methods */ +/******************************************************************************/ + +ZMQ_EXPORT void *zmq_atomic_counter_new (void); +ZMQ_EXPORT void zmq_atomic_counter_set (void *counter, int value); +ZMQ_EXPORT int zmq_atomic_counter_inc (void *counter); +ZMQ_EXPORT int zmq_atomic_counter_dec (void *counter); +ZMQ_EXPORT int zmq_atomic_counter_value (void *counter); +ZMQ_EXPORT void zmq_atomic_counter_destroy (void **counter_p); + + +/******************************************************************************/ +/* These functions are not documented by man pages -- use at your own risk. */ +/* If you need these to be part of the formal ZMQ API, then (a) write a man */ +/* page, and (b) write a test case in tests. */ +/******************************************************************************/ + +/* Helper functions are used by perf tests so that they don't have to care */ +/* about minutiae of time-related functions on different OS platforms. */ + +/* Starts the stopwatch. Returns the handle to the watch. */ +ZMQ_EXPORT void *zmq_stopwatch_start (void); + +/* Stops the stopwatch. Returns the number of microseconds elapsed since */ +/* the stopwatch was started. */ +ZMQ_EXPORT unsigned long zmq_stopwatch_stop (void *watch_); + +/* Sleeps for specified number of seconds. */ +ZMQ_EXPORT void zmq_sleep (int seconds_); + +typedef void (zmq_thread_fn) (void*); + +/* Start a thread. Returns a handle to the thread. */ +ZMQ_EXPORT void *zmq_threadstart (zmq_thread_fn* func, void* arg); + +/* Wait for thread to complete then free up resources. */ +ZMQ_EXPORT void zmq_threadclose (void* thread); + + +/******************************************************************************/ +/* These functions are DRAFT and disabled in stable releases, and subject to */ +/* change at ANY time until declared stable. */ +/******************************************************************************/ + +#ifdef ZMQ_BUILD_DRAFT_API + +/* DRAFT Socket types. */ +#define ZMQ_SERVER 12 +#define ZMQ_CLIENT 13 +#define ZMQ_RADIO 14 +#define ZMQ_DISH 15 +#define ZMQ_GATHER 16 +#define ZMQ_SCATTER 17 +#define ZMQ_DGRAM 18 + +/* DRAFT 0MQ socket events and monitoring */ +#define ZMQ_EVENT_HANDSHAKE_FAILED 0x0800 +#define ZMQ_EVENT_HANDSHAKE_SUCCEED 0x1000 + +/* DRAFT Context options */ +#define ZMQ_MSG_T_SIZE 6 + +/* DRAFT Socket methods. */ +ZMQ_EXPORT int zmq_join (void *s, const char *group); +ZMQ_EXPORT int zmq_leave (void *s, const char *group); + +/* DRAFT Msg methods. */ +ZMQ_EXPORT int zmq_msg_set_routing_id(zmq_msg_t *msg, uint32_t routing_id); +ZMQ_EXPORT uint32_t zmq_msg_routing_id(zmq_msg_t *msg); +ZMQ_EXPORT int zmq_msg_set_group(zmq_msg_t *msg, const char *group); +ZMQ_EXPORT const char *zmq_msg_group(zmq_msg_t *msg); + +/******************************************************************************/ +/* Poller polling on sockets,fd and thread-safe sockets */ +/******************************************************************************/ + +#define ZMQ_HAVE_POLLER + +typedef struct zmq_poller_event_t +{ + void *socket; +#if defined _WIN32 + SOCKET fd; +#else + int fd; +#endif + void *user_data; + short events; +} zmq_poller_event_t; + +ZMQ_EXPORT void *zmq_poller_new (void); +ZMQ_EXPORT int zmq_poller_destroy (void **poller_p); +ZMQ_EXPORT int zmq_poller_add (void *poller, void *socket, void *user_data, short events); +ZMQ_EXPORT int zmq_poller_modify (void *poller, void *socket, short events); +ZMQ_EXPORT int zmq_poller_remove (void *poller, void *socket); +ZMQ_EXPORT int zmq_poller_wait (void *poller, zmq_poller_event_t *event, long timeout); +ZMQ_EXPORT int zmq_poller_wait_all (void *poller, zmq_poller_event_t *events, int n_events, long timeout); + +#if defined _WIN32 +ZMQ_EXPORT int zmq_poller_add_fd (void *poller, SOCKET fd, void *user_data, short events); +ZMQ_EXPORT int zmq_poller_modify_fd (void *poller, SOCKET fd, short events); +ZMQ_EXPORT int zmq_poller_remove_fd (void *poller, SOCKET fd); +#else +ZMQ_EXPORT int zmq_poller_add_fd (void *poller, int fd, void *user_data, short events); +ZMQ_EXPORT int zmq_poller_modify_fd (void *poller, int fd, short events); +ZMQ_EXPORT int zmq_poller_remove_fd (void *poller, int fd); +#endif + +/******************************************************************************/ +/* Scheduling timers */ +/******************************************************************************/ + +#define ZMQ_HAVE_TIMERS + +typedef void (zmq_timer_fn)(int timer_id, void *arg); + +ZMQ_EXPORT void *zmq_timers_new (void); +ZMQ_EXPORT int zmq_timers_destroy (void **timers_p); +ZMQ_EXPORT int zmq_timers_add (void *timers, size_t interval, zmq_timer_fn handler, void *arg); +ZMQ_EXPORT int zmq_timers_cancel (void *timers, int timer_id); +ZMQ_EXPORT int zmq_timers_set_interval (void *timers, int timer_id, size_t interval); +ZMQ_EXPORT int zmq_timers_reset (void *timers, int timer_id); +ZMQ_EXPORT long zmq_timers_timeout (void *timers); +ZMQ_EXPORT int zmq_timers_execute (void *timers); + +#endif // ZMQ_BUILD_DRAFT_API + + +#undef ZMQ_EXPORT + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/aarch64-linux/include/zmq_utils.h b/phonelibs/zmq/aarch64-linux/include/zmq_utils.h new file mode 100644 index 00000000000000..f29638d5539414 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/include/zmq_utils.h @@ -0,0 +1,48 @@ +/* + Copyright (c) 2007-2016 Contributors as noted in the AUTHORS file + + This file is part of libzmq, the ZeroMQ core engine in C++. + + libzmq is free software; you can redistribute it and/or modify it under + the terms of the GNU Lesser General Public License (LGPL) as published + by the Free Software Foundation; either version 3 of the License, or + (at your option) any later version. + + As a special exception, the Contributors give you permission to link + this library with independent modules to produce an executable, + regardless of the license terms of these independent modules, and to + copy and distribute the resulting executable under terms of your choice, + provided that you also meet, for each linked independent module, the + terms and conditions of the license of that module. An independent + module is a module which is not derived from or based on this library. + If you modify this library, you must extend this exception to your + version of the library. + + libzmq 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 this program. If not, see . +*/ + +/* This file is deprecated, and all its functionality provided by zmq.h */ +/* Note that -Wpedantic compilation requires GCC to avoid using its custom + extensions such as #warning, hence the trick below. Also, pragmas for + warnings or other messages are not standard, not portable, and not all + compilers even have an equivalent concept. + So in the worst case, this include file is treated as silently empty. */ + +#if defined(__clang__) || defined(__GNUC__) || defined(__GNUG__) || defined(_MSC_VER) +#if defined(__GNUC__) || defined(__GNUG__) +#pragma GCC diagnostic push +#pragma GCC diagnostic warning "-Wcpp" +#pragma GCC diagnostic ignored "-Werror" +#pragma GCC diagnostic ignored "-Wall" +#endif +#pragma message("Warning: zmq_utils.h is deprecated. All its functionality is provided by zmq.h.") +#if defined(__GNUC__) || defined(__GNUG__) +#pragma GCC diagnostic pop +#endif +#endif diff --git a/phonelibs/zmq/aarch64-linux/include/zmsg.h b/phonelibs/zmq/aarch64-linux/include/zmsg.h new file mode 100644 index 00000000000000..d8a84d1f4198ed --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/include/zmsg.h @@ -0,0 +1,280 @@ +/* ========================================================================= + zmsg - working with multipart messages + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZMSG_H_INCLUDED__ +#define __ZMSG_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/zmsg.api" to make changes. +// @interface +// This is a stable class, and may not change except for emergencies. It +// is provided in stable builds. +// This class has draft methods, which may change over time. They are not +// in stable releases, by default. Use --enable-drafts to enable. +// Create a new empty message object +CZMQ_EXPORT zmsg_t * + zmsg_new (void); + +// Receive message from socket, returns zmsg_t object or NULL if the recv +// was interrupted. Does a blocking recv. If you want to not block then use +// the zloop class or zmsg_recv_nowait or zmq_poll to check for socket input +// before receiving. +CZMQ_EXPORT zmsg_t * + zmsg_recv (void *source); + +// Load/append an open file into new message, return the message. +// Returns NULL if the message could not be loaded. +CZMQ_EXPORT zmsg_t * + zmsg_load (FILE *file); + +// Decodes a serialized message frame created by zmsg_encode () and returns +// a new zmsg_t object. Returns NULL if the frame was badly formatted or +// there was insufficient memory to work. +CZMQ_EXPORT zmsg_t * + zmsg_decode (zframe_t *frame); + +// Generate a signal message encoding the given status. A signal is a short +// message carrying a 1-byte success/failure code (by convention, 0 means +// OK). Signals are encoded to be distinguishable from "normal" messages. +CZMQ_EXPORT zmsg_t * + zmsg_new_signal (byte status); + +// Destroy a message object and all frames it contains +CZMQ_EXPORT void + zmsg_destroy (zmsg_t **self_p); + +// Send message to destination socket, and destroy the message after sending +// it successfully. If the message has no frames, sends nothing but destroys +// the message anyhow. Nullifies the caller's reference to the message (as +// it is a destructor). +CZMQ_EXPORT int + zmsg_send (zmsg_t **self_p, void *dest); + +// Send message to destination socket as part of a multipart sequence, and +// destroy the message after sending it successfully. Note that after a +// zmsg_sendm, you must call zmsg_send or another method that sends a final +// message part. If the message has no frames, sends nothing but destroys +// the message anyhow. Nullifies the caller's reference to the message (as +// it is a destructor). +CZMQ_EXPORT int + zmsg_sendm (zmsg_t **self_p, void *dest); + +// Return size of message, i.e. number of frames (0 or more). +CZMQ_EXPORT size_t + zmsg_size (zmsg_t *self); + +// Return total size of all frames in message. +CZMQ_EXPORT size_t + zmsg_content_size (zmsg_t *self); + +// Push frame to the front of the message, i.e. before all other frames. +// Message takes ownership of frame, will destroy it when message is sent. +// Returns 0 on success, -1 on error. Deprecates zmsg_push, which did not +// nullify the caller's frame reference. +CZMQ_EXPORT int + zmsg_prepend (zmsg_t *self, zframe_t **frame_p); + +// Add frame to the end of the message, i.e. after all other frames. +// Message takes ownership of frame, will destroy it when message is sent. +// Returns 0 on success. Deprecates zmsg_add, which did not nullify the +// caller's frame reference. +CZMQ_EXPORT int + zmsg_append (zmsg_t *self, zframe_t **frame_p); + +// Remove first frame from message, if any. Returns frame, or NULL. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zframe_t * + zmsg_pop (zmsg_t *self); + +// Push block of memory to front of message, as a new frame. +// Returns 0 on success, -1 on error. +CZMQ_EXPORT int + zmsg_pushmem (zmsg_t *self, const void *data, size_t size); + +// Add block of memory to the end of the message, as a new frame. +// Returns 0 on success, -1 on error. +CZMQ_EXPORT int + zmsg_addmem (zmsg_t *self, const void *data, size_t size); + +// Push string as new frame to front of message. +// Returns 0 on success, -1 on error. +CZMQ_EXPORT int + zmsg_pushstr (zmsg_t *self, const char *string); + +// Push string as new frame to end of message. +// Returns 0 on success, -1 on error. +CZMQ_EXPORT int + zmsg_addstr (zmsg_t *self, const char *string); + +// Push formatted string as new frame to front of message. +// Returns 0 on success, -1 on error. +CZMQ_EXPORT int + zmsg_pushstrf (zmsg_t *self, const char *format, ...) CHECK_PRINTF (2); + +// Push formatted string as new frame to end of message. +// Returns 0 on success, -1 on error. +CZMQ_EXPORT int + zmsg_addstrf (zmsg_t *self, const char *format, ...) CHECK_PRINTF (2); + +// Pop frame off front of message, return as fresh string. If there were +// no more frames in the message, returns NULL. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT char * + zmsg_popstr (zmsg_t *self); + +// Push encoded message as a new frame. Message takes ownership of +// submessage, so the original is destroyed in this call. Returns 0 on +// success, -1 on error. +CZMQ_EXPORT int + zmsg_addmsg (zmsg_t *self, zmsg_t **msg_p); + +// Remove first submessage from message, if any. Returns zmsg_t, or NULL if +// decoding was not successful. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zmsg_t * + zmsg_popmsg (zmsg_t *self); + +// Remove specified frame from list, if present. Does not destroy frame. +CZMQ_EXPORT void + zmsg_remove (zmsg_t *self, zframe_t *frame); + +// Set cursor to first frame in message. Returns frame, or NULL, if the +// message is empty. Use this to navigate the frames as a list. +CZMQ_EXPORT zframe_t * + zmsg_first (zmsg_t *self); + +// Return the next frame. If there are no more frames, returns NULL. To move +// to the first frame call zmsg_first(). Advances the cursor. +CZMQ_EXPORT zframe_t * + zmsg_next (zmsg_t *self); + +// Return the last frame. If there are no frames, returns NULL. +CZMQ_EXPORT zframe_t * + zmsg_last (zmsg_t *self); + +// Save message to an open file, return 0 if OK, else -1. The message is +// saved as a series of frames, each with length and data. Note that the +// file is NOT guaranteed to be portable between operating systems, not +// versions of CZMQ. The file format is at present undocumented and liable +// to arbitrary change. +CZMQ_EXPORT int + zmsg_save (zmsg_t *self, FILE *file); + +// Serialize multipart message to a single message frame. Use this method +// to send structured messages across transports that do not support +// multipart data. Allocates and returns a new frame containing the +// serialized message. To decode a serialized message frame, use +// zmsg_decode (). +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zframe_t * + zmsg_encode (zmsg_t *self); + +// Create copy of message, as new message object. Returns a fresh zmsg_t +// object. If message is null, or memory was exhausted, returns null. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zmsg_t * + zmsg_dup (zmsg_t *self); + +// Send message to zsys log sink (may be stdout, or system facility as +// configured by zsys_set_logstream). +CZMQ_EXPORT void + zmsg_print (zmsg_t *self); + +// Return true if the two messages have the same number of frames and each +// frame in the first message is identical to the corresponding frame in the +// other message. As with zframe_eq, return false if either message is NULL. +CZMQ_EXPORT bool + zmsg_eq (zmsg_t *self, zmsg_t *other); + +// Return signal value, 0 or greater, if message is a signal, -1 if not. +CZMQ_EXPORT int + zmsg_signal (zmsg_t *self); + +// Probe the supplied object, and report if it looks like a zmsg_t. +CZMQ_EXPORT bool + zmsg_is (void *self); + +// Self test of this class. +CZMQ_EXPORT void + zmsg_test (bool verbose); + +#ifdef CZMQ_BUILD_DRAFT_API +// *** Draft method, for development use, may change without warning *** +// Return message routing ID, if the message came from a ZMQ_SERVER socket. +// Else returns zero. +CZMQ_EXPORT uint32_t + zmsg_routing_id (zmsg_t *self); + +// *** Draft method, for development use, may change without warning *** +// Set routing ID on message. This is used if/when the message is sent to a +// ZMQ_SERVER socket. +CZMQ_EXPORT void + zmsg_set_routing_id (zmsg_t *self, uint32_t routing_id); + +#endif // CZMQ_BUILD_DRAFT_API +// @end + + +// DEPRECATED as over-engineered, poor style +// Pop frame off front of message, caller now owns frame +// If next frame is empty, pops and destroys that empty frame. +CZMQ_EXPORT zframe_t * + zmsg_unwrap (zmsg_t *self); + +// DEPRECATED as poor style -- callers should use zloop or zpoller +// Receive message from socket, returns zmsg_t object, or NULL either if +// there was no input waiting, or the recv was interrupted. +CZMQ_EXPORT zmsg_t * + zmsg_recv_nowait (void *source); + +// DEPRECATED as unsafe -- does not nullify frame reference. +// Push frame plus empty frame to front of message, before first frame. +// Message takes ownership of frame, will destroy it when message is sent. +CZMQ_EXPORT void + zmsg_wrap (zmsg_t *self, zframe_t *frame); + +// DEPRECATED - will be removed for next + 1 stable release +// Add frame to the front of the message, i.e. before all other frames. +// Message takes ownership of frame, will destroy it when message is sent. +// Returns 0 on success, -1 on error. +CZMQ_EXPORT int + zmsg_push (zmsg_t *self, zframe_t *frame); + +// DEPRECATED - will be removed for next stable release +CZMQ_EXPORT int + zmsg_add (zmsg_t *self, zframe_t *frame); + +// DEPRECATED as inconsistent; breaks principle that logging should all go +// to a single destination. +// Print message to open stream +// Truncates to first 10 frames, for readability. +CZMQ_EXPORT void + zmsg_fprint (zmsg_t *self, FILE *file); + +// Compiler hints +CZMQ_EXPORT int zmsg_addstrf (zmsg_t *self, const char *format, ...) CHECK_PRINTF (2); +CZMQ_EXPORT int zmsg_pushstrf (zmsg_t *self, const char *format, ...) CHECK_PRINTF (2); + +#ifdef __cplusplus +} +#endif + +// Deprecated method aliases +#define zmsg_dump(s) zmsg_print(s) +#define zmsg_dump_to_stream(s,F) zmsg_fprint(s,F) + +#endif diff --git a/phonelibs/zmq/aarch64-linux/include/zpoller.h b/phonelibs/zmq/aarch64-linux/include/zpoller.h new file mode 100644 index 00000000000000..3b394c35161840 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/include/zpoller.h @@ -0,0 +1,87 @@ +/* ========================================================================= + zpoller - trivial socket poller class + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __zpoller_H_INCLUDED__ +#define __zpoller_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/zpoller.api" to make changes. +// @interface +// This is a stable class, and may not change except for emergencies. It +// is provided in stable builds. +// Create new poller, specifying zero or more readers. The list of +// readers ends in a NULL. Each reader can be a zsock_t instance, a +// zactor_t instance, a libzmq socket (void *), or a file handle. +CZMQ_EXPORT zpoller_t * + zpoller_new (void *reader, ...); + +// Destroy a poller +CZMQ_EXPORT void + zpoller_destroy (zpoller_t **self_p); + +// Add a reader to be polled. Returns 0 if OK, -1 on failure. The reader may +// be a libzmq void * socket, a zsock_t instance, or a zactor_t instance. +CZMQ_EXPORT int + zpoller_add (zpoller_t *self, void *reader); + +// Remove a reader from the poller; returns 0 if OK, -1 on failure. The reader +// must have been passed during construction, or in an zpoller_add () call. +CZMQ_EXPORT int + zpoller_remove (zpoller_t *self, void *reader); + +// By default the poller stops if the process receives a SIGINT or SIGTERM +// signal. This makes it impossible to shut-down message based architectures +// like zactors. This method lets you switch off break handling. The default +// nonstop setting is off (false). +CZMQ_EXPORT void + zpoller_set_nonstop (zpoller_t *self, bool nonstop); + +// Poll the registered readers for I/O, return first reader that has input. +// The reader will be a libzmq void * socket, or a zsock_t or zactor_t +// instance as specified in zpoller_new/zpoller_add. The timeout should be +// zero or greater, or -1 to wait indefinitely. Socket priority is defined +// by their order in the poll list. If you need a balanced poll, use the low +// level zmq_poll method directly. If the poll call was interrupted (SIGINT), +// or the ZMQ context was destroyed, or the timeout expired, returns NULL. +// You can test the actual exit condition by calling zpoller_expired () and +// zpoller_terminated (). The timeout is in msec. +CZMQ_EXPORT void * + zpoller_wait (zpoller_t *self, int timeout); + +// Return true if the last zpoller_wait () call ended because the timeout +// expired, without any error. +CZMQ_EXPORT bool + zpoller_expired (zpoller_t *self); + +// Return true if the last zpoller_wait () call ended because the process +// was interrupted, or the parent context was destroyed. +CZMQ_EXPORT bool + zpoller_terminated (zpoller_t *self); + +// Self test of this class. +CZMQ_EXPORT void + zpoller_test (bool verbose); + +// @end + + +#ifdef __cplusplus +} +#endif + +#endif + diff --git a/phonelibs/zmq/aarch64-linux/include/zproxy.h b/phonelibs/zmq/aarch64-linux/include/zproxy.h new file mode 100644 index 00000000000000..f672c5e72417a5 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/include/zproxy.h @@ -0,0 +1,111 @@ +/* ========================================================================= + zproxy - run a steerable proxy in the background + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZPROXY_H_INCLUDED__ +#define __ZPROXY_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @interface +// Create new zproxy actor instance. The proxy switches messages between +// a frontend socket and a backend socket; use the FRONTEND and BACKEND +// commands to configure these: +// +// zactor_t *proxy = zactor_new (zproxy, NULL); +// +// Destroy zproxy instance. This destroys the two sockets and stops any +// message flow between them: +// +// zactor_destroy (&proxy); +// +// Note that all zproxy commands are synchronous, so your application always +// waits for a signal from the actor after each command. +// +// Enable verbose logging of commands and activity: +// +// zstr_send (proxy, "VERBOSE"); +// zsock_wait (proxy); +// +// Specify frontend socket type -- see zsock_type_str () -- and attach to +// endpoints, see zsock_attach (). Note that a proxy socket is always +// serverish: +// +// zstr_sendx (proxy, "FRONTEND", "XSUB", endpoints, NULL); +// zsock_wait (proxy); +// +// Specify backend socket type -- see zsock_type_str () -- and attach to +// endpoints, see zsock_attach (). Note that a proxy socket is always +// serverish: +// +// zstr_sendx (proxy, "BACKEND", "XPUB", endpoints, NULL); +// zsock_wait (proxy); +// +// Capture all proxied messages; these are delivered to the application +// via an inproc PULL socket that you have already bound to the specified +// endpoint: +// +// zstr_sendx (proxy, "CAPTURE", endpoint, NULL); +// zsock_wait (proxy); +// +// Pause the proxy. A paused proxy will cease processing messages, causing +// them to be queued up and potentially hit the high-water mark on the +// frontend or backend socket, causing messages to be dropped, or writing +// applications to block: +// +// zstr_sendx (proxy, "PAUSE", NULL); +// zsock_wait (proxy); +// +// Resume the proxy. Note that the proxy starts automatically as soon as it +// has a properly attached frontend and backend socket: +// +// zstr_sendx (proxy, "RESUME", NULL); +// zsock_wait (proxy); +// +// Configure an authentication domain for the "FRONTEND" or "BACKEND" proxy +// socket -- see zsock_set_zap_domain (). Call before binding socket: +// +// zstr_sendx (proxy, "DOMAIN", "FRONTEND", "global", NULL); +// zsock_wait (proxy); +// +// Configure PLAIN authentication for the "FRONTEND" or "BACKEND" proxy +// socket -- see zsock_set_plain_server (). Call before binding socket: +// +// zstr_sendx (proxy, "PLAIN", "BACKEND", NULL); +// zsock_wait (proxy); +// +// Configure CURVE authentication for the "FRONTEND" or "BACKEND" proxy +// socket -- see zsock_set_curve_server () -- specifying both the public and +// secret keys of a certificate as Z85 armored strings -- see +// zcert_public_txt () and zcert_secret_txt (). Call before binding socket: +// +// zstr_sendx (proxy, "CURVE", "FRONTEND", public_txt, secret_txt, NULL); +// zsock_wait (proxy); +// +// This is the zproxy constructor as a zactor_fn; the argument is a +// character string specifying frontend and backend socket types as two +// uppercase strings separated by a hyphen: +CZMQ_EXPORT void + zproxy (zsock_t *pipe, void *unused); + +// Selftest +CZMQ_EXPORT void + zproxy_test (bool verbose); +// @end + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/aarch64-linux/include/zrex.h b/phonelibs/zmq/aarch64-linux/include/zrex.h new file mode 100644 index 00000000000000..8b50618a34837c --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/include/zrex.h @@ -0,0 +1,82 @@ +/* ========================================================================= + zrex - work with regular expressions + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZREX_H_INCLUDED__ +#define __ZREX_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @interface +// Constructor. Optionally, sets an expression against which we can match +// text and capture hits. If there is an error in the expression, reports +// zrex_valid() as false and provides the error in zrex_strerror(). If you +// set a pattern, you can call zrex_matches() to test it against text. +CZMQ_EXPORT zrex_t * + zrex_new (const char *expression); + +// Destructor +CZMQ_EXPORT void + zrex_destroy (zrex_t **self_p); + +// Return true if the expression was valid and compiled without errors. +CZMQ_EXPORT bool + zrex_valid (zrex_t *self); + +// Return the error message generated during compilation of the expression. +CZMQ_EXPORT const char * + zrex_strerror (zrex_t *self); + +// Returns true if the text matches the previously compiled expression. +// Use this method to compare one expression against many strings. +CZMQ_EXPORT bool + zrex_matches (zrex_t *self, const char *text); + +// Returns true if the text matches the supplied expression. Use this +// method to compare one string against several expressions. +CZMQ_EXPORT bool + zrex_eq (zrex_t *self, const char *text, const char *expression); + +// Returns number of hits from last zrex_matches or zrex_eq. If the text +// matched, returns 1 plus the number of capture groups. If the text did +// not match, returns zero. To retrieve individual capture groups, call +// zrex_hit (). +CZMQ_EXPORT int + zrex_hits (zrex_t *self); + +// Returns the Nth capture group from the last expression match, where +// N is 0 to the value returned by zrex_hits(). Capture group 0 is the +// whole matching string. Sequence 1 is the first capture group, if any, +// and so on. +CZMQ_EXPORT const char * + zrex_hit (zrex_t *self, uint index); + +// Fetches hits into string variables provided by caller; this makes for +// nicer code than accessing hits by index. Caller should not modify nor +// free the returned values. Returns number of strings returned. This +// method starts at hit 1, i.e. first capture group, as hit 0 is always +// the original matched string. +CZMQ_EXPORT int + zrex_fetch (zrex_t *self, const char **string_p, ...); + +// Self test of this class +CZMQ_EXPORT void + zrex_test (bool verbose); +// @end + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/aarch64-linux/include/zsock.h b/phonelibs/zmq/aarch64-linux/include/zsock.h new file mode 100644 index 00000000000000..9ab060d6a3b8e4 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/include/zsock.h @@ -0,0 +1,1159 @@ +/* ========================================================================= + zsock - high-level socket API that hides libzmq contexts and sockets + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZSOCK_H_INCLUDED__ +#define __ZSOCK_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// This interface includes some smart constructors, which create sockets with +// additional set-up. In all of these, the endpoint is NULL, or starts with +// '@' (bind) or '>' (connect). Multiple endpoints are allowed, separated by +// commas. If endpoint does not start with '@' or '>', default action depends +// on socket type. + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/zsock.api" to make changes. +// @interface +// This is a stable class, and may not change except for emergencies. It +// is provided in stable builds. +// This class has draft methods, which may change over time. They are not +// in stable releases, by default. Use --enable-drafts to enable. +// Create a new socket. Returns the new socket, or NULL if the new socket +// could not be created. Note that the symbol zsock_new (and other +// constructors/destructors for zsock) are redirected to the *_checked +// variant, enabling intelligent socket leak detection. This can have +// performance implications if you use a LOT of sockets. To turn off this +// redirection behaviour, define ZSOCK_NOCHECK. +CZMQ_EXPORT zsock_t * + zsock_new (int type); + +// Create a PUB socket. Default action is bind. +CZMQ_EXPORT zsock_t * + zsock_new_pub (const char *endpoint); + +// Create a SUB socket, and optionally subscribe to some prefix string. Default +// action is connect. +CZMQ_EXPORT zsock_t * + zsock_new_sub (const char *endpoint, const char *subscribe); + +// Create a REQ socket. Default action is connect. +CZMQ_EXPORT zsock_t * + zsock_new_req (const char *endpoint); + +// Create a REP socket. Default action is bind. +CZMQ_EXPORT zsock_t * + zsock_new_rep (const char *endpoint); + +// Create a DEALER socket. Default action is connect. +CZMQ_EXPORT zsock_t * + zsock_new_dealer (const char *endpoint); + +// Create a ROUTER socket. Default action is bind. +CZMQ_EXPORT zsock_t * + zsock_new_router (const char *endpoint); + +// Create a PUSH socket. Default action is connect. +CZMQ_EXPORT zsock_t * + zsock_new_push (const char *endpoint); + +// Create a PULL socket. Default action is bind. +CZMQ_EXPORT zsock_t * + zsock_new_pull (const char *endpoint); + +// Create an XPUB socket. Default action is bind. +CZMQ_EXPORT zsock_t * + zsock_new_xpub (const char *endpoint); + +// Create an XSUB socket. Default action is connect. +CZMQ_EXPORT zsock_t * + zsock_new_xsub (const char *endpoint); + +// Create a PAIR socket. Default action is connect. +CZMQ_EXPORT zsock_t * + zsock_new_pair (const char *endpoint); + +// Create a STREAM socket. Default action is connect. +CZMQ_EXPORT zsock_t * + zsock_new_stream (const char *endpoint); + +// Destroy the socket. You must use this for any socket created via the +// zsock_new method. +CZMQ_EXPORT void + zsock_destroy (zsock_t **self_p); + +// Bind a socket to a formatted endpoint. For tcp:// endpoints, supports +// ephemeral ports, if you specify the port number as "*". By default +// zsock uses the IANA designated range from C000 (49152) to FFFF (65535). +// To override this range, follow the "*" with "[first-last]". Either or +// both first and last may be empty. To bind to a random port within the +// range, use "!" in place of "*". +// +// Examples: +// tcp://127.0.0.1:* bind to first free port from C000 up +// tcp://127.0.0.1:! bind to random port from C000 to FFFF +// tcp://127.0.0.1:*[60000-] bind to first free port from 60000 up +// tcp://127.0.0.1:![-60000] bind to random port from C000 to 60000 +// tcp://127.0.0.1:![55000-55999] +// bind to random port from 55000 to 55999 +// +// On success, returns the actual port number used, for tcp:// endpoints, +// and 0 for other transports. On failure, returns -1. Note that when using +// ephemeral ports, a port may be reused by different services without +// clients being aware. Protocols that run on ephemeral ports should take +// this into account. +CZMQ_EXPORT int + zsock_bind (zsock_t *self, const char *format, ...) CHECK_PRINTF (2); + +// Returns last bound endpoint, if any. +CZMQ_EXPORT const char * + zsock_endpoint (zsock_t *self); + +// Unbind a socket from a formatted endpoint. +// Returns 0 if OK, -1 if the endpoint was invalid or the function +// isn't supported. +CZMQ_EXPORT int + zsock_unbind (zsock_t *self, const char *format, ...) CHECK_PRINTF (2); + +// Connect a socket to a formatted endpoint +// Returns 0 if OK, -1 if the endpoint was invalid. +CZMQ_EXPORT int + zsock_connect (zsock_t *self, const char *format, ...) CHECK_PRINTF (2); + +// Disconnect a socket from a formatted endpoint +// Returns 0 if OK, -1 if the endpoint was invalid or the function +// isn't supported. +CZMQ_EXPORT int + zsock_disconnect (zsock_t *self, const char *format, ...) CHECK_PRINTF (2); + +// Attach a socket to zero or more endpoints. If endpoints is not null, +// parses as list of ZeroMQ endpoints, separated by commas, and prefixed by +// '@' (to bind the socket) or '>' (to connect the socket). Returns 0 if all +// endpoints were valid, or -1 if there was a syntax error. If the endpoint +// does not start with '@' or '>', the serverish argument defines whether +// it is used to bind (serverish = true) or connect (serverish = false). +CZMQ_EXPORT int + zsock_attach (zsock_t *self, const char *endpoints, bool serverish); + +// Returns socket type as printable constant string. +CZMQ_EXPORT const char * + zsock_type_str (zsock_t *self); + +// Send a 'picture' message to the socket (or actor). The picture is a +// string that defines the type of each frame. This makes it easy to send +// a complex multiframe message in one call. The picture can contain any +// of these characters, each corresponding to one or two arguments: +// +// i = int (signed) +// 1 = uint8_t +// 2 = uint16_t +// 4 = uint32_t +// 8 = uint64_t +// s = char * +// b = byte *, size_t (2 arguments) +// c = zchunk_t * +// f = zframe_t * +// h = zhashx_t * +// U = zuuid_t * +// p = void * (sends the pointer value, only meaningful over inproc) +// m = zmsg_t * (sends all frames in the zmsg) +// z = sends zero-sized frame (0 arguments) +// u = uint (deprecated) +// +// Note that s, b, c, and f are encoded the same way and the choice is +// offered as a convenience to the sender, which may or may not already +// have data in a zchunk or zframe. Does not change or take ownership of +// any arguments. Returns 0 if successful, -1 if sending failed for any +// reason. +CZMQ_EXPORT int + zsock_send (void *self, const char *picture, ...); + +// Send a 'picture' message to the socket (or actor). This is a va_list +// version of zsock_send (), so please consult its documentation for the +// details. +CZMQ_EXPORT int + zsock_vsend (void *self, const char *picture, va_list argptr); + +// Receive a 'picture' message to the socket (or actor). See zsock_send for +// the format and meaning of the picture. Returns the picture elements into +// a series of pointers as provided by the caller: +// +// i = int * (stores signed integer) +// 4 = uint32_t * (stores 32-bit unsigned integer) +// 8 = uint64_t * (stores 64-bit unsigned integer) +// s = char ** (allocates new string) +// b = byte **, size_t * (2 arguments) (allocates memory) +// c = zchunk_t ** (creates zchunk) +// f = zframe_t ** (creates zframe) +// U = zuuid_t * (creates a zuuid with the data) +// h = zhashx_t ** (creates zhashx) +// p = void ** (stores pointer) +// m = zmsg_t ** (creates a zmsg with the remaing frames) +// z = null, asserts empty frame (0 arguments) +// u = uint * (stores unsigned integer, deprecated) +// +// Note that zsock_recv creates the returned objects, and the caller must +// destroy them when finished with them. The supplied pointers do not need +// to be initialized. Returns 0 if successful, or -1 if it failed to recv +// a message, in which case the pointers are not modified. When message +// frames are truncated (a short message), sets return values to zero/null. +// If an argument pointer is NULL, does not store any value (skips it). +// An 'n' picture matches an empty frame; if the message does not match, +// the method will return -1. +CZMQ_EXPORT int + zsock_recv (void *self, const char *picture, ...); + +// Receive a 'picture' message from the socket (or actor). This is a +// va_list version of zsock_recv (), so please consult its documentation +// for the details. +CZMQ_EXPORT int + zsock_vrecv (void *self, const char *picture, va_list argptr); + +// Send a binary encoded 'picture' message to the socket (or actor). This +// method is similar to zsock_send, except the arguments are encoded in a +// binary format that is compatible with zproto, and is designed to reduce +// memory allocations. The pattern argument is a string that defines the +// type of each argument. Supports these argument types: +// +// pattern C type zproto type: +// 1 uint8_t type = "number" size = "1" +// 2 uint16_t type = "number" size = "2" +// 4 uint32_t type = "number" size = "3" +// 8 uint64_t type = "number" size = "4" +// s char *, 0-255 chars type = "string" +// S char *, 0-2^32-1 chars type = "longstr" +// c zchunk_t * type = "chunk" +// f zframe_t * type = "frame" +// u zuuid_t * type = "uuid" +// m zmsg_t * type = "msg" +// p void *, sends pointer value, only over inproc +// +// Does not change or take ownership of any arguments. Returns 0 if +// successful, -1 if sending failed for any reason. +CZMQ_EXPORT int + zsock_bsend (void *self, const char *picture, ...); + +// Receive a binary encoded 'picture' message from the socket (or actor). +// This method is similar to zsock_recv, except the arguments are encoded +// in a binary format that is compatible with zproto, and is designed to +// reduce memory allocations. The pattern argument is a string that defines +// the type of each argument. See zsock_bsend for the supported argument +// types. All arguments must be pointers; this call sets them to point to +// values held on a per-socket basis. +// Note that zsock_brecv creates the returned objects, and the caller must +// destroy them when finished with them. The supplied pointers do not need +// to be initialized. Returns 0 if successful, or -1 if it failed to read +// a message. +CZMQ_EXPORT int + zsock_brecv (void *self, const char *picture, ...); + +// Set socket to use unbounded pipes (HWM=0); use this in cases when you are +// totally certain the message volume can fit in memory. This method works +// across all versions of ZeroMQ. Takes a polymorphic socket reference. +CZMQ_EXPORT void + zsock_set_unbounded (void *self); + +// Send a signal over a socket. A signal is a short message carrying a +// success/failure code (by convention, 0 means OK). Signals are encoded +// to be distinguishable from "normal" messages. Accepts a zsock_t or a +// zactor_t argument, and returns 0 if successful, -1 if the signal could +// not be sent. Takes a polymorphic socket reference. +CZMQ_EXPORT int + zsock_signal (void *self, byte status); + +// Wait on a signal. Use this to coordinate between threads, over pipe +// pairs. Blocks until the signal is received. Returns -1 on error, 0 or +// greater on success. Accepts a zsock_t or a zactor_t as argument. +// Takes a polymorphic socket reference. +CZMQ_EXPORT int + zsock_wait (void *self); + +// If there is a partial message still waiting on the socket, remove and +// discard it. This is useful when reading partial messages, to get specific +// message types. +CZMQ_EXPORT void + zsock_flush (void *self); + +// Probe the supplied object, and report if it looks like a zsock_t. +// Takes a polymorphic socket reference. +CZMQ_EXPORT bool + zsock_is (void *self); + +// Probe the supplied reference. If it looks like a zsock_t instance, return +// the underlying libzmq socket handle; else if it looks like a file +// descriptor, return NULL; else if it looks like a libzmq socket handle, +// return the supplied value. Takes a polymorphic socket reference. +CZMQ_EXPORT void * + zsock_resolve (void *self); + +// Get socket option `heartbeat_ivl`. +// Available from libzmq 4.2.0. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_heartbeat_ivl (void *self); + +// Set socket option `heartbeat_ivl`. +// Available from libzmq 4.2.0. +CZMQ_EXPORT void + zsock_set_heartbeat_ivl (void *self, int heartbeat_ivl); + +// Get socket option `heartbeat_ttl`. +// Available from libzmq 4.2.0. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_heartbeat_ttl (void *self); + +// Set socket option `heartbeat_ttl`. +// Available from libzmq 4.2.0. +CZMQ_EXPORT void + zsock_set_heartbeat_ttl (void *self, int heartbeat_ttl); + +// Get socket option `heartbeat_timeout`. +// Available from libzmq 4.2.0. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_heartbeat_timeout (void *self); + +// Set socket option `heartbeat_timeout`. +// Available from libzmq 4.2.0. +CZMQ_EXPORT void + zsock_set_heartbeat_timeout (void *self, int heartbeat_timeout); + +// Get socket option `use_fd`. +// Available from libzmq 4.2.0. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_use_fd (void *self); + +// Set socket option `use_fd`. +// Available from libzmq 4.2.0. +CZMQ_EXPORT void + zsock_set_use_fd (void *self, int use_fd); + +// Set socket option `xpub_manual`. +// Available from libzmq 4.2.0. +CZMQ_EXPORT void + zsock_set_xpub_manual (void *self, int xpub_manual); + +// Set socket option `xpub_welcome_msg`. +// Available from libzmq 4.2.0. +CZMQ_EXPORT void + zsock_set_xpub_welcome_msg (void *self, const char *xpub_welcome_msg); + +// Set socket option `stream_notify`. +// Available from libzmq 4.2.0. +CZMQ_EXPORT void + zsock_set_stream_notify (void *self, int stream_notify); + +// Get socket option `invert_matching`. +// Available from libzmq 4.2.0. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_invert_matching (void *self); + +// Set socket option `invert_matching`. +// Available from libzmq 4.2.0. +CZMQ_EXPORT void + zsock_set_invert_matching (void *self, int invert_matching); + +// Set socket option `xpub_verboser`. +// Available from libzmq 4.2.0. +CZMQ_EXPORT void + zsock_set_xpub_verboser (void *self, int xpub_verboser); + +// Get socket option `connect_timeout`. +// Available from libzmq 4.2.0. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_connect_timeout (void *self); + +// Set socket option `connect_timeout`. +// Available from libzmq 4.2.0. +CZMQ_EXPORT void + zsock_set_connect_timeout (void *self, int connect_timeout); + +// Get socket option `tcp_maxrt`. +// Available from libzmq 4.2.0. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_tcp_maxrt (void *self); + +// Set socket option `tcp_maxrt`. +// Available from libzmq 4.2.0. +CZMQ_EXPORT void + zsock_set_tcp_maxrt (void *self, int tcp_maxrt); + +// Get socket option `thread_safe`. +// Available from libzmq 4.2.0. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_thread_safe (void *self); + +// Get socket option `multicast_maxtpdu`. +// Available from libzmq 4.2.0. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_multicast_maxtpdu (void *self); + +// Set socket option `multicast_maxtpdu`. +// Available from libzmq 4.2.0. +CZMQ_EXPORT void + zsock_set_multicast_maxtpdu (void *self, int multicast_maxtpdu); + +// Get socket option `vmci_buffer_size`. +// Available from libzmq 4.2.0. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_vmci_buffer_size (void *self); + +// Set socket option `vmci_buffer_size`. +// Available from libzmq 4.2.0. +CZMQ_EXPORT void + zsock_set_vmci_buffer_size (void *self, int vmci_buffer_size); + +// Get socket option `vmci_buffer_min_size`. +// Available from libzmq 4.2.0. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_vmci_buffer_min_size (void *self); + +// Set socket option `vmci_buffer_min_size`. +// Available from libzmq 4.2.0. +CZMQ_EXPORT void + zsock_set_vmci_buffer_min_size (void *self, int vmci_buffer_min_size); + +// Get socket option `vmci_buffer_max_size`. +// Available from libzmq 4.2.0. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_vmci_buffer_max_size (void *self); + +// Set socket option `vmci_buffer_max_size`. +// Available from libzmq 4.2.0. +CZMQ_EXPORT void + zsock_set_vmci_buffer_max_size (void *self, int vmci_buffer_max_size); + +// Get socket option `vmci_connect_timeout`. +// Available from libzmq 4.2.0. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_vmci_connect_timeout (void *self); + +// Set socket option `vmci_connect_timeout`. +// Available from libzmq 4.2.0. +CZMQ_EXPORT void + zsock_set_vmci_connect_timeout (void *self, int vmci_connect_timeout); + +// Get socket option `tos`. +// Available from libzmq 4.1.0. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_tos (void *self); + +// Set socket option `tos`. +// Available from libzmq 4.1.0. +CZMQ_EXPORT void + zsock_set_tos (void *self, int tos); + +// Set socket option `router_handover`. +// Available from libzmq 4.1.0. +CZMQ_EXPORT void + zsock_set_router_handover (void *self, int router_handover); + +// Set socket option `connect_rid`. +// Available from libzmq 4.1.0. +CZMQ_EXPORT void + zsock_set_connect_rid (void *self, const char *connect_rid); + +// Set socket option `connect_rid` from 32-octet binary +// Available from libzmq 4.1.0. +CZMQ_EXPORT void + zsock_set_connect_rid_bin (void *self, const byte *connect_rid); + +// Get socket option `handshake_ivl`. +// Available from libzmq 4.1.0. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_handshake_ivl (void *self); + +// Set socket option `handshake_ivl`. +// Available from libzmq 4.1.0. +CZMQ_EXPORT void + zsock_set_handshake_ivl (void *self, int handshake_ivl); + +// Get socket option `socks_proxy`. +// Available from libzmq 4.1.0. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT char * + zsock_socks_proxy (void *self); + +// Set socket option `socks_proxy`. +// Available from libzmq 4.1.0. +CZMQ_EXPORT void + zsock_set_socks_proxy (void *self, const char *socks_proxy); + +// Set socket option `xpub_nodrop`. +// Available from libzmq 4.1.0. +CZMQ_EXPORT void + zsock_set_xpub_nodrop (void *self, int xpub_nodrop); + +// Set socket option `router_mandatory`. +// Available from libzmq 4.0.0. +CZMQ_EXPORT void + zsock_set_router_mandatory (void *self, int router_mandatory); + +// Set socket option `probe_router`. +// Available from libzmq 4.0.0. +CZMQ_EXPORT void + zsock_set_probe_router (void *self, int probe_router); + +// Set socket option `req_relaxed`. +// Available from libzmq 4.0.0. +CZMQ_EXPORT void + zsock_set_req_relaxed (void *self, int req_relaxed); + +// Set socket option `req_correlate`. +// Available from libzmq 4.0.0. +CZMQ_EXPORT void + zsock_set_req_correlate (void *self, int req_correlate); + +// Set socket option `conflate`. +// Available from libzmq 4.0.0. +CZMQ_EXPORT void + zsock_set_conflate (void *self, int conflate); + +// Get socket option `zap_domain`. +// Available from libzmq 4.0.0. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT char * + zsock_zap_domain (void *self); + +// Set socket option `zap_domain`. +// Available from libzmq 4.0.0. +CZMQ_EXPORT void + zsock_set_zap_domain (void *self, const char *zap_domain); + +// Get socket option `mechanism`. +// Available from libzmq 4.0.0. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_mechanism (void *self); + +// Get socket option `plain_server`. +// Available from libzmq 4.0.0. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_plain_server (void *self); + +// Set socket option `plain_server`. +// Available from libzmq 4.0.0. +CZMQ_EXPORT void + zsock_set_plain_server (void *self, int plain_server); + +// Get socket option `plain_username`. +// Available from libzmq 4.0.0. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT char * + zsock_plain_username (void *self); + +// Set socket option `plain_username`. +// Available from libzmq 4.0.0. +CZMQ_EXPORT void + zsock_set_plain_username (void *self, const char *plain_username); + +// Get socket option `plain_password`. +// Available from libzmq 4.0.0. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT char * + zsock_plain_password (void *self); + +// Set socket option `plain_password`. +// Available from libzmq 4.0.0. +CZMQ_EXPORT void + zsock_set_plain_password (void *self, const char *plain_password); + +// Get socket option `curve_server`. +// Available from libzmq 4.0.0. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_curve_server (void *self); + +// Set socket option `curve_server`. +// Available from libzmq 4.0.0. +CZMQ_EXPORT void + zsock_set_curve_server (void *self, int curve_server); + +// Get socket option `curve_publickey`. +// Available from libzmq 4.0.0. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT char * + zsock_curve_publickey (void *self); + +// Set socket option `curve_publickey`. +// Available from libzmq 4.0.0. +CZMQ_EXPORT void + zsock_set_curve_publickey (void *self, const char *curve_publickey); + +// Set socket option `curve_publickey` from 32-octet binary +// Available from libzmq 4.0.0. +CZMQ_EXPORT void + zsock_set_curve_publickey_bin (void *self, const byte *curve_publickey); + +// Get socket option `curve_secretkey`. +// Available from libzmq 4.0.0. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT char * + zsock_curve_secretkey (void *self); + +// Set socket option `curve_secretkey`. +// Available from libzmq 4.0.0. +CZMQ_EXPORT void + zsock_set_curve_secretkey (void *self, const char *curve_secretkey); + +// Set socket option `curve_secretkey` from 32-octet binary +// Available from libzmq 4.0.0. +CZMQ_EXPORT void + zsock_set_curve_secretkey_bin (void *self, const byte *curve_secretkey); + +// Get socket option `curve_serverkey`. +// Available from libzmq 4.0.0. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT char * + zsock_curve_serverkey (void *self); + +// Set socket option `curve_serverkey`. +// Available from libzmq 4.0.0. +CZMQ_EXPORT void + zsock_set_curve_serverkey (void *self, const char *curve_serverkey); + +// Set socket option `curve_serverkey` from 32-octet binary +// Available from libzmq 4.0.0. +CZMQ_EXPORT void + zsock_set_curve_serverkey_bin (void *self, const byte *curve_serverkey); + +// Get socket option `gssapi_server`. +// Available from libzmq 4.0.0. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_gssapi_server (void *self); + +// Set socket option `gssapi_server`. +// Available from libzmq 4.0.0. +CZMQ_EXPORT void + zsock_set_gssapi_server (void *self, int gssapi_server); + +// Get socket option `gssapi_plaintext`. +// Available from libzmq 4.0.0. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_gssapi_plaintext (void *self); + +// Set socket option `gssapi_plaintext`. +// Available from libzmq 4.0.0. +CZMQ_EXPORT void + zsock_set_gssapi_plaintext (void *self, int gssapi_plaintext); + +// Get socket option `gssapi_principal`. +// Available from libzmq 4.0.0. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT char * + zsock_gssapi_principal (void *self); + +// Set socket option `gssapi_principal`. +// Available from libzmq 4.0.0. +CZMQ_EXPORT void + zsock_set_gssapi_principal (void *self, const char *gssapi_principal); + +// Get socket option `gssapi_service_principal`. +// Available from libzmq 4.0.0. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT char * + zsock_gssapi_service_principal (void *self); + +// Set socket option `gssapi_service_principal`. +// Available from libzmq 4.0.0. +CZMQ_EXPORT void + zsock_set_gssapi_service_principal (void *self, const char *gssapi_service_principal); + +// Get socket option `ipv6`. +// Available from libzmq 4.0.0. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_ipv6 (void *self); + +// Set socket option `ipv6`. +// Available from libzmq 4.0.0. +CZMQ_EXPORT void + zsock_set_ipv6 (void *self, int ipv6); + +// Get socket option `immediate`. +// Available from libzmq 4.0.0. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_immediate (void *self); + +// Set socket option `immediate`. +// Available from libzmq 4.0.0. +CZMQ_EXPORT void + zsock_set_immediate (void *self, int immediate); + +// Get socket option `type`. +// Available from libzmq 3.0.0. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_type (void *self); + +// Get socket option `sndhwm`. +// Available from libzmq 3.0.0. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_sndhwm (void *self); + +// Set socket option `sndhwm`. +// Available from libzmq 3.0.0. +CZMQ_EXPORT void + zsock_set_sndhwm (void *self, int sndhwm); + +// Get socket option `rcvhwm`. +// Available from libzmq 3.0.0. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_rcvhwm (void *self); + +// Set socket option `rcvhwm`. +// Available from libzmq 3.0.0. +CZMQ_EXPORT void + zsock_set_rcvhwm (void *self, int rcvhwm); + +// Get socket option `affinity`. +// Available from libzmq 3.0.0. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_affinity (void *self); + +// Set socket option `affinity`. +// Available from libzmq 3.0.0. +CZMQ_EXPORT void + zsock_set_affinity (void *self, int affinity); + +// Set socket option `subscribe`. +// Available from libzmq 3.0.0. +CZMQ_EXPORT void + zsock_set_subscribe (void *self, const char *subscribe); + +// Set socket option `unsubscribe`. +// Available from libzmq 3.0.0. +CZMQ_EXPORT void + zsock_set_unsubscribe (void *self, const char *unsubscribe); + +// Get socket option `identity`. +// Available from libzmq 3.0.0. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT char * + zsock_identity (void *self); + +// Set socket option `identity`. +// Available from libzmq 3.0.0. +CZMQ_EXPORT void + zsock_set_identity (void *self, const char *identity); + +// Get socket option `rate`. +// Available from libzmq 3.0.0. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_rate (void *self); + +// Set socket option `rate`. +// Available from libzmq 3.0.0. +CZMQ_EXPORT void + zsock_set_rate (void *self, int rate); + +// Get socket option `recovery_ivl`. +// Available from libzmq 3.0.0. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_recovery_ivl (void *self); + +// Set socket option `recovery_ivl`. +// Available from libzmq 3.0.0. +CZMQ_EXPORT void + zsock_set_recovery_ivl (void *self, int recovery_ivl); + +// Get socket option `sndbuf`. +// Available from libzmq 3.0.0. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_sndbuf (void *self); + +// Set socket option `sndbuf`. +// Available from libzmq 3.0.0. +CZMQ_EXPORT void + zsock_set_sndbuf (void *self, int sndbuf); + +// Get socket option `rcvbuf`. +// Available from libzmq 3.0.0. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_rcvbuf (void *self); + +// Set socket option `rcvbuf`. +// Available from libzmq 3.0.0. +CZMQ_EXPORT void + zsock_set_rcvbuf (void *self, int rcvbuf); + +// Get socket option `linger`. +// Available from libzmq 3.0.0. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_linger (void *self); + +// Set socket option `linger`. +// Available from libzmq 3.0.0. +CZMQ_EXPORT void + zsock_set_linger (void *self, int linger); + +// Get socket option `reconnect_ivl`. +// Available from libzmq 3.0.0. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_reconnect_ivl (void *self); + +// Set socket option `reconnect_ivl`. +// Available from libzmq 3.0.0. +CZMQ_EXPORT void + zsock_set_reconnect_ivl (void *self, int reconnect_ivl); + +// Get socket option `reconnect_ivl_max`. +// Available from libzmq 3.0.0. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_reconnect_ivl_max (void *self); + +// Set socket option `reconnect_ivl_max`. +// Available from libzmq 3.0.0. +CZMQ_EXPORT void + zsock_set_reconnect_ivl_max (void *self, int reconnect_ivl_max); + +// Get socket option `backlog`. +// Available from libzmq 3.0.0. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_backlog (void *self); + +// Set socket option `backlog`. +// Available from libzmq 3.0.0. +CZMQ_EXPORT void + zsock_set_backlog (void *self, int backlog); + +// Get socket option `maxmsgsize`. +// Available from libzmq 3.0.0. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_maxmsgsize (void *self); + +// Set socket option `maxmsgsize`. +// Available from libzmq 3.0.0. +CZMQ_EXPORT void + zsock_set_maxmsgsize (void *self, int maxmsgsize); + +// Get socket option `multicast_hops`. +// Available from libzmq 3.0.0. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_multicast_hops (void *self); + +// Set socket option `multicast_hops`. +// Available from libzmq 3.0.0. +CZMQ_EXPORT void + zsock_set_multicast_hops (void *self, int multicast_hops); + +// Get socket option `rcvtimeo`. +// Available from libzmq 3.0.0. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_rcvtimeo (void *self); + +// Set socket option `rcvtimeo`. +// Available from libzmq 3.0.0. +CZMQ_EXPORT void + zsock_set_rcvtimeo (void *self, int rcvtimeo); + +// Get socket option `sndtimeo`. +// Available from libzmq 3.0.0. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_sndtimeo (void *self); + +// Set socket option `sndtimeo`. +// Available from libzmq 3.0.0. +CZMQ_EXPORT void + zsock_set_sndtimeo (void *self, int sndtimeo); + +// Set socket option `xpub_verbose`. +// Available from libzmq 3.0.0. +CZMQ_EXPORT void + zsock_set_xpub_verbose (void *self, int xpub_verbose); + +// Get socket option `tcp_keepalive`. +// Available from libzmq 3.0.0. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_tcp_keepalive (void *self); + +// Set socket option `tcp_keepalive`. +// Available from libzmq 3.0.0. +CZMQ_EXPORT void + zsock_set_tcp_keepalive (void *self, int tcp_keepalive); + +// Get socket option `tcp_keepalive_idle`. +// Available from libzmq 3.0.0. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_tcp_keepalive_idle (void *self); + +// Set socket option `tcp_keepalive_idle`. +// Available from libzmq 3.0.0. +CZMQ_EXPORT void + zsock_set_tcp_keepalive_idle (void *self, int tcp_keepalive_idle); + +// Get socket option `tcp_keepalive_cnt`. +// Available from libzmq 3.0.0. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_tcp_keepalive_cnt (void *self); + +// Set socket option `tcp_keepalive_cnt`. +// Available from libzmq 3.0.0. +CZMQ_EXPORT void + zsock_set_tcp_keepalive_cnt (void *self, int tcp_keepalive_cnt); + +// Get socket option `tcp_keepalive_intvl`. +// Available from libzmq 3.0.0. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_tcp_keepalive_intvl (void *self); + +// Set socket option `tcp_keepalive_intvl`. +// Available from libzmq 3.0.0. +CZMQ_EXPORT void + zsock_set_tcp_keepalive_intvl (void *self, int tcp_keepalive_intvl); + +// Get socket option `tcp_accept_filter`. +// Available from libzmq 3.0.0. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT char * + zsock_tcp_accept_filter (void *self); + +// Set socket option `tcp_accept_filter`. +// Available from libzmq 3.0.0. +CZMQ_EXPORT void + zsock_set_tcp_accept_filter (void *self, const char *tcp_accept_filter); + +// Get socket option `rcvmore`. +// Available from libzmq 3.0.0. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_rcvmore (void *self); + +// Get socket option `fd`. +// Available from libzmq 3.0.0. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT SOCKET + zsock_fd (void *self); + +// Get socket option `events`. +// Available from libzmq 3.0.0. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_events (void *self); + +// Get socket option `last_endpoint`. +// Available from libzmq 3.0.0. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT char * + zsock_last_endpoint (void *self); + +// Set socket option `router_raw`. +// Available from libzmq 3.0.0. +CZMQ_EXPORT void + zsock_set_router_raw (void *self, int router_raw); + +// Get socket option `ipv4only`. +// Available from libzmq 3.0.0. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_ipv4only (void *self); + +// Set socket option `ipv4only`. +// Available from libzmq 3.0.0. +CZMQ_EXPORT void + zsock_set_ipv4only (void *self, int ipv4only); + +// Set socket option `delay_attach_on_connect`. +// Available from libzmq 3.0.0. +CZMQ_EXPORT void + zsock_set_delay_attach_on_connect (void *self, int delay_attach_on_connect); + +// Self test of this class. +CZMQ_EXPORT void + zsock_test (bool verbose); + +#ifdef CZMQ_BUILD_DRAFT_API +// *** Draft method, for development use, may change without warning *** +// Create a SERVER socket. Default action is bind. +CZMQ_EXPORT zsock_t * + zsock_new_server (const char *endpoint); + +// *** Draft method, for development use, may change without warning *** +// Create a CLIENT socket. Default action is connect. +CZMQ_EXPORT zsock_t * + zsock_new_client (const char *endpoint); + +// *** Draft method, for development use, may change without warning *** +// Create a RADIO socket. Default action is bind. +CZMQ_EXPORT zsock_t * + zsock_new_radio (const char *endpoint); + +// *** Draft method, for development use, may change without warning *** +// Create a DISH socket. Default action is connect. +CZMQ_EXPORT zsock_t * + zsock_new_dish (const char *endpoint); + +// *** Draft method, for development use, may change without warning *** +// Create a GATHER socket. Default action is bind. +CZMQ_EXPORT zsock_t * + zsock_new_gather (const char *endpoint); + +// *** Draft method, for development use, may change without warning *** +// Create a SCATTER socket. Default action is connect. +CZMQ_EXPORT zsock_t * + zsock_new_scatter (const char *endpoint); + +// *** Draft method, for development use, may change without warning *** +// Return socket routing ID if any. This returns 0 if the socket is not +// of type ZMQ_SERVER or if no request was already received on it. +CZMQ_EXPORT uint32_t + zsock_routing_id (zsock_t *self); + +// *** Draft method, for development use, may change without warning *** +// Set routing ID on socket. The socket MUST be of type ZMQ_SERVER. +// This will be used when sending messages on the socket via the zsock API. +CZMQ_EXPORT void + zsock_set_routing_id (zsock_t *self, uint32_t routing_id); + +// *** Draft method, for development use, may change without warning *** +// Join a group for the RADIO-DISH pattern. Call only on ZMQ_DISH. +// Returns 0 if OK, -1 if failed. +CZMQ_EXPORT int + zsock_join (void *self, const char *group); + +// *** Draft method, for development use, may change without warning *** +// Leave a group for the RADIO-DISH pattern. Call only on ZMQ_DISH. +// Returns 0 if OK, -1 if failed. +CZMQ_EXPORT int + zsock_leave (void *self, const char *group); + +#endif // CZMQ_BUILD_DRAFT_API +// @end + + +// zsock leak detection - not a part of the official interface to zsock. This +// enables CZMQ to report socket leaks intelligently. +#if defined ZSOCK_NOCHECK + // no checking active - use the above interface methods directly. +#else +# define zsock_new(t) zsock_new_checked((t), __FILE__, __LINE__) +# define zsock_new_pub(e) zsock_new_pub_checked((e), __FILE__, __LINE__) +# define zsock_new_sub(e,s) zsock_new_sub_checked((e), (s), __FILE__, __LINE__) +# define zsock_new_req(e) zsock_new_req_checked((e), __FILE__, __LINE__) +# define zsock_new_rep(e) zsock_new_rep_checked((e), __FILE__, __LINE__) +# define zsock_new_dealer(e) zsock_new_dealer_checked((e), __FILE__, __LINE__) +# define zsock_new_router(e) zsock_new_router_checked((e), __FILE__, __LINE__) +# define zsock_new_pull(e) zsock_new_pull_checked((e), __FILE__, __LINE__) +# define zsock_new_push(e) zsock_new_push_checked((e), __FILE__, __LINE__) +# define zsock_new_xpub(e) zsock_new_xpub_checked((e), __FILE__, __LINE__) +# define zsock_new_xsub(e) zsock_new_xsub_checked((e), __FILE__, __LINE__) +# define zsock_new_pair(e) zsock_new_pair_checked((e), __FILE__, __LINE__) +# define zsock_new_stream(e) zsock_new_stream_checked((e), __FILE__, __LINE__) +# define zsock_destroy(t) zsock_destroy_checked((t), __FILE__, __LINE__) +#endif + +CZMQ_EXPORT zsock_t * + zsock_new_checked (int type, const char *filename, size_t line_nbr); + +CZMQ_EXPORT void + zsock_destroy_checked (zsock_t **self_p, const char *filename, size_t line_nbr); + +CZMQ_EXPORT zsock_t * + zsock_new_pub_checked (const char *endpoint, const char *filename, size_t line_nbr); + +CZMQ_EXPORT zsock_t * + zsock_new_sub_checked (const char *endpoint, const char *subscribe, const char *filename, size_t line_nbr); + +CZMQ_EXPORT zsock_t * + zsock_new_req_checked (const char *endpoint, const char *filename, size_t line_nbr); + +CZMQ_EXPORT zsock_t * + zsock_new_rep_checked (const char *endpoint, const char *filename, size_t line_nbr); + +CZMQ_EXPORT zsock_t * + zsock_new_dealer_checked (const char *endpoint, const char *filename, size_t line_nbr); + +CZMQ_EXPORT zsock_t * + zsock_new_router_checked (const char *endpoint, const char *filename, size_t line_nbr); + +CZMQ_EXPORT zsock_t * + zsock_new_push_checked (const char *endpoint, const char *filename, size_t line_nbr); + +CZMQ_EXPORT zsock_t * + zsock_new_pull_checked (const char *endpoint, const char *filename, size_t line_nbr); + +CZMQ_EXPORT zsock_t * + zsock_new_xpub_checked (const char *endpoint, const char *filename, size_t line_nbr); + +CZMQ_EXPORT zsock_t * + zsock_new_xsub_checked (const char *endpoint, const char *filename, size_t line_nbr); + +CZMQ_EXPORT zsock_t * + zsock_new_pair_checked (const char *endpoint, const char *filename, size_t line_nbr); + +CZMQ_EXPORT zsock_t * + zsock_new_stream_checked (const char *endpoint, const char *filename, size_t line_nbr); + +#ifdef CZMQ_BUILD_DRAFT_API +CZMQ_EXPORT zsock_t * + zsock_new_server_checked (const char *endpoint, const char *filename, size_t line_nbr); + +CZMQ_EXPORT zsock_t * + zsock_new_client_checked (const char *endpoint, const char *filename, size_t line_nbr); + +CZMQ_EXPORT zsock_t * + zsock_new_radio_checked (const char *endpoint, const char *filename, size_t line_nbr); + +CZMQ_EXPORT zsock_t * + zsock_new_dish_checked (const char *endpoint, const char *filename, size_t line_nbr); + +CZMQ_EXPORT zsock_t * + zsock_new_gather_checked (const char *endpoint, const char *filename, size_t line_nbr); + +CZMQ_EXPORT zsock_t * + zsock_new_scatter_checked (const char *endpoint, const char *filename, size_t line_nbr); +#endif // CZMQ_BUILD_DRAFT_API + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/aarch64-linux/include/zstr.h b/phonelibs/zmq/aarch64-linux/include/zstr.h new file mode 100644 index 00000000000000..67f2f852b623ea --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/include/zstr.h @@ -0,0 +1,110 @@ +/* ========================================================================= + zstr - sending and receiving strings + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZSTR_H_INCLUDED__ +#define __ZSTR_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/zstr.api" to make changes. +// @interface +// This is a stable class, and may not change except for emergencies. It +// is provided in stable builds. +// This class has draft methods, which may change over time. They are not +// in stable releases, by default. Use --enable-drafts to enable. +// Receive C string from socket. Caller must free returned string using +// zstr_free(). Returns NULL if the context is being terminated or the +// process was interrupted. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT char * + zstr_recv (void *source); + +// Receive a series of strings (until NULL) from multipart data. +// Each string is allocated and filled with string data; if there +// are not enough frames, unallocated strings are set to NULL. +// Returns -1 if the message could not be read, else returns the +// number of strings filled, zero or more. Free each returned string +// using zstr_free(). If not enough strings are provided, remaining +// multipart frames in the message are dropped. +CZMQ_EXPORT int + zstr_recvx (void *source, char **string_p, ...); + +// Send a C string to a socket, as a frame. The string is sent without +// trailing null byte; to read this you can use zstr_recv, or a similar +// method that adds a null terminator on the received string. String +// may be NULL, which is sent as "". +CZMQ_EXPORT int + zstr_send (void *dest, const char *string); + +// Send a C string to a socket, as zstr_send(), with a MORE flag, so that +// you can send further strings in the same multi-part message. +CZMQ_EXPORT int + zstr_sendm (void *dest, const char *string); + +// Send a formatted string to a socket. Note that you should NOT use +// user-supplied strings in the format (they may contain '%' which +// will create security holes). +CZMQ_EXPORT int + zstr_sendf (void *dest, const char *format, ...) CHECK_PRINTF (2); + +// Send a formatted string to a socket, as for zstr_sendf(), with a +// MORE flag, so that you can send further strings in the same multi-part +// message. +CZMQ_EXPORT int + zstr_sendfm (void *dest, const char *format, ...) CHECK_PRINTF (2); + +// Send a series of strings (until NULL) as multipart data +// Returns 0 if the strings could be sent OK, or -1 on error. +CZMQ_EXPORT int + zstr_sendx (void *dest, const char *string, ...); + +// Free a provided string, and nullify the parent pointer. Safe to call on +// a null pointer. +CZMQ_EXPORT void + zstr_free (char **string_p); + +// Self test of this class. +CZMQ_EXPORT void + zstr_test (bool verbose); + +#ifdef CZMQ_BUILD_DRAFT_API +// *** Draft method, for development use, may change without warning *** +// Accepts a void pointer and returns a fresh character string. If source +// is null, returns an empty string. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT char * + zstr_str (void *source); + +#endif // CZMQ_BUILD_DRAFT_API +// @end + + +// DEPRECATED as poor style -- callers should use zloop or zpoller +// Receive C string from socket, if socket had input ready. Caller must +// free returned string using zstr_free. Returns NULL if there was no input +// waiting, or if the context was terminated. Use zctx_interrupted to exit +// any loop that relies on this method. +CZMQ_EXPORT char * + zstr_recv_nowait (void *source); + +// Compiler hints +CZMQ_EXPORT int zstr_sendf (void *dest, const char *format, ...) CHECK_PRINTF (2); + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/aarch64-linux/include/zsys.h b/phonelibs/zmq/aarch64-linux/include/zsys.h new file mode 100644 index 00000000000000..200271d9249cbb --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/include/zsys.h @@ -0,0 +1,395 @@ +/* ========================================================================= + zsys - system-level methods + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZSYS_H_INCLUDED__ +#define __ZSYS_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @interface +#define UDP_FRAME_MAX 255 // Max size of UDP frame + +// Callback for interrupt signal handler +typedef void (zsys_handler_fn) (int signal_value); + +// Initialize CZMQ zsys layer; this happens automatically when you create +// a socket or an actor; however this call lets you force initialization +// earlier, so e.g. logging is properly set-up before you start working. +// Not threadsafe, so call only from main thread. Safe to call multiple +// times. Returns global CZMQ context. +CZMQ_EXPORT void * + zsys_init (void); + +// Optionally shut down the CZMQ zsys layer; this normally happens automatically +// when the process exits; however this call lets you force a shutdown +// earlier, avoiding any potential problems with atexit() ordering, especially +// with Windows dlls. +CZMQ_EXPORT void + zsys_shutdown (void); + +// Get a new ZMQ socket, automagically creating a ZMQ context if this is +// the first time. Caller is responsible for destroying the ZMQ socket +// before process exits, to avoid a ZMQ deadlock. Note: you should not use +// this method in CZMQ apps, use zsock_new() instead. +// *** This is for CZMQ internal use only and may change arbitrarily *** +CZMQ_EXPORT void * + zsys_socket (int type, const char *filename, size_t line_nbr); + +// Destroy/close a ZMQ socket. You should call this for every socket you +// create using zsys_socket(). +// *** This is for CZMQ internal use only and may change arbitrarily *** +CZMQ_EXPORT int + zsys_close (void *handle, const char *filename, size_t line_nbr); + +// Return ZMQ socket name for socket type +// *** This is for CZMQ internal use only and may change arbitrarily *** +CZMQ_EXPORT char * + zsys_sockname (int socktype); + +// Create a pipe, which consists of two PAIR sockets connected over inproc. +// The pipe is configured to use the zsys_pipehwm setting. Returns the +// frontend socket successful, NULL if failed. +CZMQ_EXPORT zsock_t * + zsys_create_pipe (zsock_t **backend_p); + +// Set interrupt handler; this saves the default handlers so that a +// zsys_handler_reset () can restore them. If you call this multiple times +// then the last handler will take affect. If handler_fn is NULL, disables +// default SIGINT/SIGTERM handling in CZMQ. +CZMQ_EXPORT void + zsys_handler_set (zsys_handler_fn *handler_fn); + +// Reset interrupt handler, call this at exit if needed +CZMQ_EXPORT void + zsys_handler_reset (void); + +// Set default interrupt handler, so Ctrl-C or SIGTERM will set +// zsys_interrupted. Idempotent; safe to call multiple times. +// *** This is for CZMQ internal use only and may change arbitrarily *** +CZMQ_EXPORT void + zsys_catch_interrupts (void); + +// Return 1 if file exists, else zero +CZMQ_EXPORT bool + zsys_file_exists (const char *filename); + +// Return size of file, or -1 if not found +CZMQ_EXPORT ssize_t + zsys_file_size (const char *filename); + +// Return file modification time. Returns 0 if the file does not exist. +CZMQ_EXPORT time_t + zsys_file_modified (const char *filename); + +// Return file mode; provides at least support for the POSIX S_ISREG(m) +// and S_ISDIR(m) macros and the S_IRUSR and S_IWUSR bits, on all boxes. +// Returns a mode_t cast to int, or -1 in case of error. +CZMQ_EXPORT int + zsys_file_mode (const char *filename); + +// Delete file. Does not complain if the file is absent +CZMQ_EXPORT int + zsys_file_delete (const char *filename); + +// Check if file is 'stable' +CZMQ_EXPORT bool + zsys_file_stable (const char *filename); + +// Create a file path if it doesn't exist. The file path is treated as a +// printf format. +CZMQ_EXPORT int + zsys_dir_create (const char *pathname, ...); + +// Remove a file path if empty; the pathname is treated as printf format. +CZMQ_EXPORT int + zsys_dir_delete (const char *pathname, ...); + +// Move to a specified working directory. Returns 0 if OK, -1 if this failed. +CZMQ_EXPORT int + zsys_dir_change (const char *pathname); + +// Set private file creation mode; all files created from here will be +// readable/writable by the owner only. +CZMQ_EXPORT void + zsys_file_mode_private (void); + +// Reset default file creation mode; all files created from here will use +// process file mode defaults. +CZMQ_EXPORT void + zsys_file_mode_default (void); + +// Return the CZMQ version for run-time API detection; returns version +// number into provided fields, providing reference isn't null in each case. +CZMQ_EXPORT void + zsys_version (int *major, int *minor, int *patch); + +// Format a string using printf formatting, returning a freshly allocated +// buffer. If there was insufficient memory, returns NULL. Free the returned +// string using zstr_free(). +CZMQ_EXPORT char * + zsys_sprintf (const char *format, ...); + +// Format a string with a va_list argument, returning a freshly allocated +// buffer. If there was insufficient memory, returns NULL. Free the returned +// string using zstr_free(). +CZMQ_EXPORT char * + zsys_vprintf (const char *format, va_list argptr); + +// Create UDP beacon socket; if the routable option is true, uses +// multicast (not yet implemented), else uses broadcast. This method +// and related ones might _eventually_ be moved to a zudp class. +// *** This is for CZMQ internal use only and may change arbitrarily *** +CZMQ_EXPORT SOCKET + zsys_udp_new (bool routable); + +// Close a UDP socket +// *** This is for CZMQ internal use only and may change arbitrarily *** +CZMQ_EXPORT int + zsys_udp_close (SOCKET handle); + +// Send zframe to UDP socket, return -1 if sending failed due to +// interface having disappeared (happens easily with WiFi) +// *** This is for CZMQ internal use only and may change arbitrarily *** +CZMQ_EXPORT int + zsys_udp_send (SOCKET udpsock, zframe_t *frame, inaddr_t *address, int addrlen); + +// Receive zframe from UDP socket, and set address of peer that sent it +// The peername must be a char [INET_ADDRSTRLEN] array. +// *** This is for CZMQ internal use only and may change arbitrarily *** +CZMQ_EXPORT zframe_t * + zsys_udp_recv (SOCKET udpsock, char *peername, int peerlen); + +// Handle an I/O error on some socket operation; will report and die on +// fatal errors, and continue silently on "try again" errors. +// *** This is for CZMQ internal use only and may change arbitrarily *** +CZMQ_EXPORT void + zsys_socket_error (const char *reason); + +// Return current host name, for use in public tcp:// endpoints. Caller gets +// a freshly allocated string, should free it using zstr_free(). If the host +// name is not resolvable, returns NULL. +CZMQ_EXPORT char * + zsys_hostname (void); + +// Move the current process into the background. The precise effect depends +// on the operating system. On POSIX boxes, moves to a specified working +// directory (if specified), closes all file handles, reopens stdin, stdout, +// and stderr to the null device, and sets the process to ignore SIGHUP. On +// Windows, does nothing. Returns 0 if OK, -1 if there was an error. +CZMQ_EXPORT int + zsys_daemonize (const char *workdir); + +// Drop the process ID into the lockfile, with exclusive lock, and switch +// the process to the specified group and/or user. Any of the arguments +// may be null, indicating a no-op. Returns 0 on success, -1 on failure. +// Note if you combine this with zsys_daemonize, run after, not before +// that method, or the lockfile will hold the wrong process ID. +CZMQ_EXPORT int + zsys_run_as (const char *lockfile, const char *group, const char *user); + +// Returns true if the underlying libzmq supports CURVE security. +// Uses a heuristic probe according to the version of libzmq being used. +CZMQ_EXPORT bool + zsys_has_curve (void); + +// Configure the number of I/O threads that ZeroMQ will use. A good +// rule of thumb is one thread per gigabit of traffic in or out. The +// default is 1, sufficient for most applications. If the environment +// variable ZSYS_IO_THREADS is defined, that provides the default. +// Note that this method is valid only before any socket is created. +CZMQ_EXPORT void + zsys_set_io_threads (size_t io_threads); + +// Configure the number of sockets that ZeroMQ will allow. The default +// is 1024. The actual limit depends on the system, and you can query it +// by using zsys_socket_limit (). A value of zero means "maximum". +// Note that this method is valid only before any socket is created. +CZMQ_EXPORT void + zsys_set_max_sockets (size_t max_sockets); + +// Return maximum number of ZeroMQ sockets that the system will support. +CZMQ_EXPORT size_t + zsys_socket_limit (void); + +// Configure the maximum allowed size of a message sent. +// The default is INT_MAX. +CZMQ_EXPORT void + zsys_set_max_msgsz (int max_msgsz); + +// Return maximum message size. +CZMQ_EXPORT int + zsys_max_msgsz (void); + +// Configure the default linger timeout in msecs for new zsock instances. +// You can also set this separately on each zsock_t instance. The default +// linger time is zero, i.e. any pending messages will be dropped. If the +// environment variable ZSYS_LINGER is defined, that provides the default. +// Note that process exit will typically be delayed by the linger time. +CZMQ_EXPORT void + zsys_set_linger (size_t linger); + +// Configure the default outgoing pipe limit (HWM) for new zsock instances. +// You can also set this separately on each zsock_t instance. The default +// HWM is 1,000, on all versions of ZeroMQ. If the environment variable +// ZSYS_SNDHWM is defined, that provides the default. Note that a value of +// zero means no limit, i.e. infinite memory consumption. +CZMQ_EXPORT void + zsys_set_sndhwm (size_t sndhwm); + +// Configure the default incoming pipe limit (HWM) for new zsock instances. +// You can also set this separately on each zsock_t instance. The default +// HWM is 1,000, on all versions of ZeroMQ. If the environment variable +// ZSYS_RCVHWM is defined, that provides the default. Note that a value of +// zero means no limit, i.e. infinite memory consumption. +CZMQ_EXPORT void + zsys_set_rcvhwm (size_t rcvhwm); + +// Configure the default HWM for zactor internal pipes; this is set on both +// ends of the pipe, for outgoing messages only (sndhwm). The default HWM is +// 1,000, on all versions of ZeroMQ. If the environment var ZSYS_ACTORHWM is +// defined, that provides the default. Note that a value of zero means no +// limit, i.e. infinite memory consumption. +CZMQ_EXPORT void + zsys_set_pipehwm (size_t pipehwm); + +// Return the HWM for zactor internal pipes. +CZMQ_EXPORT size_t + zsys_pipehwm (void); + +// Configure use of IPv6 for new zsock instances. By default sockets accept +// and make only IPv4 connections. When you enable IPv6, sockets will accept +// and connect to both IPv4 and IPv6 peers. You can override the setting on +// each zsock_t instance. The default is IPv4 only (ipv6 set to 0). If the +// environment variable ZSYS_IPV6 is defined (as 1 or 0), this provides the +// default. Note: has no effect on ZMQ v2. +CZMQ_EXPORT void + zsys_set_ipv6 (int ipv6); + +// Return use of IPv6 for zsock instances. +CZMQ_EXPORT int + zsys_ipv6 (void); + +// Set network interface name to use for broadcasts, particularly zbeacon. +// This lets the interface be configured for test environments where required. +// For example, on Mac OS X, zbeacon cannot bind to 255.255.255.255 which is +// the default when there is no specified interface. If the environment +// variable ZSYS_INTERFACE is set, use that as the default interface name. +// Setting the interface to "*" means "use all available interfaces". +CZMQ_EXPORT void + zsys_set_interface (const char *value); + +// Return network interface to use for broadcasts, or "" if none was set. +CZMQ_EXPORT const char * + zsys_interface (void); + +// Set IPv6 address to use zbeacon socket, particularly for receiving zbeacon. +// This needs to be set IPv6 is enabled as IPv6 can have multiple addresses +// on a given interface. If the environment variable ZSYS_IPV6_ADDRESS is set, +// use that as the default IPv6 address. +CZMQ_EXPORT void + zsys_set_ipv6_address (const char *value); + +// Return IPv6 address to use for zbeacon reception, or "" if none was set. +CZMQ_EXPORT const char * + zsys_ipv6_address (void); + +// Set IPv6 milticast address to use for sending zbeacon messages. This needs +// to be set if IPv6 is enabled. If the environment variable +// ZSYS_IPV6_MCAST_ADDRESS is set, use that as the default IPv6 multicast +// address. +CZMQ_EXPORT void + zsys_set_ipv6_mcast_address (const char *value); + +// Return IPv6 multicast address to use for sending zbeacon, or "" if none was +// set. +CZMQ_EXPORT const char * + zsys_ipv6_mcast_address (void); + +// Configure the automatic use of pre-allocated FDs when creating new sockets. +// If 0 (default), nothing will happen. Else, when a new socket is bound, the +// system API will be used to check if an existing pre-allocated FD with a +// matching port (if TCP) or path (if IPC) exists, and if it does it will be +// set via the ZMQ_USE_FD socket option so that the library will use it +// instead of creating a new socket. +CZMQ_EXPORT void + zsys_set_auto_use_fd (int auto_use_fd); + +// Return use of automatic pre-allocated FDs for zsock instances. +CZMQ_EXPORT int + zsys_auto_use_fd (void); + +// Set log identity, which is a string that prefixes all log messages sent +// by this process. The log identity defaults to the environment variable +// ZSYS_LOGIDENT, if that is set. +CZMQ_EXPORT void + zsys_set_logident (const char *value); + +// Set stream to receive log traffic. By default, log traffic is sent to +// stdout. If you set the stream to NULL, no stream will receive the log +// traffic (it may still be sent to the system facility). +CZMQ_EXPORT void + zsys_set_logstream (FILE *stream); + +// Sends log output to a PUB socket bound to the specified endpoint. To +// collect such log output, create a SUB socket, subscribe to the traffic +// you care about, and connect to the endpoint. Log traffic is sent as a +// single string frame, in the same format as when sent to stdout. The +// log system supports a single sender; multiple calls to this method will +// bind the same sender to multiple endpoints. To disable the sender, call +// this method with a null argument. +CZMQ_EXPORT void + zsys_set_logsender (const char *endpoint); + +// Enable or disable logging to the system facility (syslog on POSIX boxes, +// event log on Windows). By default this is disabled. +CZMQ_EXPORT void + zsys_set_logsystem (bool logsystem); + +// Log error condition - highest priority +CZMQ_EXPORT void + zsys_error (const char *format, ...); + +// Log warning condition - high priority +CZMQ_EXPORT void + zsys_warning (const char *format, ...); + +// Log normal, but significant, condition - normal priority +CZMQ_EXPORT void + zsys_notice (const char *format, ...); + +// Log informational message - low priority +CZMQ_EXPORT void + zsys_info (const char *format, ...); + +// Log debug-level message - lowest priority +CZMQ_EXPORT void + zsys_debug (const char *format, ...); + +// Self test of this class +CZMQ_EXPORT void + zsys_test (bool verbose); + +// Global signal indicator, TRUE when user presses Ctrl-C or the process +// gets a SIGTERM signal. +CZMQ_EXPORT extern volatile int zsys_interrupted; +// Deprecated name for this variable +CZMQ_EXPORT extern volatile int zctx_interrupted; +// @end + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/aarch64-linux/include/zuuid.h b/phonelibs/zmq/aarch64-linux/include/zuuid.h new file mode 100644 index 00000000000000..afc1104fea952b --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/include/zuuid.h @@ -0,0 +1,96 @@ +/* ========================================================================= + zuuid - UUID support class + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZUUID_H_INCLUDED__ +#define __ZUUID_H_INCLUDED__ + +#define ZUUID_LEN 16 +#define ZUUID_STR_LEN (ZUUID_LEN * 2) + +#ifdef __cplusplus +extern "C" { +#endif + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/zuuid.api" to make changes. +// @interface +// This is a stable class, and may not change except for emergencies. It +// is provided in stable builds. +// Create a new UUID object. +CZMQ_EXPORT zuuid_t * + zuuid_new (void); + +// Create UUID object from supplied ZUUID_LEN-octet value. +CZMQ_EXPORT zuuid_t * + zuuid_new_from (const byte *source); + +// Destroy a specified UUID object. +CZMQ_EXPORT void + zuuid_destroy (zuuid_t **self_p); + +// Set UUID to new supplied ZUUID_LEN-octet value. +CZMQ_EXPORT void + zuuid_set (zuuid_t *self, const byte *source); + +// Set UUID to new supplied string value skipping '-' and '{' '}' +// optional delimiters. Return 0 if OK, else returns -1. +CZMQ_EXPORT int + zuuid_set_str (zuuid_t *self, const char *source); + +// Return UUID binary data. +CZMQ_EXPORT const byte * + zuuid_data (zuuid_t *self); + +// Return UUID binary size +CZMQ_EXPORT size_t + zuuid_size (zuuid_t *self); + +// Returns UUID as string +CZMQ_EXPORT const char * + zuuid_str (zuuid_t *self); + +// Return UUID in the canonical string format: 8-4-4-4-12, in lower +// case. Caller does not modify or free returned value. See +// http://en.wikipedia.org/wiki/Universally_unique_identifier +CZMQ_EXPORT const char * + zuuid_str_canonical (zuuid_t *self); + +// Store UUID blob in target array +CZMQ_EXPORT void + zuuid_export (zuuid_t *self, byte *target); + +// Check if UUID is same as supplied value +CZMQ_EXPORT bool + zuuid_eq (zuuid_t *self, const byte *compare); + +// Check if UUID is different from supplied value +CZMQ_EXPORT bool + zuuid_neq (zuuid_t *self, const byte *compare); + +// Make copy of UUID object; if uuid is null, or memory was exhausted, +// returns null. +CZMQ_EXPORT zuuid_t * + zuuid_dup (zuuid_t *self); + +// Self test of this class. +CZMQ_EXPORT void + zuuid_test (bool verbose); + +// @end + + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/aarch64-linux/lib/libczmq.a b/phonelibs/zmq/aarch64-linux/lib/libczmq.a new file mode 100644 index 00000000000000..ba2b0a3ca663dd Binary files /dev/null and b/phonelibs/zmq/aarch64-linux/lib/libczmq.a differ diff --git a/phonelibs/zmq/aarch64-linux/lib/libczmq.la b/phonelibs/zmq/aarch64-linux/lib/libczmq.la new file mode 100755 index 00000000000000..81ef66bdbb0340 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/lib/libczmq.la @@ -0,0 +1,41 @@ +# libczmq.la - a libtool library file +# Generated by libtool (GNU libtool) 2.4.2 Debian-2.4.2-1ubuntu1 +# +# Please DO NOT delete this file! +# It is necessary for linking the library. + +# The name that we can dlopen(3). +dlname='libczmq.so.4' + +# Names of this library. +library_names='libczmq.so.4.0.2 libczmq.so.4 libczmq.so' + +# The name of the static archive. +old_library='libczmq.a' + +# Linker flags that can not go in dependency_libs. +inherited_linker_flags=' -pthread' + +# Libraries that this one depends upon. +dependency_libs=' -L/home/nvidia/build/zmq/lib /home/nvidia/build/zmq/lib/libzmq.la -lrt -lpthread -ldl -luuid' + +# Names of additional weak libraries provided by this library +weak_library_names='' + +# Version information for libczmq. +current=4 +age=0 +revision=2 + +# Is this an already installed library? +installed=yes + +# Should we warn about portability when linking against -modules? +shouldnotlink=no + +# Files to dlopen/dlpreopen +dlopen='' +dlpreopen='' + +# Directory that this library needs to be installed in: +libdir='/home/nvidia/build/zmq/lib' diff --git a/phonelibs/zmq/aarch64-linux/lib/libczmq.so b/phonelibs/zmq/aarch64-linux/lib/libczmq.so new file mode 120000 index 00000000000000..db9aa60f9b5868 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/lib/libczmq.so @@ -0,0 +1 @@ +libczmq.so.4.0.2 \ No newline at end of file diff --git a/phonelibs/zmq/aarch64-linux/lib/libczmq.so.4 b/phonelibs/zmq/aarch64-linux/lib/libczmq.so.4 new file mode 120000 index 00000000000000..db9aa60f9b5868 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/lib/libczmq.so.4 @@ -0,0 +1 @@ +libczmq.so.4.0.2 \ No newline at end of file diff --git a/phonelibs/zmq/aarch64-linux/lib/libczmq.so.4.0.2 b/phonelibs/zmq/aarch64-linux/lib/libczmq.so.4.0.2 new file mode 100755 index 00000000000000..bb9c2d52ebdaea Binary files /dev/null and b/phonelibs/zmq/aarch64-linux/lib/libczmq.so.4.0.2 differ diff --git a/phonelibs/zmq/aarch64-linux/lib/libzmq.a b/phonelibs/zmq/aarch64-linux/lib/libzmq.a new file mode 100644 index 00000000000000..7578d109e45ed4 Binary files /dev/null and b/phonelibs/zmq/aarch64-linux/lib/libzmq.a differ diff --git a/phonelibs/zmq/aarch64-linux/lib/libzmq.la b/phonelibs/zmq/aarch64-linux/lib/libzmq.la new file mode 100755 index 00000000000000..2aef5c45d0f8a6 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/lib/libzmq.la @@ -0,0 +1,41 @@ +# libzmq.la - a libtool library file +# Generated by libtool (GNU libtool) 2.4.2 Debian-2.4.2-1.7ubuntu1 +# +# Please DO NOT delete this file! +# It is necessary for linking the library. + +# The name that we can dlopen(3). +dlname='libzmq.so.5' + +# Names of this library. +library_names='libzmq.so.5.1.2 libzmq.so.5 libzmq.so' + +# The name of the static archive. +old_library='libzmq.a' + +# Linker flags that can not go in dependency_libs. +inherited_linker_flags='' + +# Libraries that this one depends upon. +dependency_libs=' -lrt -lpthread -ldl' + +# Names of additional weak libraries provided by this library +weak_library_names='' + +# Version information for libzmq. +current=6 +age=1 +revision=2 + +# Is this an already installed library? +installed=yes + +# Should we warn about portability when linking against -modules? +shouldnotlink=no + +# Files to dlopen/dlpreopen +dlopen='' +dlpreopen='' + +# Directory that this library needs to be installed in: +libdir='/home/nvidia/build/zmq/lib' diff --git a/phonelibs/zmq/aarch64-linux/lib/libzmq.so b/phonelibs/zmq/aarch64-linux/lib/libzmq.so new file mode 120000 index 00000000000000..ef44cafc6ac861 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/lib/libzmq.so @@ -0,0 +1 @@ +libzmq.so.5.1.2 \ No newline at end of file diff --git a/phonelibs/zmq/aarch64-linux/lib/libzmq.so.5 b/phonelibs/zmq/aarch64-linux/lib/libzmq.so.5 new file mode 120000 index 00000000000000..ef44cafc6ac861 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/lib/libzmq.so.5 @@ -0,0 +1 @@ +libzmq.so.5.1.2 \ No newline at end of file diff --git a/phonelibs/zmq/aarch64-linux/lib/libzmq.so.5.1.2 b/phonelibs/zmq/aarch64-linux/lib/libzmq.so.5.1.2 new file mode 100755 index 00000000000000..e96750a8ef4365 Binary files /dev/null and b/phonelibs/zmq/aarch64-linux/lib/libzmq.so.5.1.2 differ diff --git a/phonelibs/zmq/aarch64-linux/lib/pkgconfig/libczmq.pc b/phonelibs/zmq/aarch64-linux/lib/pkgconfig/libczmq.pc new file mode 100644 index 00000000000000..7740eec8c0d3b5 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/lib/pkgconfig/libczmq.pc @@ -0,0 +1,24 @@ +################################################################################ +# THIS FILE IS 100% GENERATED BY ZPROJECT; DO NOT EDIT EXCEPT EXPERIMENTALLY # +# Read the zproject/README.md for information about making permanent changes. # +################################################################################ + +prefix=/home/nvidia/build/zmq +exec_prefix=${prefix} +libdir=${exec_prefix}/lib +includedir=${prefix}/include + +Name: libczmq +Description: The high-level C binding for 0MQ +Version: 4.0.2 + +Requires:libzmq + +Libs: -L${libdir} -lczmq +Cflags: -I${includedir} +Libs.private: -lzmq -luuid + +################################################################################ +# THIS FILE IS 100% GENERATED BY ZPROJECT; DO NOT EDIT EXCEPT EXPERIMENTALLY # +# Read the zproject/README.md for information about making permanent changes. # +################################################################################ diff --git a/phonelibs/zmq/aarch64-linux/lib/pkgconfig/libzmq.pc b/phonelibs/zmq/aarch64-linux/lib/pkgconfig/libzmq.pc new file mode 100644 index 00000000000000..885271757d640f --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/lib/pkgconfig/libzmq.pc @@ -0,0 +1,11 @@ +prefix=/home/nvidia/build/zmq +exec_prefix=${prefix} +libdir=${exec_prefix}/lib +includedir=${prefix}/include + +Name: libzmq +Description: 0MQ c++ library +Version: 4.2.2 +Libs: -L${libdir} -lzmq +Libs.private: -lstdc++ +Cflags: -I${includedir} diff --git a/phonelibs/zmq/aarch64-linux/share/man/man1/zmakecert.1 b/phonelibs/zmq/aarch64-linux/share/man/man1/zmakecert.1 new file mode 100644 index 00000000000000..7a702496b821e8 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man1/zmakecert.1 @@ -0,0 +1,73 @@ +'\" t +.\" Title: zmakecert +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.76.1 +.\" Date: 12/31/2016 +.\" Manual: CZMQ Manual +.\" Source: CZMQ 4.0.2 +.\" Language: English +.\" +.TH "ZMAKECERT" "1" "12/31/2016" "CZMQ 4\&.0\&.2" "CZMQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zmakecert \- no title found +.SH "SYNOPSIS" +.sp +.nf +Please add \*(Aq@interface\*(Aq section in \*(Aq\&./\&.\&./src/zmakecert\&.c\*(Aq\&. +Please add \*(Aq@interface\*(Aq section in \*(Aq\&./\&.\&./src/zmakecert\&.c\*(Aq\&. +.fi +.SH "DESCRIPTION" +.sp +Please add \fI@header\fR section in \fI\&./\&.\&./src/zmakecert\&.c\fR\&. +.sp +Please add \fI@discuss\fR section in \fI\&./\&.\&./src/zmakecert\&.c\fR\&. +.SH "EXAMPLE" +.PP +\fBFrom zmakecert_test method\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +Please add \*(Aq@selftest\*(Aq section in \*(Aq\&./\&.\&./src/zmakecert\&.c\*(Aq\&. +.fi +.if n \{\ +.RE +.\} +.sp +.SH "AUTHORS" +.sp +The czmq manual was written by the authors in the AUTHORS file\&. +.SH "RESOURCES" +.sp +Main web site: \m[blue]\fB\%\fR\m[] +.sp +Report bugs to the email <\m[blue]\fBzeromq\-dev@lists\&.zeromq\&.org\fR\m[]\&\s-2\u[1]\d\s+2> +.SH "COPYRIGHT" +.sp +Copyright (c) the Contributors as noted in the AUTHORS file\&. This file is part of CZMQ, the high\-level C binding for 0MQ: http://czmq\&.zeromq\&.org\&. This Source Code Form is subject to the terms of the Mozilla Public License, v\&. 2\&.0\&. If a copy of the MPL was not distributed with this file, You can obtain one at http://mozilla\&.org/MPL/2\&.0/\&. LICENSE included with the czmq distribution\&. +.SH "NOTES" +.IP " 1." 4 +zeromq-dev@lists.zeromq.org +.RS 4 +\%mailto:zeromq-dev@lists.zeromq.org +.RE diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zactor.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zactor.3 new file mode 100644 index 00000000000000..481edc396e61fb --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zactor.3 @@ -0,0 +1,127 @@ +'\" t +.\" Title: zactor +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.76.1 +.\" Date: 12/31/2016 +.\" Manual: CZMQ Manual +.\" Source: CZMQ 4.0.2 +.\" Language: English +.\" +.TH "ZACTOR" "3" "12/31/2016" "CZMQ 4\&.0\&.2" "CZMQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zactor \- simple actor framework +.SH "SYNOPSIS" +.sp +.nf +// This is a stable class, and may not change except for emergencies\&. It +// is provided in stable builds\&. +// Actors get a pipe and arguments from caller +typedef void (zactor_fn) ( + zsock_t *pipe, void *args); + +// Create a new actor passing arbitrary arguments reference\&. +CZMQ_EXPORT zactor_t * + zactor_new (zactor_fn task, void *args); + +// Destroy an actor\&. +CZMQ_EXPORT void + zactor_destroy (zactor_t **self_p); + +// Send a zmsg message to the actor, take ownership of the message +// and destroy when it has been sent\&. +CZMQ_EXPORT int + zactor_send (zactor_t *self, zmsg_t **msg_p); + +// Receive a zmsg message from the actor\&. Returns NULL if the actor +// was interrupted before the message could be received, or if there +// was a timeout on the actor\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT zmsg_t * + zactor_recv (zactor_t *self); + +// Probe the supplied object, and report if it looks like a zactor_t\&. +CZMQ_EXPORT bool + zactor_is (void *self); + +// Probe the supplied reference\&. If it looks like a zactor_t instance, +// return the underlying libzmq actor handle; else if it looks like +// a libzmq actor handle, return the supplied value\&. +CZMQ_EXPORT void * + zactor_resolve (void *self); + +// Return the actor\*(Aqs zsock handle\&. Use this when you absolutely need +// to work with the zsock instance rather than the actor\&. +CZMQ_EXPORT zsock_t * + zactor_sock (zactor_t *self); + +// Self test of this class\&. +CZMQ_EXPORT void + zactor_test (bool verbose); + +Please add \*(Aq@interface\*(Aq section in \*(Aq\&./\&.\&./src/zactor\&.c\*(Aq\&. +.fi +.SH "DESCRIPTION" +.sp +The zactor class provides a simple actor framework\&. It replaces the CZMQ zthread class, which had a complex API that did not fit the CLASS standard\&. A CZMQ actor is implemented as a thread plus a PAIR\-PAIR pipe\&. The constructor and destructor are always synchronized, so the caller can be sure all resources are created, and destroyed, when these calls complete\&. (This solves a major problem with zthread, that a caller could not be sure when a child thread had finished\&.) +.sp +A zactor_t instance acts like a zsock_t and you can pass it to any CZMQ method that would take a zsock_t argument, including methods in zframe, zmsg, zstr, and zpoller\&. (zloop somehow escaped and needs catching\&.) +.sp +An actor function MUST call zsock_signal (pipe) when initialized and MUST listen to pipe and exit on $TERM command\&. +.sp +Please add \fI@discuss\fR section in \fI\&./\&.\&./src/zactor\&.c\fR\&. +.SH "EXAMPLE" +.PP +\fBFrom zactor_test method\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +zactor_t *actor = zactor_new (echo_actor, "Hello, World"); +assert (actor); +zstr_sendx (actor, "ECHO", "This is a string", NULL); +char *string = zstr_recv (actor); +assert (streq (string, "This is a string")); +free (string); +zactor_destroy (&actor); +.fi +.if n \{\ +.RE +.\} +.sp +.SH "AUTHORS" +.sp +The czmq manual was written by the authors in the AUTHORS file\&. +.SH "RESOURCES" +.sp +Main web site: \m[blue]\fB\%\fR\m[] +.sp +Report bugs to the email <\m[blue]\fBzeromq\-dev@lists\&.zeromq\&.org\fR\m[]\&\s-2\u[1]\d\s+2> +.SH "COPYRIGHT" +.sp +Copyright (c) the Contributors as noted in the AUTHORS file\&. This file is part of CZMQ, the high\-level C binding for 0MQ: http://czmq\&.zeromq\&.org\&. This Source Code Form is subject to the terms of the Mozilla Public License, v\&. 2\&.0\&. If a copy of the MPL was not distributed with this file, You can obtain one at http://mozilla\&.org/MPL/2\&.0/\&. LICENSE included with the czmq distribution\&. +.SH "NOTES" +.IP " 1." 4 +zeromq-dev@lists.zeromq.org +.RS 4 +\%mailto:zeromq-dev@lists.zeromq.org +.RE diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zarmour.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zarmour.3 new file mode 100644 index 00000000000000..ea806777259889 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zarmour.3 @@ -0,0 +1,372 @@ +'\" t +.\" Title: zarmour +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.76.1 +.\" Date: 12/31/2016 +.\" Manual: CZMQ Manual +.\" Source: CZMQ 4.0.2 +.\" Language: English +.\" +.TH "ZARMOUR" "3" "12/31/2016" "CZMQ 4\&.0\&.2" "CZMQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zarmour \- armoured text encoding and decoding +.SH "SYNOPSIS" +.sp +.nf +// This is a stable class, and may not change except for emergencies\&. It +// is provided in stable builds\&. +#define ZARMOUR_MODE_BASE64_STD 0 // Standard base 64 +#define ZARMOUR_MODE_BASE64_URL 1 // URL and filename friendly base 64 +#define ZARMOUR_MODE_BASE32_STD 2 // Standard base 32 +#define ZARMOUR_MODE_BASE32_HEX 3 // Extended hex base 32 +#define ZARMOUR_MODE_BASE16 4 // Standard base 16 +#define ZARMOUR_MODE_Z85 5 // Z85 from ZeroMQ RFC 32 + +// Create a new zarmour +CZMQ_EXPORT zarmour_t * + zarmour_new (void); + +// Destroy the zarmour +CZMQ_EXPORT void + zarmour_destroy (zarmour_t **self_p); + +// Encode a stream of bytes into an armoured string\&. Returns the armoured +// string, or NULL if there was insufficient memory available to allocate +// a new string\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT char * + zarmour_encode (zarmour_t *self, const byte *data, size_t size); + +// Decode an armoured string into a chunk\&. The decoded output is +// null\-terminated, so it may be treated as a string, if that\*(Aqs what +// it was prior to encoding\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT zchunk_t * + zarmour_decode (zarmour_t *self, const char *data); + +// Get the mode property\&. +CZMQ_EXPORT int + zarmour_mode (zarmour_t *self); + +// Get printable string for mode\&. +CZMQ_EXPORT const char * + zarmour_mode_str (zarmour_t *self); + +// Set the mode property\&. +CZMQ_EXPORT void + zarmour_set_mode (zarmour_t *self, int mode); + +// Return true if padding is turned on\&. +CZMQ_EXPORT bool + zarmour_pad (zarmour_t *self); + +// Turn padding on or off\&. Default is on\&. +CZMQ_EXPORT void + zarmour_set_pad (zarmour_t *self, bool pad); + +// Get the padding character\&. +CZMQ_EXPORT char + zarmour_pad_char (zarmour_t *self); + +// Set the padding character\&. +CZMQ_EXPORT void + zarmour_set_pad_char (zarmour_t *self, char pad_char); + +// Return if splitting output into lines is turned on\&. Default is off\&. +CZMQ_EXPORT bool + zarmour_line_breaks (zarmour_t *self); + +// Turn splitting output into lines on or off\&. +CZMQ_EXPORT void + zarmour_set_line_breaks (zarmour_t *self, bool line_breaks); + +// Get the line length used for splitting lines\&. +CZMQ_EXPORT size_t + zarmour_line_length (zarmour_t *self); + +// Set the line length used for splitting lines\&. +CZMQ_EXPORT void + zarmour_set_line_length (zarmour_t *self, size_t line_length); + +// Print properties of object +CZMQ_EXPORT void + zarmour_print (zarmour_t *self); + +// Self test of this class\&. +CZMQ_EXPORT void + zarmour_test (bool verbose); + +Please add \*(Aq@interface\*(Aq section in \*(Aq\&./\&.\&./src/zarmour\&.c\*(Aq\&. +.fi +.SH "DESCRIPTION" +.sp +zarmour \- armoured text encoding and decoding +.sp +The zarmour class implements encoding and decoding of armoured text data\&. The following codecs are implemented: * RFC 4648 (\m[blue]\fBhttp://www\&.ietf\&.org/rfc/rfc4648\&.txt\fR\m[]) \- base64 \- base64url \- base32 \- base32hex \- base16 * Z85 (\m[blue]\fBhttp://rfc\&.zeromq\&.org/spec:32\fR\m[]) All RFC4648 base64 and base32 variants support padding the output\&. The pad character is configurable\&. Default is padding on, with character \fI=\fR\&. Additionally, in some cases (e\&.g\&. MIME), splitting the output into lines of a specific length is required\&. This feature is also supported, though turned off by default\&. The z85 mode does neither padding nor line breaks; it is merely a wrapping of the corresponding libzmq methods\&. Encoding will assert if input length is not divisible by 4 and decoding will assert if input length is not divisible by 5\&. +.SH "EXAMPLE" +.PP +\fBFrom zarmour_test method\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +zarmour_t *self = zarmour_new (); +assert (self); + +int mode = zarmour_mode (self); +assert (mode == ZARMOUR_MODE_BASE64_STD); + +zarmour_set_mode (self, ZARMOUR_MODE_BASE64_URL); +mode = zarmour_mode (self); +assert (mode == ZARMOUR_MODE_BASE64_URL); + +assert (zarmour_pad (self)); +zarmour_set_pad (self, false); +assert (!zarmour_pad (self)); + +assert (zarmour_pad_char (self) == \*(Aq=\*(Aq); +zarmour_set_pad_char (self, \*(Aq!\*(Aq); +assert (zarmour_pad_char (self) == \*(Aq!\*(Aq); +zarmour_set_pad_char (self, \*(Aq=\*(Aq); +assert (zarmour_pad_char (self) == \*(Aq=\*(Aq); + +assert (!zarmour_line_breaks (self)); +zarmour_set_line_breaks (self, true); +assert (zarmour_line_breaks (self)); + +assert (zarmour_line_length (self) == 72); +zarmour_set_line_length (self, 64); +assert (zarmour_line_length (self) == 64); + +// Test against test vectors from RFC4648\&. +zarmour_set_mode (self, ZARMOUR_MODE_BASE64_STD); +if (verbose) + zarmour_print (self); + +s_armour_test (self, "", "", verbose); +s_armour_test (self, "f", "Zg", verbose); +s_armour_test (self, "fo", "Zm8", verbose); +s_armour_test (self, "foo", "Zm9v", verbose); +s_armour_test (self, "foob", "Zm9vYg", verbose); +s_armour_test (self, "fooba", "Zm9vYmE", verbose); +s_armour_test (self, "foobar", "Zm9vYmFy", verbose); +zarmour_set_pad (self, true); +if (verbose) + zarmour_print (self); + +s_armour_test (self, "", "", verbose); +s_armour_test (self, "f", "Zg==", verbose); +s_armour_test (self, "fo", "Zm8=", verbose); +s_armour_test (self, "foo", "Zm9v", verbose); +s_armour_test (self, "foob", "Zm9vYg==", verbose); +s_armour_test (self, "fooba", "Zm9vYmE=", verbose); +s_armour_test (self, "foobar", "Zm9vYmFy", verbose); + +zarmour_set_pad (self, false); +zarmour_set_mode (self, ZARMOUR_MODE_BASE64_URL); +if (verbose) + zarmour_print (self); + +s_armour_test (self, "", "", verbose); +s_armour_test (self, "f", "Zg", verbose); +s_armour_test (self, "fo", "Zm8", verbose); +s_armour_test (self, "foo", "Zm9v", verbose); +s_armour_test (self, "foob", "Zm9vYg", verbose); +s_armour_test (self, "fooba", "Zm9vYmE", verbose); +s_armour_test (self, "foobar", "Zm9vYmFy", verbose); +zarmour_set_pad (self, true); +if (verbose) + zarmour_print (self); + +s_armour_test (self, "", "", verbose); +s_armour_test (self, "f", "Zg==", verbose); +s_armour_test (self, "fo", "Zm8=", verbose); +s_armour_test (self, "foo", "Zm9v", verbose); +s_armour_test (self, "foob", "Zm9vYg==", verbose); +s_armour_test (self, "fooba", "Zm9vYmE=", verbose); +s_armour_test (self, "foobar", "Zm9vYmFy", verbose); + +zarmour_set_pad (self, false); +zarmour_set_mode (self, ZARMOUR_MODE_BASE32_STD); +if (verbose) + zarmour_print (self); + +s_armour_test (self, "", "", verbose); +s_armour_test (self, "f", "MY", verbose); +s_armour_test (self, "fo", "MZXQ", verbose); +s_armour_test (self, "foo", "MZXW6", verbose); +s_armour_test (self, "foob", "MZXW6YQ", verbose); +s_armour_test (self, "fooba", "MZXW6YTB", verbose); +s_armour_test (self, "foobar", "MZXW6YTBOI", verbose); +s_armour_decode (self, "my", "f", verbose); +s_armour_decode (self, "mzxq", "fo", verbose); +s_armour_decode (self, "mzxw6", "foo", verbose); +s_armour_decode (self, "mzxw6yq", "foob", verbose); +s_armour_decode (self, "mzxw6ytb", "fooba", verbose); +s_armour_decode (self, "mzxw6ytboi", "foobar", verbose); +zarmour_set_pad (self, true); +if (verbose) + zarmour_print (self); + +s_armour_test (self, "", "", verbose); +s_armour_test (self, "f", "MY======", verbose); +s_armour_test (self, "fo", "MZXQ====", verbose); +s_armour_test (self, "foo", "MZXW6===", verbose); +s_armour_test (self, "foob", "MZXW6YQ=", verbose); +s_armour_test (self, "fooba", "MZXW6YTB", verbose); +s_armour_test (self, "foobar", "MZXW6YTBOI======", verbose); +s_armour_decode (self, "my======", "f", verbose); +s_armour_decode (self, "mzxq====", "fo", verbose); +s_armour_decode (self, "mzxw6===", "foo", verbose); +s_armour_decode (self, "mzxw6yq=", "foob", verbose); +s_armour_decode (self, "mzxw6ytb", "fooba", verbose); +s_armour_decode (self, "mzxw6ytboi======", "foobar", verbose); + +zarmour_set_pad (self, false); +zarmour_set_mode (self, ZARMOUR_MODE_BASE32_HEX); +if (verbose) + zarmour_print (self); + +s_armour_test (self, "", "", verbose); +s_armour_test (self, "f", "CO", verbose); +s_armour_test (self, "fo", "CPNG", verbose); +s_armour_test (self, "foo", "CPNMU", verbose); +s_armour_test (self, "foob", "CPNMUOG", verbose); +s_armour_test (self, "fooba", "CPNMUOJ1", verbose); +s_armour_test (self, "foobar", "CPNMUOJ1E8", verbose); +s_armour_decode (self, "co", "f", verbose); +s_armour_decode (self, "cpng", "fo", verbose); +s_armour_decode (self, "cpnmu", "foo", verbose); +s_armour_decode (self, "cpnmuog", "foob", verbose); +s_armour_decode (self, "cpnmuoj1", "fooba", verbose); +s_armour_decode (self, "cpnmuoj1e8", "foobar", verbose); +zarmour_set_pad (self, true); +if (verbose) + zarmour_print (self); + +s_armour_test (self, "", "", verbose); +s_armour_test (self, "f", "CO======", verbose); +s_armour_test (self, "fo", "CPNG====", verbose); +s_armour_test (self, "foo", "CPNMU===", verbose); +s_armour_test (self, "foob", "CPNMUOG=", verbose); +s_armour_test (self, "fooba", "CPNMUOJ1", verbose); +s_armour_test (self, "foobar", "CPNMUOJ1E8======", verbose); +s_armour_decode (self, "co======", "f", verbose); +s_armour_decode (self, "cpng====", "fo", verbose); +s_armour_decode (self, "cpnmu===", "foo", verbose); +s_armour_decode (self, "cpnmuog=", "foob", verbose); +s_armour_decode (self, "cpnmuoj1", "fooba", verbose); +s_armour_decode (self, "cpnmuoj1e8======", "foobar", verbose); +zarmour_set_pad (self, true); + +zarmour_set_mode (self, ZARMOUR_MODE_BASE16); +if (verbose) + zarmour_print (self); + +s_armour_test (self, "", "", verbose); +s_armour_test (self, "f", "66", verbose); +s_armour_test (self, "fo", "666F", verbose); +s_armour_test (self, "foo", "666F6F", verbose); +s_armour_test (self, "foob", "666F6F62", verbose); +s_armour_test (self, "fooba", "666F6F6261", verbose); +s_armour_test (self, "foobar", "666F6F626172", verbose); +s_armour_decode (self, "666f", "fo", verbose); +s_armour_decode (self, "666f6f", "foo", verbose); +s_armour_decode (self, "666f6f62", "foob", verbose); +s_armour_decode (self, "666f6f6261", "fooba", verbose); +s_armour_decode (self, "666f6f626172", "foobar", verbose); + +#ifdef _INCLUDE_Z85 +// Z85 test is homemade; using 0, 4 and 8 bytes, with precalculated +// test vectors created with a libzmq test\&. +// \-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\- + +// Make a fake curve key from hex (base16) string, making sure +// there are no null bytes inside, so we can use our test utility +zarmour_set_mode (self, ZARMOUR_MODE_BASE16); +zarmour_set_line_breaks (self, false); + +zchunk_t *chunk = zarmour_decode (self, + "4E6F87E2FB6EB22A1EF5E257B75D79124949565F0B8B36A878A4F03111C96E0B"); +assert (chunk); + +zarmour_set_mode (self, ZARMOUR_MODE_Z85); // Z85 mode does not support padding or line breaks +zarmour_set_pad (self, false); // so these two are superfluous; +zarmour_set_line_breaks (self, false); // just for consistency +if (verbose) + zarmour_print (self); + +s_armour_test (self, "", "", verbose); +s_armour_test (self, "foob", "w]zP%", verbose); +s_armour_test (self, "foobar!!", "w]zP%vr9Im", verbose); +s_armour_test (self, (char *) zchunk_data (chunk), + "ph+{E}!&X?9}!I]W{sm(nL8@&3Yu{wC+<*\-5Y[[#", verbose); +zchunk_destroy (&chunk); +#endif + +// Armouring longer byte array to test line breaks +zarmour_set_pad (self, true); +zarmour_set_line_breaks (self, true); +byte test_data [256]; +int index; +for (index = 0; index < 256; index++) + test_data [index] = index; + +zarmour_set_mode (self, ZARMOUR_MODE_BASE64_STD); +s_armour_test_long (self, test_data, 256, verbose); +zarmour_set_mode (self, ZARMOUR_MODE_BASE64_URL); +s_armour_test_long (self, test_data, 256, verbose); +zarmour_set_mode (self, ZARMOUR_MODE_BASE32_STD); +s_armour_test_long (self, test_data, 256, verbose); +zarmour_set_mode (self, ZARMOUR_MODE_BASE32_HEX); +s_armour_test_long (self, test_data, 256, verbose); +zarmour_set_mode (self, ZARMOUR_MODE_BASE16); +s_armour_test_long (self, test_data, 256, verbose); +#ifdef _INCLUDE_Z85 +zarmour_set_mode (self, ZARMOUR_MODE_Z85); +s_armour_test_long (self, test_data, 256, verbose); +#endif + +zarmour_destroy (&self); +.fi +.if n \{\ +.RE +.\} +.sp +.SH "AUTHORS" +.sp +The czmq manual was written by the authors in the AUTHORS file\&. +.SH "RESOURCES" +.sp +Main web site: \m[blue]\fB\%\fR\m[] +.sp +Report bugs to the email <\m[blue]\fBzeromq\-dev@lists\&.zeromq\&.org\fR\m[]\&\s-2\u[1]\d\s+2> +.SH "COPYRIGHT" +.sp +Copyright (c) the Contributors as noted in the AUTHORS file\&. This file is part of CZMQ, the high\-level C binding for 0MQ: http://czmq\&.zeromq\&.org\&. This Source Code Form is subject to the terms of the Mozilla Public License, v\&. 2\&.0\&. If a copy of the MPL was not distributed with this file, You can obtain one at http://mozilla\&.org/MPL/2\&.0/\&. LICENSE included with the czmq distribution\&. +.SH "NOTES" +.IP " 1." 4 +zeromq-dev@lists.zeromq.org +.RS 4 +\%mailto:zeromq-dev@lists.zeromq.org +.RE diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zauth.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zauth.3 new file mode 100644 index 00000000000000..b119d13e9afec2 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zauth.3 @@ -0,0 +1,309 @@ +'\" t +.\" Title: zauth +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.76.1 +.\" Date: 12/31/2016 +.\" Manual: CZMQ Manual +.\" Source: CZMQ 4.0.2 +.\" Language: English +.\" +.TH "ZAUTH" "3" "12/31/2016" "CZMQ 4\&.0\&.2" "CZMQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zauth \- authentication for ZeroMQ security mechanisms +.SH "SYNOPSIS" +.sp +.nf +#define CURVE_ALLOW_ANY "*" + +// CZMQ v3 API (for use with zsock, not zsocket, which is deprecated)\&. +// +// Create new zauth actor instance\&. This installs authentication on all +// zsock sockets\&. Until you add policies, all incoming NULL connections are +// allowed (classic ZeroMQ behaviour), and all PLAIN and CURVE connections +// are denied: +// +// zactor_t *auth = zactor_new (zauth, NULL); +// +// Destroy zauth instance\&. This removes authentication and allows all +// connections to pass, without authentication: +// +// zactor_destroy (&auth); +// +// Note that all zauth commands are synchronous, so your application always +// waits for a signal from the actor after each command\&. +// +// Enable verbose logging of commands and activity\&. Verbose logging can help +// debug non\-trivial authentication policies: +// +// zstr_send (auth, "VERBOSE"); +// zsock_wait (auth); +// +// Allow (whitelist) a list of IP addresses\&. For NULL, all clients from +// these addresses will be accepted\&. For PLAIN and CURVE, they will be +// allowed to continue with authentication\&. You can call this method +// multiple times to whitelist more IP addresses\&. If you whitelist one +// or more addresses, any non\-whitelisted addresses are treated as +// blacklisted: +// +// zstr_sendx (auth, "ALLOW", "127\&.0\&.0\&.1", "127\&.0\&.0\&.2", NULL); +// zsock_wait (auth); +// +// Deny (blacklist) a list of IP addresses\&. For all security mechanisms, +// this rejects the connection without any further authentication\&. Use +// either a whitelist, or a blacklist, not not both\&. If you define both +// a whitelist and a blacklist, only the whitelist takes effect: +// +// zstr_sendx (auth, "DENY", "192\&.168\&.0\&.1", "192\&.168\&.0\&.2", NULL); +// zsock_wait (auth); +// +// Configure PLAIN authentication using a plain\-text password file\&. You can +// modify the password file at any time; zauth will reload it automatically +// if modified externally: +// +// zstr_sendx (auth, "PLAIN", filename, NULL); +// zsock_wait (auth); +// +// Configure CURVE authentication, using a directory that holds all public +// client certificates, i\&.e\&. their public keys\&. The certificates must be in +// zcert_save format\&. You can add and remove certificates in that directory +// at any time\&. To allow all client keys without checking, specify +// CURVE_ALLOW_ANY for the directory name: +// +// zstr_sendx (auth, "CURVE", directory, NULL); +// zsock_wait (auth); +// +// Configure GSSAPI authentication, using an underlying mechanism (usually +// Kerberos) to establish a secure context and perform mutual authentication: +// +// zstr_sendx (auth, "GSSAPI", NULL); +// zsock_wait (auth); +// +// This is the zauth constructor as a zactor_fn: +CZMQ_EXPORT void + zauth (zsock_t *pipe, void *certstore); + +// Selftest +CZMQ_EXPORT void + zauth_test (bool verbose); +Please add \*(Aq@interface\*(Aq section in \*(Aq\&./\&.\&./src/zauth\&.c\*(Aq\&. +.fi +.SH "DESCRIPTION" +.sp +A zauth actor takes over authentication for all incoming connections in its context\&. You can whitelist or blacklist peers based on IP address, and define policies for securing PLAIN, CURVE, and GSSAPI connections\&. +.sp +This class replaces zauth_v2, and is meant for applications that use the CZMQ v3 API (meaning, zsock)\&. +.SH "EXAMPLE" +.PP +\fBFrom zauth_test method\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +// Create temporary directory for test files +# define TESTDIR "\&.test_zauth" +zsys_dir_create (TESTDIR); + +// Check there\*(Aqs no authentication +zsock_t *server = zsock_new (ZMQ_PULL); +assert (server); +zsock_t *client = zsock_new (ZMQ_PUSH); +assert (client); +bool success = s_can_connect (&server, &client, true); +assert (success); + +// Install the authenticator +zactor_t *auth = zactor_new (zauth, NULL); +assert (auth); +if (verbose) { + zstr_sendx (auth, "VERBOSE", NULL); + zsock_wait (auth); +} +// Check there\*(Aqs no authentication on a default NULL server +success = s_can_connect (&server, &client, true); +assert (success); + +// When we set a domain on the server, we switch on authentication +// for NULL sockets, but with no policies, the client connection +// will be allowed\&. +zsock_set_zap_domain (server, "global"); +success = s_can_connect (&server, &client, true); +assert (success); + +// Blacklist 127\&.0\&.0\&.1, connection should fail +zsock_set_zap_domain (server, "global"); +zstr_sendx (auth, "DENY", "127\&.0\&.0\&.1", NULL); +zsock_wait (auth); +success = s_can_connect (&server, &client, true); +assert (!success); + +// Whitelist our address, which overrides the blacklist +zsock_set_zap_domain (server, "global"); +zstr_sendx (auth, "ALLOW", "127\&.0\&.0\&.1", NULL); +zsock_wait (auth); +success = s_can_connect (&server, &client, true); +assert (success); + +// Try PLAIN authentication +zsock_set_plain_server (server, 1); +zsock_set_plain_username (client, "admin"); +zsock_set_plain_password (client, "Password"); +success = s_can_connect (&server, &client, true); +assert (!success); + +FILE *password = fopen (TESTDIR "/password\-file", "w"); +assert (password); +fprintf (password, "admin=Password\en"); +fclose (password); +zsock_set_plain_server (server, 1); +zsock_set_plain_username (client, "admin"); +zsock_set_plain_password (client, "Password"); +zstr_sendx (auth, "PLAIN", TESTDIR "/password\-file", NULL); +zsock_wait (auth); +success = s_can_connect (&server, &client, true); +assert (success); + +zsock_set_plain_server (server, 1); +zsock_set_plain_username (client, "admin"); +zsock_set_plain_password (client, "Bogus"); +success = s_can_connect (&server, &client, true); +assert (!success); + +if (zsys_has_curve ()) { + // Try CURVE authentication + // We\*(Aqll create two new certificates and save the client public + // certificate on disk; in a real case we\*(Aqd transfer this securely + // from the client machine to the server machine\&. + zcert_t *server_cert = zcert_new (); + assert (server_cert); + zcert_t *client_cert = zcert_new (); + assert (client_cert); + const char *server_key = zcert_public_txt (server_cert); + + // Test without setting\-up any authentication + zcert_apply (server_cert, server); + zcert_apply (client_cert, client); + zsock_set_curve_server (server, 1); + zsock_set_curve_serverkey (client, server_key); + success = s_can_connect (&server, &client, true); + assert (!success); + + // Test CURVE_ALLOW_ANY + zcert_apply (server_cert, server); + zcert_apply (client_cert, client); + zsock_set_curve_server (server, 1); + zsock_set_curve_serverkey (client, server_key); + zstr_sendx (auth, "CURVE", CURVE_ALLOW_ANY, NULL); + zsock_wait (auth); + success = s_can_connect (&server, &client, true); + assert (success); + + // Test full client authentication using certificates + zcert_set_meta (client_cert, "Hello", "%s", "World!"); + zcert_apply (server_cert, server); + zcert_apply (client_cert, client); + zsock_set_curve_server (server, 1); + zsock_set_curve_serverkey (client, server_key); + zcert_save_public (client_cert, TESTDIR "/mycert\&.txt"); + zstr_sendx (auth, "CURVE", TESTDIR, NULL); + zsock_wait (auth); + success = s_can_connect (&server, &client, false); + assert (success); + +#if (ZMQ_VERSION >= ZMQ_MAKE_VERSION (4, 1, 0)) + // Test send/recv certificate metadata + zframe_t *frame = zframe_recv (server); + assert (frame != NULL); + const char *meta = zframe_meta (frame, "Hello"); + assert (meta != NULL); + assert (streq (meta, "World!")); + zframe_destroy (&frame); + s_renew_sockets(&server, &client); +#endif + + zcert_destroy (&server_cert); + zcert_destroy (&client_cert); + + // Test custom zcertstore + zcertstore_t *certstore = zcertstore_new (NULL); + zcertstore_set_loader (certstore, s_test_loader, NULL, NULL); + zactor_destroy(&auth); + auth = zactor_new (zauth, certstore); + assert (auth); + if (verbose) { + zstr_sendx (auth, "VERBOSE", NULL); + zsock_wait (auth); + } + + byte public_key [32] = { 105, 76, 150, 58, 214, 191, 218, 65, 50, 172, + 131, 188, 247, 211, 136, 170, 227, 26, 57, 170, + 185, 63, 246, 225, 177, 230, 12, 8, 134, 136, + 105, 106 }; + byte secret_key [32] = { 245, 217, 172, 73, 106, 28, 195, 17, 218, 132, + 135, 209, 99, 240, 98, 232, 7, 137, 244, 100, + 242, 23, 29, 114, 70, 223, 83, 1, 113, 207, + 132, 149 }; + zcert_t *shared_cert = zcert_new_from (public_key, secret_key); + assert (shared_cert); + zcert_apply (shared_cert, server); + zcert_apply (shared_cert, client); + zsock_set_curve_server (server, 1); + zsock_set_curve_serverkey (client, "x?T*N/1Y{8goubv{Ts}#&#f}TXJ//DVe#D2HkoLU"); + success = s_can_connect (&server, &client, true); + assert (success); + zcert_destroy (&shared_cert); +} +// Remove the authenticator and check a normal connection works +zactor_destroy (&auth); +success = s_can_connect (&server, &client, true); +assert (success); + +zsock_destroy (&client); +zsock_destroy (&server); + +// Delete all test files +zdir_t *dir = zdir_new (TESTDIR, NULL); +assert (dir); +zdir_remove (dir, true); +zdir_destroy (&dir); +.fi +.if n \{\ +.RE +.\} +.sp +.SH "AUTHORS" +.sp +The czmq manual was written by the authors in the AUTHORS file\&. +.SH "RESOURCES" +.sp +Main web site: \m[blue]\fB\%\fR\m[] +.sp +Report bugs to the email <\m[blue]\fBzeromq\-dev@lists\&.zeromq\&.org\fR\m[]\&\s-2\u[1]\d\s+2> +.SH "COPYRIGHT" +.sp +Copyright (c) the Contributors as noted in the AUTHORS file\&. This file is part of CZMQ, the high\-level C binding for 0MQ: http://czmq\&.zeromq\&.org\&. This Source Code Form is subject to the terms of the Mozilla Public License, v\&. 2\&.0\&. If a copy of the MPL was not distributed with this file, You can obtain one at http://mozilla\&.org/MPL/2\&.0/\&. LICENSE included with the czmq distribution\&. +.SH "NOTES" +.IP " 1." 4 +zeromq-dev@lists.zeromq.org +.RS 4 +\%mailto:zeromq-dev@lists.zeromq.org +.RE diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zbeacon.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zbeacon.3 new file mode 100644 index 00000000000000..40e3abbac4056a --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zbeacon.3 @@ -0,0 +1,236 @@ +'\" t +.\" Title: zbeacon +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.76.1 +.\" Date: 12/31/2016 +.\" Manual: CZMQ Manual +.\" Source: CZMQ 4.0.2 +.\" Language: English +.\" +.TH "ZBEACON" "3" "12/31/2016" "CZMQ 4\&.0\&.2" "CZMQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zbeacon \- LAN discovery and presence +.SH "SYNOPSIS" +.sp +.nf +// Create new zbeacon actor instance: +// +// zactor_t *beacon = zactor_new (zbeacon, NULL); +// +// Destroy zbeacon instance: +// +// zactor_destroy (&beacon); +// +// Enable verbose logging of commands and activity: +// +// zstr_send (beacon, "VERBOSE"); +// +// Configure beacon to run on specified UDP port, and return the name of +// the host, which can be used as endpoint for incoming connections\&. To +// force the beacon to operate on a given interface, set the environment +// variable ZSYS_INTERFACE, or call zsys_set_interface() before creating +// the beacon\&. If the system does not support UDP broadcasts (lacking a +// workable interface), returns an empty hostname: +// +// // Pictures: \*(Aqs\*(Aq = C string, \*(Aqi\*(Aq = int +// zsock_send (beacon, "si", "CONFIGURE", port_number); +// char *hostname = zstr_recv (beacon); +// +// Start broadcasting a beacon at a specified interval in msec\&. The beacon +// data can be at most UDP_FRAME_MAX bytes; this constant is defined in +// zsys\&.h to be 255: +// +// // Pictures: \*(Aqb\*(Aq = byte * data + size_t size +// zsock_send (beacon, "sbi", "PUBLISH", data, size, interval); +// +// Stop broadcasting the beacon: +// +// zstr_sendx (beacon, "SILENCE", NULL); +// +// Start listening to beacons from peers\&. The filter is used to do a prefix +// match on received beacons, to remove junk\&. Note that any received data +// that is identical to our broadcast beacon_data is discarded in any case\&. +// If the filter size is zero, we get all peer beacons: +// +// zsock_send (beacon, "sb", "SUBSCRIBE", filter_data, filter_size); +// +// Stop listening to other peers +// +// zstr_sendx (beacon, "UNSUBSCRIBE", NULL); +// +// Receive next beacon from a peer\&. Received beacons are always a 2\-frame +// message containing the ipaddress of the sender, and then the binary +// beacon data as published by the sender: +// +// zmsg_t *msg = zmsg_recv (beacon); +// +// This is the zbeacon constructor as a zactor_fn: +CZMQ_EXPORT void + zbeacon (zsock_t *pipe, void *unused); + +// Self test of this class +CZMQ_EXPORT void + zbeacon_test (bool verbose); +Please add \*(Aq@interface\*(Aq section in \*(Aq\&./\&.\&./src/zbeacon\&.c\*(Aq\&. +.fi +.SH "DESCRIPTION" +.sp +The zbeacon class implements a peer\-to\-peer discovery service for local networks\&. A beacon can broadcast and/or capture service announcements using UDP messages on the local area network\&. This implementation uses IPv4 UDP broadcasts\&. You can define the format of your outgoing beacons, and set a filter that validates incoming beacons\&. Beacons are sent and received asynchronously in the background\&. +.sp +This class replaces zbeacon_v2, and is meant for applications that use the CZMQ v3 API (meaning, zsock)\&. +.SH "EXAMPLE" +.PP +\fBFrom zbeacon_test method\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +// Test 1 \- two beacons, one speaking, one listening +// Create speaker beacon to broadcast our service +zactor_t *speaker = zactor_new (zbeacon, NULL); +assert (speaker); +if (verbose) + zstr_sendx (speaker, "VERBOSE", NULL); + +zsock_send (speaker, "si", "CONFIGURE", 9999); +char *hostname = zstr_recv (speaker); +if (!*hostname) { + printf ("OK (skipping test, no UDP broadcasting)\en"); + zactor_destroy (&speaker); + free (hostname); + return; +} +free (hostname); + +// Create listener beacon on port 9999 to lookup service +zactor_t *listener = zactor_new (zbeacon, NULL); +assert (listener); +if (verbose) + zstr_sendx (listener, "VERBOSE", NULL); +zsock_send (listener, "si", "CONFIGURE", 9999); +hostname = zstr_recv (listener); +assert (*hostname); +free (hostname); + +// We will broadcast the magic value 0xCAFE +byte announcement [2] = { 0xCA, 0xFE }; +zsock_send (speaker, "sbi", "PUBLISH", announcement, 2, 100); +// We will listen to anything (empty subscription) +zsock_send (listener, "sb", "SUBSCRIBE", "", 0); + +// Wait for at most 1/2 second if there\*(Aqs no broadcasting +zsock_set_rcvtimeo (listener, 500); +char *ipaddress = zstr_recv (listener); +if (ipaddress) { + zframe_t *content = zframe_recv (listener); + assert (zframe_size (content) == 2); + assert (zframe_data (content) [0] == 0xCA); + assert (zframe_data (content) [1] == 0xFE); + zframe_destroy (&content); + zstr_free (&ipaddress); + zstr_sendx (speaker, "SILENCE", NULL); +} +zactor_destroy (&listener); +zactor_destroy (&speaker); + +// Test subscription filter using a 3\-node setup +zactor_t *node1 = zactor_new (zbeacon, NULL); +assert (node1); +zsock_send (node1, "si", "CONFIGURE", 5670); +hostname = zstr_recv (node1); +assert (*hostname); +free (hostname); + +zactor_t *node2 = zactor_new (zbeacon, NULL); +assert (node2); +zsock_send (node2, "si", "CONFIGURE", 5670); +hostname = zstr_recv (node2); +assert (*hostname); +free (hostname); + +zactor_t *node3 = zactor_new (zbeacon, NULL); +assert (node3); +zsock_send (node3, "si", "CONFIGURE", 5670); +hostname = zstr_recv (node3); +assert (*hostname); +free (hostname); + +zsock_send (node1, "sbi", "PUBLISH", "NODE/1", 6, 250); +zsock_send (node2, "sbi", "PUBLISH", "NODE/2", 6, 250); +zsock_send (node3, "sbi", "PUBLISH", "RANDOM", 6, 250); +zsock_send (node1, "sb", "SUBSCRIBE", "NODE", 4); + +// Poll on three API sockets at once +zpoller_t *poller = zpoller_new (node1, node2, node3, NULL); +assert (poller); +int64_t stop_at = zclock_mono () + 1000; +while (zclock_mono () < stop_at) { + long timeout = (long) (stop_at \- zclock_mono ()); + if (timeout < 0) + timeout = 0; + void *which = zpoller_wait (poller, timeout * ZMQ_POLL_MSEC); + if (which) { + assert (which == node1); + char *ipaddress, *received; + zstr_recvx (node1, &ipaddress, &received, NULL); + assert (streq (received, "NODE/2")); + zstr_free (&ipaddress); + zstr_free (&received); + } +} +zpoller_destroy (&poller); + +// Stop listening +zstr_sendx (node1, "UNSUBSCRIBE", NULL); + +// Stop all node broadcasts +zstr_sendx (node1, "SILENCE", NULL); +zstr_sendx (node2, "SILENCE", NULL); +zstr_sendx (node3, "SILENCE", NULL); + +// Destroy the test nodes +zactor_destroy (&node1); +zactor_destroy (&node2); +zactor_destroy (&node3); +.fi +.if n \{\ +.RE +.\} +.sp +.SH "AUTHORS" +.sp +The czmq manual was written by the authors in the AUTHORS file\&. +.SH "RESOURCES" +.sp +Main web site: \m[blue]\fB\%\fR\m[] +.sp +Report bugs to the email <\m[blue]\fBzeromq\-dev@lists\&.zeromq\&.org\fR\m[]\&\s-2\u[1]\d\s+2> +.SH "COPYRIGHT" +.sp +Copyright (c) the Contributors as noted in the AUTHORS file\&. This file is part of CZMQ, the high\-level C binding for 0MQ: http://czmq\&.zeromq\&.org\&. This Source Code Form is subject to the terms of the Mozilla Public License, v\&. 2\&.0\&. If a copy of the MPL was not distributed with this file, You can obtain one at http://mozilla\&.org/MPL/2\&.0/\&. LICENSE included with the czmq distribution\&. +.SH "NOTES" +.IP " 1." 4 +zeromq-dev@lists.zeromq.org +.RS 4 +\%mailto:zeromq-dev@lists.zeromq.org +.RE diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zcert.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zcert.3 new file mode 100644 index 00000000000000..e2c81dbf10bd64 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zcert.3 @@ -0,0 +1,215 @@ +'\" t +.\" Title: zcert +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.76.1 +.\" Date: 12/31/2016 +.\" Manual: CZMQ Manual +.\" Source: CZMQ 4.0.2 +.\" Language: English +.\" +.TH "ZCERT" "3" "12/31/2016" "CZMQ 4\&.0\&.2" "CZMQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zcert \- work with CURVE security certificates +.SH "SYNOPSIS" +.sp +.nf +// This is a stable class, and may not change except for emergencies\&. It +// is provided in stable builds\&. +// This class has draft methods, which may change over time\&. They are not +// in stable releases, by default\&. Use \-\-enable\-drafts to enable\&. +// Create and initialize a new certificate in memory +CZMQ_EXPORT zcert_t * + zcert_new (void); + +// Accepts public/secret key pair from caller +CZMQ_EXPORT zcert_t * + zcert_new_from (const byte *public_key, const byte *secret_key); + +// Load certificate from file +CZMQ_EXPORT zcert_t * + zcert_load (const char *filename); + +// Destroy a certificate in memory +CZMQ_EXPORT void + zcert_destroy (zcert_t **self_p); + +// Return public part of key pair as 32\-byte binary string +CZMQ_EXPORT const byte * + zcert_public_key (zcert_t *self); + +// Return secret part of key pair as 32\-byte binary string +CZMQ_EXPORT const byte * + zcert_secret_key (zcert_t *self); + +// Return public part of key pair as Z85 armored string +CZMQ_EXPORT const char * + zcert_public_txt (zcert_t *self); + +// Return secret part of key pair as Z85 armored string +CZMQ_EXPORT const char * + zcert_secret_txt (zcert_t *self); + +// Set certificate metadata from formatted string\&. +CZMQ_EXPORT void + zcert_set_meta (zcert_t *self, const char *name, const char *format, \&.\&.\&.) CHECK_PRINTF (3); + +// Get metadata value from certificate; if the metadata value doesn\*(Aqt +// exist, returns NULL\&. +CZMQ_EXPORT const char * + zcert_meta (zcert_t *self, const char *name); + +// Get list of metadata fields from certificate\&. Caller is responsible for +// destroying list\&. Caller should not modify the values of list items\&. +CZMQ_EXPORT zlist_t * + zcert_meta_keys (zcert_t *self); + +// Save full certificate (public + secret) to file for persistent storage +// This creates one public file and one secret file (filename + "_secret")\&. +CZMQ_EXPORT int + zcert_save (zcert_t *self, const char *filename); + +// Save public certificate only to file for persistent storage +CZMQ_EXPORT int + zcert_save_public (zcert_t *self, const char *filename); + +// Save secret certificate only to file for persistent storage +CZMQ_EXPORT int + zcert_save_secret (zcert_t *self, const char *filename); + +// Apply certificate to socket, i\&.e\&. use for CURVE security on socket\&. +// If certificate was loaded from public file, the secret key will be +// undefined, and this certificate will not work successfully\&. +CZMQ_EXPORT void + zcert_apply (zcert_t *self, void *socket); + +// Return copy of certificate; if certificate is NULL or we exhausted +// heap memory, returns NULL\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT zcert_t * + zcert_dup (zcert_t *self); + +// Return true if two certificates have the same keys +CZMQ_EXPORT bool + zcert_eq (zcert_t *self, zcert_t *compare); + +// Print certificate contents to stdout +CZMQ_EXPORT void + zcert_print (zcert_t *self); + +// Self test of this class +CZMQ_EXPORT void + zcert_test (bool verbose); + +#ifdef CZMQ_BUILD_DRAFT_API +// *** Draft method, for development use, may change without warning *** +// Unset certificate metadata\&. +CZMQ_EXPORT void + zcert_unset_meta (zcert_t *self, const char *name); + +#endif // CZMQ_BUILD_DRAFT_API +Please add \*(Aq@interface\*(Aq section in \*(Aq\&./\&.\&./src/zcert\&.c\*(Aq\&. +.fi +.SH "DESCRIPTION" +.sp +The zcert class provides a way to create and work with security certificates for the ZMQ CURVE mechanism\&. A certificate contains a public + secret key pair, plus metadata\&. It can be used as a temporary object in memory, or persisted to disk\&. On disk, a certificate is stored as two files\&. One is public and contains only the public key\&. The second is secret and contains both keys\&. The two have the same filename, with the secret file adding "_secret"\&. To exchange certificates, send the public file via some secure route\&. Certificates are not signed but are text files that can be verified by eye\&. +.sp +Certificates are stored in the ZPL (ZMQ RFC 4) format\&. They have two sections, "metadata" and "curve"\&. The first contains a list of \fIname = value\fR pairs, one per line\&. Values may be enclosed in quotes\&. The curve section has a \fIpublic\-key = keyvalue\fR and, for secret certificates, a \fIsecret\-key = keyvalue\fR line\&. The keyvalue is a Z85\-encoded CURVE key\&. +.SH "EXAMPLE" +.PP +\fBFrom zcert_test method\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +// Create temporary directory for test files +# define TESTDIR "\&.test_zcert" +zsys_dir_create (TESTDIR); + +// Create a simple certificate with metadata +zcert_t *cert = zcert_new (); +assert (cert); +zcert_set_meta (cert, "email", "ph@imatix\&.com"); +zcert_set_meta (cert, "name", "Pieter Hintjens"); +zcert_set_meta (cert, "organization", "iMatix Corporation"); +zcert_set_meta (cert, "version", "%d", 1); +zcert_set_meta (cert, "delete_me", "now"); +zcert_unset_meta (cert, "delete_me"); +assert (streq (zcert_meta (cert, "email"), "ph@imatix\&.com")); +zlist_t *keys = zcert_meta_keys (cert); +assert (zlist_size (keys) == 4); +zlist_destroy (&keys); + +// Check the dup and eq methods +zcert_t *shadow = zcert_dup (cert); +assert (zcert_eq (cert, shadow)); +zcert_destroy (&shadow); + +// Check we can save and load certificate +zcert_save (cert, TESTDIR "/mycert\&.txt"); +assert (zsys_file_exists (TESTDIR "/mycert\&.txt")); +assert (zsys_file_exists (TESTDIR "/mycert\&.txt_secret")); + +// Load certificate, will in fact load secret one +shadow = zcert_load (TESTDIR "/mycert\&.txt"); +assert (shadow); +assert (zcert_eq (cert, shadow)); +zcert_destroy (&shadow); + +// Delete secret certificate, load public one +int rc = zsys_file_delete (TESTDIR "/mycert\&.txt_secret"); +assert (rc == 0); +shadow = zcert_load (TESTDIR "/mycert\&.txt"); + +// 32\-byte null key encodes as 40 \*(Aq0\*(Aq characters +assert (streq (zcert_secret_txt (shadow), FORTY_ZEROES)); + +zcert_destroy (&shadow); +zcert_destroy (&cert); + +// Delete all test files +zdir_t *dir = zdir_new (TESTDIR, NULL); +assert (dir); +zdir_remove (dir, true); +zdir_destroy (&dir); +.fi +.if n \{\ +.RE +.\} +.sp +.SH "AUTHORS" +.sp +The czmq manual was written by the authors in the AUTHORS file\&. +.SH "RESOURCES" +.sp +Main web site: \m[blue]\fB\%\fR\m[] +.sp +Report bugs to the email <\m[blue]\fBzeromq\-dev@lists\&.zeromq\&.org\fR\m[]\&\s-2\u[1]\d\s+2> +.SH "COPYRIGHT" +.sp +Copyright (c) the Contributors as noted in the AUTHORS file\&. This file is part of CZMQ, the high\-level C binding for 0MQ: http://czmq\&.zeromq\&.org\&. This Source Code Form is subject to the terms of the Mozilla Public License, v\&. 2\&.0\&. If a copy of the MPL was not distributed with this file, You can obtain one at http://mozilla\&.org/MPL/2\&.0/\&. LICENSE included with the czmq distribution\&. +.SH "NOTES" +.IP " 1." 4 +zeromq-dev@lists.zeromq.org +.RS 4 +\%mailto:zeromq-dev@lists.zeromq.org +.RE diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zcertstore.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zcertstore.3 new file mode 100644 index 00000000000000..5b76f253db8c1b --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zcertstore.3 @@ -0,0 +1,173 @@ +'\" t +.\" Title: zcertstore +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.76.1 +.\" Date: 12/31/2016 +.\" Manual: CZMQ Manual +.\" Source: CZMQ 4.0.2 +.\" Language: English +.\" +.TH "ZCERTSTORE" "3" "12/31/2016" "CZMQ 4\&.0\&.2" "CZMQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zcertstore \- work with CURVE security certificate stores +.SH "SYNOPSIS" +.sp +.nf +// This is a stable class, and may not change except for emergencies\&. It +// is provided in stable builds\&. +// This class has draft methods, which may change over time\&. They are not +// in stable releases, by default\&. Use \-\-enable\-drafts to enable\&. +// Create a new certificate store from a disk directory, loading and +// indexing all certificates in that location\&. The directory itself may be +// absent, and created later, or modified at any time\&. The certificate store +// is automatically refreshed on any zcertstore_lookup() call\&. If the +// location is specified as NULL, creates a pure\-memory store, which you +// can work with by inserting certificates at runtime\&. +CZMQ_EXPORT zcertstore_t * + zcertstore_new (const char *location); + +// Destroy a certificate store object in memory\&. Does not affect anything +// stored on disk\&. +CZMQ_EXPORT void + zcertstore_destroy (zcertstore_t **self_p); + +// Look up certificate by public key, returns zcert_t object if found, +// else returns NULL\&. The public key is provided in Z85 text format\&. +CZMQ_EXPORT zcert_t * + zcertstore_lookup (zcertstore_t *self, const char *public_key); + +// Insert certificate into certificate store in memory\&. Note that this +// does not save the certificate to disk\&. To do that, use zcert_save() +// directly on the certificate\&. Takes ownership of zcert_t object\&. +CZMQ_EXPORT void + zcertstore_insert (zcertstore_t *self, zcert_t **cert_p); + +// Print list of certificates in store to logging facility +CZMQ_EXPORT void + zcertstore_print (zcertstore_t *self); + +// Self test of this class +CZMQ_EXPORT void + zcertstore_test (bool verbose); + +#ifdef CZMQ_BUILD_DRAFT_API +// Loaders retrieve certificates from an arbitrary source\&. +typedef void (zcertstore_loader) ( + zcertstore_t *self); + +// Destructor for loader state\&. +typedef void (zcertstore_destructor) ( + void **self_p); + +// *** Draft method, for development use, may change without warning *** +// Override the default disk loader with a custom loader fn\&. +CZMQ_EXPORT void + zcertstore_set_loader (zcertstore_t *self, zcertstore_loader loader, zcertstore_destructor destructor, void *state); + +// *** Draft method, for development use, may change without warning *** +// Empty certificate hashtable\&. This wrapper exists to be friendly to bindings, +// which don\*(Aqt usually have access to struct internals\&. +CZMQ_EXPORT void + zcertstore_empty (zcertstore_t *self); + +#endif // CZMQ_BUILD_DRAFT_API +Please add \*(Aq@interface\*(Aq section in \*(Aq\&./\&.\&./src/zcertstore\&.c\*(Aq\&. +.fi +.SH "DESCRIPTION" +.sp +To authenticate new clients using the ZeroMQ CURVE security mechanism, we have to check that the client\(cqs public key matches a key we know and accept\&. There are numerous ways to store accepted client public keys\&. The mechanism CZMQ implements is "certificates" (plain text files) held in a "certificate store" (a disk directory)\&. This class works with such certificate stores, and lets you easily load them from disk, and check if a given client public key is known or not\&. The zcert class does the work of managing a single certificate\&. +.sp +The certificate store can be memory\-only, in which case you can load it yourself by inserting certificate objects one by one, or it can be loaded from disk, in which case you can add, modify, or remove certificates on disk at any time, and the store will detect such changes and refresh itself automatically\&. In most applications you won\(cqt use this class directly but through the zauth class, which provides a high\-level API for authentication (and manages certificate stores for you)\&. To actually create certificates on disk, use the zcert class in code, or the tools/zmakecert\&.c command line tool, or any text editor\&. The format of a certificate file is defined in the zcert man page\&. +.SH "EXAMPLE" +.PP +\fBFrom zcertstore_test method\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +// Create temporary directory for test files +# define TESTDIR "\&.test_zcertstore" +zsys_dir_create (TESTDIR); + +// Load certificate store from disk; it will be empty +zcertstore_t *certstore = zcertstore_new (TESTDIR); +assert (certstore); + +// Create a single new certificate and save to disk +zcert_t *cert = zcert_new (); +assert (cert); +char *client_key = strdup (zcert_public_txt (cert)); +assert (client_key); +zcert_set_meta (cert, "name", "John Doe"); +zcert_save (cert, TESTDIR "/mycert\&.txt"); +zcert_destroy (&cert); + +// Check that certificate store refreshes as expected +cert = zcertstore_lookup (certstore, client_key); +assert (cert); +assert (streq (zcert_meta (cert, "name"), "John Doe")); + +// Test custom loader +test_loader_state *state = (test_loader_state *) zmalloc (sizeof (test_loader_state)); +state\->index = 0; +zcertstore_set_loader (certstore, s_test_loader, s_test_destructor, (void *)state); +#if (ZMQ_VERSION_MAJOR >= 4) +cert = zcertstore_lookup (certstore, client_key); +assert (cert == NULL); +cert = zcertstore_lookup (certstore, "abcdefghijklmnopqrstuvwxyzabcdefghijklmn"); +assert (cert); +#endif + +free (client_key); + +if (verbose) + zcertstore_print (certstore); +zcertstore_destroy (&certstore); + +// Delete all test files +zdir_t *dir = zdir_new (TESTDIR, NULL); +assert (dir); +zdir_remove (dir, true); +zdir_destroy (&dir); +.fi +.if n \{\ +.RE +.\} +.sp +.SH "AUTHORS" +.sp +The czmq manual was written by the authors in the AUTHORS file\&. +.SH "RESOURCES" +.sp +Main web site: \m[blue]\fB\%\fR\m[] +.sp +Report bugs to the email <\m[blue]\fBzeromq\-dev@lists\&.zeromq\&.org\fR\m[]\&\s-2\u[1]\d\s+2> +.SH "COPYRIGHT" +.sp +Copyright (c) the Contributors as noted in the AUTHORS file\&. This file is part of CZMQ, the high\-level C binding for 0MQ: http://czmq\&.zeromq\&.org\&. This Source Code Form is subject to the terms of the Mozilla Public License, v\&. 2\&.0\&. If a copy of the MPL was not distributed with this file, You can obtain one at http://mozilla\&.org/MPL/2\&.0/\&. LICENSE included with the czmq distribution\&. +.SH "NOTES" +.IP " 1." 4 +zeromq-dev@lists.zeromq.org +.RS 4 +\%mailto:zeromq-dev@lists.zeromq.org +.RE diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zchunk.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zchunk.3 new file mode 100644 index 00000000000000..5b5d4378609b24 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zchunk.3 @@ -0,0 +1,266 @@ +'\" t +.\" Title: zchunk +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.76.1 +.\" Date: 12/31/2016 +.\" Manual: CZMQ Manual +.\" Source: CZMQ 4.0.2 +.\" Language: English +.\" +.TH "ZCHUNK" "3" "12/31/2016" "CZMQ 4\&.0\&.2" "CZMQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zchunk \- work with memory chunks +.SH "SYNOPSIS" +.sp +.nf +// This is a stable class, and may not change except for emergencies\&. It +// is provided in stable builds\&. +// Create a new chunk of the specified size\&. If you specify the data, it +// is copied into the chunk\&. If you do not specify the data, the chunk is +// allocated and left empty, and you can then add data using zchunk_append\&. +CZMQ_EXPORT zchunk_t * + zchunk_new (const void *data, size_t size); + +// Destroy a chunk +CZMQ_EXPORT void + zchunk_destroy (zchunk_t **self_p); + +// Resizes chunk max_size as requested; chunk_cur size is set to zero +CZMQ_EXPORT void + zchunk_resize (zchunk_t *self, size_t size); + +// Return chunk cur size +CZMQ_EXPORT size_t + zchunk_size (zchunk_t *self); + +// Return chunk max size +CZMQ_EXPORT size_t + zchunk_max_size (zchunk_t *self); + +// Return chunk data +CZMQ_EXPORT byte * + zchunk_data (zchunk_t *self); + +// Set chunk data from user\-supplied data; truncate if too large\&. Data may +// be null\&. Returns actual size of chunk +CZMQ_EXPORT size_t + zchunk_set (zchunk_t *self, const void *data, size_t size); + +// Fill chunk data from user\-supplied octet +CZMQ_EXPORT size_t + zchunk_fill (zchunk_t *self, byte filler, size_t size); + +// Append user\-supplied data to chunk, return resulting chunk size\&. If the +// data would exceeded the available space, it is truncated\&. If you want to +// grow the chunk to accommodate new data, use the zchunk_extend method\&. +CZMQ_EXPORT size_t + zchunk_append (zchunk_t *self, const void *data, size_t size); + +// Append user\-supplied data to chunk, return resulting chunk size\&. If the +// data would exceeded the available space, the chunk grows in size\&. +CZMQ_EXPORT size_t + zchunk_extend (zchunk_t *self, const void *data, size_t size); + +// Copy as much data from \*(Aqsource\*(Aq into the chunk as possible; returns the +// new size of chunk\&. If all data from \*(Aqsource\*(Aq is used, returns exhausted +// on the source chunk\&. Source can be consumed as many times as needed until +// it is exhausted\&. If source was already exhausted, does not change chunk\&. +CZMQ_EXPORT size_t + zchunk_consume (zchunk_t *self, zchunk_t *source); + +// Returns true if the chunk was exhausted by consume methods, or if the +// chunk has a size of zero\&. +CZMQ_EXPORT bool + zchunk_exhausted (zchunk_t *self); + +// Read chunk from an open file descriptor +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT zchunk_t * + zchunk_read (FILE *handle, size_t bytes); + +// Write chunk to an open file descriptor +CZMQ_EXPORT int + zchunk_write (zchunk_t *self, FILE *handle); + +// Try to slurp an entire file into a chunk\&. Will read up to maxsize of +// the file\&. If maxsize is 0, will attempt to read the entire file and +// fail with an assertion if that cannot fit into memory\&. Returns a new +// chunk containing the file data, or NULL if the file could not be read\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT zchunk_t * + zchunk_slurp (const char *filename, size_t maxsize); + +// Create copy of chunk, as new chunk object\&. Returns a fresh zchunk_t +// object, or null if there was not enough heap memory\&. If chunk is null, +// returns null\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT zchunk_t * + zchunk_dup (zchunk_t *self); + +// Return chunk data encoded as printable hex string\&. Caller must free +// string when finished with it\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT char * + zchunk_strhex (zchunk_t *self); + +// Return chunk data copied into freshly allocated string +// Caller must free string when finished with it\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT char * + zchunk_strdup (zchunk_t *self); + +// Return TRUE if chunk body is equal to string, excluding terminator +CZMQ_EXPORT bool + zchunk_streq (zchunk_t *self, const char *string); + +// Transform zchunk into a zframe that can be sent in a message\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT zframe_t * + zchunk_pack (zchunk_t *self); + +// Transform a zframe into a zchunk\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT zchunk_t * + zchunk_unpack (zframe_t *frame); + +// Calculate SHA1 digest for chunk, using zdigest class\&. +CZMQ_EXPORT const char * + zchunk_digest (zchunk_t *self); + +// Dump chunk to FILE stream, for debugging and tracing\&. +CZMQ_EXPORT void + zchunk_fprint (zchunk_t *self, FILE *file); + +// Dump message to stderr, for debugging and tracing\&. +// See zchunk_fprint for details +CZMQ_EXPORT void + zchunk_print (zchunk_t *self); + +// Probe the supplied object, and report if it looks like a zchunk_t\&. +CZMQ_EXPORT bool + zchunk_is (void *self); + +// Self test of this class\&. +CZMQ_EXPORT void + zchunk_test (bool verbose); + +Please add \*(Aq@interface\*(Aq section in \*(Aq\&./\&.\&./src/zchunk\&.c\*(Aq\&. +.fi +.SH "DESCRIPTION" +.sp +The zchunk class works with variable sized blobs\&. Not as efficient as ZeroMQ\(cqs messages but they do less weirdness and so are easier to understand\&. The chunk class has methods to read and write chunks from disk\&. +.sp +Please add \fI@discuss\fR section in \fI\&./\&.\&./src/zchunk\&.c\fR\&. +.SH "EXAMPLE" +.PP +\fBFrom zchunk_test method\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +zchunk_t *chunk = zchunk_new ("1234567890", 10); +assert (chunk); +assert (zchunk_size (chunk) == 10); +assert (memcmp (zchunk_data (chunk), "1234567890", 10) == 0); +zchunk_destroy (&chunk); + +chunk = zchunk_new (NULL, 10); +assert (chunk); +zchunk_append (chunk, "12345678", 8); +zchunk_append (chunk, "90ABCDEF", 8); +zchunk_append (chunk, "GHIJKLMN", 8); +assert (memcmp (zchunk_data (chunk), "1234567890", 10) == 0); +assert (zchunk_size (chunk) == 10); +assert (zchunk_streq (chunk, "1234567890")); +assert (streq (zchunk_digest (chunk), "01B307ACBA4F54F55AAFC33BB06BBBF6CA803E9A")); +char *string = zchunk_strdup (chunk); +assert (streq (string, "1234567890")); +free (string); +string = zchunk_strhex (chunk); +assert (streq (string, "31323334353637383930")); +free (string); + +zframe_t *frame = zchunk_pack (chunk); +assert (frame); + +zchunk_t *chunk2 = zchunk_unpack (frame); +assert (chunk2); +assert (memcmp (zchunk_data (chunk2), "1234567890", 10) == 0); +zframe_destroy (&frame); +zchunk_destroy (&chunk2); + +zchunk_t *copy = zchunk_dup (chunk); +assert (copy); +assert (memcmp (zchunk_data (copy), "1234567890", 10) == 0); +assert (zchunk_size (copy) == 10); +zchunk_destroy (©); +zchunk_destroy (&chunk); + +chunk = zchunk_new (NULL, 0); +zchunk_extend (chunk, "12345678", 8); +zchunk_extend (chunk, "90ABCDEF", 8); +zchunk_extend (chunk, "GHIJKLMN", 8); +assert (zchunk_size (chunk) == 24); +assert (zchunk_streq (chunk, "1234567890ABCDEFGHIJKLMN")); +zchunk_destroy (&chunk); + +copy = zchunk_new ("1234567890abcdefghij", 20); +assert (copy); +chunk = zchunk_new (NULL, 8); +assert (chunk); +zchunk_consume (chunk, copy); +assert (!zchunk_exhausted (copy)); +assert (memcmp (zchunk_data (chunk), "12345678", 8) == 0); +zchunk_set (chunk, NULL, 0); +zchunk_consume (chunk, copy); +assert (!zchunk_exhausted (copy)); +assert (memcmp (zchunk_data (chunk), "90abcdef", 8) == 0); +zchunk_set (chunk, NULL, 0); +zchunk_consume (chunk, copy); +assert (zchunk_exhausted (copy)); +assert (zchunk_size (chunk) == 4); +assert (memcmp (zchunk_data (chunk), "ghij", 4) == 0); +zchunk_destroy (©); +zchunk_destroy (&chunk); +.fi +.if n \{\ +.RE +.\} +.sp +.SH "AUTHORS" +.sp +The czmq manual was written by the authors in the AUTHORS file\&. +.SH "RESOURCES" +.sp +Main web site: \m[blue]\fB\%\fR\m[] +.sp +Report bugs to the email <\m[blue]\fBzeromq\-dev@lists\&.zeromq\&.org\fR\m[]\&\s-2\u[1]\d\s+2> +.SH "COPYRIGHT" +.sp +Copyright (c) the Contributors as noted in the AUTHORS file\&. This file is part of CZMQ, the high\-level C binding for 0MQ: http://czmq\&.zeromq\&.org\&. This Source Code Form is subject to the terms of the Mozilla Public License, v\&. 2\&.0\&. If a copy of the MPL was not distributed with this file, You can obtain one at http://mozilla\&.org/MPL/2\&.0/\&. LICENSE included with the czmq distribution\&. +.SH "NOTES" +.IP " 1." 4 +zeromq-dev@lists.zeromq.org +.RS 4 +\%mailto:zeromq-dev@lists.zeromq.org +.RE diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zclock.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zclock.3 new file mode 100644 index 00000000000000..10691d17aa7e0d --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zclock.3 @@ -0,0 +1,116 @@ +'\" t +.\" Title: zclock +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.76.1 +.\" Date: 12/31/2016 +.\" Manual: CZMQ Manual +.\" Source: CZMQ 4.0.2 +.\" Language: English +.\" +.TH "ZCLOCK" "3" "12/31/2016" "CZMQ 4\&.0\&.2" "CZMQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zclock \- millisecond clocks and delays +.SH "SYNOPSIS" +.sp +.nf +// This is a stable class, and may not change except for emergencies\&. It +// is provided in stable builds\&. +// Sleep for a number of milliseconds +CZMQ_EXPORT void + zclock_sleep (int msecs); + +// Return current system clock as milliseconds\&. Note that this clock can +// jump backwards (if the system clock is changed) so is unsafe to use for +// timers and time offsets\&. Use zclock_mono for that instead\&. +CZMQ_EXPORT int64_t + zclock_time (void); + +// Return current monotonic clock in milliseconds\&. Use this when you compute +// time offsets\&. The monotonic clock is not affected by system changes and +// so will never be reset backwards, unlike a system clock\&. +CZMQ_EXPORT int64_t + zclock_mono (void); + +// Return current monotonic clock in microseconds\&. Use this when you compute +// time offsets\&. The monotonic clock is not affected by system changes and +// so will never be reset backwards, unlike a system clock\&. +CZMQ_EXPORT int64_t + zclock_usecs (void); + +// Return formatted date/time as fresh string\&. Free using zstr_free()\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT char * + zclock_timestr (void); + +// Self test of this class\&. +CZMQ_EXPORT void + zclock_test (bool verbose); + +Please add \*(Aq@interface\*(Aq section in \*(Aq\&./\&.\&./src/zclock\&.c\*(Aq\&. +.fi +.SH "DESCRIPTION" +.sp +The zclock class provides essential sleep and system time functions, used to slow down threads for testing, and calculate timers for polling\&. Wraps the non\-portable system calls in a simple portable API\&. +.sp +The Win32 Sleep() call defaults to 16ms resolution unless the system timer resolution is increased with a call to timeBeginPeriod() permitting 1ms granularity\&. +.SH "EXAMPLE" +.PP +\fBFrom zclock_test method\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +int64_t start = zclock_time (); +zclock_sleep (10); +assert ((zclock_time () \- start) >= 10); +start = zclock_mono (); +int64_t usecs = zclock_usecs (); +zclock_sleep (10); +assert ((zclock_mono () \- start) >= 10); +assert ((zclock_usecs () \- usecs) >= 10000); +char *timestr = zclock_timestr (); +if (verbose) + puts (timestr); +free (timestr); +.fi +.if n \{\ +.RE +.\} +.sp +.SH "AUTHORS" +.sp +The czmq manual was written by the authors in the AUTHORS file\&. +.SH "RESOURCES" +.sp +Main web site: \m[blue]\fB\%\fR\m[] +.sp +Report bugs to the email <\m[blue]\fBzeromq\-dev@lists\&.zeromq\&.org\fR\m[]\&\s-2\u[1]\d\s+2> +.SH "COPYRIGHT" +.sp +Copyright (c) the Contributors as noted in the AUTHORS file\&. This file is part of CZMQ, the high\-level C binding for 0MQ: http://czmq\&.zeromq\&.org\&. This Source Code Form is subject to the terms of the Mozilla Public License, v\&. 2\&.0\&. If a copy of the MPL was not distributed with this file, You can obtain one at http://mozilla\&.org/MPL/2\&.0/\&. LICENSE included with the czmq distribution\&. +.SH "NOTES" +.IP " 1." 4 +zeromq-dev@lists.zeromq.org +.RS 4 +\%mailto:zeromq-dev@lists.zeromq.org +.RE diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zconfig.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zconfig.3 new file mode 100644 index 00000000000000..5cd00c97073ed0 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zconfig.3 @@ -0,0 +1,342 @@ +'\" t +.\" Title: zconfig +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.76.1 +.\" Date: 12/31/2016 +.\" Manual: CZMQ Manual +.\" Source: CZMQ 4.0.2 +.\" Language: English +.\" +.TH "ZCONFIG" "3" "12/31/2016" "CZMQ 4\&.0\&.2" "CZMQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zconfig \- work with config files written in rfc\&.zeromq\&.org/spec:4/ZPL\&. +.SH "SYNOPSIS" +.sp +.nf +// This is a stable class, and may not change except for emergencies\&. It +// is provided in stable builds\&. +// +typedef int (zconfig_fct) ( + zconfig_t *self, void *arg, int level); + +// Create new config item +CZMQ_EXPORT zconfig_t * + zconfig_new (const char *name, zconfig_t *parent); + +// Load a config tree from a specified ZPL text file; returns a zconfig_t +// reference for the root, if the file exists and is readable\&. Returns NULL +// if the file does not exist\&. +CZMQ_EXPORT zconfig_t * + zconfig_load (const char *filename); + +// Equivalent to zconfig_load, taking a format string instead of a fixed +// filename\&. +CZMQ_EXPORT zconfig_t * + zconfig_loadf (const char *format, \&.\&.\&.) CHECK_PRINTF (1); + +// Destroy a config item and all its children +CZMQ_EXPORT void + zconfig_destroy (zconfig_t **self_p); + +// Return name of config item +CZMQ_EXPORT char * + zconfig_name (zconfig_t *self); + +// Return value of config item +CZMQ_EXPORT char * + zconfig_value (zconfig_t *self); + +// Insert or update configuration key with value +CZMQ_EXPORT void + zconfig_put (zconfig_t *self, const char *path, const char *value); + +// Equivalent to zconfig_put, accepting a format specifier and variable +// argument list, instead of a single string value\&. +CZMQ_EXPORT void + zconfig_putf (zconfig_t *self, const char *path, const char *format, \&.\&.\&.) CHECK_PRINTF (3); + +// Get value for config item into a string value; leading slash is optional +// and ignored\&. +CZMQ_EXPORT char * + zconfig_get (zconfig_t *self, const char *path, const char *default_value); + +// Set config item name, name may be NULL +CZMQ_EXPORT void + zconfig_set_name (zconfig_t *self, const char *name); + +// Set new value for config item\&. The new value may be a string, a printf +// format, or NULL\&. Note that if string may possibly contain \*(Aq%\*(Aq, or if it +// comes from an insecure source, you must use \*(Aq%s\*(Aq as the format, followed +// by the string\&. +CZMQ_EXPORT void + zconfig_set_value (zconfig_t *self, const char *format, \&.\&.\&.) CHECK_PRINTF (2); + +// Find our first child, if any +CZMQ_EXPORT zconfig_t * + zconfig_child (zconfig_t *self); + +// Find our first sibling, if any +CZMQ_EXPORT zconfig_t * + zconfig_next (zconfig_t *self); + +// Find a config item along a path; leading slash is optional and ignored\&. +CZMQ_EXPORT zconfig_t * + zconfig_locate (zconfig_t *self, const char *path); + +// Locate the last config item at a specified depth +CZMQ_EXPORT zconfig_t * + zconfig_at_depth (zconfig_t *self, int level); + +// Execute a callback for each config item in the tree; returns zero if +// successful, else \-1\&. +CZMQ_EXPORT int + zconfig_execute (zconfig_t *self, zconfig_fct handler, void *arg); + +// Add comment to config item before saving to disk\&. You can add as many +// comment lines as you like\&. If you use a null format, all comments are +// deleted\&. +CZMQ_EXPORT void + zconfig_set_comment (zconfig_t *self, const char *format, \&.\&.\&.) CHECK_PRINTF (2); + +// Return comments of config item, as zlist\&. +CZMQ_EXPORT zlist_t * + zconfig_comments (zconfig_t *self); + +// Save a config tree to a specified ZPL text file, where a filename +// "\-" means dump to standard output\&. +CZMQ_EXPORT int + zconfig_save (zconfig_t *self, const char *filename); + +// Equivalent to zconfig_save, taking a format string instead of a fixed +// filename\&. +CZMQ_EXPORT int + zconfig_savef (zconfig_t *self, const char *format, \&.\&.\&.) CHECK_PRINTF (2); + +// Report filename used during zconfig_load, or NULL if none +CZMQ_EXPORT const char * + zconfig_filename (zconfig_t *self); + +// Reload config tree from same file that it was previously loaded from\&. +// Returns 0 if OK, \-1 if there was an error (and then does not change +// existing data)\&. +CZMQ_EXPORT int + zconfig_reload (zconfig_t **self_p); + +// Load a config tree from a memory chunk +CZMQ_EXPORT zconfig_t * + zconfig_chunk_load (zchunk_t *chunk); + +// Save a config tree to a new memory chunk +CZMQ_EXPORT zchunk_t * + zconfig_chunk_save (zconfig_t *self); + +// Load a config tree from a null\-terminated string +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT zconfig_t * + zconfig_str_load (const char *string); + +// Save a config tree to a new null terminated string +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT char * + zconfig_str_save (zconfig_t *self); + +// Return true if a configuration tree was loaded from a file and that +// file has changed in since the tree was loaded\&. +CZMQ_EXPORT bool + zconfig_has_changed (zconfig_t *self); + +// Print the config file to open stream +CZMQ_EXPORT void + zconfig_fprint (zconfig_t *self, FILE *file); + +// Print properties of object +CZMQ_EXPORT void + zconfig_print (zconfig_t *self); + +// Self test of this class +CZMQ_EXPORT void + zconfig_test (bool verbose); + +Please add \*(Aq@interface\*(Aq section in \*(Aq\&./\&.\&./src/zconfig\&.c\*(Aq\&. +.fi +.SH "DESCRIPTION" +.sp +Lets applications load, work with, and save configuration files\&. This implements rfc\&.zeromq\&.org/spec:4/ZPL, which is a simple structured text format for configuration files\&. +.sp +Here is an example ZPL stream and corresponding config structure: +.sp +.if n \{\ +.RS 4 +.\} +.nf +context + iothreads = 1 + verbose = 1 # Ask for a trace +main + type = zqueue # ZMQ_DEVICE type + frontend + option + hwm = 1000 + swap = 25000000 # 25MB + bind = \*(Aqinproc://addr1\*(Aq + bind = \*(Aqipc://addr2\*(Aq + backend + bind = inproc://addr3 +.fi +.if n \{\ +.RE +.\} +.sp +.if n \{\ +.RS 4 +.\} +.nf +root Down = child +| Across = next +v +context\-\->main +| | +| v +| type=queue\-\->frontend\-\->backend +| | | +| | v +| | bind=inproc://addr3 +| v +| option\-\->bind=inproc://addr1\-\->bind=ipc://addr2 +| | +| v +| hwm=1000\-\->swap=25000000 +v +iothreads=1\-\->verbose=false +.fi +.if n \{\ +.RE +.\} +.SH "EXAMPLE" +.PP +\fBFrom zconfig_test method\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +// Create temporary directory for test files +# define TESTDIR "\&.test_zconfig" +zsys_dir_create (TESTDIR); + +zconfig_t *root = zconfig_new ("root", NULL); +assert (root); +zconfig_t *section, *item; + +section = zconfig_new ("headers", root); +assert (section); +item = zconfig_new ("email", section); +assert (item); +zconfig_set_value (item, "some@random\&.com"); +item = zconfig_new ("name", section); +assert (item); +zconfig_set_value (item, "Justin Kayce"); +zconfig_putf (root, "/curve/secret\-key", "%s", "Top Secret"); +zconfig_set_comment (root, " CURVE certificate"); +zconfig_set_comment (root, " \-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-"); +assert (zconfig_comments (root)); +zconfig_save (root, TESTDIR "/test\&.cfg"); +zconfig_destroy (&root); +root = zconfig_load (TESTDIR "/test\&.cfg"); +if (verbose) + zconfig_save (root, "\-"); +assert (streq (zconfig_filename (root), TESTDIR "/test\&.cfg")); + +char *email = zconfig_get (root, "/headers/email", NULL); +assert (email); +assert (streq (email, "some@random\&.com")); +char *passwd = zconfig_get (root, "/curve/secret\-key", NULL); +assert (passwd); +assert (streq (passwd, "Top Secret")); + +zconfig_savef (root, "%s/%s", TESTDIR, "test\&.cfg"); +assert (!zconfig_has_changed (root)); +int rc = zconfig_reload (&root); +assert (rc == 0); +assert (!zconfig_has_changed (root)); +zconfig_destroy (&root); + +// Test chunk load/save +root = zconfig_new ("root", NULL); +assert (root); +section = zconfig_new ("section", root); +assert (section); +item = zconfig_new ("value", section); +assert (item); +zconfig_set_value (item, "somevalue"); +zconfig_t *search = zconfig_locate (root, "section/value"); +assert (search == item); +zchunk_t *chunk = zconfig_chunk_save (root); +assert (strlen ((char *) zchunk_data (chunk)) == 32); +char *string = zconfig_str_save (root); +assert (string); +assert (streq (string, (char *) zchunk_data (chunk))); +free (string); +assert (chunk); +zconfig_destroy (&root); + +root = zconfig_chunk_load (chunk); +assert (root); +char *value = zconfig_get (root, "/section/value", NULL); +assert (value); +assert (streq (value, "somevalue")); + +// Test config can\*(Aqt be saved to a file in a path that doesn\*(Aqt +// exist or isn\*(Aqt writable +rc = zconfig_savef (root, "%s/path/that/doesnt/exist/%s", TESTDIR, "test\&.cfg"); +assert (rc == \-1); + +zconfig_destroy (&root); +zchunk_destroy (&chunk); + +// Delete all test files +zdir_t *dir = zdir_new (TESTDIR, NULL); +assert (dir); +zdir_remove (dir, true); +zdir_destroy (&dir); +.fi +.if n \{\ +.RE +.\} +.sp +.SH "AUTHORS" +.sp +The czmq manual was written by the authors in the AUTHORS file\&. +.SH "RESOURCES" +.sp +Main web site: \m[blue]\fB\%\fR\m[] +.sp +Report bugs to the email <\m[blue]\fBzeromq\-dev@lists\&.zeromq\&.org\fR\m[]\&\s-2\u[1]\d\s+2> +.SH "COPYRIGHT" +.sp +Copyright (c) the Contributors as noted in the AUTHORS file\&. This file is part of CZMQ, the high\-level C binding for 0MQ: http://czmq\&.zeromq\&.org\&. This Source Code Form is subject to the terms of the Mozilla Public License, v\&. 2\&.0\&. If a copy of the MPL was not distributed with this file, You can obtain one at http://mozilla\&.org/MPL/2\&.0/\&. LICENSE included with the czmq distribution\&. +.SH "NOTES" +.IP " 1." 4 +zeromq-dev@lists.zeromq.org +.RS 4 +\%mailto:zeromq-dev@lists.zeromq.org +.RE diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zdigest.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zdigest.3 new file mode 100644 index 00000000000000..cabae72d053426 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zdigest.3 @@ -0,0 +1,120 @@ +'\" t +.\" Title: zdigest +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.76.1 +.\" Date: 12/31/2016 +.\" Manual: CZMQ Manual +.\" Source: CZMQ 4.0.2 +.\" Language: English +.\" +.TH "ZDIGEST" "3" "12/31/2016" "CZMQ 4\&.0\&.2" "CZMQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zdigest \- provides hashing functions (SHA\-1 at present) +.SH "SYNOPSIS" +.sp +.nf +// This is a stable class, and may not change except for emergencies\&. It +// is provided in stable builds\&. +// Constructor \- creates new digest object, which you use to build up a +// digest by repeatedly calling zdigest_update() on chunks of data\&. +CZMQ_EXPORT zdigest_t * + zdigest_new (void); + +// Destroy a digest object +CZMQ_EXPORT void + zdigest_destroy (zdigest_t **self_p); + +// Add buffer into digest calculation +CZMQ_EXPORT void + zdigest_update (zdigest_t *self, const byte *buffer, size_t length); + +// Return final digest hash data\&. If built without crypto support, +// returns NULL\&. +CZMQ_EXPORT const byte * + zdigest_data (zdigest_t *self); + +// Return final digest hash size +CZMQ_EXPORT size_t + zdigest_size (zdigest_t *self); + +// Return digest as printable hex string; caller should not modify nor +// free this string\&. After calling this, you may not use zdigest_update() +// on the same digest\&. If built without crypto support, returns NULL\&. +CZMQ_EXPORT char * + zdigest_string (zdigest_t *self); + +// Self test of this class\&. +CZMQ_EXPORT void + zdigest_test (bool verbose); + +Please add \*(Aq@interface\*(Aq section in \*(Aq\&./\&.\&./src/zdigest\&.c\*(Aq\&. +.fi +.SH "DESCRIPTION" +.sp +The zdigest class generates a hash from zchunks of data\&. The current algorithm is SHA\-1, chosen for speed\&. We are aiming to generate a unique digest for a file, and there are no security issues in this use case\&. +.sp +The current code depends on OpenSSL, which might be replaced by hard coded SHA\-1 implementation to reduce build dependencies\&. +.SH "EXAMPLE" +.PP +\fBFrom zdigest_test method\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +byte *buffer = (byte *) zmalloc (1024); +memset (buffer, 0xAA, 1024); + +zdigest_t *digest = zdigest_new (); +assert (digest); +zdigest_update (digest, buffer, 1024); +const byte *data = zdigest_data (digest); +assert (data [0] == 0xDE); +assert (data [1] == 0xB2); +assert (data [2] == 0x38); +assert (data [3] == 0x07); +assert (streq (zdigest_string (digest), + "DEB23807D4FE025E900FE9A9C7D8410C3DDE9671")); +zdigest_destroy (&digest); +free (buffer); +.fi +.if n \{\ +.RE +.\} +.sp +.SH "AUTHORS" +.sp +The czmq manual was written by the authors in the AUTHORS file\&. +.SH "RESOURCES" +.sp +Main web site: \m[blue]\fB\%\fR\m[] +.sp +Report bugs to the email <\m[blue]\fBzeromq\-dev@lists\&.zeromq\&.org\fR\m[]\&\s-2\u[1]\d\s+2> +.SH "COPYRIGHT" +.sp +Copyright (c) the Contributors as noted in the AUTHORS file\&. This file is part of CZMQ, the high\-level C binding for 0MQ: http://czmq\&.zeromq\&.org\&. This Source Code Form is subject to the terms of the Mozilla Public License, v\&. 2\&.0\&. If a copy of the MPL was not distributed with this file, You can obtain one at http://mozilla\&.org/MPL/2\&.0/\&. LICENSE included with the czmq distribution\&. +.SH "NOTES" +.IP " 1." 4 +zeromq-dev@lists.zeromq.org +.RS 4 +\%mailto:zeromq-dev@lists.zeromq.org +.RE diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zdir.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zdir.3 new file mode 100644 index 00000000000000..04cbc80542e838 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zdir.3 @@ -0,0 +1,287 @@ +'\" t +.\" Title: zdir +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.76.1 +.\" Date: 12/31/2016 +.\" Manual: CZMQ Manual +.\" Source: CZMQ 4.0.2 +.\" Language: English +.\" +.TH "ZDIR" "3" "12/31/2016" "CZMQ 4\&.0\&.2" "CZMQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zdir \- work with file\-system directories +.SH "SYNOPSIS" +.sp +.nf +// This is a stable class, and may not change except for emergencies\&. It +// is provided in stable builds\&. +// Create a new directory item that loads in the full tree of the specified +// path, optionally located under some parent path\&. If parent is "\-", then +// loads only the top\-level directory, and does not use parent as a path\&. +CZMQ_EXPORT zdir_t * + zdir_new (const char *path, const char *parent); + +// Destroy a directory tree and all children it contains\&. +CZMQ_EXPORT void + zdir_destroy (zdir_t **self_p); + +// Return directory path +CZMQ_EXPORT const char * + zdir_path (zdir_t *self); + +// Return last modification time for directory\&. +CZMQ_EXPORT time_t + zdir_modified (zdir_t *self); + +// Return total hierarchy size, in bytes of data contained in all files +// in the directory tree\&. +CZMQ_EXPORT off_t + zdir_cursize (zdir_t *self); + +// Return directory count +CZMQ_EXPORT size_t + zdir_count (zdir_t *self); + +// Returns a sorted list of zfile objects; Each entry in the list is a pointer +// to a zfile_t item already allocated in the zdir tree\&. Do not destroy the +// original zdir tree until you are done with this list\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT zlist_t * + zdir_list (zdir_t *self); + +// Remove directory, optionally including all files that it contains, at +// all levels\&. If force is false, will only remove the directory if empty\&. +// If force is true, will remove all files and all subdirectories\&. +CZMQ_EXPORT void + zdir_remove (zdir_t *self, bool force); + +// Calculate differences between two versions of a directory tree\&. +// Returns a list of zdir_patch_t patches\&. Either older or newer may +// be null, indicating the directory is empty/absent\&. If alias is set, +// generates virtual filename (minus path, plus alias)\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT zlist_t * + zdir_diff (zdir_t *older, zdir_t *newer, const char *alias); + +// Return full contents of directory as a zdir_patch list\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT zlist_t * + zdir_resync (zdir_t *self, const char *alias); + +// Load directory cache; returns a hash table containing the SHA\-1 digests +// of every file in the tree\&. The cache is saved between runs in \&.cache\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT zhash_t * + zdir_cache (zdir_t *self); + +// Print contents of directory to open stream +CZMQ_EXPORT void + zdir_fprint (zdir_t *self, FILE *file, int indent); + +// Print contents of directory to stdout +CZMQ_EXPORT void + zdir_print (zdir_t *self, int indent); + +// Create a new zdir_watch actor instance: +// +// zactor_t *watch = zactor_new (zdir_watch, NULL); +// +// Destroy zdir_watch instance: +// +// zactor_destroy (&watch); +// +// Enable verbose logging of commands and activity: +// +// zstr_send (watch, "VERBOSE"); +// +// Subscribe to changes to a directory path: +// +// zsock_send (watch, "ss", "SUBSCRIBE", "directory_path"); +// +// Unsubscribe from changes to a directory path: +// +// zsock_send (watch, "ss", "UNSUBSCRIBE", "directory_path"); +// +// Receive directory changes: +// zsock_recv (watch, "sp", &path, &patches); +// +// // Delete the received data\&. +// free (path); +// zlist_destroy (&patches); +CZMQ_EXPORT void + zdir_watch (zsock_t *pipe, void *unused); + +// Self test of this class\&. +CZMQ_EXPORT void + zdir_test (bool verbose); + +Please add \*(Aq@interface\*(Aq section in \*(Aq\&./\&.\&./src/zdir\&.c\*(Aq\&. +.fi +.SH "DESCRIPTION" +.sp +The zdir class gives access to the file system index\&. It will load a directory tree (a directory plus all child directories) into a zdir structure and then let you navigate that structure\&. It exists mainly to wrap non\-portable OS functions to do this\&. +.sp +Please add \fI@discuss\fR section in \fI\&./\&.\&./src/zdir\&.c\fR\&. +.SH "EXAMPLE" +.PP +\fBFrom zdir_test method\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +// need to create a file in the test directory we\*(Aqre watching +// in order to ensure the directory exists +zfile_t *initfile = zfile_new ("\&./zdir\-test\-dir", "initial_file"); +assert (initfile); +zfile_output (initfile); +fprintf (zfile_handle (initfile), "initial file\en"); +zfile_close (initfile); +zfile_destroy (&initfile); + +zdir_t *older = zdir_new ("zdir\-test\-dir", NULL); +assert (older); +if (verbose) { + printf ("\en"); + zdir_dump (older, 0); +} +zdir_t *newer = zdir_new ("\&.", NULL); +assert (newer); +zlist_t *patches = zdir_diff (older, newer, "/"); +assert (patches); +while (zlist_size (patches)) { + zdir_patch_t *patch = (zdir_patch_t *) zlist_pop (patches); + zdir_patch_destroy (&patch); +} +zlist_destroy (&patches); +zdir_destroy (&older); +zdir_destroy (&newer); + +zdir_t *nosuch = zdir_new ("does\-not\-exist", NULL); +assert (nosuch == NULL); + +// zdir_watch test: +zactor_t *watch = zactor_new (zdir_watch, NULL); +assert (watch); + +if (verbose) { + zsock_send (watch, "s", "VERBOSE"); + assert (zsock_wait (watch) == 0); +} + +zclock_sleep (1001); // wait for initial file to become \*(Aqstable\*(Aq + +zsock_send (watch, "si", "TIMEOUT", 100); +assert (zsock_wait (watch) == 0); + +zsock_send (watch, "ss", "SUBSCRIBE", "zdir\-test\-dir"); +assert (zsock_wait (watch) == 0); + +zsock_send (watch, "ss", "UNSUBSCRIBE", "zdir\-test\-dir"); +assert (zsock_wait (watch) == 0); + +zsock_send (watch, "ss", "SUBSCRIBE", "zdir\-test\-dir"); +assert (zsock_wait (watch) == 0); + +zfile_t *newfile = zfile_new ("zdir\-test\-dir", "test_abc"); +zfile_output (newfile); +fprintf (zfile_handle (newfile), "test file\en"); +zfile_close (newfile); + +zpoller_t *watch_poll = zpoller_new (watch, NULL); + +// poll for a certain timeout before giving up and failing the test\&. +assert (zpoller_wait (watch_poll, 1001) == watch); + +// wait for notification of the file being added +char *path; +int rc = zsock_recv (watch, "sp", &path, &patches); +assert (rc == 0); + +assert (streq (path, "zdir\-test\-dir")); +free (path); + +assert (zlist_size (patches) == 1); + +zdir_patch_t *patch = (zdir_patch_t *) zlist_pop (patches); +assert (streq (zdir_patch_path (patch), "zdir\-test\-dir")); + +zfile_t *patch_file = zdir_patch_file (patch); +assert (streq (zfile_filename (patch_file, ""), "zdir\-test\-dir/test_abc")); + +zdir_patch_destroy (&patch); +zlist_destroy (&patches); + +// remove the file +zfile_remove (newfile); +zfile_destroy (&newfile); + +// poll for a certain timeout before giving up and failing the test\&. +assert (zpoller_wait (watch_poll, 1001) == watch); + +// wait for notification of the file being removed +rc = zsock_recv (watch, "sp", &path, &patches); +assert (rc == 0); + +assert (streq (path, "zdir\-test\-dir")); +free (path); + +assert (zlist_size (patches) == 1); + +patch = (zdir_patch_t *) zlist_pop (patches); +assert (streq (zdir_patch_path (patch), "zdir\-test\-dir")); + +patch_file = zdir_patch_file (patch); +assert (streq (zfile_filename (patch_file, ""), "zdir\-test\-dir/test_abc")); + +zdir_patch_destroy (&patch); +zlist_destroy (&patches); + +zpoller_destroy (&watch_poll); +zactor_destroy (&watch); + +// clean up by removing the test directory\&. +zdir_t *testdir = zdir_new ("zdir\-test\-dir", NULL); +zdir_remove (testdir, true); +zdir_destroy (&testdir); +.fi +.if n \{\ +.RE +.\} +.sp +.SH "AUTHORS" +.sp +The czmq manual was written by the authors in the AUTHORS file\&. +.SH "RESOURCES" +.sp +Main web site: \m[blue]\fB\%\fR\m[] +.sp +Report bugs to the email <\m[blue]\fBzeromq\-dev@lists\&.zeromq\&.org\fR\m[]\&\s-2\u[1]\d\s+2> +.SH "COPYRIGHT" +.sp +Copyright (c) the Contributors as noted in the AUTHORS file\&. This file is part of CZMQ, the high\-level C binding for 0MQ: http://czmq\&.zeromq\&.org\&. This Source Code Form is subject to the terms of the Mozilla Public License, v\&. 2\&.0\&. If a copy of the MPL was not distributed with this file, You can obtain one at http://mozilla\&.org/MPL/2\&.0/\&. LICENSE included with the czmq distribution\&. +.SH "NOTES" +.IP " 1." 4 +zeromq-dev@lists.zeromq.org +.RS 4 +\%mailto:zeromq-dev@lists.zeromq.org +.RE diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zdir_patch.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zdir_patch.3 new file mode 100644 index 00000000000000..61789b32c0477c --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zdir_patch.3 @@ -0,0 +1,129 @@ +'\" t +.\" Title: zdir_patch +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.76.1 +.\" Date: 12/31/2016 +.\" Manual: CZMQ Manual +.\" Source: CZMQ 4.0.2 +.\" Language: English +.\" +.TH "ZDIR_PATCH" "3" "12/31/2016" "CZMQ 4\&.0\&.2" "CZMQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zdir_patch \- work with directory patches +.SH "SYNOPSIS" +.sp +.nf +// This is a stable class, and may not change except for emergencies\&. It +// is provided in stable builds\&. +#define ZDIR_PATCH_CREATE 1 // Creates a new file +#define ZDIR_PATCH_DELETE 2 // Delete a file + +// Create new patch +CZMQ_EXPORT zdir_patch_t * + zdir_patch_new (const char *path, zfile_t *file, int op, const char *alias); + +// Destroy a patch +CZMQ_EXPORT void + zdir_patch_destroy (zdir_patch_t **self_p); + +// Create copy of a patch\&. If the patch is null, or memory was exhausted, +// returns null\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT zdir_patch_t * + zdir_patch_dup (zdir_patch_t *self); + +// Return patch file directory path +CZMQ_EXPORT const char * + zdir_patch_path (zdir_patch_t *self); + +// Return patch file item +CZMQ_EXPORT zfile_t * + zdir_patch_file (zdir_patch_t *self); + +// Return operation +CZMQ_EXPORT int + zdir_patch_op (zdir_patch_t *self); + +// Return patch virtual file path +CZMQ_EXPORT const char * + zdir_patch_vpath (zdir_patch_t *self); + +// Calculate hash digest for file (create only) +CZMQ_EXPORT void + zdir_patch_digest_set (zdir_patch_t *self); + +// Return hash digest for patch file +CZMQ_EXPORT const char * + zdir_patch_digest (zdir_patch_t *self); + +// Self test of this class\&. +CZMQ_EXPORT void + zdir_patch_test (bool verbose); + +Please add \*(Aq@interface\*(Aq section in \*(Aq\&./\&.\&./src/zdir_patch\&.c\*(Aq\&. +.fi +.SH "DESCRIPTION" +.sp +The zdir_patch class works with one patch, which says "create this file" or "delete this file" (referring to a zfile item each time)\&. +.sp +Please add \fI@discuss\fR section in \fI\&./\&.\&./src/zdir_patch\&.c\fR\&. +.SH "EXAMPLE" +.PP +\fBFrom zdir_patch_test method\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +zfile_t *file = zfile_new ("\&.", "bilbo"); +assert (file); +zdir_patch_t *patch = zdir_patch_new ("\&.", file, patch_create, "/"); +assert (patch); +zfile_destroy (&file); + +file = zdir_patch_file (patch); +assert (file); +assert (streq (zfile_filename (file, "\&."), "bilbo")); +assert (streq (zdir_patch_vpath (patch), "/bilbo")); +zdir_patch_destroy (&patch); +.fi +.if n \{\ +.RE +.\} +.sp +.SH "AUTHORS" +.sp +The czmq manual was written by the authors in the AUTHORS file\&. +.SH "RESOURCES" +.sp +Main web site: \m[blue]\fB\%\fR\m[] +.sp +Report bugs to the email <\m[blue]\fBzeromq\-dev@lists\&.zeromq\&.org\fR\m[]\&\s-2\u[1]\d\s+2> +.SH "COPYRIGHT" +.sp +Copyright (c) the Contributors as noted in the AUTHORS file\&. This file is part of CZMQ, the high\-level C binding for 0MQ: http://czmq\&.zeromq\&.org\&. This Source Code Form is subject to the terms of the Mozilla Public License, v\&. 2\&.0\&. If a copy of the MPL was not distributed with this file, You can obtain one at http://mozilla\&.org/MPL/2\&.0/\&. LICENSE included with the czmq distribution\&. +.SH "NOTES" +.IP " 1." 4 +zeromq-dev@lists.zeromq.org +.RS 4 +\%mailto:zeromq-dev@lists.zeromq.org +.RE diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zfile.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zfile.3 new file mode 100644 index 00000000000000..f3b6591812528f --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zfile.3 @@ -0,0 +1,340 @@ +'\" t +.\" Title: zfile +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.76.1 +.\" Date: 12/31/2016 +.\" Manual: CZMQ Manual +.\" Source: CZMQ 4.0.2 +.\" Language: English +.\" +.TH "ZFILE" "3" "12/31/2016" "CZMQ 4\&.0\&.2" "CZMQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zfile \- provides methods to work with files in a portable fashion\&. +.SH "SYNOPSIS" +.sp +.nf +// This is a stable class, and may not change except for emergencies\&. It +// is provided in stable builds\&. +// If file exists, populates properties\&. CZMQ supports portable symbolic +// links, which are files with the extension "\&.ln"\&. A symbolic link is a +// text file containing one line, the filename of a target file\&. Reading +// data from the symbolic link actually reads from the target file\&. Path +// may be NULL, in which case it is not used\&. +CZMQ_EXPORT zfile_t * + zfile_new (const char *path, const char *name); + +// Destroy a file item +CZMQ_EXPORT void + zfile_destroy (zfile_t **self_p); + +// Duplicate a file item, returns a newly constructed item\&. If the file +// is null, or memory was exhausted, returns null\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT zfile_t * + zfile_dup (zfile_t *self); + +// Return file name, remove path if provided +CZMQ_EXPORT const char * + zfile_filename (zfile_t *self, const char *path); + +// Refresh file properties from disk; this is not done automatically +// on access methods, otherwise it is not possible to compare directory +// snapshots\&. +CZMQ_EXPORT void + zfile_restat (zfile_t *self); + +// Return when the file was last modified\&. If you want this to reflect the +// current situation, call zfile_restat before checking this property\&. +CZMQ_EXPORT time_t + zfile_modified (zfile_t *self); + +// Return the last\-known size of the file\&. If you want this to reflect the +// current situation, call zfile_restat before checking this property\&. +CZMQ_EXPORT off_t + zfile_cursize (zfile_t *self); + +// Return true if the file is a directory\&. If you want this to reflect +// any external changes, call zfile_restat before checking this property\&. +CZMQ_EXPORT bool + zfile_is_directory (zfile_t *self); + +// Return true if the file is a regular file\&. If you want this to reflect +// any external changes, call zfile_restat before checking this property\&. +CZMQ_EXPORT bool + zfile_is_regular (zfile_t *self); + +// Return true if the file is readable by this process\&. If you want this to +// reflect any external changes, call zfile_restat before checking this +// property\&. +CZMQ_EXPORT bool + zfile_is_readable (zfile_t *self); + +// Return true if the file is writeable by this process\&. If you want this +// to reflect any external changes, call zfile_restat before checking this +// property\&. +CZMQ_EXPORT bool + zfile_is_writeable (zfile_t *self); + +// Check if file has stopped changing and can be safely processed\&. +// Updates the file statistics from disk at every call\&. +CZMQ_EXPORT bool + zfile_is_stable (zfile_t *self); + +// Return true if the file was changed on disk since the zfile_t object +// was created, or the last zfile_restat() call made on it\&. +CZMQ_EXPORT bool + zfile_has_changed (zfile_t *self); + +// Remove the file from disk +CZMQ_EXPORT void + zfile_remove (zfile_t *self); + +// Open file for reading +// Returns 0 if OK, \-1 if not found or not accessible +CZMQ_EXPORT int + zfile_input (zfile_t *self); + +// Open file for writing, creating directory if needed +// File is created if necessary; chunks can be written to file at any +// location\&. Returns 0 if OK, \-1 if error\&. +CZMQ_EXPORT int + zfile_output (zfile_t *self); + +// Read chunk from file at specified position\&. If this was the last chunk, +// sets the eof property\&. Returns a null chunk in case of error\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT zchunk_t * + zfile_read (zfile_t *self, size_t bytes, off_t offset); + +// Returns true if zfile_read() just read the last chunk in the file\&. +CZMQ_EXPORT bool + zfile_eof (zfile_t *self); + +// Write chunk to file at specified position +// Return 0 if OK, else \-1 +CZMQ_EXPORT int + zfile_write (zfile_t *self, zchunk_t *chunk, off_t offset); + +// Read next line of text from file\&. Returns a pointer to the text line, +// or NULL if there was nothing more to read from the file\&. +CZMQ_EXPORT const char * + zfile_readln (zfile_t *self); + +// Close file, if open +CZMQ_EXPORT void + zfile_close (zfile_t *self); + +// Return file handle, if opened +CZMQ_EXPORT FILE * + zfile_handle (zfile_t *self); + +// Calculate SHA1 digest for file, using zdigest class\&. +CZMQ_EXPORT const char * + zfile_digest (zfile_t *self); + +// Self test of this class\&. +CZMQ_EXPORT void + zfile_test (bool verbose); + +// These methods are deprecated, and now moved to zsys class\&. +CZMQ_EXPORT bool + zfile_exists (const char *filename); +CZMQ_EXPORT ssize_t + zfile_size (const char *filename); +CZMQ_EXPORT mode_t + zfile_mode (const char *filename); +CZMQ_EXPORT int + zfile_delete (const char *filename); +CZMQ_EXPORT bool + zfile_stable (const char *filename); +CZMQ_EXPORT int + zfile_mkdir (const char *pathname); +CZMQ_EXPORT int + zfile_rmdir (const char *pathname); +CZMQ_EXPORT void + zfile_mode_private (void); +CZMQ_EXPORT void + zfile_mode_default (void); +Please add \*(Aq@interface\*(Aq section in \*(Aq\&./\&.\&./src/zfile\&.c\*(Aq\&. +.fi +.SH "DESCRIPTION" +.sp +The zfile class provides methods to work with disk files\&. A file object provides the modified date, current size, and type of the file\&. You can create a file object for a filename that does not yet exist\&. To read or write data from the file, use the input and output methods, and then read and write chunks\&. The output method lets you both read and write chunks, at any offset\&. Finally, this class provides portable symbolic links\&. If a filename ends in "\&.ln", the first line of text in the file is read, and used as the underlying file for read/write operations\&. This lets you manipulate (e\&.g\&.) copy symbolic links without copying the perhaps very large files they point to\&. +.sp +This class is a new API, deprecating the old zfile class (which still exists but is implemented in zsys now)\&. +.SH "EXAMPLE" +.PP +\fBFrom zfile_test method\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +zfile_t *file = zfile_new (NULL, "bilbo"); +assert (file); +assert (streq (zfile_filename (file, "\&."), "bilbo")); +assert (zfile_is_readable (file) == false); +zfile_destroy (&file); + +// Create a test file in some random subdirectory +file = zfile_new ("\&./this/is/a/test", "bilbo"); +assert (file); +int rc = zfile_output (file); +assert (rc == 0); +zchunk_t *chunk = zchunk_new (NULL, 100); +assert (chunk); +zchunk_fill (chunk, 0, 100); + +// Write 100 bytes at position 1,000,000 in the file +rc = zfile_write (file, chunk, 1000000); +assert (rc == 0); +zchunk_destroy (&chunk); +zfile_close (file); +assert (zfile_is_readable (file)); +assert (zfile_cursize (file) == 1000100); +assert (!zfile_is_stable (file)); +assert (zfile_digest (file)); + +// Now truncate file from outside +int handle = open ("\&./this/is/a/test/bilbo", O_WRONLY | O_TRUNC | O_BINARY, 0); +assert (handle >= 0); +rc = write (handle, "Hello, World\en", 13); +assert (rc == 13); +close (handle); +assert (zfile_has_changed (file)); +zclock_sleep (1001); +assert (zfile_has_changed (file)); + +assert (!zfile_is_stable (file)); +zfile_restat (file); +assert (zfile_is_stable (file)); +assert (streq (zfile_digest (file), "4AB299C8AD6ED14F31923DD94F8B5F5CB89DFB54")); + +// Check we can read from file +rc = zfile_input (file); +assert (rc == 0); +chunk = zfile_read (file, 1000100, 0); +assert (chunk); +assert (zchunk_size (chunk) == 13); +zchunk_destroy (&chunk); +zfile_close (file); + +// Check we can read lines from file +rc = zfile_input (file); +assert (rc == 0); +const char *line = zfile_readln (file); +assert (streq (line, "Hello, World")); +line = zfile_readln (file); +assert (line == NULL); +zfile_close (file); + +// Try some fun with symbolic links +zfile_t *link = zfile_new ("\&./this/is/a/test", "bilbo\&.ln"); +assert (link); +rc = zfile_output (link); +assert (rc == 0); +fprintf (zfile_handle (link), "\&./this/is/a/test/bilbo\en"); +zfile_destroy (&link); + +link = zfile_new ("\&./this/is/a/test", "bilbo\&.ln"); +assert (link); +rc = zfile_input (link); +assert (rc == 0); +chunk = zfile_read (link, 1000100, 0); +assert (chunk); +assert (zchunk_size (chunk) == 13); +zchunk_destroy (&chunk); +zfile_destroy (&link); + +// Remove file and directory +zdir_t *dir = zdir_new ("\&./this", NULL); +assert (dir); +assert (zdir_cursize (dir) == 26); +zdir_remove (dir, true); +assert (zdir_cursize (dir) == 0); +zdir_destroy (&dir); + +// Check we can no longer read from file +assert (zfile_is_readable (file)); +zfile_restat (file); +assert (!zfile_is_readable (file)); +rc = zfile_input (file); +assert (rc == \-1); +zfile_destroy (&file); + +file = zfile_new ("\&./", "eof_checkfile"); +assert (file); +// 1\&. Write something first +rc = zfile_output (file); +assert (rc == 0); +chunk = zchunk_new ("123456789", 9); +assert (chunk); + +rc = zfile_write (file, chunk, 0); +assert (rc == 0); +zchunk_destroy (&chunk); +zfile_close (file); +assert (zfile_cursize (file) == 9); + +// 2\&. Read the written something +rc = zfile_input (file); +assert (rc != \-1); +// try to read more bytes than there is in the file +chunk = zfile_read (file, 1000, 0); +assert (zfile_eof(file)); +assert (zchunk_streq (chunk, "123456789")); +zchunk_destroy (&chunk); + +// reading is ok +chunk = zfile_read (file, 5, 0); +assert (!zfile_eof(file)); +assert (zchunk_streq (chunk, "12345")); +zchunk_destroy (&chunk); + +// read from non zero offset until the end +chunk = zfile_read (file, 5, 5); +assert (zfile_eof(file)); +assert (zchunk_streq (chunk, "6789")); +zchunk_destroy (&chunk); +zfile_remove (file); +.fi +.if n \{\ +.RE +.\} +.sp +.SH "AUTHORS" +.sp +The czmq manual was written by the authors in the AUTHORS file\&. +.SH "RESOURCES" +.sp +Main web site: \m[blue]\fB\%\fR\m[] +.sp +Report bugs to the email <\m[blue]\fBzeromq\-dev@lists\&.zeromq\&.org\fR\m[]\&\s-2\u[1]\d\s+2> +.SH "COPYRIGHT" +.sp +Copyright (c) the Contributors as noted in the AUTHORS file\&. This file is part of CZMQ, the high\-level C binding for 0MQ: http://czmq\&.zeromq\&.org\&. This Source Code Form is subject to the terms of the Mozilla Public License, v\&. 2\&.0\&. If a copy of the MPL was not distributed with this file, You can obtain one at http://mozilla\&.org/MPL/2\&.0/\&. LICENSE included with the czmq distribution\&. +.SH "NOTES" +.IP " 1." 4 +zeromq-dev@lists.zeromq.org +.RS 4 +\%mailto:zeromq-dev@lists.zeromq.org +.RE diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zframe.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zframe.3 new file mode 100644 index 00000000000000..f723dd61054003 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zframe.3 @@ -0,0 +1,357 @@ +'\" t +.\" Title: zframe +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.76.1 +.\" Date: 12/31/2016 +.\" Manual: CZMQ Manual +.\" Source: CZMQ 4.0.2 +.\" Language: English +.\" +.TH "ZFRAME" "3" "12/31/2016" "CZMQ 4\&.0\&.2" "CZMQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zframe \- working with single message frames +.SH "SYNOPSIS" +.sp +.nf +// This is a stable class, and may not change except for emergencies\&. It +// is provided in stable builds\&. +// This class has draft methods, which may change over time\&. They are not +// in stable releases, by default\&. Use \-\-enable\-drafts to enable\&. +#define ZFRAME_MORE 1 // +#define ZFRAME_REUSE 2 // +#define ZFRAME_DONTWAIT 4 // + +// Create a new frame\&. If size is not null, allocates the frame data +// to the specified size\&. If additionally, data is not null, copies +// size octets from the specified data into the frame body\&. +CZMQ_EXPORT zframe_t * + zframe_new (const void *data, size_t size); + +// Create an empty (zero\-sized) frame +CZMQ_EXPORT zframe_t * + zframe_new_empty (void); + +// Create a frame with a specified string content\&. +CZMQ_EXPORT zframe_t * + zframe_from (const char *string); + +// Receive frame from socket, returns zframe_t object or NULL if the recv +// was interrupted\&. Does a blocking recv, if you want to not block then use +// zpoller or zloop\&. +CZMQ_EXPORT zframe_t * + zframe_recv (void *source); + +// Destroy a frame +CZMQ_EXPORT void + zframe_destroy (zframe_t **self_p); + +// Send a frame to a socket, destroy frame after sending\&. +// Return \-1 on error, 0 on success\&. +CZMQ_EXPORT int + zframe_send (zframe_t **self_p, void *dest, int flags); + +// Return number of bytes in frame data +CZMQ_EXPORT size_t + zframe_size (zframe_t *self); + +// Return address of frame data +CZMQ_EXPORT byte * + zframe_data (zframe_t *self); + +// Return meta data property for frame +// Caller must free string when finished with it\&. +CZMQ_EXPORT const char * + zframe_meta (zframe_t *self, const char *property); + +// Create a new frame that duplicates an existing frame\&. If frame is null, +// or memory was exhausted, returns null\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT zframe_t * + zframe_dup (zframe_t *self); + +// Return frame data encoded as printable hex string, useful for 0MQ UUIDs\&. +// Caller must free string when finished with it\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT char * + zframe_strhex (zframe_t *self); + +// Return frame data copied into freshly allocated string +// Caller must free string when finished with it\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT char * + zframe_strdup (zframe_t *self); + +// Return TRUE if frame body is equal to string, excluding terminator +CZMQ_EXPORT bool + zframe_streq (zframe_t *self, const char *string); + +// Return frame MORE indicator (1 or 0), set when reading frame from socket +// or by the zframe_set_more() method +CZMQ_EXPORT int + zframe_more (zframe_t *self); + +// Set frame MORE indicator (1 or 0)\&. Note this is NOT used when sending +// frame to socket, you have to specify flag explicitly\&. +CZMQ_EXPORT void + zframe_set_more (zframe_t *self, int more); + +// Return TRUE if two frames have identical size and data +// If either frame is NULL, equality is always false\&. +CZMQ_EXPORT bool + zframe_eq (zframe_t *self, zframe_t *other); + +// Set new contents for frame +CZMQ_EXPORT void + zframe_reset (zframe_t *self, const void *data, size_t size); + +// Send message to zsys log sink (may be stdout, or system facility as +// configured by zsys_set_logstream)\&. Prefix shows before frame, if not null\&. +CZMQ_EXPORT void + zframe_print (zframe_t *self, const char *prefix); + +// Probe the supplied object, and report if it looks like a zframe_t\&. +CZMQ_EXPORT bool + zframe_is (void *self); + +// Self test of this class\&. +CZMQ_EXPORT void + zframe_test (bool verbose); + +#ifdef CZMQ_BUILD_DRAFT_API +// *** Draft method, for development use, may change without warning *** +// Return frame routing ID, if the frame came from a ZMQ_SERVER socket\&. +// Else returns zero\&. +CZMQ_EXPORT uint32_t + zframe_routing_id (zframe_t *self); + +// *** Draft method, for development use, may change without warning *** +// Set routing ID on frame\&. This is used if/when the frame is sent to a +// ZMQ_SERVER socket\&. +CZMQ_EXPORT void + zframe_set_routing_id (zframe_t *self, uint32_t routing_id); + +// *** Draft method, for development use, may change without warning *** +// Return frame group of radio\-dish pattern\&. +CZMQ_EXPORT const char * + zframe_group (zframe_t *self); + +// *** Draft method, for development use, may change without warning *** +// Set group on frame\&. This is used if/when the frame is sent to a +// ZMQ_RADIO socket\&. +// Return \-1 on error, 0 on success\&. +CZMQ_EXPORT int + zframe_set_group (zframe_t *self, const char *group); + +#endif // CZMQ_BUILD_DRAFT_API +Please add \*(Aq@interface\*(Aq section in \*(Aq\&./\&.\&./src/zframe\&.c\*(Aq\&. +.fi +.SH "DESCRIPTION" +.sp +The zframe class provides methods to send and receive single message frames across 0MQ sockets\&. A \fIframe\fR corresponds to one zmq_msg_t\&. When you read a frame from a socket, the zframe_more() method indicates if the frame is part of an unfinished multipart message\&. The zframe_send method normally destroys the frame, but with the ZFRAME_REUSE flag, you can send the same frame many times\&. Frames are binary, and this class has no special support for text data\&. +.sp +Please add \fI@discuss\fR section in \fI\&./\&.\&./src/zframe\&.c\fR\&. +.SH "EXAMPLE" +.PP +\fBFrom zframe_test method\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +// Create two PAIR sockets and connect over inproc +zsock_t *output = zsock_new_pair ("@tcp://127\&.0\&.0\&.1:9001"); +assert (output); +zsock_t *input = zsock_new_pair (">tcp://127\&.0\&.0\&.1:9001"); +assert (input); + +// Send five different frames, test ZFRAME_MORE +int frame_nbr; +for (frame_nbr = 0; frame_nbr < 5; frame_nbr++) { + frame = zframe_new ("Hello", 5); + assert (frame); + rc = zframe_send (&frame, output, ZFRAME_MORE); + assert (rc == 0); +} +// Send same frame five times, test ZFRAME_REUSE +frame = zframe_new ("Hello", 5); +assert (frame); +for (frame_nbr = 0; frame_nbr < 5; frame_nbr++) { + rc = zframe_send (&frame, output, ZFRAME_MORE + ZFRAME_REUSE); + assert (rc == 0); +} +assert (frame); +zframe_t *copy = zframe_dup (frame); +assert (zframe_eq (frame, copy)); +zframe_destroy (&frame); +assert (!zframe_eq (frame, copy)); +assert (zframe_size (copy) == 5); +zframe_destroy (©); +assert (!zframe_eq (frame, copy)); + +// Test zframe_new_empty +frame = zframe_new_empty (); +assert (frame); +assert (zframe_size (frame) == 0); +zframe_destroy (&frame); + +// Send END frame +frame = zframe_new ("NOT", 3); +assert (frame); +zframe_reset (frame, "END", 3); +char *string = zframe_strhex (frame); +assert (streq (string, "454E44")); +free (string); +string = zframe_strdup (frame); +assert (streq (string, "END")); +free (string); +rc = zframe_send (&frame, output, 0); +assert (rc == 0); + +// Read and count until we receive END +frame_nbr = 0; +for (frame_nbr = 0;; frame_nbr++) { + zframe_t *frame = zframe_recv (input); + if (zframe_streq (frame, "END")) { + zframe_destroy (&frame); + break; + } + assert (zframe_more (frame)); + zframe_set_more (frame, 0); + assert (zframe_more (frame) == 0); + zframe_destroy (&frame); +} +assert (frame_nbr == 10); + +#if (ZMQ_VERSION >= ZMQ_MAKE_VERSION (4, 1, 0)) +// Test zframe_meta +frame = zframe_new ("Hello", 5); +assert (frame); +rc = zframe_send (&frame, output, 0); +assert (rc == 0); +frame = zframe_recv (input); +const char *meta = zframe_meta (frame, "Socket\-Type"); +assert (meta != NULL); +assert (streq (meta, "PAIR")); +assert (zframe_meta (frame, "nonexistent") == NULL); +zframe_destroy (&frame); +#endif + +zsock_destroy (&input); +zsock_destroy (&output); + +#if defined (ZMQ_SERVER) +// Create server and client sockets and connect over inproc +zsock_t *server = zsock_new_server ("inproc://zframe\-test\-routing"); +assert (server); +zsock_t *client = zsock_new_client ("inproc://zframe\-test\-routing"); +assert (client); + +// Send request from client to server +zframe_t *request = zframe_new ("Hello", 5); +assert (request); +rc = zframe_send (&request, client, 0); +assert (rc == 0); +assert (!request); + +// Read request and send reply +request = zframe_recv (server); +assert (request); +assert (zframe_streq (request, "Hello")); +assert (zframe_routing_id (request)); + +zframe_t *reply = zframe_new ("World", 5); +assert (reply); +zframe_set_routing_id (reply, zframe_routing_id (request)); +rc = zframe_send (&reply, server, 0); +assert (rc == 0); +zframe_destroy (&request); + +// Read reply +reply = zframe_recv (client); +assert (zframe_streq (reply, "World")); +assert (zframe_routing_id (reply) == 0); +zframe_destroy (&reply); + +// Client and server disallow multipart +frame = zframe_new ("Hello", 5); +rc = zframe_send (&frame, client, ZFRAME_MORE); +assert (rc == \-1); +rc = zframe_send (&frame, server, ZFRAME_MORE); +assert (rc == \-1); +zframe_destroy (&frame); + +zsock_destroy (&client); +zsock_destroy (&server); +#endif + +#ifdef ZMQ_RADIO +// Create radio and dish sockets and connect over inproc +zsock_t *radio = zsock_new_radio ("inproc://zframe\-test\-radio"); +assert (radio); +zsock_t *dish = zsock_new_dish ("inproc://zframe\-test\-radio"); +assert (dish); + +// Join the group +rc = zsock_join (dish, "World"); +assert (rc == 0); + +// Publish message from radio +zframe_t *message = zframe_new ("Hello", 5); +assert (message); +rc = zframe_set_group (message, "World"); +assert (rc == 0); +rc = zframe_send (&message, radio, 0); +assert (rc == 0); +assert (!message); + +// Receive the message from dish +message = zframe_recv (dish); +assert (message); +assert (zframe_streq (message, "Hello")); +assert (strcmp("World", zframe_group (message)) == 0); +zframe_destroy (&message); + +zsock_destroy (&dish); +zsock_destroy (&radio); +#endif +.fi +.if n \{\ +.RE +.\} +.sp +.SH "AUTHORS" +.sp +The czmq manual was written by the authors in the AUTHORS file\&. +.SH "RESOURCES" +.sp +Main web site: \m[blue]\fB\%\fR\m[] +.sp +Report bugs to the email <\m[blue]\fBzeromq\-dev@lists\&.zeromq\&.org\fR\m[]\&\s-2\u[1]\d\s+2> +.SH "COPYRIGHT" +.sp +Copyright (c) the Contributors as noted in the AUTHORS file\&. This file is part of CZMQ, the high\-level C binding for 0MQ: http://czmq\&.zeromq\&.org\&. This Source Code Form is subject to the terms of the Mozilla Public License, v\&. 2\&.0\&. If a copy of the MPL was not distributed with this file, You can obtain one at http://mozilla\&.org/MPL/2\&.0/\&. LICENSE included with the czmq distribution\&. +.SH "NOTES" +.IP " 1." 4 +zeromq-dev@lists.zeromq.org +.RS 4 +\%mailto:zeromq-dev@lists.zeromq.org +.RE diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zgossip.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zgossip.3 new file mode 100644 index 00000000000000..170d3a2271bc83 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zgossip.3 @@ -0,0 +1,338 @@ +'\" t +.\" Title: zgossip +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.76.1 +.\" Date: 12/31/2016 +.\" Manual: CZMQ Manual +.\" Source: CZMQ 4.0.2 +.\" Language: English +.\" +.TH "ZGOSSIP" "3" "12/31/2016" "CZMQ 4\&.0\&.2" "CZMQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zgossip \- decentralized configuration management +.SH "SYNOPSIS" +.sp +.nf +// To work with zgossip, use the CZMQ zactor API: +// +// Create new zgossip instance, passing logging prefix: +// +// zactor_t *zgossip = zactor_new (zgossip, "myname"); +// +// Destroy zgossip instance +// +// zactor_destroy (&zgossip); +// +// Enable verbose logging of commands and activity: +// +// zstr_send (zgossip, "VERBOSE"); +// +// Bind zgossip to specified endpoint\&. TCP endpoints may specify +// the port number as "*" to aquire an ephemeral port: +// +// zstr_sendx (zgossip, "BIND", endpoint, NULL); +// +// Return assigned port number, specifically when BIND was done using an +// an ephemeral port: +// +// zstr_sendx (zgossip, "PORT", NULL); +// char *command, *port_str; +// zstr_recvx (zgossip, &command, &port_str, NULL); +// assert (streq (command, "PORT")); +// +// Specify configuration file to load, overwriting any previous loaded +// configuration file or options: +// +// zstr_sendx (zgossip, "LOAD", filename, NULL); +// +// Set configuration path value: +// +// zstr_sendx (zgossip, "SET", path, value, NULL); +// +// Save configuration data to config file on disk: +// +// zstr_sendx (zgossip, "SAVE", filename, NULL); +// +// Send zmsg_t instance to zgossip: +// +// zactor_send (zgossip, &msg); +// +// Receive zmsg_t instance from zgossip: +// +// zmsg_t *msg = zactor_recv (zgossip); +// +// This is the zgossip constructor as a zactor_fn: +// +CZMQ_EXPORT void + zgossip (zsock_t *pipe, void *args); + +// Self test of this class +CZMQ_EXPORT void + zgossip_test (bool verbose); +Please add \*(Aq@interface\*(Aq section in \*(Aq\&./\&.\&./src/zgossip\&.c\*(Aq\&. +.fi +.SH "DESCRIPTION" +.sp +Implements a gossip protocol for decentralized configuration management\&. Your applications nodes form a loosely connected network (which can have cycles), and publish name/value tuples\&. Each node re\-distributes the new tuples it receives, so that the entire network eventually achieves a consistent state\&. The current design does not expire tuples\&. +.sp +Provides these commands (sent as multipart strings to the actor): +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +BIND endpoint \(em binds the gossip service to specified endpoint +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +PORT \(em returns the last TCP port, if any, used for binding +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +LOAD configfile \(em load configuration from specified file +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +SET configpath value \(em set configuration path = value +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +SAVE configfile \(em save configuration to specified file +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +CONNECT endpoint \(em connect the gossip service to the specified peer +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +PUBLISH key value \(em publish a key/value pair to the gossip cluster +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +STATUS \(em return number of key/value pairs held by gossip service +.RE +.sp +Returns these messages: +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +PORT number \(em reply to PORT command +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +STATUS number \(em reply to STATUS command +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +DELIVER key value \(em new tuple delivered from network +.RE +.sp +The gossip protocol distributes information around a loosely\-connected network of gossip services\&. The information consists of name/value pairs published by applications at any point in the network\&. The goal of the gossip protocol is to create eventual consistency between all the using applications\&. +.sp +The name/value pairs (tuples) can be used for configuration data, for status updates, for presence, or for discovery\&. When used for discovery, the gossip protocol works as an alternative to e\&.g\&. UDP beaconing\&. +.sp +The gossip network consists of a set of loosely\-coupled nodes that exchange tuples\&. Nodes can be connected across arbitrary transports, so the gossip network can have nodes that communicate over inproc, over IPC, and/or over TCP, at the same time\&. +.sp +Each node runs the same stack, which is a server\-client hybrid using a modified Harmony pattern (from Chapter 8 of the Guide): \m[blue]\fBhttp://zguide\&.zeromq\&.org/page:all#True\-Peer\-Connectivity\-Harmony\-Pattern\fR\m[] +.sp +Each node provides a ROUTER socket that accepts client connections on an key defined by the application via a BIND command\&. The state machine for these connections is in zgossip\&.xml, and the generated code is in zgossip_engine\&.inc\&. +.sp +Each node additionally creates outbound connections via DEALER sockets to a set of servers ("remotes"), and under control of the calling app, which sends CONNECT commands for each configured remote\&. +.sp +The messages between client and server are defined in zgossip_msg\&.xml\&. We built this stack using the zeromq/zproto toolkit\&. +.sp +To join the gossip network, a node connects to one or more peers\&. Each peer acts as a forwarder\&. This loosely\-coupled network can scale to thousands of nodes\&. However the gossip protocol is NOT designed to be efficient, and should not be used for application data, as the same tuples may be sent many times across the network\&. +.sp +The basic logic of the gossip service is to accept PUBLISH messages from its owning application, and to forward these to every remote, and every client it talks to\&. When a node gets a duplicate tuple, it throws it away\&. When a node gets a new tuple, it stores it, and fowards it as just described\&. At any point the application can access the node\(cqs set of tuples\&. +.sp +At present there is no way to expire tuples from the network\&. +.sp +The assumptions in this design are: +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +The data set is slow\-changing\&. Thus, the cost of the gossip protocol is irrelevant with respect to other traffic\&. +.RE +.SH "EXAMPLE" +.PP +\fBFrom zgossip_test method\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +// Test basic client\-to\-server operation of the protocol +zactor_t *server = zactor_new (zgossip, "server"); +assert (server); +if (verbose) + zstr_send (server, "VERBOSE"); +zstr_sendx (server, "BIND", "inproc://zgossip", NULL); + +zsock_t *client = zsock_new (ZMQ_DEALER); +assert (client); +zsock_set_rcvtimeo (client, 2000); +int rc = zsock_connect (client, "inproc://zgossip"); +assert (rc == 0); + +// Send HELLO, which gets no message +zgossip_msg_t *message = zgossip_msg_new (); +zgossip_msg_set_id (message, ZGOSSIP_MSG_HELLO); +zgossip_msg_send (message, client); + +// Send PING, expect PONG back +zgossip_msg_set_id (message, ZGOSSIP_MSG_PING); +zgossip_msg_send (message, client); +zgossip_msg_recv (message, client); +assert (zgossip_msg_id (message) == ZGOSSIP_MSG_PONG); +zgossip_msg_destroy (&message); + +zactor_destroy (&server); +zsock_destroy (&client); + +// Test peer\-to\-peer operations +zactor_t *base = zactor_new (zgossip, "base"); +assert (base); +if (verbose) + zstr_send (base, "VERBOSE"); +// Set a 100msec timeout on clients so we can test expiry +zstr_sendx (base, "SET", "server/timeout", "100", NULL); +zstr_sendx (base, "BIND", "inproc://base", NULL); + +zactor_t *alpha = zactor_new (zgossip, "alpha"); +assert (alpha); +zstr_sendx (alpha, "CONNECT", "inproc://base", NULL); +zstr_sendx (alpha, "PUBLISH", "inproc://alpha\-1", "service1", NULL); +zstr_sendx (alpha, "PUBLISH", "inproc://alpha\-2", "service2", NULL); + +zactor_t *beta = zactor_new (zgossip, "beta"); +assert (beta); +zstr_sendx (beta, "CONNECT", "inproc://base", NULL); +zstr_sendx (beta, "PUBLISH", "inproc://beta\-1", "service1", NULL); +zstr_sendx (beta, "PUBLISH", "inproc://beta\-2", "service2", NULL); + +// got nothing +zclock_sleep (200); + +zactor_destroy (&base); +zactor_destroy (&alpha); +zactor_destroy (&beta); +.fi +.if n \{\ +.RE +.\} +.sp +.SH "AUTHORS" +.sp +The czmq manual was written by the authors in the AUTHORS file\&. +.SH "RESOURCES" +.sp +Main web site: \m[blue]\fB\%\fR\m[] +.sp +Report bugs to the email <\m[blue]\fBzeromq\-dev@lists\&.zeromq\&.org\fR\m[]\&\s-2\u[1]\d\s+2> +.SH "COPYRIGHT" +.sp +Copyright (c) the Contributors as noted in the AUTHORS file\&. This file is part of CZMQ, the high\-level C binding for 0MQ: http://czmq\&.zeromq\&.org\&. This Source Code Form is subject to the terms of the Mozilla Public License, v\&. 2\&.0\&. If a copy of the MPL was not distributed with this file, You can obtain one at http://mozilla\&.org/MPL/2\&.0/\&. LICENSE included with the czmq distribution\&. +.SH "NOTES" +.IP " 1." 4 +zeromq-dev@lists.zeromq.org +.RS 4 +\%mailto:zeromq-dev@lists.zeromq.org +.RE diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zhash.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zhash.3 new file mode 100644 index 00000000000000..8d0d45ab3f3184 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zhash.3 @@ -0,0 +1,382 @@ +'\" t +.\" Title: zhash +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.76.1 +.\" Date: 12/31/2016 +.\" Manual: CZMQ Manual +.\" Source: CZMQ 4.0.2 +.\" Language: English +.\" +.TH "ZHASH" "3" "12/31/2016" "CZMQ 4\&.0\&.2" "CZMQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zhash \- simple generic hash container +.SH "SYNOPSIS" +.sp +.nf +// This is a stable class, and may not change except for emergencies\&. It +// is provided in stable builds\&. +// Callback function for zhash_freefn method +typedef void (zhash_free_fn) ( + void *data); + +// Create a new, empty hash container +CZMQ_EXPORT zhash_t * + zhash_new (void); + +// Unpack binary frame into a new hash table\&. Packed data must follow format +// defined by zhash_pack\&. Hash table is set to autofree\&. An empty frame +// unpacks to an empty hash table\&. +CZMQ_EXPORT zhash_t * + zhash_unpack (zframe_t *frame); + +// Destroy a hash container and all items in it +CZMQ_EXPORT void + zhash_destroy (zhash_t **self_p); + +// Insert item into hash table with specified key and item\&. +// If key is already present returns \-1 and leaves existing item unchanged +// Returns 0 on success\&. +CZMQ_EXPORT int + zhash_insert (zhash_t *self, const char *key, void *item); + +// Update item into hash table with specified key and item\&. +// If key is already present, destroys old item and inserts new one\&. +// Use free_fn method to ensure deallocator is properly called on item\&. +CZMQ_EXPORT void + zhash_update (zhash_t *self, const char *key, void *item); + +// Remove an item specified by key from the hash table\&. If there was no such +// item, this function does nothing\&. +CZMQ_EXPORT void + zhash_delete (zhash_t *self, const char *key); + +// Return the item at the specified key, or null +CZMQ_EXPORT void * + zhash_lookup (zhash_t *self, const char *key); + +// Reindexes an item from an old key to a new key\&. If there was no such +// item, does nothing\&. Returns 0 if successful, else \-1\&. +CZMQ_EXPORT int + zhash_rename (zhash_t *self, const char *old_key, const char *new_key); + +// Set a free function for the specified hash table item\&. When the item is +// destroyed, the free function, if any, is called on that item\&. +// Use this when hash items are dynamically allocated, to ensure that +// you don\*(Aqt have memory leaks\&. You can pass \*(Aqfree\*(Aq or NULL as a free_fn\&. +// Returns the item, or NULL if there is no such item\&. +CZMQ_EXPORT void * + zhash_freefn (zhash_t *self, const char *key, zhash_free_fn free_fn); + +// Return the number of keys/items in the hash table +CZMQ_EXPORT size_t + zhash_size (zhash_t *self); + +// Make copy of hash table; if supplied table is null, returns null\&. +// Does not copy items themselves\&. Rebuilds new table so may be slow on +// very large tables\&. NOTE: only works with item values that are strings +// since there\*(Aqs no other way to know how to duplicate the item value\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT zhash_t * + zhash_dup (zhash_t *self); + +// Return keys for items in table +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT zlist_t * + zhash_keys (zhash_t *self); + +// Simple iterator; returns first item in hash table, in no given order, +// or NULL if the table is empty\&. This method is simpler to use than the +// foreach() method, which is deprecated\&. To access the key for this item +// use zhash_cursor()\&. NOTE: do NOT modify the table while iterating\&. +CZMQ_EXPORT void * + zhash_first (zhash_t *self); + +// Simple iterator; returns next item in hash table, in no given order, +// or NULL if the last item was already returned\&. Use this together with +// zhash_first() to process all items in a hash table\&. If you need the +// items in sorted order, use zhash_keys() and then zlist_sort()\&. To +// access the key for this item use zhash_cursor()\&. NOTE: do NOT modify +// the table while iterating\&. +CZMQ_EXPORT void * + zhash_next (zhash_t *self); + +// After a successful first/next method, returns the key for the item that +// was returned\&. This is a constant string that you may not modify or +// deallocate, and which lasts as long as the item in the hash\&. After an +// unsuccessful first/next, returns NULL\&. +CZMQ_EXPORT const char * + zhash_cursor (zhash_t *self); + +// Add a comment to hash table before saving to disk\&. You can add as many +// comment lines as you like\&. These comment lines are discarded when loading +// the file\&. If you use a null format, all comments are deleted\&. +CZMQ_EXPORT void + zhash_comment (zhash_t *self, const char *format, \&.\&.\&.) CHECK_PRINTF (2); + +// Serialize hash table to a binary frame that can be sent in a message\&. +// The packed format is compatible with the \*(Aqdictionary\*(Aq type defined in +// http://rfc\&.zeromq\&.org/spec:35/FILEMQ, and implemented by zproto: +// +// ; A list of name/value pairs +// dictionary = dict\-count *( dict\-name dict\-value ) +// dict\-count = number\-4 +// dict\-value = longstr +// dict\-name = string +// +// ; Strings are always length + text contents +// longstr = number\-4 *VCHAR +// string = number\-1 *VCHAR +// +// ; Numbers are unsigned integers in network byte order +// number\-1 = 1OCTET +// number\-4 = 4OCTET +// +// Comments are not included in the packed data\&. Item values MUST be +// strings\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT zframe_t * + zhash_pack (zhash_t *self); + +// Save hash table to a text file in name=value format\&. Hash values must be +// printable strings; keys may not contain \*(Aq=\*(Aq character\&. Returns 0 if OK, +// else \-1 if a file error occurred\&. +CZMQ_EXPORT int + zhash_save (zhash_t *self, const char *filename); + +// Load hash table from a text file in name=value format; hash table must +// already exist\&. Hash values must printable strings; keys may not contain +// \*(Aq=\*(Aq character\&. Returns 0 if OK, else \-1 if a file was not readable\&. +CZMQ_EXPORT int + zhash_load (zhash_t *self, const char *filename); + +// When a hash table was loaded from a file by zhash_load, this method will +// reload the file if it has been modified since, and is "stable", i\&.e\&. not +// still changing\&. Returns 0 if OK, \-1 if there was an error reloading the +// file\&. +CZMQ_EXPORT int + zhash_refresh (zhash_t *self); + +// Set hash for automatic value destruction +CZMQ_EXPORT void + zhash_autofree (zhash_t *self); + +// Self test of this class\&. +CZMQ_EXPORT void + zhash_test (bool verbose); + +Please add \*(Aq@interface\*(Aq section in \*(Aq\&./\&.\&./src/zhash\&.c\*(Aq\&. +.fi +.SH "DESCRIPTION" +.sp +zhash is an expandable hash table container\&. This is a simple container\&. For heavy\-duty applications we recommend using zhashx\&. +.sp +Note that it\(cqs relatively slow (50K insertions/deletes per second), so don\(cqt do inserts/updates on the critical path for message I/O\&. It can do 2\&.5M lookups per second for 16\-char keys\&. Timed on a 1\&.6GHz CPU\&. +.SH "EXAMPLE" +.PP +\fBFrom zhash_test method\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +zhash_t *hash = zhash_new (); +assert (hash); +assert (zhash_size (hash) == 0); +assert (zhash_first (hash) == NULL); +assert (zhash_cursor (hash) == NULL); + +// Insert some items +int rc; +rc = zhash_insert (hash, "DEADBEEF", "dead beef"); +char *item = (char *) zhash_first (hash); +assert (streq (zhash_cursor (hash), "DEADBEEF")); +assert (streq (item, "dead beef")); +assert (rc == 0); +rc = zhash_insert (hash, "ABADCAFE", "a bad cafe"); +assert (rc == 0); +rc = zhash_insert (hash, "C0DEDBAD", "coded bad"); +assert (rc == 0); +rc = zhash_insert (hash, "DEADF00D", "dead food"); +assert (rc == 0); +assert (zhash_size (hash) == 4); + +// Look for existing items +item = (char *) zhash_lookup (hash, "DEADBEEF"); +assert (streq (item, "dead beef")); +item = (char *) zhash_lookup (hash, "ABADCAFE"); +assert (streq (item, "a bad cafe")); +item = (char *) zhash_lookup (hash, "C0DEDBAD"); +assert (streq (item, "coded bad")); +item = (char *) zhash_lookup (hash, "DEADF00D"); +assert (streq (item, "dead food")); + +// Look for non\-existent items +item = (char *) zhash_lookup (hash, "foo"); +assert (item == NULL); + +// Try to insert duplicate items +rc = zhash_insert (hash, "DEADBEEF", "foo"); +assert (rc == \-1); +item = (char *) zhash_lookup (hash, "DEADBEEF"); +assert (streq (item, "dead beef")); + +// Some rename tests + +// Valid rename, key is now LIVEBEEF +rc = zhash_rename (hash, "DEADBEEF", "LIVEBEEF"); +assert (rc == 0); +item = (char *) zhash_lookup (hash, "LIVEBEEF"); +assert (streq (item, "dead beef")); + +// Trying to rename an unknown item to a non\-existent key +rc = zhash_rename (hash, "WHATBEEF", "NONESUCH"); +assert (rc == \-1); + +// Trying to rename an unknown item to an existing key +rc = zhash_rename (hash, "WHATBEEF", "LIVEBEEF"); +assert (rc == \-1); +item = (char *) zhash_lookup (hash, "LIVEBEEF"); +assert (streq (item, "dead beef")); + +// Trying to rename an existing item to another existing item +rc = zhash_rename (hash, "LIVEBEEF", "ABADCAFE"); +assert (rc == \-1); +item = (char *) zhash_lookup (hash, "LIVEBEEF"); +assert (streq (item, "dead beef")); +item = (char *) zhash_lookup (hash, "ABADCAFE"); +assert (streq (item, "a bad cafe")); + +// Test keys method +zlist_t *keys = zhash_keys (hash); +assert (zlist_size (keys) == 4); +zlist_destroy (&keys); + +// Test dup method +zhash_t *copy = zhash_dup (hash); +assert (zhash_size (copy) == 4); +item = (char *) zhash_lookup (copy, "LIVEBEEF"); +assert (item); +assert (streq (item, "dead beef")); +zhash_destroy (©); + +// Test pack/unpack methods +zframe_t *frame = zhash_pack (hash); +copy = zhash_unpack (frame); +zframe_destroy (&frame); +assert (zhash_size (copy) == 4); +item = (char *) zhash_lookup (copy, "LIVEBEEF"); +assert (item); +assert (streq (item, "dead beef")); +zhash_destroy (©); + +// Test save and load +zhash_comment (hash, "This is a test file"); +zhash_comment (hash, "Created by %s", "czmq_selftest"); +zhash_save (hash, "\&.cache"); +copy = zhash_new (); +assert (copy); +zhash_load (copy, "\&.cache"); +item = (char *) zhash_lookup (copy, "LIVEBEEF"); +assert (item); +assert (streq (item, "dead beef")); +zhash_destroy (©); +zsys_file_delete ("\&.cache"); + +// Delete a item +zhash_delete (hash, "LIVEBEEF"); +item = (char *) zhash_lookup (hash, "LIVEBEEF"); +assert (item == NULL); +assert (zhash_size (hash) == 3); + +// Check that the queue is robust against random usage +struct { + char name [100]; + bool exists; +} testset [200]; +memset (testset, 0, sizeof (testset)); +int testmax = 200, testnbr, iteration; + +srandom ((unsigned) time (NULL)); +for (iteration = 0; iteration < 25000; iteration++) { + testnbr = randof (testmax); + assert (testnbr != testmax); + assert (testnbr < testmax); + if (testset [testnbr]\&.exists) { + item = (char *) zhash_lookup (hash, testset [testnbr]\&.name); + assert (item); + zhash_delete (hash, testset [testnbr]\&.name); + testset [testnbr]\&.exists = false; + } + else { + sprintf (testset [testnbr]\&.name, "%x\-%x", rand (), rand ()); + if (zhash_insert (hash, testset [testnbr]\&.name, "") == 0) + testset [testnbr]\&.exists = true; + } +} +// Test 10K lookups +for (iteration = 0; iteration < 10000; iteration++) + item = (char *) zhash_lookup (hash, "DEADBEEFABADCAFE"); + +// Destructor should be safe to call twice +zhash_destroy (&hash); +zhash_destroy (&hash); +assert (hash == NULL); + +// Test autofree; automatically copies and frees string values +hash = zhash_new (); +assert (hash); +zhash_autofree (hash); +char value [255]; +strcpy (value, "This is a string"); +rc = zhash_insert (hash, "key1", value); +assert (rc == 0); +strcpy (value, "Inserting with the same key will fail"); +rc = zhash_insert (hash, "key1", value); +assert (rc == \-1); +strcpy (value, "Ring a ding ding"); +rc = zhash_insert (hash, "key2", value); +assert (rc == 0); +assert (streq ((char *) zhash_lookup (hash, "key1"), "This is a string")); +assert (streq ((char *) zhash_lookup (hash, "key2"), "Ring a ding ding")); +zhash_destroy (&hash); +.fi +.if n \{\ +.RE +.\} +.sp +.SH "AUTHORS" +.sp +The czmq manual was written by the authors in the AUTHORS file\&. +.SH "RESOURCES" +.sp +Main web site: \m[blue]\fB\%\fR\m[] +.sp +Report bugs to the email <\m[blue]\fBzeromq\-dev@lists\&.zeromq\&.org\fR\m[]\&\s-2\u[1]\d\s+2> +.SH "COPYRIGHT" +.sp +Copyright (c) the Contributors as noted in the AUTHORS file\&. This file is part of CZMQ, the high\-level C binding for 0MQ: http://czmq\&.zeromq\&.org\&. This Source Code Form is subject to the terms of the Mozilla Public License, v\&. 2\&.0\&. If a copy of the MPL was not distributed with this file, You can obtain one at http://mozilla\&.org/MPL/2\&.0/\&. LICENSE included with the czmq distribution\&. +.SH "NOTES" +.IP " 1." 4 +zeromq-dev@lists.zeromq.org +.RS 4 +\%mailto:zeromq-dev@lists.zeromq.org +.RE diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zhashx.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zhashx.3 new file mode 100644 index 00000000000000..d78b29a4312ecb --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zhashx.3 @@ -0,0 +1,498 @@ +'\" t +.\" Title: zhashx +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.76.1 +.\" Date: 12/31/2016 +.\" Manual: CZMQ Manual +.\" Source: CZMQ 4.0.2 +.\" Language: English +.\" +.TH "ZHASHX" "3" "12/31/2016" "CZMQ 4\&.0\&.2" "CZMQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zhashx \- extended generic hash container +.SH "SYNOPSIS" +.sp +.nf +// This is a stable class, and may not change except for emergencies\&. It +// is provided in stable builds\&. +// This class has draft methods, which may change over time\&. They are not +// in stable releases, by default\&. Use \-\-enable\-drafts to enable\&. +// Destroy an item +typedef void (zhashx_destructor_fn) ( + void **item); + +// Duplicate an item +typedef void * (zhashx_duplicator_fn) ( + const void *item); + +// Compare two items, for sorting +typedef int (zhashx_comparator_fn) ( + const void *item1, const void *item2); + +// compare two items, for sorting +typedef void (zhashx_free_fn) ( + void *data); + +// compare two items, for sorting +typedef size_t (zhashx_hash_fn) ( + const void *key); + +// Serializes an item to a longstr\&. +// The caller takes ownership of the newly created object\&. +typedef char * (zhashx_serializer_fn) ( + const void *item); + +// Deserializes a longstr into an item\&. +// The caller takes ownership of the newly created object\&. +typedef void * (zhashx_deserializer_fn) ( + const char *item_str); + +// Create a new, empty hash container +CZMQ_EXPORT zhashx_t * + zhashx_new (void); + +// Unpack binary frame into a new hash table\&. Packed data must follow format +// defined by zhashx_pack\&. Hash table is set to autofree\&. An empty frame +// unpacks to an empty hash table\&. +CZMQ_EXPORT zhashx_t * + zhashx_unpack (zframe_t *frame); + +// Destroy a hash container and all items in it +CZMQ_EXPORT void + zhashx_destroy (zhashx_t **self_p); + +// Insert item into hash table with specified key and item\&. +// If key is already present returns \-1 and leaves existing item unchanged +// Returns 0 on success\&. +CZMQ_EXPORT int + zhashx_insert (zhashx_t *self, const void *key, void *item); + +// Update or insert item into hash table with specified key and item\&. If the +// key is already present, destroys old item and inserts new one\&. If you set +// a container item destructor, this is called on the old value\&. If the key +// was not already present, inserts a new item\&. Sets the hash cursor to the +// new item\&. +CZMQ_EXPORT void + zhashx_update (zhashx_t *self, const void *key, void *item); + +// Remove an item specified by key from the hash table\&. If there was no such +// item, this function does nothing\&. +CZMQ_EXPORT void + zhashx_delete (zhashx_t *self, const void *key); + +// Delete all items from the hash table\&. If the key destructor is +// set, calls it on every key\&. If the item destructor is set, calls +// it on every item\&. +CZMQ_EXPORT void + zhashx_purge (zhashx_t *self); + +// Return the item at the specified key, or null +CZMQ_EXPORT void * + zhashx_lookup (zhashx_t *self, const void *key); + +// Reindexes an item from an old key to a new key\&. If there was no such +// item, does nothing\&. Returns 0 if successful, else \-1\&. +CZMQ_EXPORT int + zhashx_rename (zhashx_t *self, const void *old_key, const void *new_key); + +// Set a free function for the specified hash table item\&. When the item is +// destroyed, the free function, if any, is called on that item\&. +// Use this when hash items are dynamically allocated, to ensure that +// you don\*(Aqt have memory leaks\&. You can pass \*(Aqfree\*(Aq or NULL as a free_fn\&. +// Returns the item, or NULL if there is no such item\&. +CZMQ_EXPORT void * + zhashx_freefn (zhashx_t *self, const void *key, zhashx_free_fn free_fn); + +// Return the number of keys/items in the hash table +CZMQ_EXPORT size_t + zhashx_size (zhashx_t *self); + +// Return a zlistx_t containing the keys for the items in the +// table\&. Uses the key_duplicator to duplicate all keys and sets the +// key_destructor as destructor for the list\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT zlistx_t * + zhashx_keys (zhashx_t *self); + +// Return a zlistx_t containing the values for the items in the +// table\&. Uses the duplicator to duplicate all items and sets the +// destructor as destructor for the list\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT zlistx_t * + zhashx_values (zhashx_t *self); + +// Simple iterator; returns first item in hash table, in no given order, +// or NULL if the table is empty\&. This method is simpler to use than the +// foreach() method, which is deprecated\&. To access the key for this item +// use zhashx_cursor()\&. NOTE: do NOT modify the table while iterating\&. +CZMQ_EXPORT void * + zhashx_first (zhashx_t *self); + +// Simple iterator; returns next item in hash table, in no given order, +// or NULL if the last item was already returned\&. Use this together with +// zhashx_first() to process all items in a hash table\&. If you need the +// items in sorted order, use zhashx_keys() and then zlistx_sort()\&. To +// access the key for this item use zhashx_cursor()\&. NOTE: do NOT modify +// the table while iterating\&. +CZMQ_EXPORT void * + zhashx_next (zhashx_t *self); + +// After a successful first/next method, returns the key for the item that +// was returned\&. This is a constant string that you may not modify or +// deallocate, and which lasts as long as the item in the hash\&. After an +// unsuccessful first/next, returns NULL\&. +CZMQ_EXPORT const void * + zhashx_cursor (zhashx_t *self); + +// Add a comment to hash table before saving to disk\&. You can add as many +// comment lines as you like\&. These comment lines are discarded when loading +// the file\&. If you use a null format, all comments are deleted\&. +CZMQ_EXPORT void + zhashx_comment (zhashx_t *self, const char *format, \&.\&.\&.) CHECK_PRINTF (2); + +// Save hash table to a text file in name=value format\&. Hash values must be +// printable strings; keys may not contain \*(Aq=\*(Aq character\&. Returns 0 if OK, +// else \-1 if a file error occurred\&. +CZMQ_EXPORT int + zhashx_save (zhashx_t *self, const char *filename); + +// Load hash table from a text file in name=value format; hash table must +// already exist\&. Hash values must printable strings; keys may not contain +// \*(Aq=\*(Aq character\&. Returns 0 if OK, else \-1 if a file was not readable\&. +CZMQ_EXPORT int + zhashx_load (zhashx_t *self, const char *filename); + +// When a hash table was loaded from a file by zhashx_load, this method will +// reload the file if it has been modified since, and is "stable", i\&.e\&. not +// still changing\&. Returns 0 if OK, \-1 if there was an error reloading the +// file\&. +CZMQ_EXPORT int + zhashx_refresh (zhashx_t *self); + +// Serialize hash table to a binary frame that can be sent in a message\&. +// The packed format is compatible with the \*(Aqdictionary\*(Aq type defined in +// http://rfc\&.zeromq\&.org/spec:35/FILEMQ, and implemented by zproto: +// +// ; A list of name/value pairs +// dictionary = dict\-count *( dict\-name dict\-value ) +// dict\-count = number\-4 +// dict\-value = longstr +// dict\-name = string +// +// ; Strings are always length + text contents +// longstr = number\-4 *VCHAR +// string = number\-1 *VCHAR +// +// ; Numbers are unsigned integers in network byte order +// number\-1 = 1OCTET +// number\-4 = 4OCTET +// +// Comments are not included in the packed data\&. Item values MUST be +// strings\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT zframe_t * + zhashx_pack (zhashx_t *self); + +// Make a copy of the list; items are duplicated if you set a duplicator +// for the list, otherwise not\&. Copying a null reference returns a null +// reference\&. Note that this method\*(Aqs behavior changed slightly for CZMQ +// v3\&.x, as it does not set nor respect autofree\&. It does however let you +// duplicate any hash table safely\&. The old behavior is in zhashx_dup_v2\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT zhashx_t * + zhashx_dup (zhashx_t *self); + +// Set a user\-defined deallocator for hash items; by default items are not +// freed when the hash is destroyed\&. +CZMQ_EXPORT void + zhashx_set_destructor (zhashx_t *self, zhashx_destructor_fn destructor); + +// Set a user\-defined duplicator for hash items; by default items are not +// copied when the hash is duplicated\&. +CZMQ_EXPORT void + zhashx_set_duplicator (zhashx_t *self, zhashx_duplicator_fn duplicator); + +// Set a user\-defined deallocator for keys; by default keys are freed +// when the hash is destroyed using free()\&. +CZMQ_EXPORT void + zhashx_set_key_destructor (zhashx_t *self, zhashx_destructor_fn destructor); + +// Set a user\-defined duplicator for keys; by default keys are duplicated +// using strdup\&. +CZMQ_EXPORT void + zhashx_set_key_duplicator (zhashx_t *self, zhashx_duplicator_fn duplicator); + +// Set a user\-defined comparator for keys; by default keys are +// compared using strcmp\&. +CZMQ_EXPORT void + zhashx_set_key_comparator (zhashx_t *self, zhashx_comparator_fn comparator); + +// Set a user\-defined comparator for keys; by default keys are +// compared using strcmp\&. +CZMQ_EXPORT void + zhashx_set_key_hasher (zhashx_t *self, zhashx_hash_fn hasher); + +// Make copy of hash table; if supplied table is null, returns null\&. +// Does not copy items themselves\&. Rebuilds new table so may be slow on +// very large tables\&. NOTE: only works with item values that are strings +// since there\*(Aqs no other way to know how to duplicate the item value\&. +CZMQ_EXPORT zhashx_t * + zhashx_dup_v2 (zhashx_t *self); + +// Self test of this class\&. +CZMQ_EXPORT void + zhashx_test (bool verbose); + +#ifdef CZMQ_BUILD_DRAFT_API +// *** Draft method, for development use, may change without warning *** +// Same as unpack but uses a user\-defined deserializer function to convert +// a longstr back into item format\&. +CZMQ_EXPORT zhashx_t * + zhashx_unpack_own (zframe_t *frame, zhashx_deserializer_fn deserializer); + +// *** Draft method, for development use, may change without warning *** +// Same as pack but uses a user\-defined serializer function to convert items +// into longstr\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT zframe_t * + zhashx_pack_own (zhashx_t *self, zhashx_serializer_fn serializer); + +#endif // CZMQ_BUILD_DRAFT_API +Please add \*(Aq@interface\*(Aq section in \*(Aq\&./\&.\&./src/zhashx\&.c\*(Aq\&. +.fi +.SH "DESCRIPTION" +.sp +zhashx is an extended hash table container with more functionality than zhash, its simpler cousin\&. +.sp +The hash table always has a size that is prime and roughly doubles its size when 75% full\&. In case of hash collisions items are chained in a linked list\&. The hash table size is increased slightly (up to 5 times before roughly doubling the size) when an overly long chain (between 1 and 63 items depending on table size) is detected\&. +.SH "EXAMPLE" +.PP +\fBFrom zhashx_test method\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +zhashx_t *hash = zhashx_new (); +assert (hash); +assert (zhashx_size (hash) == 0); +assert (zhashx_first (hash) == NULL); +assert (zhashx_cursor (hash) == NULL); + +// Insert some items +int rc; +rc = zhashx_insert (hash, "DEADBEEF", "dead beef"); +char *item = (char *) zhashx_first (hash); +assert (streq ((char *) zhashx_cursor (hash), "DEADBEEF")); +assert (streq (item, "dead beef")); +assert (rc == 0); +rc = zhashx_insert (hash, "ABADCAFE", "a bad cafe"); +assert (rc == 0); +rc = zhashx_insert (hash, "C0DEDBAD", "coded bad"); +assert (rc == 0); +rc = zhashx_insert (hash, "DEADF00D", "dead food"); +assert (rc == 0); +assert (zhashx_size (hash) == 4); + +// Look for existing items +item = (char *) zhashx_lookup (hash, "DEADBEEF"); +assert (streq (item, "dead beef")); +item = (char *) zhashx_lookup (hash, "ABADCAFE"); +assert (streq (item, "a bad cafe")); +item = (char *) zhashx_lookup (hash, "C0DEDBAD"); +assert (streq (item, "coded bad")); +item = (char *) zhashx_lookup (hash, "DEADF00D"); +assert (streq (item, "dead food")); + +// Look for non\-existent items +item = (char *) zhashx_lookup (hash, "foo"); +assert (item == NULL); + +// Try to insert duplicate items +rc = zhashx_insert (hash, "DEADBEEF", "foo"); +assert (rc == \-1); +item = (char *) zhashx_lookup (hash, "DEADBEEF"); +assert (streq (item, "dead beef")); + +// Some rename tests + +// Valid rename, key is now LIVEBEEF +rc = zhashx_rename (hash, "DEADBEEF", "LIVEBEEF"); +assert (rc == 0); +item = (char *) zhashx_lookup (hash, "LIVEBEEF"); +assert (streq (item, "dead beef")); + +// Trying to rename an unknown item to a non\-existent key +rc = zhashx_rename (hash, "WHATBEEF", "NONESUCH"); +assert (rc == \-1); + +// Trying to rename an unknown item to an existing key +rc = zhashx_rename (hash, "WHATBEEF", "LIVEBEEF"); +assert (rc == \-1); +item = (char *) zhashx_lookup (hash, "LIVEBEEF"); +assert (streq (item, "dead beef")); + +// Trying to rename an existing item to another existing item +rc = zhashx_rename (hash, "LIVEBEEF", "ABADCAFE"); +assert (rc == \-1); +item = (char *) zhashx_lookup (hash, "LIVEBEEF"); +assert (streq (item, "dead beef")); +item = (char *) zhashx_lookup (hash, "ABADCAFE"); +assert (streq (item, "a bad cafe")); + +// Test keys method +zlistx_t *keys = zhashx_keys (hash); +assert (zlistx_size (keys) == 4); +zlistx_destroy (&keys); + +zlistx_t *values = zhashx_values(hash); +assert (zlistx_size (values) == 4); +zlistx_destroy (&values); + +// Test dup method +zhashx_t *copy = zhashx_dup (hash); +assert (zhashx_size (copy) == 4); +item = (char *) zhashx_lookup (copy, "LIVEBEEF"); +assert (item); +assert (streq (item, "dead beef")); +zhashx_destroy (©); + +// Test pack/unpack methods +zframe_t *frame = zhashx_pack (hash); +copy = zhashx_unpack (frame); +zframe_destroy (&frame); +assert (zhashx_size (copy) == 4); +item = (char *) zhashx_lookup (copy, "LIVEBEEF"); +assert (item); +assert (streq (item, "dead beef")); +zhashx_destroy (©); + +#ifdef CZMQ_BUILD_DRAFT_API +// Test own pack/unpack methods +zhashx_t *own_hash = zhashx_new (); +zhashx_set_destructor (own_hash, s_test_destroy_int); +assert (own_hash); +int *val1 = (int *) zmalloc (sizeof (int)); +int *val2 = (int *) zmalloc (sizeof (int)); +*val1 = 25; +*val2 = 100; +zhashx_insert (own_hash, "val1", val1); +zhashx_insert (own_hash, "val2", val2); +frame = zhashx_pack_own (own_hash, s_test_serialize_int); +copy = zhashx_unpack_own (frame, s_test_deserialze_int); +zhashx_set_destructor (copy, s_test_destroy_int); +zframe_destroy (&frame); +assert (zhashx_size (copy) == 2); +assert (*((int *) zhashx_lookup (copy, "val1")) == 25); +assert (*((int *) zhashx_lookup (copy, "val2")) == 100); +zhashx_destroy (©); +zhashx_destroy (&own_hash); +#endif // CZMQ_BUILD_DRAFT_API + +// Test save and load +zhashx_comment (hash, "This is a test file"); +zhashx_comment (hash, "Created by %s", "czmq_selftest"); +zhashx_save (hash, "\&.cache"); +copy = zhashx_new (); +assert (copy); +zhashx_load (copy, "\&.cache"); +item = (char *) zhashx_lookup (copy, "LIVEBEEF"); +assert (item); +assert (streq (item, "dead beef")); +zhashx_destroy (©); +zsys_file_delete ("\&.cache"); + +// Delete a item +zhashx_delete (hash, "LIVEBEEF"); +item = (char *) zhashx_lookup (hash, "LIVEBEEF"); +assert (item == NULL); +assert (zhashx_size (hash) == 3); + +// Check that the queue is robust against random usage +struct { + char name [100]; + bool exists; +} testset [200]; +memset (testset, 0, sizeof (testset)); +int testmax = 200, testnbr, iteration; + +srandom ((unsigned) time (NULL)); +for (iteration = 0; iteration < 25000; iteration++) { + testnbr = randof (testmax); + if (testset [testnbr]\&.exists) { + item = (char *) zhashx_lookup (hash, testset [testnbr]\&.name); + assert (item); + zhashx_delete (hash, testset [testnbr]\&.name); + testset [testnbr]\&.exists = false; + } + else { + sprintf (testset [testnbr]\&.name, "%x\-%x", rand (), rand ()); + if (zhashx_insert (hash, testset [testnbr]\&.name, "") == 0) + testset [testnbr]\&.exists = true; + } +} +// Test 10K lookups +for (iteration = 0; iteration < 10000; iteration++) + item = (char *) zhashx_lookup (hash, "DEADBEEFABADCAFE"); + +// Destructor should be safe to call twice +zhashx_destroy (&hash); +zhashx_destroy (&hash); +assert (hash == NULL); + +// Test destructor; automatically copies and frees string values +hash = zhashx_new (); +assert (hash); +zhashx_set_destructor (hash, (zhashx_destructor_fn *) zstr_free); +zhashx_set_duplicator (hash, (zhashx_duplicator_fn *) strdup); +char value [255]; +strcpy (value, "This is a string"); +rc = zhashx_insert (hash, "key1", value); +assert (rc == 0); +strcpy (value, "Ring a ding ding"); +rc = zhashx_insert (hash, "key2", value); +assert (rc == 0); +assert (streq ((char *) zhashx_lookup (hash, "key1"), "This is a string")); +assert (streq ((char *) zhashx_lookup (hash, "key2"), "Ring a ding ding")); +zhashx_destroy (&hash); +.fi +.if n \{\ +.RE +.\} +.sp +.SH "AUTHORS" +.sp +The czmq manual was written by the authors in the AUTHORS file\&. +.SH "RESOURCES" +.sp +Main web site: \m[blue]\fB\%\fR\m[] +.sp +Report bugs to the email <\m[blue]\fBzeromq\-dev@lists\&.zeromq\&.org\fR\m[]\&\s-2\u[1]\d\s+2> +.SH "COPYRIGHT" +.sp +Copyright (c) the Contributors as noted in the AUTHORS file\&. This file is part of CZMQ, the high\-level C binding for 0MQ: http://czmq\&.zeromq\&.org\&. This Source Code Form is subject to the terms of the Mozilla Public License, v\&. 2\&.0\&. If a copy of the MPL was not distributed with this file, You can obtain one at http://mozilla\&.org/MPL/2\&.0/\&. LICENSE included with the czmq distribution\&. +.SH "NOTES" +.IP " 1." 4 +zeromq-dev@lists.zeromq.org +.RS 4 +\%mailto:zeromq-dev@lists.zeromq.org +.RE diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/ziflist.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/ziflist.3 new file mode 100644 index 00000000000000..b50b06c0f3b98c --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/ziflist.3 @@ -0,0 +1,134 @@ +'\" t +.\" Title: ziflist +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.76.1 +.\" Date: 12/31/2016 +.\" Manual: CZMQ Manual +.\" Source: CZMQ 4.0.2 +.\" Language: English +.\" +.TH "ZIFLIST" "3" "12/31/2016" "CZMQ 4\&.0\&.2" "CZMQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +ziflist \- list of network interfaces available on system +.SH "SYNOPSIS" +.sp +.nf +// This is a stable class, and may not change except for emergencies\&. It +// is provided in stable builds\&. +// Get a list of network interfaces currently defined on the system +CZMQ_EXPORT ziflist_t * + ziflist_new (void); + +// Destroy a ziflist instance +CZMQ_EXPORT void + ziflist_destroy (ziflist_t **self_p); + +// Reload network interfaces from system +CZMQ_EXPORT void + ziflist_reload (ziflist_t *self); + +// Return the number of network interfaces on system +CZMQ_EXPORT size_t + ziflist_size (ziflist_t *self); + +// Get first network interface, return NULL if there are none +CZMQ_EXPORT const char * + ziflist_first (ziflist_t *self); + +// Get next network interface, return NULL if we hit the last one +CZMQ_EXPORT const char * + ziflist_next (ziflist_t *self); + +// Return the current interface IP address as a printable string +CZMQ_EXPORT const char * + ziflist_address (ziflist_t *self); + +// Return the current interface broadcast address as a printable string +CZMQ_EXPORT const char * + ziflist_broadcast (ziflist_t *self); + +// Return the current interface network mask as a printable string +CZMQ_EXPORT const char * + ziflist_netmask (ziflist_t *self); + +// Return the list of interfaces\&. +CZMQ_EXPORT void + ziflist_print (ziflist_t *self); + +// Self test of this class\&. +CZMQ_EXPORT void + ziflist_test (bool verbose); + +Please add \*(Aq@interface\*(Aq section in \*(Aq\&./\&.\&./src/ziflist\&.c\*(Aq\&. +.fi +.SH "DESCRIPTION" +.sp +The ziflist class takes a snapshot of the network interfaces that the system currently supports (this can change arbitrarily, especially on mobile devices)\&. The caller can then access the network interface information using an iterator that works like zlistx\&. Only stores those interfaces with broadcast capability, and ignores the loopback interface\&. +.sp +Please add \fI@discuss\fR section in \fI\&./\&.\&./src/ziflist\&.c\fR\&. +.SH "EXAMPLE" +.PP +\fBFrom ziflist_test method\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +ziflist_t *iflist = ziflist_new (); +assert (iflist); + +size_t items = ziflist_size (iflist); + +if (verbose) { + printf ("ziflist: interfaces=%zu\en", ziflist_size (iflist)); + const char *name = ziflist_first (iflist); + while (name) { + printf (" \- name=%s address=%s netmask=%s broadcast=%s\en", + name, ziflist_address (iflist), ziflist_netmask (iflist), ziflist_broadcast (iflist)); + name = ziflist_next (iflist); + } +} +ziflist_reload (iflist); +assert (items == ziflist_size (iflist)); +ziflist_destroy (&iflist); +.fi +.if n \{\ +.RE +.\} +.sp +.SH "AUTHORS" +.sp +The czmq manual was written by the authors in the AUTHORS file\&. +.SH "RESOURCES" +.sp +Main web site: \m[blue]\fB\%\fR\m[] +.sp +Report bugs to the email <\m[blue]\fBzeromq\-dev@lists\&.zeromq\&.org\fR\m[]\&\s-2\u[1]\d\s+2> +.SH "COPYRIGHT" +.sp +Copyright (c) the Contributors as noted in the AUTHORS file\&. This file is part of CZMQ, the high\-level C binding for 0MQ: http://czmq\&.zeromq\&.org\&. This Source Code Form is subject to the terms of the Mozilla Public License, v\&. 2\&.0\&. If a copy of the MPL was not distributed with this file, You can obtain one at http://mozilla\&.org/MPL/2\&.0/\&. LICENSE included with the czmq distribution\&. +.SH "NOTES" +.IP " 1." 4 +zeromq-dev@lists.zeromq.org +.RS 4 +\%mailto:zeromq-dev@lists.zeromq.org +.RE diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zlist.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zlist.3 new file mode 100644 index 00000000000000..a7131f40e00e1f --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zlist.3 @@ -0,0 +1,316 @@ +'\" t +.\" Title: zlist +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.76.1 +.\" Date: 12/31/2016 +.\" Manual: CZMQ Manual +.\" Source: CZMQ 4.0.2 +.\" Language: English +.\" +.TH "ZLIST" "3" "12/31/2016" "CZMQ 4\&.0\&.2" "CZMQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zlist \- simple generic list container +.SH "SYNOPSIS" +.sp +.nf +// This is a stable class, and may not change except for emergencies\&. It +// is provided in stable builds\&. +// Comparison function e\&.g\&. for sorting and removing\&. +typedef int (zlist_compare_fn) ( + void *item1, void *item2); + +// Callback function for zlist_freefn method +typedef void (zlist_free_fn) ( + void *data); + +// Create a new list container +CZMQ_EXPORT zlist_t * + zlist_new (void); + +// Destroy a list container +CZMQ_EXPORT void + zlist_destroy (zlist_t **self_p); + +// Return the item at the head of list\&. If the list is empty, returns NULL\&. +// Leaves cursor pointing at the head item, or NULL if the list is empty\&. +CZMQ_EXPORT void * + zlist_first (zlist_t *self); + +// Return the next item\&. If the list is empty, returns NULL\&. To move to +// the start of the list call zlist_first ()\&. Advances the cursor\&. +CZMQ_EXPORT void * + zlist_next (zlist_t *self); + +// Return the item at the tail of list\&. If the list is empty, returns NULL\&. +// Leaves cursor pointing at the tail item, or NULL if the list is empty\&. +CZMQ_EXPORT void * + zlist_last (zlist_t *self); + +// Return first item in the list, or null, leaves the cursor +CZMQ_EXPORT void * + zlist_head (zlist_t *self); + +// Return last item in the list, or null, leaves the cursor +CZMQ_EXPORT void * + zlist_tail (zlist_t *self); + +// Return the current item of list\&. If the list is empty, returns NULL\&. +// Leaves cursor pointing at the current item, or NULL if the list is empty\&. +CZMQ_EXPORT void * + zlist_item (zlist_t *self); + +// Append an item to the end of the list, return 0 if OK or \-1 if this +// failed for some reason (out of memory)\&. Note that if a duplicator has +// been set, this method will also duplicate the item\&. +CZMQ_EXPORT int + zlist_append (zlist_t *self, void *item); + +// Push an item to the start of the list, return 0 if OK or \-1 if this +// failed for some reason (out of memory)\&. Note that if a duplicator has +// been set, this method will also duplicate the item\&. +CZMQ_EXPORT int + zlist_push (zlist_t *self, void *item); + +// Pop the item off the start of the list, if any +CZMQ_EXPORT void * + zlist_pop (zlist_t *self); + +// Checks if an item already is present\&. Uses compare method to determine if +// items are equal\&. If the compare method is NULL the check will only compare +// pointers\&. Returns true if item is present else false\&. +CZMQ_EXPORT bool + zlist_exists (zlist_t *self, void *item); + +// Remove the specified item from the list if present +CZMQ_EXPORT void + zlist_remove (zlist_t *self, void *item); + +// Make a copy of list\&. If the list has autofree set, the copied list will +// duplicate all items, which must be strings\&. Otherwise, the list will hold +// pointers back to the items in the original list\&. If list is null, returns +// NULL\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT zlist_t * + zlist_dup (zlist_t *self); + +// Purge all items from list +CZMQ_EXPORT void + zlist_purge (zlist_t *self); + +// Return number of items in the list +CZMQ_EXPORT size_t + zlist_size (zlist_t *self); + +// Sort the list\&. If the compare function is null, sorts the list by +// ascending key value using a straight ASCII comparison\&. If you specify +// a compare function, this decides how items are sorted\&. The sort is not +// stable, so may reorder items with the same keys\&. The algorithm used is +// combsort, a compromise between performance and simplicity\&. +CZMQ_EXPORT void + zlist_sort (zlist_t *self, zlist_compare_fn compare); + +// Set list for automatic item destruction; item values MUST be strings\&. +// By default a list item refers to a value held elsewhere\&. When you set +// this, each time you append or push a list item, zlist will take a copy +// of the string value\&. Then, when you destroy the list, it will free all +// item values automatically\&. If you use any other technique to allocate +// list values, you must free them explicitly before destroying the list\&. +// The usual technique is to pop list items and destroy them, until the +// list is empty\&. +CZMQ_EXPORT void + zlist_autofree (zlist_t *self); + +// Sets a compare function for this list\&. The function compares two items\&. +// It returns an integer less than, equal to, or greater than zero if the +// first item is found, respectively, to be less than, to match, or be +// greater than the second item\&. +// This function is used for sorting, removal and exists checking\&. +CZMQ_EXPORT void + zlist_comparefn (zlist_t *self, zlist_compare_fn fn); + +// Set a free function for the specified list item\&. When the item is +// destroyed, the free function, if any, is called on that item\&. +// Use this when list items are dynamically allocated, to ensure that +// you don\*(Aqt have memory leaks\&. You can pass \*(Aqfree\*(Aq or NULL as a free_fn\&. +// Returns the item, or NULL if there is no such item\&. +CZMQ_EXPORT void * + zlist_freefn (zlist_t *self, void *item, zlist_free_fn fn, bool at_tail); + +// Self test of this class\&. +CZMQ_EXPORT void + zlist_test (bool verbose); + +Please add \*(Aq@interface\*(Aq section in \*(Aq\&./\&.\&./src/zlist\&.c\*(Aq\&. +.fi +.SH "DESCRIPTION" +.sp +Provides a generic container implementing a fast singly\-linked list\&. You can use this to construct multi\-dimensional lists, and other structures together with other generic containers like zhash\&. This is a simple class\&. For demanding applications we recommend using zlistx\&. +.sp +To iterate through a list, use zlist_first to get the first item, then loop while not null, and do zlist_next at the end of each iteration\&. +.SH "EXAMPLE" +.PP +\fBFrom zlist_test method\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +zlist_t *list = zlist_new (); +assert (list); +assert (zlist_size (list) == 0); + +// Three items we\*(Aqll use as test data +// List items are void *, not particularly strings +char *cheese = "boursin"; +char *bread = "baguette"; +char *wine = "bordeaux"; + +zlist_append (list, cheese); +assert (zlist_size (list) == 1); +assert ( zlist_exists (list, cheese)); +assert (!zlist_exists (list, bread)); +assert (!zlist_exists (list, wine)); +zlist_append (list, bread); +assert (zlist_size (list) == 2); +assert ( zlist_exists (list, cheese)); +assert ( zlist_exists (list, bread)); +assert (!zlist_exists (list, wine)); +zlist_append (list, wine); +assert (zlist_size (list) == 3); +assert ( zlist_exists (list, cheese)); +assert ( zlist_exists (list, bread)); +assert ( zlist_exists (list, wine)); + +assert (zlist_head (list) == cheese); +assert (zlist_next (list) == cheese); + +assert (zlist_first (list) == cheese); +assert (zlist_tail (list) == wine); +assert (zlist_next (list) == bread); + +assert (zlist_first (list) == cheese); +assert (zlist_next (list) == bread); +assert (zlist_next (list) == wine); +assert (zlist_next (list) == NULL); +// After we reach end of list, next wraps around +assert (zlist_next (list) == cheese); +assert (zlist_size (list) == 3); + +zlist_remove (list, wine); +assert (zlist_size (list) == 2); + +assert (zlist_first (list) == cheese); +zlist_remove (list, cheese); +assert (zlist_size (list) == 1); +assert (zlist_first (list) == bread); + +zlist_remove (list, bread); +assert (zlist_size (list) == 0); + +zlist_append (list, cheese); +zlist_append (list, bread); +assert (zlist_last (list) == bread); +zlist_remove (list, bread); +assert (zlist_last (list) == cheese); +zlist_remove (list, cheese); +assert (zlist_last (list) == NULL); + +zlist_push (list, cheese); +assert (zlist_size (list) == 1); +assert (zlist_first (list) == cheese); + +zlist_push (list, bread); +assert (zlist_size (list) == 2); +assert (zlist_first (list) == bread); +assert (zlist_item (list) == bread); + +zlist_append (list, wine); +assert (zlist_size (list) == 3); +assert (zlist_first (list) == bread); + +zlist_t *sub_list = zlist_dup (list); +assert (sub_list); +assert (zlist_size (sub_list) == 3); + +zlist_sort (list, NULL); +char *item; +item = (char *) zlist_pop (list); +assert (item == bread); +item = (char *) zlist_pop (list); +assert (item == wine); +item = (char *) zlist_pop (list); +assert (item == cheese); +assert (zlist_size (list) == 0); + +assert (zlist_size (sub_list) == 3); +zlist_push (list, sub_list); +zlist_t *sub_list_2 = zlist_dup (sub_list); +zlist_append (list, sub_list_2); +assert (zlist_freefn (list, sub_list, &s_zlist_free, false) == sub_list); +assert (zlist_freefn (list, sub_list_2, &s_zlist_free, true) == sub_list_2); +zlist_destroy (&list); + +// Test autofree functionality +list = zlist_new (); +assert (list); +zlist_autofree (list); +// Set equals function otherwise equals will not work as autofree copies strings +zlist_comparefn (list, (zlist_compare_fn *) strcmp); +zlist_push (list, bread); +zlist_append (list, cheese); +assert (zlist_size (list) == 2); +zlist_append (list, wine); +assert (zlist_exists (list, wine)); +zlist_remove (list, wine); +assert (!zlist_exists (list, wine)); +assert (streq ((const char *) zlist_first (list), bread)); +item = (char *) zlist_pop (list); +assert (streq (item, bread)); +free (item); +item = (char *) zlist_pop (list); +assert (streq (item, cheese)); +free (item); + +zlist_destroy (&list); +assert (list == NULL); +.fi +.if n \{\ +.RE +.\} +.sp +.SH "AUTHORS" +.sp +The czmq manual was written by the authors in the AUTHORS file\&. +.SH "RESOURCES" +.sp +Main web site: \m[blue]\fB\%\fR\m[] +.sp +Report bugs to the email <\m[blue]\fBzeromq\-dev@lists\&.zeromq\&.org\fR\m[]\&\s-2\u[1]\d\s+2> +.SH "COPYRIGHT" +.sp +Copyright (c) the Contributors as noted in the AUTHORS file\&. This file is part of CZMQ, the high\-level C binding for 0MQ: http://czmq\&.zeromq\&.org\&. This Source Code Form is subject to the terms of the Mozilla Public License, v\&. 2\&.0\&. If a copy of the MPL was not distributed with this file, You can obtain one at http://mozilla\&.org/MPL/2\&.0/\&. LICENSE included with the czmq distribution\&. +.SH "NOTES" +.IP " 1." 4 +zeromq-dev@lists.zeromq.org +.RS 4 +\%mailto:zeromq-dev@lists.zeromq.org +.RE diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zlistx.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zlistx.3 new file mode 100644 index 00000000000000..2e1068554b6945 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zlistx.3 @@ -0,0 +1,346 @@ +'\" t +.\" Title: zlistx +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.76.1 +.\" Date: 12/31/2016 +.\" Manual: CZMQ Manual +.\" Source: CZMQ 4.0.2 +.\" Language: English +.\" +.TH "ZLISTX" "3" "12/31/2016" "CZMQ 4\&.0\&.2" "CZMQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zlistx \- extended generic list container +.SH "SYNOPSIS" +.sp +.nf +// This is a stable class, and may not change except for emergencies\&. It +// is provided in stable builds\&. +// Destroy an item +typedef void (zlistx_destructor_fn) ( + void **item); + +// Duplicate an item +typedef void * (zlistx_duplicator_fn) ( + const void *item); + +// Compare two items, for sorting +typedef int (zlistx_comparator_fn) ( + const void *item1, const void *item2); + +// Create a new, empty list\&. +CZMQ_EXPORT zlistx_t * + zlistx_new (void); + +// Destroy a list\&. If an item destructor was specified, all items in the +// list are automatically destroyed as well\&. +CZMQ_EXPORT void + zlistx_destroy (zlistx_t **self_p); + +// Add an item to the head of the list\&. Calls the item duplicator, if any, +// on the item\&. Resets cursor to list head\&. Returns an item handle on +// success, NULL if memory was exhausted\&. +CZMQ_EXPORT void * + zlistx_add_start (zlistx_t *self, void *item); + +// Add an item to the tail of the list\&. Calls the item duplicator, if any, +// on the item\&. Resets cursor to list head\&. Returns an item handle on +// success, NULL if memory was exhausted\&. +CZMQ_EXPORT void * + zlistx_add_end (zlistx_t *self, void *item); + +// Return the number of items in the list +CZMQ_EXPORT size_t + zlistx_size (zlistx_t *self); + +// Return first item in the list, or null, leaves the cursor +CZMQ_EXPORT void * + zlistx_head (zlistx_t *self); + +// Return last item in the list, or null, leaves the cursor +CZMQ_EXPORT void * + zlistx_tail (zlistx_t *self); + +// Return the item at the head of list\&. If the list is empty, returns NULL\&. +// Leaves cursor pointing at the head item, or NULL if the list is empty\&. +CZMQ_EXPORT void * + zlistx_first (zlistx_t *self); + +// Return the next item\&. At the end of the list (or in an empty list), +// returns NULL\&. Use repeated zlistx_next () calls to work through the list +// from zlistx_first ()\&. First time, acts as zlistx_first()\&. +CZMQ_EXPORT void * + zlistx_next (zlistx_t *self); + +// Return the previous item\&. At the start of the list (or in an empty list), +// returns NULL\&. Use repeated zlistx_prev () calls to work through the list +// backwards from zlistx_last ()\&. First time, acts as zlistx_last()\&. +CZMQ_EXPORT void * + zlistx_prev (zlistx_t *self); + +// Return the item at the tail of list\&. If the list is empty, returns NULL\&. +// Leaves cursor pointing at the tail item, or NULL if the list is empty\&. +CZMQ_EXPORT void * + zlistx_last (zlistx_t *self); + +// Returns the value of the item at the cursor, or NULL if the cursor is +// not pointing to an item\&. +CZMQ_EXPORT void * + zlistx_item (zlistx_t *self); + +// Returns the handle of the item at the cursor, or NULL if the cursor is +// not pointing to an item\&. +CZMQ_EXPORT void * + zlistx_cursor (zlistx_t *self); + +// Returns the item associated with the given list handle, or NULL if passed +// in handle is NULL\&. Asserts that the passed in handle points to a list element\&. +CZMQ_EXPORT void * + zlistx_handle_item (void *handle); + +// Find an item in the list, searching from the start\&. Uses the item +// comparator, if any, else compares item values directly\&. Returns the +// item handle found, or NULL\&. Sets the cursor to the found item, if any\&. +CZMQ_EXPORT void * + zlistx_find (zlistx_t *self, void *item); + +// Detach an item from the list, using its handle\&. The item is not modified, +// and the caller is responsible for destroying it if necessary\&. If handle is +// null, detaches the first item on the list\&. Returns item that was detached, +// or null if none was\&. If cursor was at item, moves cursor to previous item, +// so you can detach items while iterating forwards through a list\&. +CZMQ_EXPORT void * + zlistx_detach (zlistx_t *self, void *handle); + +// Detach item at the cursor, if any, from the list\&. The item is not modified, +// and the caller is responsible for destroying it as necessary\&. Returns item +// that was detached, or null if none was\&. Moves cursor to previous item, so +// you can detach items while iterating forwards through a list\&. +CZMQ_EXPORT void * + zlistx_detach_cur (zlistx_t *self); + +// Delete an item, using its handle\&. Calls the item destructor is any is +// set\&. If handle is null, deletes the first item on the list\&. Returns 0 +// if an item was deleted, \-1 if not\&. If cursor was at item, moves cursor +// to previous item, so you can delete items while iterating forwards +// through a list\&. +CZMQ_EXPORT int + zlistx_delete (zlistx_t *self, void *handle); + +// Move an item to the start of the list, via its handle\&. +CZMQ_EXPORT void + zlistx_move_start (zlistx_t *self, void *handle); + +// Move an item to the end of the list, via its handle\&. +CZMQ_EXPORT void + zlistx_move_end (zlistx_t *self, void *handle); + +// Remove all items from the list, and destroy them if the item destructor +// is set\&. +CZMQ_EXPORT void + zlistx_purge (zlistx_t *self); + +// Sort the list\&. If an item comparator was set, calls that to compare +// items, otherwise compares on item value\&. The sort is not stable, so may +// reorder equal items\&. +CZMQ_EXPORT void + zlistx_sort (zlistx_t *self); + +// Create a new node and insert it into a sorted list\&. Calls the item +// duplicator, if any, on the item\&. If low_value is true, starts searching +// from the start of the list, otherwise searches from the end\&. Use the item +// comparator, if any, to find where to place the new node\&. Returns a handle +// to the new node, or NULL if memory was exhausted\&. Resets the cursor to the +// list head\&. +CZMQ_EXPORT void * + zlistx_insert (zlistx_t *self, void *item, bool low_value); + +// Move an item, specified by handle, into position in a sorted list\&. Uses +// the item comparator, if any, to determine the new location\&. If low_value +// is true, starts searching from the start of the list, otherwise searches +// from the end\&. +CZMQ_EXPORT void + zlistx_reorder (zlistx_t *self, void *handle, bool low_value); + +// Make a copy of the list; items are duplicated if you set a duplicator +// for the list, otherwise not\&. Copying a null reference returns a null +// reference\&. +CZMQ_EXPORT zlistx_t * + zlistx_dup (zlistx_t *self); + +// Set a user\-defined deallocator for list items; by default items are not +// freed when the list is destroyed\&. +CZMQ_EXPORT void + zlistx_set_destructor (zlistx_t *self, zlistx_destructor_fn destructor); + +// Set a user\-defined duplicator for list items; by default items are not +// copied when the list is duplicated\&. +CZMQ_EXPORT void + zlistx_set_duplicator (zlistx_t *self, zlistx_duplicator_fn duplicator); + +// Set a user\-defined comparator for zlistx_find and zlistx_sort; the method +// must return \-1, 0, or 1 depending on whether item1 is less than, equal to, +// or greater than, item2\&. +CZMQ_EXPORT void + zlistx_set_comparator (zlistx_t *self, zlistx_comparator_fn comparator); + +// Self test of this class\&. +CZMQ_EXPORT void + zlistx_test (bool verbose); + +Please add \*(Aq@interface\*(Aq section in \*(Aq\&./\&.\&./src/zlistx\&.c\*(Aq\&. +.fi +.SH "DESCRIPTION" +.sp +Provides a generic doubly\-linked list container\&. This container provides hooks for duplicator, comparator, and destructor functions\&. These tie into CZMQ and standard C semantics, so e\&.g\&. for string items you can use strdup, strcmp, and zstr_free\&. To store custom objects, define your own duplicator and comparator, and use the standard object destructor\&. +.sp +This is a reworking of the simpler zlist container\&. It is faster to insert and delete items anywhere in the list, and to keep ordered lists\&. +.SH "EXAMPLE" +.PP +\fBFrom zlistx_test method\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +zlistx_t *list = zlistx_new (); +assert (list); +assert (zlistx_size (list) == 0); + +// Test operations on an empty list +assert (zlistx_first (list) == NULL); +assert (zlistx_last (list) == NULL); +assert (zlistx_next (list) == NULL); +assert (zlistx_prev (list) == NULL); +assert (zlistx_find (list, "hello") == NULL); +assert (zlistx_delete (list, NULL) == \-1); +assert (zlistx_detach (list, NULL) == NULL); +assert (zlistx_delete (list, NULL) == \-1); +assert (zlistx_detach (list, NULL) == NULL); +zlistx_purge (list); +zlistx_sort (list); + +// Use item handlers +zlistx_set_destructor (list, (zlistx_destructor_fn *) zstr_free); +zlistx_set_duplicator (list, (zlistx_duplicator_fn *) strdup); +zlistx_set_comparator (list, (zlistx_comparator_fn *) strcmp); + +// Try simple insert/sort/delete/next +assert (zlistx_next (list) == NULL); +zlistx_add_end (list, "world"); +assert (streq ((char *) zlistx_next (list), "world")); +zlistx_add_end (list, "hello"); +assert (streq ((char *) zlistx_prev (list), "hello")); +zlistx_sort (list); +assert (zlistx_size (list) == 2); +void *handle = zlistx_find (list, "hello"); +char *item1 = (char *) zlistx_item (list); +char *item2 = (char *) zlistx_handle_item (handle); +assert (item1 == item2); +assert (streq (item1, "hello")); +zlistx_delete (list, handle); +assert (zlistx_size (list) == 1); +char *string = (char *) zlistx_detach (list, NULL); +assert (streq (string, "world")); +free (string); +assert (zlistx_size (list) == 0); + +// Check next/back work +// Now populate the list with items +zlistx_add_start (list, "five"); +zlistx_add_end (list, "six"); +zlistx_add_start (list, "four"); +zlistx_add_end (list, "seven"); +zlistx_add_start (list, "three"); +zlistx_add_end (list, "eight"); +zlistx_add_start (list, "two"); +zlistx_add_end (list, "nine"); +zlistx_add_start (list, "one"); +zlistx_add_end (list, "ten"); + +// Test our navigation skills +assert (zlistx_size (list) == 10); +assert (streq ((char *) zlistx_last (list), "ten")); +assert (streq ((char *) zlistx_prev (list), "nine")); +assert (streq ((char *) zlistx_prev (list), "eight")); +assert (streq ((char *) zlistx_prev (list), "seven")); +assert (streq ((char *) zlistx_prev (list), "six")); +assert (streq ((char *) zlistx_prev (list), "five")); +assert (streq ((char *) zlistx_first (list), "one")); +assert (streq ((char *) zlistx_next (list), "two")); +assert (streq ((char *) zlistx_next (list), "three")); +assert (streq ((char *) zlistx_next (list), "four")); + +// Sort by alphabetical order +zlistx_sort (list); +assert (streq ((char *) zlistx_first (list), "eight")); +assert (streq ((char *) zlistx_last (list), "two")); + +// Moving items around +handle = zlistx_find (list, "six"); +zlistx_move_start (list, handle); +assert (streq ((char *) zlistx_first (list), "six")); +zlistx_move_end (list, handle); +assert (streq ((char *) zlistx_last (list), "six")); +zlistx_sort (list); +assert (streq ((char *) zlistx_last (list), "two")); + +// Copying a list +zlistx_t *copy = zlistx_dup (list); +assert (copy); +assert (zlistx_size (copy) == 10); +assert (streq ((char *) zlistx_first (copy), "eight")); +assert (streq ((char *) zlistx_last (copy), "two")); +zlistx_destroy (©); + +// Delete items while iterating +string = (char *) zlistx_first (list); +assert (streq (string, "eight")); +string = (char *) zlistx_next (list); +assert (streq (string, "five")); +zlistx_delete (list, zlistx_cursor (list)); +string = (char *) zlistx_next (list); +assert (streq (string, "four")); + +zlistx_purge (list); +zlistx_destroy (&list); +.fi +.if n \{\ +.RE +.\} +.sp +.SH "AUTHORS" +.sp +The czmq manual was written by the authors in the AUTHORS file\&. +.SH "RESOURCES" +.sp +Main web site: \m[blue]\fB\%\fR\m[] +.sp +Report bugs to the email <\m[blue]\fBzeromq\-dev@lists\&.zeromq\&.org\fR\m[]\&\s-2\u[1]\d\s+2> +.SH "COPYRIGHT" +.sp +Copyright (c) the Contributors as noted in the AUTHORS file\&. This file is part of CZMQ, the high\-level C binding for 0MQ: http://czmq\&.zeromq\&.org\&. This Source Code Form is subject to the terms of the Mozilla Public License, v\&. 2\&.0\&. If a copy of the MPL was not distributed with this file, You can obtain one at http://mozilla\&.org/MPL/2\&.0/\&. LICENSE included with the czmq distribution\&. +.SH "NOTES" +.IP " 1." 4 +zeromq-dev@lists.zeromq.org +.RS 4 +\%mailto:zeromq-dev@lists.zeromq.org +.RE diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zloop.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zloop.3 new file mode 100644 index 00000000000000..7d5c84949f542e --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zloop.3 @@ -0,0 +1,261 @@ +'\" t +.\" Title: zloop +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.76.1 +.\" Date: 12/31/2016 +.\" Manual: CZMQ Manual +.\" Source: CZMQ 4.0.2 +.\" Language: English +.\" +.TH "ZLOOP" "3" "12/31/2016" "CZMQ 4\&.0\&.2" "CZMQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zloop \- event\-driven reactor +.SH "SYNOPSIS" +.sp +.nf +// This is a stable class, and may not change except for emergencies\&. It +// is provided in stable builds\&. +// Callback function for reactor socket activity +typedef int (zloop_reader_fn) ( + zloop_t *loop, zsock_t *reader, void *arg); + +// Callback function for reactor events (low\-level) +typedef int (zloop_fn) ( + zloop_t *loop, zmq_pollitem_t *item, void *arg); + +// Callback for reactor timer events +typedef int (zloop_timer_fn) ( + zloop_t *loop, int timer_id, void *arg); + +// Create a new zloop reactor +CZMQ_EXPORT zloop_t * + zloop_new (void); + +// Destroy a reactor +CZMQ_EXPORT void + zloop_destroy (zloop_t **self_p); + +// Register socket reader with the reactor\&. When the reader has messages, +// the reactor will call the handler, passing the arg\&. Returns 0 if OK, \-1 +// if there was an error\&. If you register the same socket more than once, +// each instance will invoke its corresponding handler\&. +CZMQ_EXPORT int + zloop_reader (zloop_t *self, zsock_t *sock, zloop_reader_fn handler, void *arg); + +// Cancel a socket reader from the reactor\&. If multiple readers exist for +// same socket, cancels ALL of them\&. +CZMQ_EXPORT void + zloop_reader_end (zloop_t *self, zsock_t *sock); + +// Configure a registered reader to ignore errors\&. If you do not set this, +// then readers that have errors are removed from the reactor silently\&. +CZMQ_EXPORT void + zloop_reader_set_tolerant (zloop_t *self, zsock_t *sock); + +// Register low\-level libzmq pollitem with the reactor\&. When the pollitem +// is ready, will call the handler, passing the arg\&. Returns 0 if OK, \-1 +// if there was an error\&. If you register the pollitem more than once, each +// instance will invoke its corresponding handler\&. A pollitem with +// socket=NULL and fd=0 means \*(Aqpoll on FD zero\*(Aq\&. +CZMQ_EXPORT int + zloop_poller (zloop_t *self, zmq_pollitem_t *item, zloop_fn handler, void *arg); + +// Cancel a pollitem from the reactor, specified by socket or FD\&. If both +// are specified, uses only socket\&. If multiple poll items exist for same +// socket/FD, cancels ALL of them\&. +CZMQ_EXPORT void + zloop_poller_end (zloop_t *self, zmq_pollitem_t *item); + +// Configure a registered poller to ignore errors\&. If you do not set this, +// then poller that have errors are removed from the reactor silently\&. +CZMQ_EXPORT void + zloop_poller_set_tolerant (zloop_t *self, zmq_pollitem_t *item); + +// Register a timer that expires after some delay and repeats some number of +// times\&. At each expiry, will call the handler, passing the arg\&. To run a +// timer forever, use 0 times\&. Returns a timer_id that is used to cancel the +// timer in the future\&. Returns \-1 if there was an error\&. +CZMQ_EXPORT int + zloop_timer (zloop_t *self, size_t delay, size_t times, zloop_timer_fn handler, void *arg); + +// Cancel a specific timer identified by a specific timer_id (as returned by +// zloop_timer)\&. +CZMQ_EXPORT int + zloop_timer_end (zloop_t *self, int timer_id); + +// Register a ticket timer\&. Ticket timers are very fast in the case where +// you use a lot of timers (thousands), and frequently remove and add them\&. +// The main use case is expiry timers for servers that handle many clients, +// and which reset the expiry timer for each message received from a client\&. +// Whereas normal timers perform poorly as the number of clients grows, the +// cost of ticket timers is constant, no matter the number of clients\&. You +// must set the ticket delay using zloop_set_ticket_delay before creating a +// ticket\&. Returns a handle to the timer that you should use in +// zloop_ticket_reset and zloop_ticket_delete\&. +CZMQ_EXPORT void * + zloop_ticket (zloop_t *self, zloop_timer_fn handler, void *arg); + +// Reset a ticket timer, which moves it to the end of the ticket list and +// resets its execution time\&. This is a very fast operation\&. +CZMQ_EXPORT void + zloop_ticket_reset (zloop_t *self, void *handle); + +// Delete a ticket timer\&. We do not actually delete the ticket here, as +// other code may still refer to the ticket\&. We mark as deleted, and remove +// later and safely\&. +CZMQ_EXPORT void + zloop_ticket_delete (zloop_t *self, void *handle); + +// Set the ticket delay, which applies to all tickets\&. If you lower the +// delay and there are already tickets created, the results are undefined\&. +CZMQ_EXPORT void + zloop_set_ticket_delay (zloop_t *self, size_t ticket_delay); + +// Set hard limit on number of timers allowed\&. Setting more than a small +// number of timers (10\-100) can have a dramatic impact on the performance +// of the reactor\&. For high\-volume cases, use ticket timers\&. If the hard +// limit is reached, the reactor stops creating new timers and logs an +// error\&. +CZMQ_EXPORT void + zloop_set_max_timers (zloop_t *self, size_t max_timers); + +// Set verbose tracing of reactor on/off\&. The default verbose setting is +// off (false)\&. +CZMQ_EXPORT void + zloop_set_verbose (zloop_t *self, bool verbose); + +// By default the reactor stops if the process receives a SIGINT or SIGTERM +// signal\&. This makes it impossible to shut\-down message based architectures +// like zactors\&. This method lets you switch off break handling\&. The default +// nonstop setting is off (false)\&. +CZMQ_EXPORT void + zloop_set_nonstop (zloop_t *self, bool nonstop); + +// Start the reactor\&. Takes control of the thread and returns when the 0MQ +// context is terminated or the process is interrupted, or any event handler +// returns \-1\&. Event handlers may register new sockets and timers, and +// cancel sockets\&. Returns 0 if interrupted, \-1 if canceled by a handler\&. +CZMQ_EXPORT int + zloop_start (zloop_t *self); + +// Self test of this class\&. +CZMQ_EXPORT void + zloop_test (bool verbose); + +Please add \*(Aq@interface\*(Aq section in \*(Aq\&./\&.\&./src/zloop\&.c\*(Aq\&. +.fi +.SH "DESCRIPTION" +.sp +The zloop class provides an event\-driven reactor pattern\&. The reactor handles zmq_pollitem_t items (pollers or writers, sockets or fds), and once\-off or repeated timers\&. Its resolution is 1 msec\&. It uses a tickless timer to reduce CPU interrupts in inactive processes\&. +.sp +Please add \fI@discuss\fR section in \fI\&./\&.\&./src/zloop\&.c\fR\&. +.SH "EXAMPLE" +.PP +\fBFrom zloop_test method\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +// Create two PAIR sockets and connect over inproc +zsock_t *output = zsock_new (ZMQ_PAIR); +assert (output); +zsock_bind (output, "inproc://zloop\&.test"); + +zsock_t *input = zsock_new (ZMQ_PAIR); +assert (input); +zsock_connect (input, "inproc://zloop\&.test"); + +zloop_t *loop = zloop_new (); +assert (loop); +zloop_set_verbose (loop, verbose); + +// Create a timer that will be cancelled +int timer_id = zloop_timer (loop, 1000, 1, s_timer_event, NULL); +zloop_timer (loop, 5, 1, s_cancel_timer_event, &timer_id); + +// After 20 msecs, send a ping message to output3 +zloop_timer (loop, 20, 1, s_timer_event, output); + +// Set up some tickets that will never expire +zloop_set_ticket_delay (loop, 10000); +void *ticket1 = zloop_ticket (loop, s_timer_event, NULL); +void *ticket2 = zloop_ticket (loop, s_timer_event, NULL); +void *ticket3 = zloop_ticket (loop, s_timer_event, NULL); + +// When we get the ping message, end the reactor +rc = zloop_reader (loop, input, s_socket_event, NULL); +assert (rc == 0); +zloop_reader_set_tolerant (loop, input); +zloop_start (loop); + +zloop_ticket_delete (loop, ticket1); +zloop_ticket_delete (loop, ticket2); +zloop_ticket_delete (loop, ticket3); + +// Check whether loop properly ignores zsys_interrupted flag +// when asked to +zloop_destroy (&loop); +loop = zloop_new (); + +bool timer_event_called = false; +zloop_timer (loop, 1, 1, s_timer_event3, &timer_event_called); + +zsys_interrupted = 1; +zloop_start (loop); +// zloop returns immediately without giving any handler a chance to run +assert (!timer_event_called); + +zloop_set_nonstop (loop, true); +zloop_start (loop); +// zloop runs the handler which will terminate the loop +assert (timer_event_called); +zsys_interrupted = 0; + +// cleanup +zloop_destroy (&loop); +assert (loop == NULL); + +zsock_destroy (&input); +zsock_destroy (&output); +.fi +.if n \{\ +.RE +.\} +.sp +.SH "AUTHORS" +.sp +The czmq manual was written by the authors in the AUTHORS file\&. +.SH "RESOURCES" +.sp +Main web site: \m[blue]\fB\%\fR\m[] +.sp +Report bugs to the email <\m[blue]\fBzeromq\-dev@lists\&.zeromq\&.org\fR\m[]\&\s-2\u[1]\d\s+2> +.SH "COPYRIGHT" +.sp +Copyright (c) the Contributors as noted in the AUTHORS file\&. This file is part of CZMQ, the high\-level C binding for 0MQ: http://czmq\&.zeromq\&.org\&. This Source Code Form is subject to the terms of the Mozilla Public License, v\&. 2\&.0\&. If a copy of the MPL was not distributed with this file, You can obtain one at http://mozilla\&.org/MPL/2\&.0/\&. LICENSE included with the czmq distribution\&. +.SH "NOTES" +.IP " 1." 4 +zeromq-dev@lists.zeromq.org +.RS 4 +\%mailto:zeromq-dev@lists.zeromq.org +.RE diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zmonitor.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zmonitor.3 new file mode 100644 index 00000000000000..8d716863d4544c --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zmonitor.3 @@ -0,0 +1,157 @@ +'\" t +.\" Title: zmonitor +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.76.1 +.\" Date: 12/31/2016 +.\" Manual: CZMQ Manual +.\" Source: CZMQ 4.0.2 +.\" Language: English +.\" +.TH "ZMONITOR" "3" "12/31/2016" "CZMQ 4\&.0\&.2" "CZMQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zmonitor \- socket event monitor +.SH "SYNOPSIS" +.sp +.nf +// Create new zmonitor actor instance to monitor a zsock_t socket: +// +// zactor_t *monitor = zactor_new (zmonitor, mysocket); +// +// Destroy zmonitor instance\&. +// +// zactor_destroy (&monitor); +// +// Enable verbose logging of commands and activity\&. +// +// zstr_send (monitor, "VERBOSE"); +// +// Listen to monitor event type (zero or types, ending in NULL): +// zstr_sendx (monitor, "LISTEN", type, \&.\&.\&., NULL); +// +// Events: +// CONNECTED +// CONNECT_DELAYED +// CONNECT_RETRIED +// LISTENING +// BIND_FAILED +// ACCEPTED +// ACCEPT_FAILED +// CLOSED +// CLOSE_FAILED +// DISCONNECTED +// MONITOR_STOPPED +// ALL +// +// Start monitor; after this, any further LISTEN commands are ignored\&. +// +// zstr_send (monitor, "START"); +// zsock_wait (monitor); +// +// Receive next monitor event: +// +// zmsg_t *msg = zmsg_recv (monitor); +// +// This is the zmonitor constructor as a zactor_fn; the argument can be +// a zactor_t, zsock_t, or libzmq void * socket: +CZMQ_EXPORT void + zmonitor (zsock_t *pipe, void *sock); + +// Selftest +CZMQ_EXPORT void + zmonitor_test (bool verbose); +Please add \*(Aq@interface\*(Aq section in \*(Aq\&./\&.\&./src/zmonitor\&.c\*(Aq\&. +.fi +.SH "DESCRIPTION" +.sp +The zmonitor actor provides an API for obtaining socket events such as connected, listen, disconnected, etc\&. Socket events are only available for sockets connecting or bound to ipc:// and tcp:// endpoints\&. +.sp +This class wraps the ZMQ socket monitor API, see zmq_socket_monitor for details\&. Works on all versions of libzmq from 3\&.2 onwards\&. This class replaces zproxy_v2, and is meant for applications that use the CZMQ v3 API (meaning, zsock)\&. +.SH "EXAMPLE" +.PP +\fBFrom zmonitor_test method\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +zsock_t *client = zsock_new (ZMQ_DEALER); +assert (client); +zactor_t *clientmon = zactor_new (zmonitor, client); +assert (clientmon); +if (verbose) + zstr_sendx (clientmon, "VERBOSE", NULL); +zstr_sendx (clientmon, "LISTEN", "LISTENING", "ACCEPTED", NULL); +zstr_sendx (clientmon, "START", NULL); +zsock_wait (clientmon); + +zsock_t *server = zsock_new (ZMQ_DEALER); +assert (server); +zactor_t *servermon = zactor_new (zmonitor, server); +assert (servermon); +if (verbose) + zstr_sendx (servermon, "VERBOSE", NULL); +zstr_sendx (servermon, "LISTEN", "CONNECTED", "DISCONNECTED", NULL); +zstr_sendx (servermon, "START", NULL); +zsock_wait (servermon); + +// Allow a brief time for the message to get there\&.\&.\&. +zmq_poll (NULL, 0, 200); + +// Check client is now listening +int port_nbr = zsock_bind (client, "tcp://127\&.0\&.0\&.1:*"); +assert (port_nbr != \-1); +s_assert_event (clientmon, "LISTENING"); + +// Check server connected to client +zsock_connect (server, "tcp://127\&.0\&.0\&.1:%d", port_nbr); +s_assert_event (servermon, "CONNECTED"); + +// Check client accepted connection +s_assert_event (clientmon, "ACCEPTED"); + +zactor_destroy (&clientmon); +zactor_destroy (&servermon); +zsock_destroy (&client); +zsock_destroy (&server); +#endif +.fi +.if n \{\ +.RE +.\} +.sp +.SH "AUTHORS" +.sp +The czmq manual was written by the authors in the AUTHORS file\&. +.SH "RESOURCES" +.sp +Main web site: \m[blue]\fB\%\fR\m[] +.sp +Report bugs to the email <\m[blue]\fBzeromq\-dev@lists\&.zeromq\&.org\fR\m[]\&\s-2\u[1]\d\s+2> +.SH "COPYRIGHT" +.sp +Copyright (c) the Contributors as noted in the AUTHORS file\&. This file is part of CZMQ, the high\-level C binding for 0MQ: http://czmq\&.zeromq\&.org\&. This Source Code Form is subject to the terms of the Mozilla Public License, v\&. 2\&.0\&. If a copy of the MPL was not distributed with this file, You can obtain one at http://mozilla\&.org/MPL/2\&.0/\&. LICENSE included with the czmq distribution\&. +.SH "NOTES" +.IP " 1." 4 +zeromq-dev@lists.zeromq.org +.RS 4 +\%mailto:zeromq-dev@lists.zeromq.org +.RE diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_atomic_counter_dec.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_atomic_counter_dec.3 new file mode 100644 index 00000000000000..40fde8be8d9bfb --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_atomic_counter_dec.3 @@ -0,0 +1,73 @@ +'\" t +.\" Title: zmq_atomic_counter_dec +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.78.1 +.\" Date: 02/18/2017 +.\" Manual: 0MQ Manual +.\" Source: 0MQ 4.2.2 +.\" Language: English +.\" +.TH "ZMQ_ATOMIC_COUNTER_D" "3" "02/18/2017" "0MQ 4\&.2\&.2" "0MQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zmq_atomic_counter_dec \- decrement an atomic counter +.SH "SYNOPSIS" +.sp +\fBint zmq_atomic_counter_dec (void *counter);\fR +.SH "DESCRIPTION" +.sp +The \fIzmq_atomic_counter_dec\fR function decrements an atomic counter in a threadsafe fashion\&. This function uses platform specific atomic operations\&. +.SH "RETURN VALUE" +.sp +The \fIzmq_atomic_counter_dec()\fR function returns 1 if the counter is greater than zero after decrementing, or zero if the counter reached zero\&. +.SH "EXAMPLE" +.PP +\fBTest code for atomic counters\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +void *counter = zmq_atomic_counter_new (); +assert (zmq_atomic_counter_value (counter) == 0); +assert (zmq_atomic_counter_inc (counter) == 0); +assert (zmq_atomic_counter_inc (counter) == 1); +assert (zmq_atomic_counter_inc (counter) == 2); +assert (zmq_atomic_counter_value (counter) == 3); +assert (zmq_atomic_counter_dec (counter) == 1); +assert (zmq_atomic_counter_dec (counter) == 1); +assert (zmq_atomic_counter_dec (counter) == 0); +zmq_atomic_counter_set (counter, 2); +assert (zmq_atomic_counter_dec (counter) == 1); +assert (zmq_atomic_counter_dec (counter) == 0); +zmq_atomic_counter_destroy (&counter); +return 0; +.fi +.if n \{\ +.RE +.\} +.sp +.SH "SEE ALSO" +.sp +\fBzmq_atomic_counter_new\fR(3) \fBzmq_atomic_counter_set\fR(3) \fBzmq_atomic_counter_inc\fR(3) \fBzmq_atomic_counter_value\fR(3) \fBzmq_atomic_counter_destroy\fR(3) +.SH "AUTHORS" +.sp +This page was written by the 0MQ community\&. To make a change please read the 0MQ Contribution Policy at \m[blue]\fBhttp://www\&.zeromq\&.org/docs:contributing\fR\m[]\&. diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_atomic_counter_destroy.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_atomic_counter_destroy.3 new file mode 100644 index 00000000000000..b37bd42407a586 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_atomic_counter_destroy.3 @@ -0,0 +1,73 @@ +'\" t +.\" Title: zmq_atomic_counter_destroy +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.78.1 +.\" Date: 02/18/2017 +.\" Manual: 0MQ Manual +.\" Source: 0MQ 4.2.2 +.\" Language: English +.\" +.TH "ZMQ_ATOMIC_COUNTER_D" "3" "02/18/2017" "0MQ 4\&.2\&.2" "0MQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zmq_atomic_counter_destroy \- destroy an atomic counter +.SH "SYNOPSIS" +.sp +\fBvoid zmq_atomic_counter_destroy (void **counter_p);\fR +.SH "DESCRIPTION" +.sp +The \fIzmq_atomic_counter_destroy\fR function destroys an atomic counter and nullifies its reference\&. Pass the address of an atomic counter (void **) rather than the counter itself\&. You must destroy all counters that you create, to avoid memory leakage\&. This function uses platform specific atomic operations\&. +.SH "RETURN VALUE" +.sp +The \fIzmq_atomic_counter_destroy()\fR function has no return value\&. +.SH "EXAMPLE" +.PP +\fBTest code for atomic counters\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +void *counter = zmq_atomic_counter_new (); +assert (zmq_atomic_counter_value (counter) == 0); +assert (zmq_atomic_counter_inc (counter) == 0); +assert (zmq_atomic_counter_inc (counter) == 1); +assert (zmq_atomic_counter_inc (counter) == 2); +assert (zmq_atomic_counter_value (counter) == 3); +assert (zmq_atomic_counter_dec (counter) == 1); +assert (zmq_atomic_counter_dec (counter) == 1); +assert (zmq_atomic_counter_dec (counter) == 0); +zmq_atomic_counter_set (counter, 2); +assert (zmq_atomic_counter_dec (counter) == 1); +assert (zmq_atomic_counter_dec (counter) == 0); +zmq_atomic_counter_destroy (&counter); +return 0; +.fi +.if n \{\ +.RE +.\} +.sp +.SH "SEE ALSO" +.sp +\fBzmq_atomic_counter_new\fR(3) \fBzmq_atomic_counter_set\fR(3) \fBzmq_atomic_counter_inc\fR(3) \fBzmq_atomic_counter_dec\fR(3) \fBzmq_atomic_counter_value\fR(3) +.SH "AUTHORS" +.sp +This page was written by the 0MQ community\&. To make a change please read the 0MQ Contribution Policy at \m[blue]\fBhttp://www\&.zeromq\&.org/docs:contributing\fR\m[]\&. diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_atomic_counter_inc.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_atomic_counter_inc.3 new file mode 100644 index 00000000000000..8d7064f9ccd5b6 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_atomic_counter_inc.3 @@ -0,0 +1,73 @@ +'\" t +.\" Title: zmq_atomic_counter_inc +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.78.1 +.\" Date: 02/18/2017 +.\" Manual: 0MQ Manual +.\" Source: 0MQ 4.2.2 +.\" Language: English +.\" +.TH "ZMQ_ATOMIC_COUNTER_I" "3" "02/18/2017" "0MQ 4\&.2\&.2" "0MQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zmq_atomic_counter_inc \- increment an atomic counter +.SH "SYNOPSIS" +.sp +\fBint zmq_atomic_counter_inc (void *counter);\fR +.SH "DESCRIPTION" +.sp +The \fIzmq_atomic_counter_inc\fR function increments an atomic counter in a threadsafe fashion\&. This function uses platform specific atomic operations\&. +.SH "RETURN VALUE" +.sp +The \fIzmq_atomic_counter_inc()\fR function returns the old value of the counter, before incrementing\&. +.SH "EXAMPLE" +.PP +\fBTest code for atomic counters\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +void *counter = zmq_atomic_counter_new (); +assert (zmq_atomic_counter_value (counter) == 0); +assert (zmq_atomic_counter_inc (counter) == 0); +assert (zmq_atomic_counter_inc (counter) == 1); +assert (zmq_atomic_counter_inc (counter) == 2); +assert (zmq_atomic_counter_value (counter) == 3); +assert (zmq_atomic_counter_dec (counter) == 1); +assert (zmq_atomic_counter_dec (counter) == 1); +assert (zmq_atomic_counter_dec (counter) == 0); +zmq_atomic_counter_set (counter, 2); +assert (zmq_atomic_counter_dec (counter) == 1); +assert (zmq_atomic_counter_dec (counter) == 0); +zmq_atomic_counter_destroy (&counter); +return 0; +.fi +.if n \{\ +.RE +.\} +.sp +.SH "SEE ALSO" +.sp +\fBzmq_atomic_counter_new\fR(3) \fBzmq_atomic_counter_set\fR(3) \fBzmq_atomic_counter_dec\fR(3) \fBzmq_atomic_counter_value\fR(3) \fBzmq_atomic_counter_destroy\fR(3) +.SH "AUTHORS" +.sp +This page was written by the 0MQ community\&. To make a change please read the 0MQ Contribution Policy at \m[blue]\fBhttp://www\&.zeromq\&.org/docs:contributing\fR\m[]\&. diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_atomic_counter_new.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_atomic_counter_new.3 new file mode 100644 index 00000000000000..124130917b0936 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_atomic_counter_new.3 @@ -0,0 +1,73 @@ +'\" t +.\" Title: zmq_atomic_counter_new +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.78.1 +.\" Date: 02/18/2017 +.\" Manual: 0MQ Manual +.\" Source: 0MQ 4.2.2 +.\" Language: English +.\" +.TH "ZMQ_ATOMIC_COUNTER_N" "3" "02/18/2017" "0MQ 4\&.2\&.2" "0MQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zmq_atomic_counter_new \- create a new atomic counter +.SH "SYNOPSIS" +.sp +\fBvoid *zmq_atomic_counter_new (void);\fR +.SH "DESCRIPTION" +.sp +The \fIzmq_atomic_counter_new\fR function creates a new atomic counter\&. You can use this in multithreaded applications to do, for example, reference counting of shared objects\&. The atomic counter is at least 32 bits large\&. This function uses platform specific atomic operations\&. +.SH "RETURN VALUE" +.sp +The \fIzmq_atomic_counter_new()\fR function returns the new atomic counter if successful\&. Otherwise it returns NULL\&. +.SH "EXAMPLE" +.PP +\fBTest code for atomic counters\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +void *counter = zmq_atomic_counter_new (); +assert (zmq_atomic_counter_value (counter) == 0); +assert (zmq_atomic_counter_inc (counter) == 0); +assert (zmq_atomic_counter_inc (counter) == 1); +assert (zmq_atomic_counter_inc (counter) == 2); +assert (zmq_atomic_counter_value (counter) == 3); +assert (zmq_atomic_counter_dec (counter) == 1); +assert (zmq_atomic_counter_dec (counter) == 1); +assert (zmq_atomic_counter_dec (counter) == 0); +zmq_atomic_counter_set (counter, 2); +assert (zmq_atomic_counter_dec (counter) == 1); +assert (zmq_atomic_counter_dec (counter) == 0); +zmq_atomic_counter_destroy (&counter); +return 0; +.fi +.if n \{\ +.RE +.\} +.sp +.SH "SEE ALSO" +.sp +\fBzmq_atomic_counter_set\fR(3) \fBzmq_atomic_counter_inc\fR(3) \fBzmq_atomic_counter_dec\fR(3) \fBzmq_atomic_counter_value\fR(3) \fBzmq_atomic_counter_destroy\fR(3) +.SH "AUTHORS" +.sp +This page was written by the 0MQ community\&. To make a change please read the 0MQ Contribution Policy at \m[blue]\fBhttp://www\&.zeromq\&.org/docs:contributing\fR\m[]\&. diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_atomic_counter_set.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_atomic_counter_set.3 new file mode 100644 index 00000000000000..5cdac995d6ceec --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_atomic_counter_set.3 @@ -0,0 +1,73 @@ +'\" t +.\" Title: zmq_atomic_counter_set +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.78.1 +.\" Date: 02/18/2017 +.\" Manual: 0MQ Manual +.\" Source: 0MQ 4.2.2 +.\" Language: English +.\" +.TH "ZMQ_ATOMIC_COUNTER_S" "3" "02/18/2017" "0MQ 4\&.2\&.2" "0MQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zmq_atomic_counter_set \- set atomic counter to new value +.SH "SYNOPSIS" +.sp +\fBvoid zmq_atomic_counter_set (void *counter, int value);\fR +.SH "DESCRIPTION" +.sp +The \fIzmq_atomic_counter_set\fR function sets the counter to a new value, in a threadsafe fashion\&. The largest value that is guaranteed to work across all platforms is 2^31\-1\&. This function uses platform specific atomic operations\&. +.SH "RETURN VALUE" +.sp +The \fIzmq_atomic_counter_set()\fR function has no return value\&. +.SH "EXAMPLE" +.PP +\fBTest code for atomic counters\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +void *counter = zmq_atomic_counter_new (); +assert (zmq_atomic_counter_value (counter) == 0); +assert (zmq_atomic_counter_inc (counter) == 0); +assert (zmq_atomic_counter_inc (counter) == 1); +assert (zmq_atomic_counter_inc (counter) == 2); +assert (zmq_atomic_counter_value (counter) == 3); +assert (zmq_atomic_counter_dec (counter) == 1); +assert (zmq_atomic_counter_dec (counter) == 1); +assert (zmq_atomic_counter_dec (counter) == 0); +zmq_atomic_counter_set (counter, 2); +assert (zmq_atomic_counter_dec (counter) == 1); +assert (zmq_atomic_counter_dec (counter) == 0); +zmq_atomic_counter_destroy (&counter); +return 0; +.fi +.if n \{\ +.RE +.\} +.sp +.SH "SEE ALSO" +.sp +\fBzmq_atomic_counter_new\fR(3) \fBzmq_atomic_counter_inc\fR(3) \fBzmq_atomic_counter_dec\fR(3) \fBzmq_atomic_counter_value\fR(3) \fBzmq_atomic_counter_destroy\fR(3) +.SH "AUTHORS" +.sp +This page was written by the 0MQ community\&. To make a change please read the 0MQ Contribution Policy at \m[blue]\fBhttp://www\&.zeromq\&.org/docs:contributing\fR\m[]\&. diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_atomic_counter_value.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_atomic_counter_value.3 new file mode 100644 index 00000000000000..f62f8b4714758e --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_atomic_counter_value.3 @@ -0,0 +1,73 @@ +'\" t +.\" Title: zmq_atomic_counter_value +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.78.1 +.\" Date: 02/18/2017 +.\" Manual: 0MQ Manual +.\" Source: 0MQ 4.2.2 +.\" Language: English +.\" +.TH "ZMQ_ATOMIC_COUNTER_V" "3" "02/18/2017" "0MQ 4\&.2\&.2" "0MQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zmq_atomic_counter_value \- return value of atomic counter +.SH "SYNOPSIS" +.sp +\fBint zmq_atomic_counter_value (void *counter);\fR +.SH "DESCRIPTION" +.sp +The \fIzmq_atomic_counter_value\fR function returns the value of an atomic counter\&. This function uses platform specific atomic operations\&. +.SH "RETURN VALUE" +.sp +The \fIzmq_atomic_counter_value()\fR function returns the new atomic counter if successful\&. Otherwise it returns NULL\&. +.SH "EXAMPLE" +.PP +\fBTest code for atomic counters\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +void *counter = zmq_atomic_counter_new (); +assert (zmq_atomic_counter_value (counter) == 0); +assert (zmq_atomic_counter_inc (counter) == 0); +assert (zmq_atomic_counter_inc (counter) == 1); +assert (zmq_atomic_counter_inc (counter) == 2); +assert (zmq_atomic_counter_value (counter) == 3); +assert (zmq_atomic_counter_dec (counter) == 1); +assert (zmq_atomic_counter_dec (counter) == 1); +assert (zmq_atomic_counter_dec (counter) == 0); +zmq_atomic_counter_set (counter, 2); +assert (zmq_atomic_counter_dec (counter) == 1); +assert (zmq_atomic_counter_dec (counter) == 0); +zmq_atomic_counter_destroy (&counter); +return 0; +.fi +.if n \{\ +.RE +.\} +.sp +.SH "SEE ALSO" +.sp +\fBzmq_atomic_counter_new\fR(3) \fBzmq_atomic_counter_set\fR(3) \fBzmq_atomic_counter_inc\fR(3) \fBzmq_atomic_counter_dec\fR(3) \fBzmq_atomic_counter_destroy\fR(3) +.SH "AUTHORS" +.sp +This page was written by the 0MQ community\&. To make a change please read the 0MQ Contribution Policy at \m[blue]\fBhttp://www\&.zeromq\&.org/docs:contributing\fR\m[]\&. diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_bind.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_bind.3 new file mode 100644 index 00000000000000..472961186563c6 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_bind.3 @@ -0,0 +1,200 @@ +'\" t +.\" Title: zmq_bind +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.78.1 +.\" Date: 02/18/2017 +.\" Manual: 0MQ Manual +.\" Source: 0MQ 4.2.2 +.\" Language: English +.\" +.TH "ZMQ_BIND" "3" "02/18/2017" "0MQ 4\&.2\&.2" "0MQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zmq_bind \- accept incoming connections on a socket +.SH "SYNOPSIS" +.sp +\fBint zmq_bind (void \fR\fB\fI*socket\fR\fR\fB, const char \fR\fB\fI*endpoint\fR\fR\fB);\fR +.SH "DESCRIPTION" +.sp +The \fIzmq_bind()\fR function binds the \fIsocket\fR to a local \fIendpoint\fR and then accepts incoming connections on that endpoint\&. +.sp +The \fIendpoint\fR is a string consisting of a \fItransport\fR:// followed by an \fIaddress\fR\&. The \fItransport\fR specifies the underlying protocol to use\&. The \fIaddress\fR specifies the transport\-specific address to bind to\&. +.sp +0MQ provides the the following transports: +.PP +\fItcp\fR +.RS 4 +unicast transport using TCP, see +\fBzmq_tcp\fR(7) +.RE +.PP +\fIipc\fR +.RS 4 +local inter\-process communication transport, see +\fBzmq_ipc\fR(7) +.RE +.PP +\fIinproc\fR +.RS 4 +local in\-process (inter\-thread) communication transport, see +\fBzmq_inproc\fR(7) +.RE +.PP +\fIpgm\fR, \fIepgm\fR +.RS 4 +reliable multicast transport using PGM, see +\fBzmq_pgm\fR(7) +.RE +.PP +\fIvmci\fR +.RS 4 +virtual machine communications interface (VMCI), see +\fBzmq_vmci\fR(7) +.RE +.sp +Every 0MQ socket type except \fIZMQ_PAIR\fR supports one\-to\-many and many\-to\-one semantics\&. The precise semantics depend on the socket type and are defined in \fBzmq_socket\fR(3)\&. +.sp +The \fIipc\fR, \fItcp\fR and \fIvmci\fR transports accept wildcard addresses: see \fBzmq_ipc\fR(7), \fBzmq_tcp\fR(7) and \fBzmq_vmci\fR(7) for details\&. +.if n \{\ +.sp +.\} +.RS 4 +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBNote\fR +.ps -1 +.br +.sp +the address syntax may be different for \fIzmq_bind()\fR and \fIzmq_connect()\fR especially for the \fItcp\fR, \fIpgm\fR and \fIepgm\fR transports\&. +.sp .5v +.RE +.if n \{\ +.sp +.\} +.RS 4 +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBNote\fR +.ps -1 +.br +.sp +following a \fIzmq_bind()\fR, the socket enters a \fImute\fR state unless or until at least one incoming or outgoing connection is made, at which point the socket enters a \fIready\fR state\&. In the mute state, the socket blocks or drops messages according to the socket type, as defined in \fBzmq_socket\fR(3)\&. By contrast, following a libzmq:zmq_connect[3], the socket enters the \fIready\fR state\&. +.sp .5v +.RE +.SH "RETURN VALUE" +.sp +The \fIzmq_bind()\fR function returns zero if successful\&. Otherwise it returns \-1 and sets \fIerrno\fR to one of the values defined below\&. +.SH "ERRORS" +.PP +\fBEINVAL\fR +.RS 4 +The endpoint supplied is invalid\&. +.RE +.PP +\fBEPROTONOSUPPORT\fR +.RS 4 +The requested +\fItransport\fR +protocol is not supported\&. +.RE +.PP +\fBENOCOMPATPROTO\fR +.RS 4 +The requested +\fItransport\fR +protocol is not compatible with the socket type\&. +.RE +.PP +\fBEADDRINUSE\fR +.RS 4 +The requested +\fIaddress\fR +is already in use\&. +.RE +.PP +\fBEADDRNOTAVAIL\fR +.RS 4 +The requested +\fIaddress\fR +was not local\&. +.RE +.PP +\fBENODEV\fR +.RS 4 +The requested +\fIaddress\fR +specifies a nonexistent interface\&. +.RE +.PP +\fBETERM\fR +.RS 4 +The 0MQ +\fIcontext\fR +associated with the specified +\fIsocket\fR +was terminated\&. +.RE +.PP +\fBENOTSOCK\fR +.RS 4 +The provided +\fIsocket\fR +was invalid\&. +.RE +.PP +\fBEMTHREAD\fR +.RS 4 +No I/O thread is available to accomplish the task\&. +.RE +.SH "EXAMPLE" +.PP +\fBBinding a publisher socket to an in-process and a TCP transport\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +/* Create a ZMQ_PUB socket */ +void *socket = zmq_socket (context, ZMQ_PUB); +assert (socket); +/* Bind it to a in\-process transport with the address \*(Aqmy_publisher\*(Aq */ +int rc = zmq_bind (socket, "inproc://my_publisher"); +assert (rc == 0); +/* Bind it to a TCP transport on port 5555 of the \*(Aqeth0\*(Aq interface */ +rc = zmq_bind (socket, "tcp://eth0:5555"); +assert (rc == 0); +.fi +.if n \{\ +.RE +.\} +.sp +.SH "SEE ALSO" +.sp +\fBzmq_connect\fR(3) \fBzmq_socket\fR(3) \fBzmq\fR(7) +.SH "AUTHORS" +.sp +This page was written by the 0MQ community\&. To make a change please read the 0MQ Contribution Policy at \m[blue]\fBhttp://www\&.zeromq\&.org/docs:contributing\fR\m[]\&. diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_close.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_close.3 new file mode 100644 index 00000000000000..f3b45dc49e8cbf --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_close.3 @@ -0,0 +1,70 @@ +'\" t +.\" Title: zmq_close +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.78.1 +.\" Date: 02/18/2017 +.\" Manual: 0MQ Manual +.\" Source: 0MQ 4.2.2 +.\" Language: English +.\" +.TH "ZMQ_CLOSE" "3" "02/18/2017" "0MQ 4\&.2\&.2" "0MQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zmq_close \- close 0MQ socket +.SH "SYNOPSIS" +.sp +\fBint zmq_close (void \fR\fB\fI*socket\fR\fR\fB);\fR +.SH "DESCRIPTION" +.sp +The \fIzmq_close()\fR function shall destroy the socket referenced by the \fIsocket\fR argument\&. Any outstanding messages physically received from the network but not yet received by the application with \fIzmq_recv()\fR shall be discarded\&. The behaviour for discarding messages sent by the application with \fIzmq_send()\fR but not yet physically transferred to the network depends on the value of the \fIZMQ_LINGER\fR socket option for the specified \fIsocket\fR\&. +.if n \{\ +.sp +.\} +.RS 4 +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBNote\fR +.ps -1 +.br +.sp +The default setting of \fIZMQ_LINGER\fR does not discard unsent messages; this behaviour may cause the application to block when calling \fIzmq_ctx_term()\fR\&. For details refer to \fBzmq_setsockopt\fR(3) and \fBzmq_ctx_term\fR(3)\&. +.sp .5v +.RE +.SH "RETURN VALUE" +.sp +The \fIzmq_close()\fR function shall return zero if successful\&. Otherwise it shall return \-1 and set \fIerrno\fR to one of the values defined below\&. +.SH "ERRORS" +.PP +\fBENOTSOCK\fR +.RS 4 +The provided +\fIsocket\fR +was invalid\&. +.RE +.SH "SEE ALSO" +.sp +\fBzmq_socket\fR(3) \fBzmq_ctx_term\fR(3) \fBzmq_setsockopt\fR(3) \fBzmq\fR(7) +.SH "AUTHORS" +.sp +This page was written by the 0MQ community\&. To make a change please read the 0MQ Contribution Policy at \m[blue]\fBhttp://www\&.zeromq\&.org/docs:contributing\fR\m[]\&. diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_connect.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_connect.3 new file mode 100644 index 00000000000000..ba263b85f82616 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_connect.3 @@ -0,0 +1,177 @@ +'\" t +.\" Title: zmq_connect +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.78.1 +.\" Date: 02/18/2017 +.\" Manual: 0MQ Manual +.\" Source: 0MQ 4.2.2 +.\" Language: English +.\" +.TH "ZMQ_CONNECT" "3" "02/18/2017" "0MQ 4\&.2\&.2" "0MQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zmq_connect \- create outgoing connection from socket +.SH "SYNOPSIS" +.sp +\fBint zmq_connect (void \fR\fB\fI*socket\fR\fR\fB, const char \fR\fB\fI*endpoint\fR\fR\fB);\fR +.SH "DESCRIPTION" +.sp +The \fIzmq_connect()\fR function connects the \fIsocket\fR to an \fIendpoint\fR and then accepts incoming connections on that endpoint\&. +.sp +The \fIendpoint\fR is a string consisting of a \fItransport\fR:// followed by an \fIaddress\fR\&. The \fItransport\fR specifies the underlying protocol to use\&. The \fIaddress\fR specifies the transport\-specific address to connect to\&. +.sp +0MQ provides the the following transports: +.PP +\fItcp\fR +.RS 4 +unicast transport using TCP, see +\fBzmq_tcp\fR(7) +.RE +.PP +\fIipc\fR +.RS 4 +local inter\-process communication transport, see +\fBzmq_ipc\fR(7) +.RE +.PP +\fIinproc\fR +.RS 4 +local in\-process (inter\-thread) communication transport, see +\fBzmq_inproc\fR(7) +.RE +.PP +\fIpgm\fR, \fIepgm\fR +.RS 4 +reliable multicast transport using PGM, see +\fBzmq_pgm\fR(7) +.RE +.PP +\fIvmci\fR +.RS 4 +virtual machine communications interface (VMCI), see +\fBzmq_vmci\fR(7) +.RE +.sp +Every 0MQ socket type except \fIZMQ_PAIR\fR supports one\-to\-many and many\-to\-one semantics\&. The precise semantics depend on the socket type and are defined in \fBzmq_socket\fR(3)\&. +.if n \{\ +.sp +.\} +.RS 4 +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBNote\fR +.ps -1 +.br +.sp +for most transports and socket types the connection is not performed immediately but as needed by 0MQ\&. Thus a successful call to \fIzmq_connect()\fR does not mean that the connection was or could actually be established\&. Because of this, for most transports and socket types the order in which a \fIserver\fR socket is bound and a \fIclient\fR socket is connected to it does not matter\&. The first exception is when using the inproc:// transport: you must call \fIzmq_bind()\fR before calling \fIzmq_connect()\fR\&. The second exception are \fIZMQ_PAIR\fR sockets, which do not automatically reconnect to endpoints\&. +.sp .5v +.RE +.if n \{\ +.sp +.\} +.RS 4 +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBNote\fR +.ps -1 +.br +.sp +following a \fIzmq_connect()\fR, for socket types except for ZMQ_ROUTER, the socket enters its normal \fIready\fR state\&. By contrast, following a \fIzmq_bind()\fR alone, the socket enters a \fImute\fR state in which the socket blocks or drops messages according to the socket type, as defined in \fBzmq_socket\fR(3)\&. A ZMQ_ROUTER socket enters its normal \fIready\fR state for a specific peer only when handshaking is complete for that peer, which may take an arbitrary time\&. +.sp .5v +.RE +.SH "RETURN VALUE" +.sp +The \fIzmq_connect()\fR function returns zero if successful\&. Otherwise it returns \-1 and sets \fIerrno\fR to one of the values defined below\&. +.SH "ERRORS" +.PP +\fBEINVAL\fR +.RS 4 +The endpoint supplied is invalid\&. +.RE +.PP +\fBEPROTONOSUPPORT\fR +.RS 4 +The requested +\fItransport\fR +protocol is not supported\&. +.RE +.PP +\fBENOCOMPATPROTO\fR +.RS 4 +The requested +\fItransport\fR +protocol is not compatible with the socket type\&. +.RE +.PP +\fBETERM\fR +.RS 4 +The 0MQ +\fIcontext\fR +associated with the specified +\fIsocket\fR +was terminated\&. +.RE +.PP +\fBENOTSOCK\fR +.RS 4 +The provided +\fIsocket\fR +was invalid\&. +.RE +.PP +\fBEMTHREAD\fR +.RS 4 +No I/O thread is available to accomplish the task\&. +.RE +.SH "EXAMPLE" +.PP +\fBConnecting a subscriber socket to an in-process and a TCP transport\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +/* Create a ZMQ_SUB socket */ +void *socket = zmq_socket (context, ZMQ_SUB); +assert (socket); +/* Connect it to an in\-process transport with the address \*(Aqmy_publisher\*(Aq */ +int rc = zmq_connect (socket, "inproc://my_publisher"); +assert (rc == 0); +/* Connect it to the host server001, port 5555 using a TCP transport */ +rc = zmq_connect (socket, "tcp://server001:5555"); +assert (rc == 0); +.fi +.if n \{\ +.RE +.\} +.sp +.SH "SEE ALSO" +.sp +\fBzmq_bind\fR(3) \fBzmq_socket\fR(3) \fBzmq\fR(7) +.SH "AUTHORS" +.sp +This page was written by the 0MQ community\&. To make a change please read the 0MQ Contribution Policy at \m[blue]\fBhttp://www\&.zeromq\&.org/docs:contributing\fR\m[]\&. diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_ctx_get.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_ctx_get.3 new file mode 100644 index 00000000000000..fef5be66499bd1 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_ctx_get.3 @@ -0,0 +1,106 @@ +'\" t +.\" Title: zmq_ctx_get +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.78.1 +.\" Date: 02/18/2017 +.\" Manual: 0MQ Manual +.\" Source: 0MQ 4.2.2 +.\" Language: English +.\" +.TH "ZMQ_CTX_GET" "3" "02/18/2017" "0MQ 4\&.2\&.2" "0MQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zmq_ctx_get \- get context options +.SH "SYNOPSIS" +.sp +\fBint zmq_ctx_get (void \fR\fB\fI*context\fR\fR\fB, int \fR\fB\fIoption_name\fR\fR\fB);\fR +.SH "DESCRIPTION" +.sp +The \fIzmq_ctx_get()\fR function shall return the option specified by the \fIoption_name\fR argument\&. +.sp +The \fIzmq_ctx_get()\fR function accepts the following option names: +.SS "ZMQ_IO_THREADS: Get number of I/O threads" +.sp +The \fIZMQ_IO_THREADS\fR argument returns the size of the 0MQ thread pool for this context\&. +.SS "ZMQ_MAX_SOCKETS: Get maximum number of sockets" +.sp +The \fIZMQ_MAX_SOCKETS\fR argument returns the maximum number of sockets allowed for this context\&. +.SS "ZMQ_MAX_MSGSZ: Get maximum message size" +.sp +The \fIZMQ_MAX_MSGSZ\fR argument returns the maximum size of a message allowed for this context\&. Default value is INT_MAX\&. +.SS "ZMQ_SOCKET_LIMIT: Get largest configurable number of sockets" +.sp +The \fIZMQ_SOCKET_LIMIT\fR argument returns the largest number of sockets that \fBzmq_ctx_set\fR(3) will accept\&. +.SS "ZMQ_IPV6: Set IPv6 option" +.sp +The \fIZMQ_IPV6\fR argument returns the IPv6 option for the context\&. +.SS "ZMQ_BLOCKY: Get blocky setting" +.sp +The \fIZMQ_BLOCKY\fR argument returns 1 if the context will block on terminate, zero if the "block forever on context termination" gambit was disabled by setting ZMQ_BLOCKY to false on all new contexts\&. +.SS "ZMQ_MSG_T_SIZE: Get the zmq_msg_t size at runtime" +.sp +The \fIZMQ_MSG_T_SIZE\fR argument returns the size of the zmq_msg_t structure at runtime, as defined in the include/zmq\&.h public header\&. This is useful for example for FFI bindings that can\(cqt simply do a sizeof()\&. NOTE: in DRAFT state, not yet available in stable releases\&. +.SH "RETURN VALUE" +.sp +The \fIzmq_ctx_get()\fR function returns a value of 0 or greater if successful\&. Otherwise it returns \-1 and sets \fIerrno\fR to one of the values defined below\&. +.SH "ERRORS" +.PP +\fBEINVAL\fR +.RS 4 +The requested option +\fIoption_name\fR +is unknown\&. +.RE +.SH "EXAMPLE" +.PP +\fBSetting a limit on the number of sockets\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +void *context = zmq_ctx_new (); +zmq_ctx_set (context, ZMQ_MAX_SOCKETS, 256); +int max_sockets = zmq_ctx_get (context, ZMQ_MAX_SOCKETS); +assert (max_sockets == 256); +.fi +.if n \{\ +.RE +.\} +.PP +\fBSwitching off the context deadlock gambit\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +zmq_ctx_set (ctx, ZMQ_BLOCKY, false); +.fi +.if n \{\ +.RE +.\} +.sp +.SH "SEE ALSO" +.sp +\fBzmq_ctx_set\fR(3) \fBzmq\fR(7) +.SH "AUTHORS" +.sp +This page was written by the 0MQ community\&. To make a change please read the 0MQ Contribution Policy at \m[blue]\fBhttp://www\&.zeromq\&.org/docs:contributing\fR\m[]\&. diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_ctx_new.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_ctx_new.3 new file mode 100644 index 00000000000000..23d1af87f73c83 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_ctx_new.3 @@ -0,0 +1,55 @@ +'\" t +.\" Title: zmq_ctx_new +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.78.1 +.\" Date: 02/18/2017 +.\" Manual: 0MQ Manual +.\" Source: 0MQ 4.2.2 +.\" Language: English +.\" +.TH "ZMQ_CTX_NEW" "3" "02/18/2017" "0MQ 4\&.2\&.2" "0MQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zmq_ctx_new \- create new 0MQ context +.SH "SYNOPSIS" +.sp +\fBvoid *zmq_ctx_new ();\fR +.SH "DESCRIPTION" +.sp +The \fIzmq_ctx_new()\fR function creates a new 0MQ \fIcontext\fR\&. +.sp +This function replaces the deprecated function \fBzmq_init\fR(3)\&. +.PP +\fBThread safety\fR. A 0MQ +\fIcontext\fR +is thread safe and may be shared among as many application threads as necessary, without any additional locking required on the part of the caller\&. +.SH "RETURN VALUE" +.sp +The \fIzmq_ctx_new()\fR function shall return an opaque handle to the newly created \fIcontext\fR if successful\&. Otherwise it shall return NULL and set \fIerrno\fR to one of the values defined below\&. +.SH "ERRORS" +.sp +No error values are defined for this function\&. +.SH "SEE ALSO" +.sp +\fBzmq\fR(7) \fBzmq_ctx_set\fR(3) \fBzmq_ctx_get\fR(3) \fBzmq_ctx_term\fR(3) +.SH "AUTHORS" +.sp +This page was written by the 0MQ community\&. To make a change please read the 0MQ Contribution Policy at \m[blue]\fBhttp://www\&.zeromq\&.org/docs:contributing\fR\m[]\&. diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_ctx_set.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_ctx_set.3 new file mode 100644 index 00000000000000..b7d3e39cbc9945 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_ctx_set.3 @@ -0,0 +1,186 @@ +'\" t +.\" Title: zmq_ctx_set +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.78.1 +.\" Date: 02/18/2017 +.\" Manual: 0MQ Manual +.\" Source: 0MQ 4.2.2 +.\" Language: English +.\" +.TH "ZMQ_CTX_SET" "3" "02/18/2017" "0MQ 4\&.2\&.2" "0MQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zmq_ctx_set \- set context options +.SH "SYNOPSIS" +.sp +\fBint zmq_ctx_set (void \fR\fB\fI*context\fR\fR\fB, int \fR\fB\fIoption_name\fR\fR\fB, int \fR\fB\fIoption_value\fR\fR\fB);\fR +.SH "DESCRIPTION" +.sp +The \fIzmq_ctx_set()\fR function shall set the option specified by the \fIoption_name\fR argument to the value of the \fIoption_value\fR argument\&. +.sp +The \fIzmq_ctx_set()\fR function accepts the following options: +.SS "ZMQ_BLOCKY: Fix blocky behavior" +.sp +By default the context will block, forever, on a zmq_ctx_term call\&. The assumption behind this behavior is that abrupt termination will cause message loss\&. Most real applications use some form of handshaking to ensure applications receive termination messages, and then terminate the context with \fIZMQ_LINGER\fR set to zero on all sockets\&. This setting is an easier way to get the same result\&. When \fIZMQ_BLOCKY\fR is set to false, all new sockets are given a linger timeout of zero\&. You must still close all sockets before calling zmq_ctx_term\&. +.TS +tab(:); +lt lt. +T{ +.sp +Default value +T}:T{ +.sp +true (old behavior) +T} +.TE +.sp 1 +.SS "ZMQ_IO_THREADS: Set number of I/O threads" +.sp +The \fIZMQ_IO_THREADS\fR argument specifies the size of the 0MQ thread pool to handle I/O operations\&. If your application is using only the \fIinproc\fR transport for messaging you may set this to zero, otherwise set it to at least one\&. This option only applies before creating any sockets on the context\&. +.TS +tab(:); +lt lt. +T{ +.sp +Default value +T}:T{ +.sp +1 +T} +.TE +.sp 1 +.SS "ZMQ_THREAD_SCHED_POLICY: Set scheduling policy for I/O threads" +.sp +The \fIZMQ_THREAD_SCHED_POLICY\fR argument sets the scheduling policy for internal context\(cqs thread pool\&. This option is not available on windows\&. Supported values for this option can be found in sched\&.h file, or at \m[blue]\fBhttp://man7\&.org/linux/man\-pages/man2/sched_setscheduler\&.2\&.html\fR\m[]\&. This option only applies before creating any sockets on the context\&. +.TS +tab(:); +lt lt. +T{ +.sp +Default value +T}:T{ +.sp +\-1 +T} +.TE +.sp 1 +.SS "ZMQ_THREAD_PRIORITY: Set scheduling priority for I/O threads" +.sp +The \fIZMQ_THREAD_PRIORITY\fR argument sets scheduling priority for internal context\(cqs thread pool\&. This option is not available on windows\&. Supported values for this option depend on chosen scheduling policy\&. Details can be found in sched\&.h file, or at \m[blue]\fBhttp://man7\&.org/linux/man\-pages/man2/sched_setscheduler\&.2\&.html\fR\m[]\&. This option only applies before creating any sockets on the context\&. +.TS +tab(:); +lt lt. +T{ +.sp +Default value +T}:T{ +.sp +\-1 +T} +.TE +.sp 1 +.SS "ZMQ_MAX_MSGSZ: Set maximum message size" +.sp +The \fIZMQ_MAX_MSGSZ\fR argument sets the maximum allowed size of a message sent in the context\&. You can query the maximal allowed value with \fBzmq_ctx_get\fR(3) using the \fIZMQ_MAX_MSGSZ\fR option\&. +.TS +tab(:); +lt lt +lt lt. +T{ +.sp +Default value +T}:T{ +.sp +INT_MAX +T} +T{ +.sp +Maximum value +T}:T{ +.sp +INT_MAX +T} +.TE +.sp 1 +.SS "ZMQ_MAX_SOCKETS: Set maximum number of sockets" +.sp +The \fIZMQ_MAX_SOCKETS\fR argument sets the maximum number of sockets allowed on the context\&. You can query the maximal allowed value with \fBzmq_ctx_get\fR(3) using the \fIZMQ_SOCKET_LIMIT\fR option\&. +.TS +tab(:); +lt lt. +T{ +.sp +Default value +T}:T{ +.sp +1024 +T} +.TE +.sp 1 +.SS "ZMQ_IPV6: Set IPv6 option" +.sp +The \fIZMQ_IPV6\fR argument sets the IPv6 value for all sockets created in the context from this point onwards\&. A value of 1 means IPv6 is enabled, while 0 means the socket will use only IPv4\&. When IPv6 is enabled, a socket will connect to, or accept connections from, both IPv4 and IPv6 hosts\&. +.TS +tab(:); +lt lt. +T{ +.sp +Default value +T}:T{ +.sp +0 +T} +.TE +.sp 1 +.SH "RETURN VALUE" +.sp +The \fIzmq_ctx_set()\fR function returns zero if successful\&. Otherwise it returns \-1 and sets \fIerrno\fR to one of the values defined below\&. +.SH "ERRORS" +.PP +\fBEINVAL\fR +.RS 4 +The requested option +\fIoption_name\fR +is unknown\&. +.RE +.SH "EXAMPLE" +.PP +\fBSetting a limit on the number of sockets\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +void *context = zmq_ctx_new (); +zmq_ctx_set (context, ZMQ_MAX_SOCKETS, 256); +int max_sockets = zmq_ctx_get (context, ZMQ_MAX_SOCKETS); +assert (max_sockets == 256); +.fi +.if n \{\ +.RE +.\} +.sp +.SH "SEE ALSO" +.sp +\fBzmq_ctx_get\fR(3) \fBzmq\fR(7) +.SH "AUTHORS" +.sp +This page was written by the 0MQ community\&. To make a change please read the 0MQ Contribution Policy at \m[blue]\fBhttp://www\&.zeromq\&.org/docs:contributing\fR\m[]\&. diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_ctx_shutdown.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_ctx_shutdown.3 new file mode 100644 index 00000000000000..1e1d21dea3891f --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_ctx_shutdown.3 @@ -0,0 +1,58 @@ +'\" t +.\" Title: zmq_ctx_shutdown +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.78.1 +.\" Date: 02/18/2017 +.\" Manual: 0MQ Manual +.\" Source: 0MQ 4.2.2 +.\" Language: English +.\" +.TH "ZMQ_CTX_SHUTDOWN" "3" "02/18/2017" "0MQ 4\&.2\&.2" "0MQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zmq_ctx_shutdown \- shutdown a 0MQ context +.SH "SYNOPSIS" +.sp +\fBint zmq_ctx_shutdown (void \fR\fB\fI*context\fR\fR\fB);\fR +.SH "DESCRIPTION" +.sp +The \fIzmq_ctx_shutdown()\fR function shall shutdown the 0MQ context \fIcontext\fR\&. +.sp +Context shutdown will cause any blocking operations currently in progress on sockets open within \fIcontext\fR to return immediately with an error code of ETERM\&. With the exception of \fIzmq_close()\fR, any further operations on sockets open within \fIcontext\fR shall fail with an error code of ETERM\&. +.sp +This function is optional, client code is still required to call the \fBzmq_ctx_term\fR(3) function to free all resources allocated by zeromq\&. +.SH "RETURN VALUE" +.sp +The \fIzmq_ctx_shutdown()\fR function shall return zero if successful\&. Otherwise it shall return \-1 and set \fIerrno\fR to one of the values defined below\&. +.SH "ERRORS" +.PP +\fBEFAULT\fR +.RS 4 +The provided +\fIcontext\fR +was invalid\&. +.RE +.SH "SEE ALSO" +.sp +\fBzmq\fR(7) \fBzmq_init\fR(3) \fBzmq_ctx_term\fR(3) \fBzmq_close\fR(3) \fBzmq_setsockopt\fR(3) +.SH "AUTHORS" +.sp +This page was written by the 0MQ community\&. To make a change please read the 0MQ Contribution Policy at \m[blue]\fBhttp://www\&.zeromq\&.org/docs:contributing\fR\m[]\&. diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_ctx_term.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_ctx_term.3 new file mode 100644 index 00000000000000..c7a5700f4e862b --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_ctx_term.3 @@ -0,0 +1,126 @@ +'\" t +.\" Title: zmq_ctx_term +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.78.1 +.\" Date: 02/18/2017 +.\" Manual: 0MQ Manual +.\" Source: 0MQ 4.2.2 +.\" Language: English +.\" +.TH "ZMQ_CTX_TERM" "3" "02/18/2017" "0MQ 4\&.2\&.2" "0MQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zmq_ctx_term \- terminate a 0MQ context +.SH "SYNOPSIS" +.sp +\fBint zmq_ctx_term (void \fR\fB\fI*context\fR\fR\fB);\fR +.SH "DESCRIPTION" +.sp +The \fIzmq_ctx_term()\fR function shall destroy the 0MQ context \fIcontext\fR\&. +.sp +Context termination is performed in the following steps: +.sp +.RS 4 +.ie n \{\ +\h'-04' 1.\h'+01'\c +.\} +.el \{\ +.sp -1 +.IP " 1." 4.2 +.\} +Any blocking operations currently in progress on sockets open within +\fIcontext\fR +shall return immediately with an error code of ETERM\&. With the exception of +\fIzmq_close()\fR, any further operations on sockets open within +\fIcontext\fR +shall fail with an error code of ETERM\&. +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04' 2.\h'+01'\c +.\} +.el \{\ +.sp -1 +.IP " 2." 4.2 +.\} +After interrupting all blocking calls, +\fIzmq_ctx_term()\fR +shall +\fIblock\fR +until the following conditions are satisfied: +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +All sockets open within +\fIcontext\fR +have been closed with +\fIzmq_close()\fR\&. +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +For each socket within +\fIcontext\fR, all messages sent by the application with +\fIzmq_send()\fR +have either been physically transferred to a network peer, or the socket\(cqs linger period set with the +\fIZMQ_LINGER\fR +socket option has expired\&. +.RE +.RE +.sp +For further details regarding socket linger behaviour refer to the \fIZMQ_LINGER\fR option in \fBzmq_setsockopt\fR(3)\&. +.sp +This function replaces the deprecated functions \fBzmq_term\fR(3) and \fBzmq_ctx_destroy\fR(3)\&. +.SH "RETURN VALUE" +.sp +The \fIzmq_ctx_term()\fR function shall return zero if successful\&. Otherwise it shall return \-1 and set \fIerrno\fR to one of the values defined below\&. +.SH "ERRORS" +.PP +\fBEFAULT\fR +.RS 4 +The provided +\fIcontext\fR +was invalid\&. +.RE +.PP +\fBEINTR\fR +.RS 4 +Termination was interrupted by a signal\&. It can be restarted if needed\&. +.RE +.SH "SEE ALSO" +.sp +\fBzmq\fR(7) \fBzmq_init\fR(3) \fBzmq_close\fR(3) \fBzmq_setsockopt\fR(3) +.SH "AUTHORS" +.sp +This page was written by the 0MQ community\&. To make a change please read the 0MQ Contribution Policy at \m[blue]\fBhttp://www\&.zeromq\&.org/docs:contributing\fR\m[]\&. diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_curve_keypair.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_curve_keypair.3 new file mode 100644 index 00000000000000..5a58963cff6361 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_curve_keypair.3 @@ -0,0 +1,69 @@ +'\" t +.\" Title: zmq_curve_keypair +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.78.1 +.\" Date: 02/18/2017 +.\" Manual: 0MQ Manual +.\" Source: 0MQ 4.2.2 +.\" Language: English +.\" +.TH "ZMQ_CURVE_KEYPAIR" "3" "02/18/2017" "0MQ 4\&.2\&.2" "0MQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zmq_curve_keypair \- generate a new CURVE keypair +.SH "SYNOPSIS" +.sp +\fBint zmq_curve_keypair (char *z85_public_key, char *z85_secret_key);\fR +.SH "DESCRIPTION" +.sp +The \fIzmq_curve_keypair()\fR function shall return a newly generated random keypair consisting of a public key and a secret key\&. The caller provides two buffers, each at least 41 octets large, in which this method will store the keys\&. The keys are encoded using \fBzmq_z85_encode\fR(3)\&. +.SH "RETURN VALUE" +.sp +The \fIzmq_curve_keypair()\fR function shall return 0 if successful, else it shall return \-1 and set \fIerrno\fR to one of the values defined below\&. +.SH "ERRORS" +.PP +\fBENOTSUP\fR +.RS 4 +The libzmq library was not built with cryptographic support (libsodium)\&. +.RE +.SH "EXAMPLE" +.PP +\fBGenerating a new CURVE keypair\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +char public_key [41]; +char secret_key [41]; +int rc = zmq_curve_keypair (public_key, secret_key); +assert (rc == 0); +.fi +.if n \{\ +.RE +.\} +.sp +.SH "SEE ALSO" +.sp +\fBzmq_z85_decode\fR(3) \fBzmq_z85_encode\fR(3) \fBzmq_curve\fR(7) +.SH "AUTHORS" +.sp +This page was written by the 0MQ community\&. To make a change please read the 0MQ Contribution Policy at \m[blue]\fBhttp://www\&.zeromq\&.org/docs:contributing\fR\m[]\&. diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_curve_public.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_curve_public.3 new file mode 100644 index 00000000000000..f7dceeb5d94d3e --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_curve_public.3 @@ -0,0 +1,73 @@ +'\" t +.\" Title: zmq_curve_public +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.78.1 +.\" Date: 02/18/2017 +.\" Manual: 0MQ Manual +.\" Source: 0MQ 4.2.2 +.\" Language: English +.\" +.TH "ZMQ_CURVE_PUBLIC" "3" "02/18/2017" "0MQ 4\&.2\&.2" "0MQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zmq_curve_public \- derive the public key from a private key +.SH "SYNOPSIS" +.sp +\fBint zmq_curve_public (char *z85_public_key, char *z85_secret_key);\fR +.SH "DESCRIPTION" +.sp +The \fIzmq_curve_public()\fR function shall derive the public key from a private key\&. The caller provides two buffers, each at least 41 octets large\&. In z85_secret_key the caller shall provide the private key, and the function will store the public key in z85_public_key\&. The keys are encoded using \fBzmq_z85_encode\fR(3)\&. +.SH "RETURN VALUE" +.sp +The \fIzmq_curve_public()\fR function shall return 0 if successful, else it shall return \-1 and set \fIerrno\fR to one of the values defined below\&. +.SH "ERRORS" +.PP +\fBENOTSUP\fR +.RS 4 +The libzmq library was not built with cryptographic support (libsodium)\&. +.RE +.SH "EXAMPLE" +.PP +\fBDeriving the public key from a CURVE private key\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +char public_key [41]; +char secret_key [41]; +int rc = zmq_curve_keypair (public_key, secret_key); +assert (rc == 0); +char derived_public[41]; +rc = zmq_curve_public (derived_public, secret_key); +assert (rc == 0); +assert (!strcmp (derived_public, public_key)); +.fi +.if n \{\ +.RE +.\} +.sp +.SH "SEE ALSO" +.sp +\fBzmq_z85_decode\fR(3) \fBzmq_z85_encode\fR(3) \fBzmq_curve_keypair\fR(3) \fBzmq_curve\fR(7) +.SH "AUTHORS" +.sp +This page was written by the 0MQ community\&. To make a change please read the 0MQ Contribution Policy at \m[blue]\fBhttp://www\&.zeromq\&.org/docs:contributing\fR\m[]\&. diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_disconnect.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_disconnect.3 new file mode 100644 index 00000000000000..ff5075fd31f794 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_disconnect.3 @@ -0,0 +1,113 @@ +'\" t +.\" Title: zmq_disconnect +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.78.1 +.\" Date: 02/18/2017 +.\" Manual: 0MQ Manual +.\" Source: 0MQ 4.2.2 +.\" Language: English +.\" +.TH "ZMQ_DISCONNECT" "3" "02/18/2017" "0MQ 4\&.2\&.2" "0MQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zmq_disconnect \- Disconnect a socket +.SH "SYNOPSIS" +.sp +\fBint zmq_disconnect (void \fR\fB\fI*socket\fR\fR\fB, const char \fR\fB\fI*endpoint\fR\fR\fB);\fR +.SH "DESCRIPTION" +.sp +The \fIzmq_disconnect()\fR function shall disconnect a socket specified by the \fIsocket\fR argument from the endpoint specified by the \fIendpoint\fR argument\&. Any outstanding messages physically received from the network but not yet received by the application with \fIzmq_recv()\fR shall be discarded\&. The behaviour for discarding messages sent by the application with \fIzmq_send()\fR but not yet physically transferred to the network depends on the value of the \fIZMQ_LINGER\fR socket option for the specified \fIsocket\fR\&. +.sp +The \fIendpoint\fR argument is as described in \fBzmq_connect\fR(3) +.if n \{\ +.sp +.\} +.RS 4 +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBNote\fR +.ps -1 +.br +.sp +The default setting of \fIZMQ_LINGER\fR does not discard unsent messages; this behaviour may cause the application to block when calling \fIzmq_ctx_term()\fR\&. For details refer to \fBzmq_setsockopt\fR(3) and \fBzmq_ctx_term\fR(3)\&. +.sp .5v +.RE +.SH "RETURN VALUE" +.sp +The \fIzmq_disconnect()\fR function shall return zero if successful\&. Otherwise it shall return \-1 and set \fIerrno\fR to one of the values defined below\&. +.SH "ERRORS" +.PP +\fBEINVAL\fR +.RS 4 +The endpoint supplied is invalid\&. +.RE +.PP +\fBETERM\fR +.RS 4 +The 0MQ +\fIcontext\fR +associated with the specified +\fIsocket\fR +was terminated\&. +.RE +.PP +\fBENOTSOCK\fR +.RS 4 +The provided +\fIsocket\fR +was invalid\&. +.RE +.PP +\fBENOENT\fR +.RS 4 +The provided endpoint is not connected\&. +.RE +.SH "EXAMPLE" +.PP +\fBConnecting a subscriber socket to an in-process and a TCP transport\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +/* Create a ZMQ_SUB socket */ +void *socket = zmq_socket (context, ZMQ_SUB); +assert (socket); +/* Connect it to the host server001, port 5555 using a TCP transport */ +rc = zmq_connect (socket, "tcp://server001:5555"); +assert (rc == 0); +/* Disconnect from the previously connected endpoint */ +rc = zmq_disconnect (socket, "tcp://server001:5555"); +assert (rc == 0); +.fi +.if n \{\ +.RE +.\} +.sp +.SH "SEE ALSO" +.sp +\fBzmq_connect\fR(3) \fBzmq_socket\fR(3) \fBzmq\fR(7) +.SH "AUTHORS" +.sp +This page was written by the 0MQ community\&. To make a change please read the 0MQ Contribution Policy at \m[blue]\fBhttp://www\&.zeromq\&.org/docs:contributing\fR\m[]\&. diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_errno.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_errno.3 new file mode 100644 index 00000000000000..b7cb977fd1906e --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_errno.3 @@ -0,0 +1,67 @@ +'\" t +.\" Title: zmq_errno +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.78.1 +.\" Date: 02/18/2017 +.\" Manual: 0MQ Manual +.\" Source: 0MQ 4.2.2 +.\" Language: English +.\" +.TH "ZMQ_ERRNO" "3" "02/18/2017" "0MQ 4\&.2\&.2" "0MQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zmq_errno \- retrieve value of errno for the calling thread +.SH "SYNOPSIS" +.sp +\fBint zmq_errno (void);\fR +.SH "DESCRIPTION" +.sp +The \fIzmq_errno()\fR function shall retrieve the value of the \fIerrno\fR variable for the calling thread\&. +.sp +The \fIzmq_errno()\fR function is provided to assist users on non\-POSIX systems who are experiencing issues with retrieving the correct value of \fIerrno\fR directly\&. Specifically, users on Win32 systems whose application is using a different C run\-time library from the C run\-time library in use by 0MQ will need to use \fIzmq_errno()\fR for correct operation\&. +.if n \{\ +.sp +.\} +.RS 4 +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBImportant\fR +.ps -1 +.br +.sp +Users not experiencing issues with retrieving the correct value of \fIerrno\fR should not use this function and should instead access the \fIerrno\fR variable directly\&. +.sp .5v +.RE +.SH "RETURN VALUE" +.sp +The \fIzmq_errno()\fR function shall return the value of the \fIerrno\fR variable for the calling thread\&. +.SH "ERRORS" +.sp +No errors are defined\&. +.SH "SEE ALSO" +.sp +\fBzmq\fR(7) +.SH "AUTHORS" +.sp +This page was written by the 0MQ community\&. To make a change please read the 0MQ Contribution Policy at \m[blue]\fBhttp://www\&.zeromq\&.org/docs:contributing\fR\m[]\&. diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_getsockopt.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_getsockopt.3 new file mode 100644 index 00000000000000..7a51c1e6788c02 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_getsockopt.3 @@ -0,0 +1,2298 @@ +'\" t +.\" Title: zmq_getsockopt +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.78.1 +.\" Date: 02/18/2017 +.\" Manual: 0MQ Manual +.\" Source: 0MQ 4.2.2 +.\" Language: English +.\" +.TH "ZMQ_GETSOCKOPT" "3" "02/18/2017" "0MQ 4\&.2\&.2" "0MQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zmq_getsockopt \- get 0MQ socket options +.SH "SYNOPSIS" +.sp +\fBint zmq_getsockopt (void \fR\fB\fI*socket\fR\fR\fB, int \fR\fB\fIoption_name\fR\fR\fB, void \fR\fB\fI*option_value\fR\fR\fB, size_t \fR\fB\fI*option_len\fR\fR\fB);\fR +.SH "DESCRIPTION" +.sp +The \fIzmq_getsockopt()\fR function shall retrieve the value for the option specified by the \fIoption_name\fR argument for the 0MQ socket pointed to by the \fIsocket\fR argument, and store it in the buffer pointed to by the \fIoption_value\fR argument\&. The \fIoption_len\fR argument is the size in bytes of the buffer pointed to by \fIoption_value\fR; upon successful completion \fIzmq_getsockopt()\fR shall modify the \fIoption_len\fR argument to indicate the actual size of the option value stored in the buffer\&. +.sp +The following options can be retrieved with the \fIzmq_getsockopt()\fR function: +.SS "ZMQ_AFFINITY: Retrieve I/O thread affinity" +.sp +The \fIZMQ_AFFINITY\fR option shall retrieve the I/O thread affinity for newly created connections on the specified \fIsocket\fR\&. +.sp +Affinity determines which threads from the 0MQ I/O thread pool associated with the socket\(cqs \fIcontext\fR shall handle newly created connections\&. A value of zero specifies no affinity, meaning that work shall be distributed fairly among all 0MQ I/O threads in the thread pool\&. For non\-zero values, the lowest bit corresponds to thread 1, second lowest bit to thread 2 and so on\&. For example, a value of 3 specifies that subsequent connections on \fIsocket\fR shall be handled exclusively by I/O threads 1 and 2\&. +.sp +See also \fBzmq_init\fR(3) for details on allocating the number of I/O threads for a specific \fIcontext\fR\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +uint64_t +T} +T{ +.sp +Option value unit +T}:T{ +.sp +N/A (bitmap) +T} +T{ +.sp +Default value +T}:T{ +.sp +0 +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +N/A +T} +.TE +.sp 1 +.SS "ZMQ_BACKLOG: Retrieve maximum length of the queue of outstanding connections" +.sp +The \fIZMQ_BACKLOG\fR option shall retrieve the maximum length of the queue of outstanding peer connections for the specified \fIsocket\fR; this only applies to connection\-oriented transports\&. For details refer to your operating system documentation for the \fIlisten\fR function\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +connections +T} +T{ +.sp +Default value +T}:T{ +.sp +100 +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, only for connection\-oriented transports +T} +.TE +.sp 1 +.SS "ZMQ_CONNECT_TIMEOUT: Retrieve connect() timeout" +.sp +Retrieves how long to wait before timing\-out a connect() system call\&. The connect() system call normally takes a long time before it returns a time out error\&. Setting this option allows the library to time out the call at an earlier interval\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +milliseconds +T} +T{ +.sp +Default value +T}:T{ +.sp +0 (disabled) +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, when using TCP transports\&. +T} +.TE +.sp 1 +.SS "ZMQ_CURVE_PUBLICKEY: Retrieve current CURVE public key" +.sp +Retrieves the current long term public key for the socket\&. You can provide either a 32 byte buffer, to retrieve the binary key value, or a 41 byte buffer, to retrieve the key in a printable Z85 format\&. NOTE: to fetch a printable key, the buffer must be 41 bytes large to hold the 40\-char key value and one null byte\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +binary data or Z85 text string +T} +T{ +.sp +Option value size +T}:T{ +.sp +32 or 41 +T} +T{ +.sp +Default value +T}:T{ +.sp +null +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, when using TCP transport +T} +.TE +.sp 1 +.SS "ZMQ_CURVE_SECRETKEY: Retrieve current CURVE secret key" +.sp +Retrieves the current long term secret key for the socket\&. You can provide either a 32 byte buffer, to retrieve the binary key value, or a 41 byte buffer, to retrieve the key in a printable Z85 format\&. NOTE: to fetch a printable key, the buffer must be 41 bytes large to hold the 40\-char key value and one null byte\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +binary data or Z85 text string +T} +T{ +.sp +Option value size +T}:T{ +.sp +32 or 41 +T} +T{ +.sp +Default value +T}:T{ +.sp +null +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, when using TCP transport +T} +.TE +.sp 1 +.SS "ZMQ_CURVE_SERVERKEY: Retrieve current CURVE server key" +.sp +Retrieves the current server key for the client socket\&. You can provide either a 32 byte buffer, to retrieve the binary key value, or a 41\-byte buffer, to retrieve the key in a printable Z85 format\&. NOTE: to fetch a printable key, the buffer must be 41 bytes large to hold the 40\-char key value and one null byte\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +binary data or Z85 text string +T} +T{ +.sp +Option value size +T}:T{ +.sp +32 or 41 +T} +T{ +.sp +Default value +T}:T{ +.sp +null +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, when using TCP transport +T} +.TE +.sp 1 +.SS "ZMQ_EVENTS: Retrieve socket event state" +.sp +The \fIZMQ_EVENTS\fR option shall retrieve the event state for the specified \fIsocket\fR\&. The returned value is a bit mask constructed by OR\(cqing a combination of the following event flags: +.PP +\fBZMQ_POLLIN\fR +.RS 4 +Indicates that at least one message may be received from the specified socket without blocking\&. +.RE +.PP +\fBZMQ_POLLOUT\fR +.RS 4 +Indicates that at least one message may be sent to the specified socket without blocking\&. +.RE +.sp +The combination of a file descriptor returned by the \fIZMQ_FD\fR option being ready for reading but no actual events returned by a subsequent retrieval of the \fIZMQ_EVENTS\fR option is valid; applications should simply ignore this case and restart their polling operation/event loop\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +N/A (flags) +T} +T{ +.sp +Default value +T}:T{ +.sp +N/A +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all +T} +.TE +.sp 1 +.SS "ZMQ_FD: Retrieve file descriptor associated with the socket" +.sp +The \fIZMQ_FD\fR option shall retrieve the file descriptor associated with the specified \fIsocket\fR\&. The returned file descriptor can be used to integrate the socket into an existing event loop; the 0MQ library shall signal any pending events on the socket in an \fIedge\-triggered\fR fashion by making the file descriptor become ready for reading\&. +.if n \{\ +.sp +.\} +.RS 4 +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBNote\fR +.ps -1 +.br +.sp +The ability to read from the returned file descriptor does not necessarily indicate that messages are available to be read from, or can be written to, the underlying socket; applications must retrieve the actual event state with a subsequent retrieval of the \fIZMQ_EVENTS\fR option\&. +.sp .5v +.RE +.if n \{\ +.sp +.\} +.RS 4 +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBNote\fR +.ps -1 +.br +.sp +The returned file descriptor is also used internally by the \fIzmq_send\fR and \fIzmq_recv\fR functions\&. As the descriptor is edge triggered, applications must update the state of \fIZMQ_EVENTS\fR after each invocation of \fIzmq_send\fR or \fIzmq_recv\fR\&.To be more explicit: after calling \fIzmq_send\fR the socket may become readable (and vice versa) without triggering a read event on the file descriptor\&. +.sp .5v +.RE +.if n \{\ +.sp +.\} +.RS 4 +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBCaution\fR +.ps -1 +.br +.sp +The returned file descriptor is intended for use with a \fIpoll\fR or similar system call only\&. Applications must never attempt to read or write data to it directly, neither should they try to close it\&. +.sp .5v +.RE +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int on POSIX systems, SOCKET on Windows +T} +T{ +.sp +Option value unit +T}:T{ +.sp +N/A +T} +T{ +.sp +Default value +T}:T{ +.sp +N/A +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all +T} +.TE +.sp 1 +.SS "ZMQ_GSSAPI_PLAINTEXT: Retrieve GSSAPI plaintext or encrypted status" +.sp +Returns the \fIZMQ_GSSAPI_PLAINTEXT\fR option, if any, previously set on the socket\&. A value of \fI1\fR means that communications will be plaintext\&. A value of \fI0\fR means communications will be encrypted\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +0, 1 +T} +T{ +.sp +Default value +T}:T{ +.sp +0 (false) +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, when using TCP or IPC transports +T} +.TE +.sp 1 +.SS "ZMQ_GSSAPI_PRINCIPAL: Retrieve the name of the GSSAPI principal" +.sp +The \fIZMQ_GSSAPI_PRINCIPAL\fR option shall retrieve the principal name set for the GSSAPI security mechanism\&. The returned value shall be a NULL\-terminated string and MAY be empty\&. The returned size SHALL include the terminating null byte\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +NULL\-terminated character string +T} +T{ +.sp +Option value unit +T}:T{ +.sp +N/A +T} +T{ +.sp +Default value +T}:T{ +.sp +null string +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, when using TCP or IPC transports +T} +.TE +.sp 1 +.SS "ZMQ_GSSAPI_SERVER: Retrieve current GSSAPI server role" +.sp +Returns the \fIZMQ_GSSAPI_SERVER\fR option, if any, previously set on the socket\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +0, 1 +T} +T{ +.sp +Default value +T}:T{ +.sp +0 (false) +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, when using TCP or IPC transports +T} +.TE +.sp 1 +.SS "ZMQ_GSSAPI_SERVICE_PRINCIPAL: Retrieve the name of the GSSAPI service principal" +.sp +The \fIZMQ_GSSAPI_SERVICE_PRINCIPAL\fR option shall retrieve the principal name of the GSSAPI server to which a GSSAPI client socket intends to connect\&. The returned value shall be a NULL\-terminated string and MAY be empty\&. The returned size SHALL include the terminating null byte\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +NULL\-terminated character string +T} +T{ +.sp +Option value unit +T}:T{ +.sp +N/A +T} +T{ +.sp +Default value +T}:T{ +.sp +null string +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, when using TCP or IPC transports +T} +.TE +.sp 1 +.SS "ZMQ_HANDSHAKE_IVL: Retrieve maximum handshake interval" +.sp +The \fIZMQ_HANDSHAKE_IVL\fR option shall retrieve the maximum handshake interval for the specified \fIsocket\fR\&. Handshaking is the exchange of socket configuration information (socket type, identity, security) that occurs when a connection is first opened, only for connection\-oriented transports\&. If handshaking does not complete within the configured time, the connection shall be closed\&. The value 0 means no handshake time limit\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +milliseconds +T} +T{ +.sp +Default value +T}:T{ +.sp +30000 +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all but ZMQ_STREAM, only for connection\-oriented transports +T} +.TE +.sp 1 +.SS "ZMQ_IDENTITY: Retrieve socket identity" +.sp +The \fIZMQ_IDENTITY\fR option shall retrieve the identity of the specified \fIsocket\fR\&. Socket identity is used only by request/reply pattern\&. Namely, it can be used in tandem with ROUTER socket to route messages to the peer with specific identity\&. +.sp +Identity should be at least one byte and at most 255 bytes long\&. Identities starting with binary zero are reserved for use by 0MQ infrastructure\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +binary data +T} +T{ +.sp +Option value unit +T}:T{ +.sp +N/A +T} +T{ +.sp +Default value +T}:T{ +.sp +NULL +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +ZMQ_REP, ZMQ_REQ, ZMQ_ROUTER, ZMQ_DEALER\&. +T} +.TE +.sp 1 +.SS "ZMQ_IMMEDIATE: Retrieve attach\-on\-connect value" +.sp +Retrieve the state of the attach on connect value\&. If set to 1, will delay the attachment of a pipe on connect until the underlying connection has completed\&. This will cause the socket to block if there are no other connections, but will prevent queues from filling on pipes awaiting connection\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +boolean +T} +T{ +.sp +Default value +T}:T{ +.sp +0 (false) +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, primarily when using TCP/IPC transports\&. +T} +.TE +.sp 1 +.SS "ZMQ_INVERT_MATCHING: Retrieve inverted filtering status" +.sp +Returns the value of the \fIZMQ_INVERT_MATCHING\fR option\&. A value of 1 means the socket uses inverted prefix matching\&. +.sp +On \fIPUB\fR and \fIXPUB\fR sockets, this causes messages to be sent to all connected sockets \fIexcept\fR those subscribed to a prefix that matches the message\&. On \fISUB\fR sockets, this causes only incoming messages that do \fInot\fR match any of the socket\(cqs subscriptions to be received by the user\&. +.sp +Whenever \fIZMQ_INVERT_MATCHING\fR is set to 1 on a \fIPUB\fR socket, all \fISUB\fR sockets connecting to it must also have the option set to 1\&. Failure to do so will have the \fISUB\fR sockets reject everything the \fIPUB\fR socket sends them\&. \fIXSUB\fR sockets do not need to do this because they do not filter incoming messages\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +0,1 +T} +T{ +.sp +Default value +T}:T{ +.sp +0 +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +ZMQ_PUB, ZMQ_XPUB, ZMQ_SUB +T} +.TE +.sp 1 +.SS "ZMQ_IPV4ONLY: Retrieve IPv4\-only socket override status" +.sp +Retrieve the IPv4\-only option for the socket\&. This option is deprecated\&. Please use the ZMQ_IPV6 option\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +boolean +T} +T{ +.sp +Default value +T}:T{ +.sp +1 (true) +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, when using TCP transports\&. +T} +.TE +.sp 1 +.SS "ZMQ_IPV6: Retrieve IPv6 socket status" +.sp +Retrieve the IPv6 option for the socket\&. A value of 1 means IPv6 is enabled on the socket, while 0 means the socket will use only IPv4\&. When IPv6 is enabled the socket will connect to, or accept connections from, both IPv4 and IPv6 hosts\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +boolean +T} +T{ +.sp +Default value +T}:T{ +.sp +0 (false) +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, when using TCP transports\&. +T} +.TE +.sp 1 +.SS "ZMQ_LAST_ENDPOINT: Retrieve the last endpoint set" +.sp +The \fIZMQ_LAST_ENDPOINT\fR option shall retrieve the last endpoint bound for TCP and IPC transports\&. The returned value will be a string in the form of a ZMQ DSN\&. Note that if the TCP host is INADDR_ANY, indicated by a *, then the returned address will be 0\&.0\&.0\&.0 (for IPv4)\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +NULL\-terminated character string +T} +T{ +.sp +Option value unit +T}:T{ +.sp +N/A +T} +T{ +.sp +Default value +T}:T{ +.sp +NULL +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, when binding TCP or IPC transports +T} +.TE +.sp 1 +.SS "ZMQ_LINGER: Retrieve linger period for socket shutdown" +.sp +The \fIZMQ_LINGER\fR option shall retrieve the linger period for the specified \fIsocket\fR\&. The linger period determines how long pending messages which have yet to be sent to a peer shall linger in memory after a socket is closed with \fBzmq_close\fR(3), and further affects the termination of the socket\(cqs context with \fBzmq_ctx_term\fR(3)\&. The following outlines the different behaviours: +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +The default value of +\fI\-1\fR +specifies an infinite linger period\&. Pending messages shall not be discarded after a call to +\fIzmq_close()\fR; attempting to terminate the socket\(cqs context with +\fIzmq_ctx_term()\fR +shall block until all pending messages have been sent to a peer\&. +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +The value of +\fI0\fR +specifies no linger period\&. Pending messages shall be discarded immediately when the socket is closed with +\fIzmq_close()\fR\&. +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +Positive values specify an upper bound for the linger period in milliseconds\&. Pending messages shall not be discarded after a call to +\fIzmq_close()\fR; attempting to terminate the socket\(cqs context with +\fIzmq_ctx_term()\fR +shall block until either all pending messages have been sent to a peer, or the linger period expires, after which any pending messages shall be discarded\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +Option value type +T}:T{ +int +T} +T{ +Option value unit +T}:T{ +milliseconds +T} +T{ +Default value +T}:T{ +\-1 (infinite) +T} +T{ +Applicable socket types +T}:T{ +all +T} +.TE +.sp 1 +.RE +.SS "ZMQ_MAXMSGSIZE: Maximum acceptable inbound message size" +.sp +The option shall retrieve limit for the inbound messages\&. If a peer sends a message larger than ZMQ_MAXMSGSIZE it is disconnected\&. Value of \-1 means \fIno limit\fR\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int64_t +T} +T{ +.sp +Option value unit +T}:T{ +.sp +bytes +T} +T{ +.sp +Default value +T}:T{ +.sp +\-1 +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all +T} +.TE +.sp 1 +.SS "ZMQ_MECHANISM: Retrieve current security mechanism" +.sp +The \fIZMQ_MECHANISM\fR option shall retrieve the current security mechanism for the socket\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +ZMQ_NULL, ZMQ_PLAIN, ZMQ_CURVE, or ZMQ_GSSAPI +T} +T{ +.sp +Default value +T}:T{ +.sp +ZMQ_NULL +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, when using TCP or IPC transports +T} +.TE +.sp 1 +.SS "ZMQ_MULTICAST_HOPS: Maximum network hops for multicast packets" +.sp +The option shall retrieve time\-to\-live used for outbound multicast packets\&. The default of 1 means that the multicast packets don\(cqt leave the local network\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +network hops +T} +T{ +.sp +Default value +T}:T{ +.sp +1 +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, when using multicast transports +T} +.TE +.sp 1 +.SS "ZMQ_MULTICAST_MAXTPDU: Maximum transport data unit size for multicast packets" +.sp +The \fIZMQ_MULTICAST_MAXTPDU\fR option shall retrieve the maximum transport data unit size used for outbound multicast packets\&. +.sp +This must be set at or below the minimum Maximum Transmission Unit (MTU) for all network paths over which multicast reception is required\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +bytes +T} +T{ +.sp +Default value +T}:T{ +.sp +1500 +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, when using multicast transports +T} +.TE +.sp 1 +.SS "ZMQ_PLAIN_PASSWORD: Retrieve current password" +.sp +The \fIZMQ_PLAIN_PASSWORD\fR option shall retrieve the last password set for the PLAIN security mechanism\&. The returned value shall be a NULL\-terminated string and MAY be empty\&. The returned size SHALL include the terminating null byte\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +NULL\-terminated character string +T} +T{ +.sp +Option value unit +T}:T{ +.sp +N/A +T} +T{ +.sp +Default value +T}:T{ +.sp +null string +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, when using TCP or IPC transports +T} +.TE +.sp 1 +.SS "ZMQ_PLAIN_SERVER: Retrieve current PLAIN server role" +.sp +Returns the \fIZMQ_PLAIN_SERVER\fR option, if any, previously set on the socket\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +0, 1 +T} +T{ +.sp +Default value +T}:T{ +.sp +int +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, when using TCP or IPC transports +T} +.TE +.sp 1 +.SS "ZMQ_PLAIN_USERNAME: Retrieve current PLAIN username" +.sp +The \fIZMQ_PLAIN_USERNAME\fR option shall retrieve the last username set for the PLAIN security mechanism\&. The returned value shall be a NULL\-terminated string and MAY be empty\&. The returned size SHALL include the terminating null byte\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +NULL\-terminated character string +T} +T{ +.sp +Option value unit +T}:T{ +.sp +N/A +T} +T{ +.sp +Default value +T}:T{ +.sp +null string +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, when using TCP or IPC transports +T} +.TE +.sp 1 +.SS "ZMQ_USE_FD: Retrieve the pre\-allocated socket file descriptor" +.sp +The \fIZMQ_USE_FD\fR option shall retrieve the pre\-allocated file descriptor that has been assigned to a ZMQ socket, if any\&. \-1 shall be returned if a pre\-allocated file descriptor was not set for the socket\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +file descriptor +T} +T{ +.sp +Default value +T}:T{ +.sp +\-1 +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all bound sockets, when using IPC or TCP transport +T} +.TE +.sp 1 +.SS "ZMQ_RATE: Retrieve multicast data rate" +.sp +The \fIZMQ_RATE\fR option shall retrieve the maximum send or receive data rate for multicast transports using the specified \fIsocket\fR\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +kilobits per second +T} +T{ +.sp +Default value +T}:T{ +.sp +100 +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, when using multicast transports +T} +.TE +.sp 1 +.SS "ZMQ_RCVBUF: Retrieve kernel receive buffer size" +.sp +The \fIZMQ_RCVBUF\fR option shall retrieve the underlying kernel receive buffer size for the specified \fIsocket\fR\&. For details refer to your operating system documentation for the \fISO_RCVBUF\fR socket option\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +bytes +T} +T{ +.sp +Default value +T}:T{ +.sp +8192 +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all +T} +.TE +.sp 1 +.SS "ZMQ_RCVHWM: Retrieve high water mark for inbound messages" +.sp +The \fIZMQ_RCVHWM\fR option shall return the high water mark for inbound messages on the specified \fIsocket\fR\&. The high water mark is a hard limit on the maximum number of outstanding messages 0MQ shall queue in memory for any single peer that the specified \fIsocket\fR is communicating with\&. A value of zero means no limit\&. +.sp +If this limit has been reached the socket shall enter an exceptional state and depending on the socket type, 0MQ shall take appropriate action such as blocking or dropping sent messages\&. Refer to the individual socket descriptions in \fBzmq_socket\fR(3) for details on the exact action taken for each socket type\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +messages +T} +T{ +.sp +Default value +T}:T{ +.sp +1000 +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all +T} +.TE +.sp 1 +.SS "ZMQ_RCVMORE: More message data parts to follow" +.sp +The \fIZMQ_RCVMORE\fR option shall return True (1) if the message part last received from the \fIsocket\fR was a data part with more parts to follow\&. If there are no data parts to follow, this option shall return False (0)\&. +.sp +Refer to \fBzmq_send\fR(3) and \fBzmq_recv\fR(3) for a detailed description of multi\-part messages\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +boolean +T} +T{ +.sp +Default value +T}:T{ +.sp +N/A +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all +T} +.TE +.sp 1 +.SS "ZMQ_RCVTIMEO: Maximum time before a socket operation returns with EAGAIN" +.sp +Retrieve the timeout for recv operation on the socket\&. If the value is 0, \fIzmq_recv(3)\fR will return immediately, with a EAGAIN error if there is no message to receive\&. If the value is \-1, it will block until a message is available\&. For all other values, it will wait for a message for that amount of time before returning with an EAGAIN error\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +milliseconds +T} +T{ +.sp +Default value +T}:T{ +.sp +\-1 (infinite) +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all +T} +.TE +.sp 1 +.SS "ZMQ_RECONNECT_IVL: Retrieve reconnection interval" +.sp +The \fIZMQ_RECONNECT_IVL\fR option shall retrieve the initial reconnection interval for the specified \fIsocket\fR\&. The reconnection interval is the period 0MQ shall wait between attempts to reconnect disconnected peers when using connection\-oriented transports\&. The value \-1 means no reconnection\&. +.if n \{\ +.sp +.\} +.RS 4 +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBNote\fR +.ps -1 +.br +.sp +The reconnection interval may be randomized by 0MQ to prevent reconnection storms in topologies with a large number of peers per socket\&. +.sp .5v +.RE +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +milliseconds +T} +T{ +.sp +Default value +T}:T{ +.sp +100 +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, only for connection\-oriented transports +T} +.TE +.sp 1 +.SS "ZMQ_RECONNECT_IVL_MAX: Retrieve maximum reconnection interval" +.sp +The \fIZMQ_RECONNECT_IVL_MAX\fR option shall retrieve the maximum reconnection interval for the specified \fIsocket\fR\&. This is the maximum period 0MQ shall wait between attempts to reconnect\&. On each reconnect attempt, the previous interval shall be doubled untill ZMQ_RECONNECT_IVL_MAX is reached\&. This allows for exponential backoff strategy\&. Default value means no exponential backoff is performed and reconnect interval calculations are only based on ZMQ_RECONNECT_IVL\&. +.if n \{\ +.sp +.\} +.RS 4 +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBNote\fR +.ps -1 +.br +.sp +Values less than ZMQ_RECONNECT_IVL will be ignored\&. +.sp .5v +.RE +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +milliseconds +T} +T{ +.sp +Default value +T}:T{ +.sp +0 (only use ZMQ_RECONNECT_IVL) +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, only for connection\-oriented transport +T} +.TE +.sp 1 +.SS "ZMQ_RECOVERY_IVL: Get multicast recovery interval" +.sp +The \fIZMQ_RECOVERY_IVL\fR option shall retrieve the recovery interval for multicast transports using the specified \fIsocket\fR\&. The recovery interval determines the maximum time in milliseconds that a receiver can be absent from a multicast group before unrecoverable data loss will occur\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +milliseconds +T} +T{ +.sp +Default value +T}:T{ +.sp +10000 +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, when using multicast transports +T} +.TE +.sp 1 +.SS "ZMQ_SNDBUF: Retrieve kernel transmit buffer size" +.sp +The \fIZMQ_SNDBUF\fR option shall retrieve the underlying kernel transmit buffer size for the specified \fIsocket\fR\&. For details refer to your operating system documentation for the \fISO_SNDBUF\fR socket option\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +bytes +T} +T{ +.sp +Default value +T}:T{ +.sp +8192 +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all +T} +.TE +.sp 1 +.SS "ZMQ_SNDHWM: Retrieves high water mark for outbound messages" +.sp +The \fIZMQ_SNDHWM\fR option shall return the high water mark for outbound messages on the specified \fIsocket\fR\&. The high water mark is a hard limit on the maximum number of outstanding messages 0MQ shall queue in memory for any single peer that the specified \fIsocket\fR is communicating with\&. A value of zero means no limit\&. +.sp +If this limit has been reached the socket shall enter an exceptional state and depending on the socket type, 0MQ shall take appropriate action such as blocking or dropping sent messages\&. Refer to the individual socket descriptions in \fBzmq_socket\fR(3) for details on the exact action taken for each socket type\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +messages +T} +T{ +.sp +Default value +T}:T{ +.sp +1000 +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all +T} +.TE +.sp 1 +.SS "ZMQ_SNDTIMEO: Maximum time before a socket operation returns with EAGAIN" +.sp +Retrieve the timeout for send operation on the socket\&. If the value is 0, \fIzmq_send(3)\fR will return immediately, with a EAGAIN error if the message cannot be sent\&. If the value is \-1, it will block until the message is sent\&. For all other values, it will try to send the message for that amount of time before returning with an EAGAIN error\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +milliseconds +T} +T{ +.sp +Default value +T}:T{ +.sp +\-1 (infinite) +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all +T} +.TE +.sp 1 +.SS "ZMQ_SOCKS_PROXY: Retrieve SOCKS5 proxy address" +.sp +The \fIZMQ_SOCKS_PROXY\fR option shall retrieve the SOCKS5 proxy address in string format\&. The returned value shall be a NULL\-terminated string and MAY be empty\&. The returned size SHALL include the terminating null byte\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +NULL\-terminated character string +T} +T{ +.sp +Option value unit +T}:T{ +.sp +N/A +T} +T{ +.sp +Default value +T}:T{ +.sp +null string +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, when using TCP transports +T} +.TE +.sp 1 +.SS "ZMQ_TCP_KEEPALIVE: Override SO_KEEPALIVE socket option" +.sp +Override \fISO_KEEPALIVE\fR socket option(where supported by OS)\&. The default value of \-1 means to skip any overrides and leave it to OS default\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +\-1,0,1 +T} +T{ +.sp +Default value +T}:T{ +.sp +\-1 (leave to OS default) +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, when using TCP transports\&. +T} +.TE +.sp 1 +.SS "ZMQ_TCP_KEEPALIVE_CNT: Override TCP_KEEPCNT socket option" +.sp +Override \fITCP_KEEPCNT\fR socket option(where supported by OS)\&. The default value of \-1 means to skip any overrides and leave it to OS default\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +\-1,>0 +T} +T{ +.sp +Default value +T}:T{ +.sp +\-1 (leave to OS default) +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, when using TCP transports\&. +T} +.TE +.sp 1 +.SS "ZMQ_TCP_KEEPALIVE_IDLE: Override TCP_KEEPIDLE (or TCP_KEEPALIVE on some OS)" +.sp +Override \fITCP_KEEPIDLE\fR(or \fITCP_KEEPALIVE\fR on some OS) socket option (where supported by OS)\&. The default value of \-1 means to skip any overrides and leave it to OS default\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +\-1,>0 +T} +T{ +.sp +Default value +T}:T{ +.sp +\-1 (leave to OS default) +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, when using TCP transports\&. +T} +.TE +.sp 1 +.SS "ZMQ_TCP_KEEPALIVE_INTVL: Override TCP_KEEPINTVL socket option" +.sp +Override \fITCP_KEEPINTVL\fR socket option(where supported by OS)\&. The default value of \-1 means to skip any overrides and leave it to OS default\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +\-1,>0 +T} +T{ +.sp +Default value +T}:T{ +.sp +\-1 (leave to OS default) +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, when using TCP transports\&. +T} +.TE +.sp 1 +.SS "ZMQ_TCP_MAXRT: Retrieve Max TCP Retransmit Timeout" +.sp +On OSes where it is supported, retrieves how long before an unacknowledged TCP retransmit times out\&. The system normally attempts many TCP retransmits following an exponential backoff strategy\&. This means that after a network outage, it may take a long time before the session can be re\-established\&. Setting this option allows the timeout to happen at a shorter interval\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +milliseconds +T} +T{ +.sp +Default value +T}:T{ +.sp +0 (leave to OS default) +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, when using TCP transports\&. +T} +.TE +.sp 1 +.SS "ZMQ_THREAD_SAFE: Retrieve socket thread safety" +.sp +The \fIZMQ_THREAD_SAFE\fR option shall retrieve a boolean value indicating whether or not the socket is threadsafe\&. Currently \fIZMQ_CLIENT\fR and \fIZMQ_SERVER\fR sockets are threadsafe\&. +.TS +tab(:); +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +boolean +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all +T} +.TE +.sp 1 +.SS "ZMQ_TOS: Retrieve the Type\-of\-Service socket override status" +.sp +Retrieve the IP_TOS option for the socket\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +>0 +T} +T{ +.sp +Default value +T}:T{ +.sp +0 +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, only for connection\-oriented transports +T} +.TE +.sp 1 +.SS "ZMQ_TYPE: Retrieve socket type" +.sp +The \fIZMQ_TYPE\fR option shall retrieve the socket type for the specified \fIsocket\fR\&. The socket type is specified at socket creation time and cannot be modified afterwards\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +N/A +T} +T{ +.sp +Default value +T}:T{ +.sp +N/A +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all +T} +.TE +.sp 1 +.SS "ZMQ_ZAP_DOMAIN: Retrieve RFC 27 authentication domain" +.sp +The \fIZMQ_ZAP_DOMAIN\fR option shall retrieve the last ZAP domain set for the socket\&. The returned value shall be a NULL\-terminated string and MAY be empty\&. The returned size SHALL include the terminating null byte\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +character string +T} +T{ +.sp +Option value unit +T}:T{ +.sp +N/A +T} +T{ +.sp +Default value +T}:T{ +.sp +not set +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, when using TCP transport +T} +.TE +.sp 1 +.SS "ZMQ_VMCI_BUFFER_SIZE: Retrieve buffer size of the VMCI socket" +.sp +The ZMQ_VMCI_BUFFER_SIZE option shall retrieve the size of the underlying buffer for the socket\&. Used during negotiation before the connection is established\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +uint64_t +T} +T{ +.sp +Option value unit +T}:T{ +.sp +bytes +T} +T{ +.sp +Default value +T}:T{ +.sp +65546 +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, when using VMCI transport +T} +.TE +.sp 1 +.SS "ZMQ_VMCI_BUFFER_MIN_SIZE: Retrieve min buffer size of the VMCI socket" +.sp +The ZMQ_VMCI_BUFFER_MIN_SIZE option shall retrieve the min size of the underlying buffer for the socket\&. Used during negotiation before the connection is established\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +uint64_t +T} +T{ +.sp +Option value unit +T}:T{ +.sp +bytes +T} +T{ +.sp +Default value +T}:T{ +.sp +128 +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, when using VMCI transport +T} +.TE +.sp 1 +.SS "ZMQ_VMCI_BUFFER_MAX_SIZE: Retrieve max buffer size of the VMCI socket" +.sp +The ZMQ_VMCI_BUFFER_MAX_SIZE option shall retrieve the max size of the underlying buffer for the socket\&. Used during negotiation before the connection is established\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +uint64_t +T} +T{ +.sp +Option value unit +T}:T{ +.sp +bytes +T} +T{ +.sp +Default value +T}:T{ +.sp +262144 +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, when using VMCI transport +T} +.TE +.sp 1 +.SS "ZMQ_VMCI_CONNECT_TIMEOUT: Retrieve connection timeout of the VMCI socket" +.sp +The ZMQ_VMCI_CONNECT_TIMEOUT option shall retrieve connection timeout for the socket\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +milliseconds +T} +T{ +.sp +Default value +T}:T{ +.sp +\-1 +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, when using VMCI transport +T} +.TE +.sp 1 +.SH "RETURN VALUE" +.sp +The \fIzmq_getsockopt()\fR function shall return zero if successful\&. Otherwise it shall return \-1 and set \fIerrno\fR to one of the values defined below\&. +.SH "ERRORS" +.PP +\fBEINVAL\fR +.RS 4 +The requested option +\fIoption_name\fR +is unknown, or the requested +\fIoption_len\fR +or +\fIoption_value\fR +is invalid, or the size of the buffer pointed to by +\fIoption_value\fR, as specified by +\fIoption_len\fR, is insufficient for storing the option value\&. +.RE +.PP +\fBETERM\fR +.RS 4 +The 0MQ +\fIcontext\fR +associated with the specified +\fIsocket\fR +was terminated\&. +.RE +.PP +\fBENOTSOCK\fR +.RS 4 +The provided +\fIsocket\fR +was invalid\&. +.RE +.PP +\fBEINTR\fR +.RS 4 +The operation was interrupted by delivery of a signal\&. +.RE +.SH "EXAMPLE" +.PP +\fBRetrieving the high water mark for outgoing messages\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +/* Retrieve high water mark into sndhwm */ +int sndhwm; +size_t sndhwm_size = sizeof (sndhwm); +rc = zmq_getsockopt (socket, ZMQ_SNDHWM, &sndhwm, &sndhwm_size); +assert (rc == 0); +.fi +.if n \{\ +.RE +.\} +.sp +.SH "SEE ALSO" +.sp +\fBzmq_setsockopt\fR(3) \fBzmq_socket\fR(3) \fBzmq\fR(7) +.SH "AUTHORS" +.sp +This page was written by the 0MQ community\&. To make a change please read the 0MQ Contribution Policy at \m[blue]\fBhttp://www\&.zeromq\&.org/docs:contributing\fR\m[]\&. diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_has.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_has.3 new file mode 100644 index 00000000000000..37a01001056863 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_has.3 @@ -0,0 +1,124 @@ +'\" t +.\" Title: zmq_has +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.78.1 +.\" Date: 02/18/2017 +.\" Manual: 0MQ Manual +.\" Source: 0MQ 4.2.2 +.\" Language: English +.\" +.TH "ZMQ_HAS" "3" "02/18/2017" "0MQ 4\&.2\&.2" "0MQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zmq_has \- check a ZMQ capability +.SH "SYNOPSIS" +.sp +\fBint zmq_has (const char *capability);\fR +.SH "DESCRIPTION" +.sp +The \fIzmq_has()\fR function shall report whether a specified capability is available in the library\&. This allows bindings and applications to probe a library directly, for transport and security options\&. +.sp +Capabilities shall be lowercase strings\&. The following capabilities are defined: +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +ipc \- the library supports the ipc:// protocol +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +pgm \- the library supports the pgm:// protocol +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +tipc \- the library supports the tipc:// protocol +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +norm \- the library supports the norm:// protocol +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +curve \- the library supports the CURVE security mechanism +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +gssapi \- the library supports the GSSAPI security mechanism +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +draft \- the library is built with the draft api +.RE +.sp +When this method is provided, the zmq\&.h header file will define ZMQ_HAS_CAPABILITIES\&. +.SH "RETURN VALUE" +.sp +The \fIzmq_has()\fR function shall return 1 if the specified capability is provided\&. Otherwise it shall return 0\&. +.SH "AUTHORS" +.sp +This page was written by the 0MQ community\&. To make a change please read the 0MQ Contribution Policy at \m[blue]\fBhttp://www\&.zeromq\&.org/docs:contributing\fR\m[]\&. diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_msg_close.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_msg_close.3 new file mode 100644 index 00000000000000..098a5a8b3c4eba --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_msg_close.3 @@ -0,0 +1,70 @@ +'\" t +.\" Title: zmq_msg_close +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.78.1 +.\" Date: 02/18/2017 +.\" Manual: 0MQ Manual +.\" Source: 0MQ 4.2.2 +.\" Language: English +.\" +.TH "ZMQ_MSG_CLOSE" "3" "02/18/2017" "0MQ 4\&.2\&.2" "0MQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zmq_msg_close \- release 0MQ message +.SH "SYNOPSIS" +.sp +\fBint zmq_msg_close (zmq_msg_t \fR\fB\fI*msg\fR\fR\fB);\fR +.SH "DESCRIPTION" +.sp +The \fIzmq_msg_close()\fR function shall inform the 0MQ infrastructure that any resources associated with the message object referenced by \fImsg\fR are no longer required and may be released\&. Actual release of resources associated with the message object shall be postponed by 0MQ until all users of the message or underlying data buffer have indicated it is no longer required\&. +.sp +Applications should ensure that \fIzmq_msg_close()\fR is called once a message is no longer required, otherwise memory leaks may occur\&. Note that this is NOT necessary after a successful \fIzmq_msg_send()\fR\&. +.if n \{\ +.sp +.\} +.RS 4 +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBCaution\fR +.ps -1 +.br +.sp +Never access \fIzmq_msg_t\fR members directly, instead always use the \fIzmq_msg\fR family of functions\&. +.sp .5v +.RE +.SH "RETURN VALUE" +.sp +The \fIzmq_msg_close()\fR function shall return zero if successful\&. Otherwise it shall return \-1 and set \fIerrno\fR to one of the values defined below\&. +.SH "ERRORS" +.PP +\fBEFAULT\fR +.RS 4 +Invalid message\&. +.RE +.SH "SEE ALSO" +.sp +\fBzmq_msg_init\fR(3) \fBzmq_msg_init_size\fR(3) \fBzmq_msg_init_data\fR(3) \fBzmq_msg_data\fR(3) \fBzmq_msg_size\fR(3) \fBzmq\fR(7) +.SH "AUTHORS" +.sp +This page was written by the 0MQ community\&. To make a change please read the 0MQ Contribution Policy at \m[blue]\fBhttp://www\&.zeromq\&.org/docs:contributing\fR\m[]\&. diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_msg_copy.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_msg_copy.3 new file mode 100644 index 00000000000000..d8136ef9aaa45c --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_msg_copy.3 @@ -0,0 +1,106 @@ +'\" t +.\" Title: zmq_msg_copy +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.78.1 +.\" Date: 02/18/2017 +.\" Manual: 0MQ Manual +.\" Source: 0MQ 4.2.2 +.\" Language: English +.\" +.TH "ZMQ_MSG_COPY" "3" "02/18/2017" "0MQ 4\&.2\&.2" "0MQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zmq_msg_copy \- copy content of a message to another message +.SH "SYNOPSIS" +.sp +\fBint zmq_msg_copy (zmq_msg_t \fR\fB\fI*dest\fR\fR\fB, zmq_msg_t \fR\fB\fI*src\fR\fR\fB);\fR +.SH "DESCRIPTION" +.sp +The \fIzmq_msg_copy()\fR function shall copy the message object referenced by \fIsrc\fR to the message object referenced by \fIdest\fR\&. The original content of \fIdest\fR, if any, shall be released\&. You must initialise \fIdest\fR before copying to it\&. +.if n \{\ +.sp +.\} +.RS 4 +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBCaution\fR +.ps -1 +.br +.sp +The implementation may choose not to physically copy the message content, rather to share the underlying buffer between \fIsrc\fR and \fIdest\fR\&. Avoid modifying message content after a message has been copied with \fIzmq_msg_copy()\fR, doing so can result in undefined behaviour\&. If what you need is an actual hard copy, allocate a new message using \fIzmq_msg_init_size()\fR and copy the message content using \fImemcpy()\fR\&. +.sp .5v +.RE +.if n \{\ +.sp +.\} +.RS 4 +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBCaution\fR +.ps -1 +.br +.sp +Never access \fIzmq_msg_t\fR members directly, instead always use the \fIzmq_msg\fR family of functions\&. +.sp .5v +.RE +.SH "RETURN VALUE" +.sp +The \fIzmq_msg_copy()\fR function shall return zero if successful\&. Otherwise it shall return \-1 and set \fIerrno\fR to one of the values defined below\&. +.SH "ERRORS" +.PP +\fBEFAULT\fR +.RS 4 +Invalid message\&. +.RE +.SH "EXAMPLE" +.PP +\fBCopying a message\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +zmq_msg_t msg; +zmq_msg_init_size (&msg, 255); +memcpy (zmq_msg_data (&msg, "Hello, World", 12); +zmq_msg_t copy; +zmq_msg_init (©); +zmq_msg_copy (©, &msg); +\&.\&.\&. +zmq_msg_close (©); +zmq_msg_close (&msg); +.fi +.if n \{\ +.RE +.\} +.sp +.SH "SEE ALSO" +.sp +\fBzmq_msg_move\fR(3) \fBzmq_msg_init\fR(3) \fBzmq_msg_init_size\fR(3) \fBzmq_msg_init_data\fR(3) \fBzmq_msg_close\fR(3) \fBzmq\fR(7) +.SH "AUTHORS" +.sp +This page was written by the 0MQ community\&. To make a change please read the 0MQ Contribution Policy at \m[blue]\fBhttp://www\&.zeromq\&.org/docs:contributing\fR\m[]\&. diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_msg_data.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_msg_data.3 new file mode 100644 index 00000000000000..7525f5cce86928 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_msg_data.3 @@ -0,0 +1,65 @@ +'\" t +.\" Title: zmq_msg_data +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.78.1 +.\" Date: 02/18/2017 +.\" Manual: 0MQ Manual +.\" Source: 0MQ 4.2.2 +.\" Language: English +.\" +.TH "ZMQ_MSG_DATA" "3" "02/18/2017" "0MQ 4\&.2\&.2" "0MQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zmq_msg_data \- retrieve pointer to message content +.SH "SYNOPSIS" +.sp +\fBvoid *zmq_msg_data (zmq_msg_t \fR\fB\fI*msg\fR\fR\fB);\fR +.SH "DESCRIPTION" +.sp +The \fIzmq_msg_data()\fR function shall return a pointer to the message content of the message object referenced by \fImsg\fR\&. +.if n \{\ +.sp +.\} +.RS 4 +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBCaution\fR +.ps -1 +.br +.sp +Never access \fIzmq_msg_t\fR members directly, instead always use the \fIzmq_msg\fR family of functions\&. +.sp .5v +.RE +.SH "RETURN VALUE" +.sp +Upon successful completion, \fIzmq_msg_data()\fR shall return a pointer to the message content\&. +.SH "ERRORS" +.sp +No errors are defined\&. +.SH "SEE ALSO" +.sp +\fBzmq_msg_size\fR(3) \fBzmq_msg_init\fR(3) \fBzmq_msg_init_size\fR(3) \fBzmq_msg_init_data\fR(3) \fBzmq_msg_close\fR(3) \fBzmq\fR(7) +.SH "AUTHORS" +.sp +This page was written by the 0MQ community\&. To make a change please read the 0MQ Contribution Policy at \m[blue]\fBhttp://www\&.zeromq\&.org/docs:contributing\fR\m[]\&. diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_msg_get.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_msg_get.3 new file mode 100644 index 00000000000000..ec1764be3848a3 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_msg_get.3 @@ -0,0 +1,104 @@ +'\" t +.\" Title: zmq_msg_get +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.78.1 +.\" Date: 02/18/2017 +.\" Manual: 0MQ Manual +.\" Source: 0MQ 4.2.2 +.\" Language: English +.\" +.TH "ZMQ_MSG_GET" "3" "02/18/2017" "0MQ 4\&.2\&.2" "0MQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zmq_msg_get \- get message property +.SH "SYNOPSIS" +.sp +\fBint zmq_msg_get (zmq_msg_t \fR\fB\fI*message\fR\fR\fB, int \fR\fB\fIproperty\fR\fR\fB);\fR +.SH "DESCRIPTION" +.sp +The \fIzmq_msg_get()\fR function shall return the value for the property specified by the \fIproperty\fR argument for the message pointed to by the \fImessage\fR argument\&. +.sp +The following properties can be retrieved with the \fIzmq_msg_get()\fR function: +.PP +\fBZMQ_MORE\fR +.RS 4 +Indicates that there are more message frames to follow after the +\fImessage\fR\&. +.RE +.PP +\fBZMQ_SRCFD\fR +.RS 4 +Returns the file descriptor of the socket the +\fImessage\fR +was read from\&. This allows application to retrieve the remote endpoint via +\fIgetpeername(2)\fR\&. Be aware that the respective socket might be closed already, reused even\&. Currently only implemented for TCP sockets\&. +.RE +.PP +\fBZMQ_SHARED\fR +.RS 4 +Indicates that a message MAY share underlying storage with another copy of this message\&. +.RE +.SH "RETURN VALUE" +.sp +The \fIzmq_msg_get()\fR function shall return the value for the property if successful\&. Otherwise it shall return \-1 and set \fIerrno\fR to one of the values defined below\&. +.SH "ERRORS" +.PP +\fBEINVAL\fR +.RS 4 +The requested +\fIproperty\fR +is unknown\&. +.RE +.SH "EXAMPLE" +.PP +\fBReceiving a multi-frame message\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +zmq_msg_t frame; +while (true) { + // Create an empty 0MQ message to hold the message frame + int rc = zmq_msg_init (&frame); + assert (rc == 0); + // Block until a message is available to be received from socket + rc = zmq_msg_recv (socket, &frame, 0); + assert (rc != \-1); + if (zmq_msg_get (&frame, ZMQ_MORE)) + fprintf (stderr, "more\en"); + else { + fprintf (stderr, "end\en"); + break; + } + zmq_msg_close (&frame); +} +.fi +.if n \{\ +.RE +.\} +.sp +.SH "SEE ALSO" +.sp +\fBzmq_msg_set\fR(3) \fBzmq_msg_init\fR(3) \fBzmq_msg_close\fR(3) \fBzmq\fR(7) +.SH "AUTHORS" +.sp +This page was written by the 0MQ community\&. To make a change please read the 0MQ Contribution Policy at \m[blue]\fBhttp://www\&.zeromq\&.org/docs:contributing\fR\m[]\&. diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_msg_gets.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_msg_gets.3 new file mode 100644 index 00000000000000..2624896f605299 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_msg_gets.3 @@ -0,0 +1,93 @@ +'\" t +.\" Title: zmq_msg_gets +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.78.1 +.\" Date: 02/18/2017 +.\" Manual: 0MQ Manual +.\" Source: 0MQ 4.2.2 +.\" Language: English +.\" +.TH "ZMQ_MSG_GETS" "3" "02/18/2017" "0MQ 4\&.2\&.2" "0MQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zmq_msg_gets \- get message metadata property +.SH "SYNOPSIS" +.sp +\fBconst char *zmq_msg_gets (zmq_msg_t \fR\fB\fI*message\fR\fR\fB, const char *\fR\fB\fIproperty\fR\fR\fB);\fR +.SH "DESCRIPTION" +.sp +The \fIzmq_msg_gets()\fR function shall return the string value for the metadata property specified by the \fIproperty\fR argument for the message pointed to by the \fImessage\fR argument\&. Both the \fIproperty\fR argument and the \fIvalue\fR shall be NULL\-terminated UTF8\-encoded strings\&. +.sp +Metadata is defined on a per\-connection basis during the ZeroMQ connection handshake as specified in \&. +.sp +The following ZMTP properties can be retrieved with the \fIzmq_msg_gets()\fR function: +.sp +.if n \{\ +.RS 4 +.\} +.nf +Socket\-Type +Identity +Resource +.fi +.if n \{\ +.RE +.\} +.sp +Additionally, when available for the underlying transport, the \fBPeer\-Address\fR property will return the IP address of the remote endpoint as returned by getnameinfo(2)\&. +.sp +Other properties may be defined based on the underlying security mechanism, see ZAP authenticated connection sample below\&. +.SH "RETURN VALUE" +.sp +The \fIzmq_msg_gets()\fR function shall return the string value for the property if successful\&. Otherwise it shall return NULL and set \fIerrno\fR to one of the values defined below\&. The caller shall not modify or free the returned value, which shall be owned by the message\&. The encoding of the property and value shall be UTF8\&. +.SH "ERRORS" +.PP +\fBEINVAL\fR +.RS 4 +The requested +\fIproperty\fR +is unknown\&. +.RE +.SH "EXAMPLE" +.PP +\fBGetting the ZAP authenticated user id for a message:\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +zmq_msg_t msg; +zmq_msg_init (&msg); +rc = zmq_msg_recv (&msg, dealer, 0); +assert (rc != \-1); +const char *user_id = zmq_msg_gets (&msg, "User\-Id"); +zmq_msg_close (&msg); +.fi +.if n \{\ +.RE +.\} +.sp +.SH "SEE ALSO" +.sp +\fBzmq\fR(7) +.SH "AUTHORS" +.sp +This page was written by the 0MQ community\&. To make a change please read the 0MQ Contribution Policy at \m[blue]\fBhttp://www\&.zeromq\&.org/docs:contributing\fR\m[]\&. diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_msg_init.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_msg_init.3 new file mode 100644 index 00000000000000..baf280b251f482 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_msg_init.3 @@ -0,0 +1,99 @@ +'\" t +.\" Title: zmq_msg_init +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.78.1 +.\" Date: 02/18/2017 +.\" Manual: 0MQ Manual +.\" Source: 0MQ 4.2.2 +.\" Language: English +.\" +.TH "ZMQ_MSG_INIT" "3" "02/18/2017" "0MQ 4\&.2\&.2" "0MQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zmq_msg_init \- initialise empty 0MQ message +.SH "SYNOPSIS" +.sp +\fBint zmq_msg_init (zmq_msg_t \fR\fB\fI*msg\fR\fR\fB);\fR +.SH "DESCRIPTION" +.sp +The \fIzmq_msg_init()\fR function shall initialise the message object referenced by \fImsg\fR to represent an empty message\&. This function is most useful when called before receiving a message with \fIzmq_recv()\fR\&. +.if n \{\ +.sp +.\} +.RS 4 +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBCaution\fR +.ps -1 +.br +.sp +Never access \fIzmq_msg_t\fR members directly, instead always use the \fIzmq_msg\fR family of functions\&. +.sp .5v +.RE +.if n \{\ +.sp +.\} +.RS 4 +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBCaution\fR +.ps -1 +.br +.sp +The functions \fIzmq_msg_init()\fR, \fIzmq_msg_init_data()\fR and \fIzmq_msg_init_size()\fR are mutually exclusive\&. Never initialise the same \fIzmq_msg_t\fR twice\&. +.sp .5v +.RE +.SH "RETURN VALUE" +.sp +The \fIzmq_msg_init()\fR function always returns zero\&. +.SH "ERRORS" +.sp +No errors are defined\&. +.SH "EXAMPLE" +.PP +\fBReceiving a message from a socket\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +zmq_msg_t msg; +rc = zmq_msg_init (&msg); +assert (rc == 0); +int nbytes = zmq_recv (socket, &msg, 0); +assert (nbytes != \-1); +.fi +.if n \{\ +.RE +.\} +.sp +.SH "SEE ALSO" +.sp +\fBzmq_msg_init_size\fR(3) \fBzmq_msg_init_data\fR(3) \fBzmq_msg_close\fR(3) \fBzmq_msg_data\fR(3) \fBzmq_msg_size\fR(3) \fBzmq\fR(7) +.SH "AUTHORS" +.sp +This page was written by the 0MQ community\&. To make a change please read the 0MQ Contribution Policy at \m[blue]\fBhttp://www\&.zeromq\&.org/docs:contributing\fR\m[]\&. diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_msg_init_data.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_msg_init_data.3 new file mode 100644 index 00000000000000..1130b76c72251f --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_msg_init_data.3 @@ -0,0 +1,146 @@ +'\" t +.\" Title: zmq_msg_init_data +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.78.1 +.\" Date: 02/18/2017 +.\" Manual: 0MQ Manual +.\" Source: 0MQ 4.2.2 +.\" Language: English +.\" +.TH "ZMQ_MSG_INIT_DATA" "3" "02/18/2017" "0MQ 4\&.2\&.2" "0MQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zmq_msg_init_data \- initialise 0MQ message from a supplied buffer +.SH "SYNOPSIS" +.sp +\fBtypedef void (zmq_free_fn) (void \fR\fB\fI*data\fR\fR\fB, void \fR\fB\fI*hint\fR\fR\fB);\fR +.sp +\fBint zmq_msg_init_data (zmq_msg_t \fR\fB\fI*msg\fR\fR\fB, void \fR\fB\fI*data\fR\fR\fB, size_t \fR\fB\fIsize\fR\fR\fB, zmq_free_fn \fR\fB\fI*ffn\fR\fR\fB, void \fR\fB\fI*hint\fR\fR\fB);\fR +.SH "DESCRIPTION" +.sp +The \fIzmq_msg_init_data()\fR function shall initialise the message object referenced by \fImsg\fR to represent the content referenced by the buffer located at address \fIdata\fR, \fIsize\fR bytes long\&. No copy of \fIdata\fR shall be performed and 0MQ shall take ownership of the supplied buffer\&. +.sp +If provided, the deallocation function \fIffn\fR shall be called once the data buffer is no longer required by 0MQ, with the \fIdata\fR and \fIhint\fR arguments supplied to \fIzmq_msg_init_data()\fR\&. +.if n \{\ +.sp +.\} +.RS 4 +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBCaution\fR +.ps -1 +.br +.sp +Never access \fIzmq_msg_t\fR members directly, instead always use the \fIzmq_msg\fR family of functions\&. +.sp .5v +.RE +.if n \{\ +.sp +.\} +.RS 4 +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBCaution\fR +.ps -1 +.br +.sp +The deallocation function \fIffn\fR needs to be thread\-safe, since it will be called from an arbitrary thread\&. +.sp .5v +.RE +.if n \{\ +.sp +.\} +.RS 4 +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBCaution\fR +.ps -1 +.br +.sp +If the deallocation function is not provided, the allocated memory will not be freed, and this may cause a memory leak\&. +.sp .5v +.RE +.if n \{\ +.sp +.\} +.RS 4 +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBCaution\fR +.ps -1 +.br +.sp +The functions \fIzmq_msg_init()\fR, \fIzmq_msg_init_data()\fR and \fIzmq_msg_init_size()\fR are mutually exclusive\&. Never initialise the same \fIzmq_msg_t\fR twice\&. +.sp .5v +.RE +.SH "RETURN VALUE" +.sp +The \fIzmq_msg_init_data()\fR function shall return zero if successful\&. Otherwise it shall return \-1 and set \fIerrno\fR to one of the values defined below\&. +.SH "ERRORS" +.PP +\fBENOMEM\fR +.RS 4 +Insufficient storage space is available\&. +.RE +.SH "EXAMPLE" +.PP +\fBInitialising a message from a supplied buffer\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +void my_free (void *data, void *hint) +{ + free (data); +} + + /* \&.\&.\&. */ + +void *data = malloc (6); +assert (data); +memcpy (data, "ABCDEF", 6); +zmq_msg_t msg; +rc = zmq_msg_init_data (&msg, data, 6, my_free, NULL); +assert (rc == 0); +.fi +.if n \{\ +.RE +.\} +.sp +.SH "SEE ALSO" +.sp +\fBzmq_msg_init_size\fR(3) \fBzmq_msg_init\fR(3) \fBzmq_msg_close\fR(3) \fBzmq_msg_data\fR(3) \fBzmq_msg_size\fR(3) \fBzmq\fR(7) +.SH "AUTHORS" +.sp +This page was written by the 0MQ community\&. To make a change please read the 0MQ Contribution Policy at \m[blue]\fBhttp://www\&.zeromq\&.org/docs:contributing\fR\m[]\&. diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_msg_init_size.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_msg_init_size.3 new file mode 100644 index 00000000000000..f0f4eb51edafec --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_msg_init_size.3 @@ -0,0 +1,86 @@ +'\" t +.\" Title: zmq_msg_init_size +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.78.1 +.\" Date: 02/18/2017 +.\" Manual: 0MQ Manual +.\" Source: 0MQ 4.2.2 +.\" Language: English +.\" +.TH "ZMQ_MSG_INIT_SIZE" "3" "02/18/2017" "0MQ 4\&.2\&.2" "0MQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zmq_msg_init_size \- initialise 0MQ message of a specified size +.SH "SYNOPSIS" +.sp +\fBint zmq_msg_init_size (zmq_msg_t \fR\fB\fI*msg\fR\fR\fB, size_t \fR\fB\fIsize\fR\fR\fB);\fR +.SH "DESCRIPTION" +.sp +The \fIzmq_msg_init_size()\fR function shall allocate any resources required to store a message \fIsize\fR bytes long and initialise the message object referenced by \fImsg\fR to represent the newly allocated message\&. +.sp +The implementation shall choose whether to store message content on the stack (small messages) or on the heap (large messages)\&. For performance reasons \fIzmq_msg_init_size()\fR shall not clear the message data\&. +.if n \{\ +.sp +.\} +.RS 4 +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBCaution\fR +.ps -1 +.br +.sp +Never access \fIzmq_msg_t\fR members directly, instead always use the \fIzmq_msg\fR family of functions\&. +.sp .5v +.RE +.if n \{\ +.sp +.\} +.RS 4 +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBCaution\fR +.ps -1 +.br +.sp +The functions \fIzmq_msg_init()\fR, \fIzmq_msg_init_data()\fR and \fIzmq_msg_init_size()\fR are mutually exclusive\&. Never initialise the same \fIzmq_msg_t\fR twice\&. +.sp .5v +.RE +.SH "RETURN VALUE" +.sp +The \fIzmq_msg_init_size()\fR function shall return zero if successful\&. Otherwise it shall return \-1 and set \fIerrno\fR to one of the values defined below\&. +.SH "ERRORS" +.PP +\fBENOMEM\fR +.RS 4 +Insufficient storage space is available\&. +.RE +.SH "SEE ALSO" +.sp +\fBzmq_msg_init_data\fR(3) \fBzmq_msg_init\fR(3) \fBzmq_msg_close\fR(3) \fBzmq_msg_data\fR(3) \fBzmq_msg_size\fR(3) \fBzmq\fR(7) +.SH "AUTHORS" +.sp +This page was written by the 0MQ community\&. To make a change please read the 0MQ Contribution Policy at \m[blue]\fBhttp://www\&.zeromq\&.org/docs:contributing\fR\m[]\&. diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_msg_more.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_msg_more.3 new file mode 100644 index 00000000000000..d10ff83f8923b1 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_msg_more.3 @@ -0,0 +1,75 @@ +'\" t +.\" Title: zmq_msg_more +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.78.1 +.\" Date: 02/18/2017 +.\" Manual: 0MQ Manual +.\" Source: 0MQ 4.2.2 +.\" Language: English +.\" +.TH "ZMQ_MSG_MORE" "3" "02/18/2017" "0MQ 4\&.2\&.2" "0MQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zmq_msg_more \- indicate if there are more message parts to receive +.SH "SYNOPSIS" +.sp +\fBint zmq_msg_more (zmq_msg_t \fR\fB\fI*message\fR\fR\fB);\fR +.SH "DESCRIPTION" +.sp +The \fIzmq_msg_more()\fR function indicates whether this is part of a multi\-part message, and there are further parts to receive\&. This method can safely be called after \fIzmq_msg_close()\fR\&. This method is identical to \fIzmq_msg_get()\fR with an argument of ZMQ_MORE\&. +.SH "RETURN VALUE" +.sp +The \fIzmq_msg_more()\fR function shall return zero if this is the final part of a multi\-part message, or the only part of a single\-part message\&. It shall return 1 if there are further parts to receive\&. +.SH "EXAMPLE" +.PP +\fBReceiving a multi-part message\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +zmq_msg_t part; +while (true) { + // Create an empty 0MQ message to hold the message part + int rc = zmq_msg_init (&part); + assert (rc == 0); + // Block until a message is available to be received from socket + rc = zmq_msg_recv (socket, &part, 0); + assert (rc != \-1); + if (zmq_msg_more (&part)) + fprintf (stderr, "more\en"); + else { + fprintf (stderr, "end\en"); + break; + } + zmq_msg_close (&part); +} +.fi +.if n \{\ +.RE +.\} +.sp +.SH "SEE ALSO" +.sp +\fBzmq_msg_get\fR(3) \fBzmq_msg_set\fR(3) \fBzmq_msg_init\fR(3) \fBzmq_msg_close\fR(3) \fBzmq\fR(7) +.SH "AUTHORS" +.sp +This page was written by the 0MQ community\&. To make a change please read the 0MQ Contribution Policy at \m[blue]\fBhttp://www\&.zeromq\&.org/docs:contributing\fR\m[]\&. diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_msg_move.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_msg_move.3 new file mode 100644 index 00000000000000..7328f994645581 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_msg_move.3 @@ -0,0 +1,68 @@ +'\" t +.\" Title: zmq_msg_move +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.78.1 +.\" Date: 02/18/2017 +.\" Manual: 0MQ Manual +.\" Source: 0MQ 4.2.2 +.\" Language: English +.\" +.TH "ZMQ_MSG_MOVE" "3" "02/18/2017" "0MQ 4\&.2\&.2" "0MQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zmq_msg_move \- move content of a message to another message +.SH "SYNOPSIS" +.sp +\fBint zmq_msg_move (zmq_msg_t \fR\fB\fI*dest\fR\fR\fB, zmq_msg_t \fR\fB\fI*src\fR\fR\fB);\fR +.SH "DESCRIPTION" +.sp +The \fIzmq_msg_move()\fR function shall move the content of the message object referenced by \fIsrc\fR to the message object referenced by \fIdest\fR\&. No actual copying of message content is performed, \fIdest\fR is simply updated to reference the new content\&. \fIsrc\fR becomes an empty message after calling \fIzmq_msg_move()\fR\&. The original content of \fIdest\fR, if any, shall be released\&. +.if n \{\ +.sp +.\} +.RS 4 +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBCaution\fR +.ps -1 +.br +.sp +Never access \fIzmq_msg_t\fR members directly, instead always use the \fIzmq_msg\fR family of functions\&. +.sp .5v +.RE +.SH "RETURN VALUE" +.sp +The \fIzmq_msg_move()\fR function shall return zero if successful\&. Otherwise it shall return \-1 and set \fIerrno\fR to one of the values defined below\&. +.SH "ERRORS" +.PP +\fBEFAULT\fR +.RS 4 +Invalid message\&. +.RE +.SH "SEE ALSO" +.sp +\fBzmq_msg_copy\fR(3) \fBzmq_msg_init\fR(3) \fBzmq_msg_init_size\fR(3) \fBzmq_msg_init_data\fR(3) \fBzmq_msg_close\fR(3) \fBzmq\fR(7) +.SH "AUTHORS" +.sp +This page was written by the 0MQ community\&. To make a change please read the 0MQ Contribution Policy at \m[blue]\fBhttp://www\&.zeromq\&.org/docs:contributing\fR\m[]\&. diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_msg_recv.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_msg_recv.3 new file mode 100644 index 00000000000000..3f8b8a3e7b9cb7 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_msg_recv.3 @@ -0,0 +1,161 @@ +'\" t +.\" Title: zmq_msg_recv +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.78.1 +.\" Date: 02/18/2017 +.\" Manual: 0MQ Manual +.\" Source: 0MQ 4.2.2 +.\" Language: English +.\" +.TH "ZMQ_MSG_RECV" "3" "02/18/2017" "0MQ 4\&.2\&.2" "0MQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zmq_msg_recv \- receive a message part from a socket +.SH "SYNOPSIS" +.sp +\fBint zmq_msg_recv (zmq_msg_t \fR\fB\fI*msg\fR\fR\fB, void \fR\fB\fI*socket\fR\fR\fB, int \fR\fB\fIflags\fR\fR\fB);\fR +.SH "DESCRIPTION" +.sp +The \fIzmq_msg_recv()\fR function is identical to \fBzmq_recvmsg\fR(3), which shall be deprecated in future versions\&. \fIzmq_msg_recv()\fR is more consistent with other message manipulation functions\&. +.sp +The \fIzmq_msg_recv()\fR function shall receive a message part from the socket referenced by the \fIsocket\fR argument and store it in the message referenced by the \fImsg\fR argument\&. Any content previously stored in \fImsg\fR shall be properly deallocated\&. If there are no message parts available on the specified \fIsocket\fR the \fIzmq_msg_recv()\fR function shall block until the request can be satisfied\&. The \fIflags\fR argument is a combination of the flags defined below: +.PP +\fBZMQ_DONTWAIT\fR +.RS 4 +Specifies that the operation should be performed in non\-blocking mode\&. If there are no messages available on the specified +\fIsocket\fR, the +\fIzmq_msg_recv()\fR +function shall fail with +\fIerrno\fR +set to EAGAIN\&. +.RE +.SS "Multi\-part messages" +.sp +A 0MQ message is composed of 1 or more message parts\&. Each message part is an independent \fIzmq_msg_t\fR in its own right\&. 0MQ ensures atomic delivery of messages: peers shall receive either all \fImessage parts\fR of a message or none at all\&. The total number of message parts is unlimited except by available memory\&. +.sp +An application that processes multi\-part messages must use the \fIZMQ_RCVMORE\fR \fBzmq_getsockopt\fR(3) option after calling \fIzmq_msg_recv()\fR to determine if there are further parts to receive\&. +.SH "RETURN VALUE" +.sp +The \fIzmq_msg_recv()\fR function shall return number of bytes in the message if successful\&. Otherwise it shall return \-1 and set \fIerrno\fR to one of the values defined below\&. +.SH "ERRORS" +.PP +\fBEAGAIN\fR +.RS 4 +Non\-blocking mode was requested and no messages are available at the moment\&. +.RE +.PP +\fBENOTSUP\fR +.RS 4 +The +\fIzmq_msg_recv()\fR +operation is not supported by this socket type\&. +.RE +.PP +\fBEFSM\fR +.RS 4 +The +\fIzmq_msg_recv()\fR +operation cannot be performed on this socket at the moment due to the socket not being in the appropriate state\&. This error may occur with socket types that switch between several states, such as ZMQ_REP\&. See the +\fImessaging patterns\fR +section of +\fBzmq_socket\fR(3) +for more information\&. +.RE +.PP +\fBETERM\fR +.RS 4 +The 0MQ +\fIcontext\fR +associated with the specified +\fIsocket\fR +was terminated\&. +.RE +.PP +\fBENOTSOCK\fR +.RS 4 +The provided +\fIsocket\fR +was invalid\&. +.RE +.PP +\fBEINTR\fR +.RS 4 +The operation was interrupted by delivery of a signal before a message was available\&. +.RE +.PP +\fBEFAULT\fR +.RS 4 +The message passed to the function was invalid\&. +.RE +.SH "EXAMPLE" +.PP +\fBReceiving a message from a socket\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +/* Create an empty 0MQ message */ +zmq_msg_t msg; +int rc = zmq_msg_init (&msg); +assert (rc == 0); +/* Block until a message is available to be received from socket */ +rc = zmq_msg_recv (&msg, socket, 0); +assert (rc != \-1); +/* Release message */ +zmq_msg_close (&msg); +.fi +.if n \{\ +.RE +.\} +.PP +\fBReceiving a multi-part message\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +int more; +size_t more_size = sizeof (more); +do { + /* Create an empty 0MQ message to hold the message part */ + zmq_msg_t part; + int rc = zmq_msg_init (&part); + assert (rc == 0); + /* Block until a message is available to be received from socket */ + rc = zmq_msg_recv (&part, socket, 0); + assert (rc != \-1); + /* Determine if more message parts are to follow */ + rc = zmq_getsockopt (socket, ZMQ_RCVMORE, &more, &more_size); + assert (rc == 0); + zmq_msg_close (&part); +} while (more); +.fi +.if n \{\ +.RE +.\} +.sp +.SH "SEE ALSO" +.sp +\fBzmq_recv\fR(3) \fBzmq_send\fR(3) \fBzmq_msg_send\fR(3) \fBzmq_getsockopt\fR(3) \fBzmq_socket\fR(7) \fBzmq\fR(7) +.SH "AUTHORS" +.sp +This page was written by the 0MQ community\&. To make a change please read the 0MQ Contribution Policy at \m[blue]\fBhttp://www\&.zeromq\&.org/docs:contributing\fR\m[]\&. diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_msg_routing_id.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_msg_routing_id.3 new file mode 100644 index 00000000000000..94a832143b458f --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_msg_routing_id.3 @@ -0,0 +1,76 @@ +'\" t +.\" Title: zmq_msg_routing_id +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.78.1 +.\" Date: 02/18/2017 +.\" Manual: 0MQ Manual +.\" Source: 0MQ 4.2.2 +.\" Language: English +.\" +.TH "ZMQ_MSG_ROUTING_ID" "3" "02/18/2017" "0MQ 4\&.2\&.2" "0MQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zmq_msg_routing_id \- return routing ID for message, if any +.SH "SYNOPSIS" +.sp +\fBuint32_t zmq_msg_routing_id (zmq_msg_t \fR\fB\fI*message\fR\fR\fB);\fR +.SH "DESCRIPTION" +.sp +The \fIzmq_msg_routing_id()\fR function returns the routing ID for the message, if any\&. The routing ID is set on all messages received from a \fIZMQ_SERVER\fR socket\&. To send a message to a \fIZMQ_SERVER\fR socket you must set the routing ID of a connected \fIZMQ_CLIENT\fR peer\&. Routing IDs are transient\&. +.SH "RETURN VALUE" +.sp +The \fIzmq_msg_routing_id()\fR function shall return zero if there is no routing ID, otherwise it shall return an unsigned 32\-bit integer greater than zero\&. +.SH "EXAMPLE" +.PP +\fBReceiving a client message and routing ID\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +void *ctx = zmq_ctx_new (); +assert (ctx); + +void *server = zmq_socket (ctx, ZMQ_SERVER); +assert (server); +int rc = zmq_bind (server, "tcp://127\&.0\&.0\&.1:8080"); +assert (rc == 0); + +zmq_msg_t message; +rc = zmq_msg_init (&message); +assert (rc == 0); + +// Receive a message from socket +rc = zmq_msg_recv (server, &message, 0); +assert (rc != \-1); +uint32_t routing_id = zmq_msg_routing_id (&message); +assert (routing_id); +.fi +.if n \{\ +.RE +.\} +.sp +.SH "SEE ALSO" +.sp +\fBzmq_msg_set_routing_id\fR(3) +.SH "AUTHORS" +.sp +This page was written by the 0MQ community\&. To make a change please read the 0MQ Contribution Policy at \m[blue]\fBhttp://www\&.zeromq\&.org/docs:contributing\fR\m[]\&. diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_msg_send.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_msg_send.3 new file mode 100644 index 00000000000000..a6070a8672b301 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_msg_send.3 @@ -0,0 +1,184 @@ +'\" t +.\" Title: zmq_msg_send +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.78.1 +.\" Date: 02/18/2017 +.\" Manual: 0MQ Manual +.\" Source: 0MQ 4.2.2 +.\" Language: English +.\" +.TH "ZMQ_MSG_SEND" "3" "02/18/2017" "0MQ 4\&.2\&.2" "0MQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zmq_msg_send \- send a message part on a socket +.SH "SYNOPSIS" +.sp +\fBint zmq_msg_send (zmq_msg_t \fR\fB\fI*msg\fR\fR\fB, void \fR\fB\fI*socket\fR\fR\fB, int \fR\fB\fIflags\fR\fR\fB);\fR +.SH "DESCRIPTION" +.sp +The \fIzmq_msg_send()\fR function is identical to \fBzmq_sendmsg\fR(3), which shall be deprecated in future versions\&. \fIzmq_msg_send()\fR is more consistent with other message manipulation functions\&. +.sp +The \fIzmq_msg_send()\fR function shall queue the message referenced by the \fImsg\fR argument to be sent to the socket referenced by the \fIsocket\fR argument\&. The \fIflags\fR argument is a combination of the flags defined below: +.PP +\fBZMQ_DONTWAIT\fR +.RS 4 +For socket types (DEALER, PUSH) that block when there are no available peers (or all peers have full high\-water mark), specifies that the operation should be performed in non\-blocking mode\&. If the message cannot be queued on the +\fIsocket\fR, the +\fIzmq_msg_send()\fR +function shall fail with +\fIerrno\fR +set to EAGAIN\&. +.RE +.PP +\fBZMQ_SNDMORE\fR +.RS 4 +Specifies that the message being sent is a multi\-part message, and that further message parts are to follow\&. Refer to the section regarding multi\-part messages below for a detailed description\&. +.RE +.sp +The \fIzmq_msg_t\fR structure passed to \fIzmq_msg_send()\fR is nullified during the call\&. If you want to send the same message to multiple sockets you have to copy it (e\&.g\&. using \fIzmq_msg_copy()\fR)\&. +.if n \{\ +.sp +.\} +.RS 4 +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBNote\fR +.ps -1 +.br +.sp +A successful invocation of \fIzmq_msg_send()\fR does not indicate that the message has been transmitted to the network, only that it has been queued on the \fIsocket\fR and 0MQ has assumed responsibility for the message\&. You do not need to call \fIzmq_msg_close()\fR after a successful \fIzmq_msg_send()\fR\&. +.sp .5v +.RE +.SS "Multi\-part messages" +.sp +A 0MQ message is composed of 1 or more message parts\&. Each message part is an independent \fIzmq_msg_t\fR in its own right\&. 0MQ ensures atomic delivery of messages: peers shall receive either all \fImessage parts\fR of a message or none at all\&. The total number of message parts is unlimited except by available memory\&. +.sp +An application that sends multi\-part messages must use the \fIZMQ_SNDMORE\fR flag when sending each message part except the final one\&. +.SH "RETURN VALUE" +.sp +The \fIzmq_msg_send()\fR function shall return number of bytes in the message if successful\&. Otherwise it shall return \-1 and set \fIerrno\fR to one of the values defined below\&. +.SH "ERRORS" +.PP +\fBEAGAIN\fR +.RS 4 +Non\-blocking mode was requested and the message cannot be sent at the moment\&. +.RE +.PP +\fBENOTSUP\fR +.RS 4 +The +\fIzmq_msg_send()\fR +operation is not supported by this socket type\&. +.RE +.PP +\fBEINVAL\fR +.RS 4 +The sender tried to send multipart data, which the socket type does not allow\&. +.RE +.PP +\fBEFSM\fR +.RS 4 +The +\fIzmq_msg_send()\fR +operation cannot be performed on this socket at the moment due to the socket not being in the appropriate state\&. This error may occur with socket types that switch between several states, such as ZMQ_REP\&. See the +\fImessaging patterns\fR +section of +\fBzmq_socket\fR(3) +for more information\&. +.RE +.PP +\fBETERM\fR +.RS 4 +The 0MQ +\fIcontext\fR +associated with the specified +\fIsocket\fR +was terminated\&. +.RE +.PP +\fBENOTSOCK\fR +.RS 4 +The provided +\fIsocket\fR +was invalid\&. +.RE +.PP +\fBEINTR\fR +.RS 4 +The operation was interrupted by delivery of a signal before the message was sent\&. +.RE +.PP +\fBEFAULT\fR +.RS 4 +Invalid message\&. +.RE +.PP +\fBEHOSTUNREACH\fR +.RS 4 +The message cannot be routed\&. +.RE +.SH "EXAMPLE" +.PP +\fBFilling in a message and sending it to a socket\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +/* Create a new message, allocating 6 bytes for message content */ +zmq_msg_t msg; +int rc = zmq_msg_init_size (&msg, 6); +assert (rc == 0); +/* Fill in message content with \*(AqAAAAAA\*(Aq */ +memset (zmq_msg_data (&msg), \*(AqA\*(Aq, 6); +/* Send the message to the socket */ +rc = zmq_msg_send (&msg, socket, 0); +assert (rc == 6); +.fi +.if n \{\ +.RE +.\} +.PP +\fBSending a multi-part message\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +/* Send a multi\-part message consisting of three parts to socket */ +rc = zmq_msg_send (&part1, socket, ZMQ_SNDMORE); +rc = zmq_msg_send (&part2, socket, ZMQ_SNDMORE); +/* Final part; no more parts to follow */ +rc = zmq_msg_send (&part3, socket, 0); +.fi +.if n \{\ +.RE +.\} +.sp +.SH "SEE ALSO" +.sp +\fBzmq_recv\fR(3) \fBzmq_send\fR(3) \fBzmq_msg_recv\fR(3) \fBzmq_socket\fR(7) \fBzmq\fR(7) +.SH "AUTHORS" +.sp +This page was written by the 0MQ community\&. To make a change please read the 0MQ Contribution Policy at \m[blue]\fBhttp://www\&.zeromq\&.org/docs:contributing\fR\m[]\&. diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_msg_set.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_msg_set.3 new file mode 100644 index 00000000000000..a2c5da543ba0a4 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_msg_set.3 @@ -0,0 +1,56 @@ +'\" t +.\" Title: zmq_msg_set +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.78.1 +.\" Date: 02/18/2017 +.\" Manual: 0MQ Manual +.\" Source: 0MQ 4.2.2 +.\" Language: English +.\" +.TH "ZMQ_MSG_SET" "3" "02/18/2017" "0MQ 4\&.2\&.2" "0MQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zmq_msg_set \- set message property +.SH "SYNOPSIS" +.sp +\fBint zmq_msg_set (zmq_msg_t \fR\fB\fI*message\fR\fR\fB, int \fR\fB\fIproperty\fR\fR\fB, int \fR\fB\fIvalue\fR\fR\fB);\fR +.SH "DESCRIPTION" +.sp +The \fIzmq_msg_set()\fR function shall set the property specified by the \fIproperty\fR argument to the value of the \fIvalue\fR argument for the 0MQ message fragment pointed to by the \fImessage\fR argument\&. +.sp +Currently the \fIzmq_msg_set()\fR function does not support any property names\&. +.SH "RETURN VALUE" +.sp +The \fIzmq_msg_set()\fR function shall return zero if successful\&. Otherwise it shall return \-1 and set \fIerrno\fR to one of the values defined below\&. +.SH "ERRORS" +.PP +\fBEINVAL\fR +.RS 4 +The requested property +\fIproperty\fR +is unknown\&. +.RE +.SH "SEE ALSO" +.sp +\fBzmq_msg_get\fR(3) \fBzmq\fR(7) +.SH "AUTHORS" +.sp +This page was written by the 0MQ community\&. To make a change please read the 0MQ Contribution Policy at \m[blue]\fBhttp://www\&.zeromq\&.org/docs:contributing\fR\m[]\&. diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_msg_set_routing_id.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_msg_set_routing_id.3 new file mode 100644 index 00000000000000..c11c84cd678e38 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_msg_set_routing_id.3 @@ -0,0 +1,54 @@ +'\" t +.\" Title: zmq_msg_set_routing_id +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.78.1 +.\" Date: 02/18/2017 +.\" Manual: 0MQ Manual +.\" Source: 0MQ 4.2.2 +.\" Language: English +.\" +.TH "ZMQ_MSG_SET_ROUTING_" "3" "02/18/2017" "0MQ 4\&.2\&.2" "0MQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zmq_msg_set_routing_id \- set routing ID property on message +.SH "SYNOPSIS" +.sp +\fBint zmq_msg_set_routing_id (zmq_msg_t \fR\fB\fI*message\fR\fR\fB, uint32_t \fR\fB\fIrouting_id\fR\fR\fB);\fR +.SH "DESCRIPTION" +.sp +The \fIzmq_msg_set_routing_id()\fR function sets the \fIrouting_id\fR specified, on the the message pointed to by the \fImessage\fR argument\&. The \fIrouting_id\fR must be greater than zero\&. To get a valid routing ID, you must receive a message from a \fIZMQ_SERVER\fR socket, and use the libzmq:zmq_msg_routing_id method\&. Routing IDs are transient\&. +.SH "RETURN VALUE" +.sp +The \fIzmq_msg_set_routing_id()\fR function shall return zero if successful\&. Otherwise it shall return \-1 and set \fIerrno\fR to one of the values defined below\&. +.SH "ERRORS" +.PP +\fBEINVAL\fR +.RS 4 +The provided +\fIrouting_id\fR +is zero\&. +.RE +.SH "SEE ALSO" +.sp +\fBzmq_msg_routing_id\fR(3) \fBzmq\fR(7) +.SH "AUTHORS" +.sp +This page was written by the 0MQ community\&. To make a change please read the 0MQ Contribution Policy at \m[blue]\fBhttp://www\&.zeromq\&.org/docs:contributing\fR\m[]\&. diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_msg_size.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_msg_size.3 new file mode 100644 index 00000000000000..7e808b7223e21c --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_msg_size.3 @@ -0,0 +1,65 @@ +'\" t +.\" Title: zmq_msg_size +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.78.1 +.\" Date: 02/18/2017 +.\" Manual: 0MQ Manual +.\" Source: 0MQ 4.2.2 +.\" Language: English +.\" +.TH "ZMQ_MSG_SIZE" "3" "02/18/2017" "0MQ 4\&.2\&.2" "0MQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zmq_msg_size \- retrieve message content size in bytes +.SH "SYNOPSIS" +.sp +\fBsize_t zmq_msg_size (zmq_msg_t \fR\fB\fI*msg\fR\fR\fB);\fR +.SH "DESCRIPTION" +.sp +The \fIzmq_msg_size()\fR function shall return the size in bytes of the content of the message object referenced by \fImsg\fR\&. +.if n \{\ +.sp +.\} +.RS 4 +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBCaution\fR +.ps -1 +.br +.sp +Never access \fIzmq_msg_t\fR members directly, instead always use the \fIzmq_msg\fR family of functions\&. +.sp .5v +.RE +.SH "RETURN VALUE" +.sp +Upon successful completion, \fIzmq_msg_size()\fR shall return the size of the message content in bytes\&. +.SH "ERRORS" +.sp +No errors are defined\&. +.SH "SEE ALSO" +.sp +\fBzmq_msg_data\fR(3) \fBzmq_msg_init\fR(3) \fBzmq_msg_init_size\fR(3) \fBzmq_msg_init_data\fR(3) \fBzmq_msg_close\fR(3) \fBzmq\fR(7) +.SH "AUTHORS" +.sp +This page was written by the 0MQ community\&. To make a change please read the 0MQ Contribution Policy at \m[blue]\fBhttp://www\&.zeromq\&.org/docs:contributing\fR\m[]\&. diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_poll.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_poll.3 new file mode 100644 index 00000000000000..928bde440e2110 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_poll.3 @@ -0,0 +1,182 @@ +'\" t +.\" Title: zmq_poll +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.78.1 +.\" Date: 02/18/2017 +.\" Manual: 0MQ Manual +.\" Source: 0MQ 4.2.2 +.\" Language: English +.\" +.TH "ZMQ_POLL" "3" "02/18/2017" "0MQ 4\&.2\&.2" "0MQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zmq_poll \- input/output multiplexing +.SH "SYNOPSIS" +.sp +\fBint zmq_poll (zmq_pollitem_t \fR\fB\fI*items\fR\fR\fB, int \fR\fB\fInitems\fR\fR\fB, long \fR\fB\fItimeout\fR\fR\fB);\fR +.SH "DESCRIPTION" +.sp +The \fIzmq_poll()\fR function provides a mechanism for applications to multiplex input/output events in a level\-triggered fashion over a set of sockets\&. Each member of the array pointed to by the \fIitems\fR argument is a \fBzmq_pollitem_t\fR structure\&. The \fInitems\fR argument specifies the number of items in the \fIitems\fR array\&. The \fBzmq_pollitem_t\fR structure is defined as follows: +.sp +.if n \{\ +.RS 4 +.\} +.nf +typedef struct +{ + void \fI*socket\fR; + int \fIfd\fR; + short \fIevents\fR; + short \fIrevents\fR; +} zmq_pollitem_t; +.fi +.if n \{\ +.RE +.\} +.sp +For each \fBzmq_pollitem_t\fR item, \fIzmq_poll()\fR shall examine either the 0MQ socket referenced by \fIsocket\fR \fBor\fR the standard socket specified by the file descriptor \fIfd\fR, for the event(s) specified in \fIevents\fR\&. If both \fIsocket\fR and \fIfd\fR are set in a single \fBzmq_pollitem_t\fR, the 0MQ socket referenced by \fIsocket\fR shall take precedence and the value of \fIfd\fR shall be ignored\&. +.sp +For each \fBzmq_pollitem_t\fR item, \fIzmq_poll()\fR shall first clear the \fIrevents\fR member, and then indicate any requested events that have occurred by setting the bit corresponding to the event condition in the \fIrevents\fR member\&. +.sp +If none of the requested events have occurred on any \fBzmq_pollitem_t\fR item, \fIzmq_poll()\fR shall wait \fItimeout\fR milliseconds for an event to occur on any of the requested items\&. If the value of \fItimeout\fR is 0, \fIzmq_poll()\fR shall return immediately\&. If the value of \fItimeout\fR is \-1, \fIzmq_poll()\fR shall block indefinitely until a requested event has occurred on at least one \fBzmq_pollitem_t\fR\&. +.sp +The \fIevents\fR and \fIrevents\fR members of \fBzmq_pollitem_t\fR are bit masks constructed by OR\(cqing a combination of the following event flags: +.PP +\fBZMQ_POLLIN\fR +.RS 4 +For 0MQ sockets, at least one message may be received from the +\fIsocket\fR +without blocking\&. For standard sockets this is equivalent to the +\fIPOLLIN\fR +flag of the +\fIpoll()\fR +system call and generally means that at least one byte of data may be read from +\fIfd\fR +without blocking\&. +.RE +.PP +\fBZMQ_POLLOUT\fR +.RS 4 +For 0MQ sockets, at least one message may be sent to the +\fIsocket\fR +without blocking\&. For standard sockets this is equivalent to the +\fIPOLLOUT\fR +flag of the +\fIpoll()\fR +system call and generally means that at least one byte of data may be written to +\fIfd\fR +without blocking\&. +.RE +.PP +\fBZMQ_POLLERR\fR +.RS 4 +For standard sockets, this flag is passed through +\fIzmq_poll()\fR +to the underlying +\fIpoll()\fR +system call and generally means that some sort of error condition is present on the socket specified by +\fIfd\fR\&. For 0MQ sockets this flag has no effect if set in +\fIevents\fR, and shall never be returned in +\fIrevents\fR +by +\fIzmq_poll()\fR\&. +.RE +.PP +\fBZMQ_POLLPRI\fR +.RS 4 +For 0MQ sockets this flags is of no use\&. For standard sockets this means there is urgent data to read\&. Refer to the POLLPRI flag for more informations\&. For file descriptor, refer to your use case: as an example, GPIO interrupts are signaled through a POLLPRI event\&. This flag has no effect on Windows\&. +.RE +.if n \{\ +.sp +.\} +.RS 4 +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBNote\fR +.ps -1 +.br +.sp +The \fIzmq_poll()\fR function may be implemented or emulated using operating system interfaces other than \fIpoll()\fR, and as such may be subject to the limits of those interfaces in ways not defined in this documentation\&. +.sp .5v +.RE +.SH "RETURN VALUE" +.sp +Upon successful completion, the \fIzmq_poll()\fR function shall return the number of \fBzmq_pollitem_t\fR structures with events signaled in \fIrevents\fR or 0 if no events have been signaled\&. Upon failure, \fIzmq_poll()\fR shall return \-1 and set \fIerrno\fR to one of the values defined below\&. +.SH "ERRORS" +.PP +\fBETERM\fR +.RS 4 +At least one of the members of the +\fIitems\fR +array refers to a +\fIsocket\fR +whose associated 0MQ +\fIcontext\fR +was terminated\&. +.RE +.PP +\fBEFAULT\fR +.RS 4 +The provided +\fIitems\fR +was not valid (NULL)\&. +.RE +.PP +\fBEINTR\fR +.RS 4 +The operation was interrupted by delivery of a signal before any events were available\&. +.RE +.SH "EXAMPLE" +.PP +\fBPolling indefinitely for input events on both a 0MQ socket and a standard socket.\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +zmq_pollitem_t items [2]; +/* First item refers to 0MQ socket \*(Aqsocket\*(Aq */ +items[0]\&.socket = socket; +items[0]\&.events = ZMQ_POLLIN; +/* Second item refers to standard socket \*(Aqfd\*(Aq */ +items[1]\&.socket = NULL; +items[1]\&.fd = fd; +items[1]\&.events = ZMQ_POLLIN; +/* Poll for events indefinitely */ +int rc = zmq_poll (items, 2, \-1); +assert (rc >= 0); +/* Returned events will be stored in items[]\&.revents */ +.fi +.if n \{\ +.RE +.\} +.sp +.SH "SEE ALSO" +.sp +\fBzmq_socket\fR(3) \fBzmq_send\fR(3) \fBzmq_recv\fR(3) \fBzmq\fR(7) +.sp +Your operating system documentation for the \fIpoll()\fR system call\&. +.SH "AUTHORS" +.sp +This page was written by the 0MQ community\&. To make a change please read the 0MQ Contribution Policy at \m[blue]\fBhttp://www\&.zeromq\&.org/docs:contributing\fR\m[]\&. diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_proxy.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_proxy.3 new file mode 100644 index 00000000000000..73b244b7f377c8 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_proxy.3 @@ -0,0 +1,89 @@ +'\" t +.\" Title: zmq_proxy +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.78.1 +.\" Date: 02/18/2017 +.\" Manual: 0MQ Manual +.\" Source: 0MQ 4.2.2 +.\" Language: English +.\" +.TH "ZMQ_PROXY" "3" "02/18/2017" "0MQ 4\&.2\&.2" "0MQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zmq_proxy \- start built\-in 0MQ proxy +.SH "SYNOPSIS" +.sp +\fBint zmq_proxy (const void \fR\fB\fI*frontend\fR\fR\fB, const void \fR\fB\fI*backend\fR\fR\fB, const void \fR\fB\fI*capture\fR\fR\fB);\fR +.SH "DESCRIPTION" +.sp +The \fIzmq_proxy()\fR function starts the built\-in 0MQ proxy in the current application thread\&. +.sp +The proxy connects a frontend socket to a backend socket\&. Conceptually, data flows from frontend to backend\&. Depending on the socket types, replies may flow in the opposite direction\&. The direction is conceptual only; the proxy is fully symmetric and there is no technical difference between frontend and backend\&. +.sp +Before calling \fIzmq_proxy()\fR you must set any socket options, and connect or bind both frontend and backend sockets\&. The two conventional proxy models are: +.sp +\fIzmq_proxy()\fR runs in the current thread and returns only if/when the current context is closed\&. +.sp +If the capture socket is not NULL, the proxy shall send all messages, received on both frontend and backend, to the capture socket\&. The capture socket should be a \fIZMQ_PUB\fR, \fIZMQ_DEALER\fR, \fIZMQ_PUSH\fR, or \fIZMQ_PAIR\fR socket\&. +.sp +Refer to \fBzmq_socket\fR(3) for a description of the available socket types\&. +.SH "EXAMPLE USAGE" +.SS "Shared Queue" +.sp +When the frontend is a ZMQ_ROUTER socket, and the backend is a ZMQ_DEALER socket, the proxy shall act as a shared queue that collects requests from a set of clients, and distributes these fairly among a set of services\&. Requests shall be fair\-queued from frontend connections and distributed evenly across backend connections\&. Replies shall automatically return to the client that made the original request\&. +.SS "Forwarder" +.sp +When the frontend is a ZMQ_XSUB socket, and the backend is a ZMQ_XPUB socket, the proxy shall act as a message forwarder that collects messages from a set of publishers and forwards these to a set of subscribers\&. This may be used to bridge networks transports, e\&.g\&. read on tcp:// and forward on pgm://\&. +.SS "Streamer" +.sp +When the frontend is a ZMQ_PULL socket, and the backend is a ZMQ_PUSH socket, the proxy shall collect tasks from a set of clients and forwards these to a set of workers using the pipeline pattern\&. +.SH "RETURN VALUE" +.sp +The \fIzmq_proxy()\fR function always returns \-1 and \fIerrno\fR set to \fBETERM\fR or \fBEINTR\fR (the 0MQ \fIcontext\fR associated with either of the specified sockets was terminated)\&. +.SH "EXAMPLE" +.PP +\fBCreating a shared queue proxy\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +// Create frontend and backend sockets +void *frontend = zmq_socket (context, ZMQ_ROUTER); +assert (backend); +void *backend = zmq_socket (context, ZMQ_DEALER); +assert (frontend); +// Bind both sockets to TCP ports +assert (zmq_bind (frontend, "tcp://*:5555") == 0); +assert (zmq_bind (backend, "tcp://*:5556") == 0); +// Start the queue proxy, which runs until ETERM +zmq_proxy (frontend, backend, NULL); +.fi +.if n \{\ +.RE +.\} +.sp +.SH "SEE ALSO" +.sp +\fBzmq_bind\fR(3) \fBzmq_connect\fR(3) \fBzmq_socket\fR(3) \fBzmq\fR(7) +.SH "AUTHORS" +.sp +This page was written by the 0MQ community\&. To make a change please read the 0MQ Contribution Policy at \m[blue]\fBhttp://www\&.zeromq\&.org/docs:contributing\fR\m[]\&. diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_proxy_steerable.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_proxy_steerable.3 new file mode 100644 index 00000000000000..2cf1209e9c7dd5 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_proxy_steerable.3 @@ -0,0 +1,112 @@ +'\" t +.\" Title: zmq_proxy_steerable +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.78.1 +.\" Date: 02/18/2017 +.\" Manual: 0MQ Manual +.\" Source: 0MQ 4.2.2 +.\" Language: English +.\" +.TH "ZMQ_PROXY_STEERABLE" "3" "02/18/2017" "0MQ 4\&.2\&.2" "0MQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zmq_proxy_steerable \- built\-in 0MQ proxy with control flow +.SH "SYNOPSIS" +.sp +\fBint zmq_proxy_steerable (const void \fR\fB\fI*frontend\fR\fR\fB, const void \fR\fB\fI*backend\fR\fR\fB, const void \fR\fB\fI*capture\fR\fR\fB, const void \fR\fB\fI*control\fR\fR\fB);\fR +.SH "DESCRIPTION" +.sp +The \fIzmq_proxy_steerable()\fR function starts the built\-in 0MQ proxy in the current application thread, as \fIzmq_proxy()\fR do\&. Please, refer to this function for the general description and usage\&. We describe here only the additional control flow provided by the socket passed as the fourth argument "control"\&. +.sp +If the control socket is not NULL, the proxy supports control flow\&. If \fIPAUSE\fR is received on this socket, the proxy suspends its activities\&. If \fIRESUME\fR is received, it goes on\&. If \fITERMINATE\fR is received, it terminates smoothly\&. At start, the proxy runs normally as if zmq_proxy was used\&. +.sp +If the control socket is NULL, the function behave exactly as if zmq_proxy had been called\&. +.sp +Refer to \fBzmq_socket\fR(3) for a description of the available socket types\&. Refer to \fBzmq_proxy\fR(3) for a description of the zmq_proxy\&. +.SH "EXAMPLE USAGE" +.sp +cf zmq_proxy +.SH "RETURN VALUE" +.sp +The \fIzmq_proxy_steerable()\fR function returns 0 if TERMINATE is sent to its control socket\&. Otherwise, it returns \-1 and \fIerrno\fR set to \fBETERM\fR or \fBEINTR\fR (the 0MQ \fIcontext\fR associated with either of the specified sockets was terminated)\&. +.SH "EXAMPLE" +.PP +\fBCreating a shared queue proxy\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +// Create frontend, backend and control sockets +void *frontend = zmq_socket (context, ZMQ_ROUTER); +assert (backend); +void *backend = zmq_socket (context, ZMQ_DEALER); +assert (frontend); +void *control = zmq_socket (context, ZMQ_SUB); +assert (control); + +// Bind sockets to TCP ports +assert (zmq_bind (frontend, "tcp://*:5555") == 0); +assert (zmq_bind (backend, "tcp://*:5556") == 0); +assert (zmq_connect (control, "tcp://*:5557") == 0); + +// Subscribe to the control socket since we have chosen SUB here +assert (zmq_setsockopt (control, ZMQ_SUBSCRIBE, "", 0)); + +// Start the queue proxy, which runs until ETERM or "TERMINATE" +// received on the control socket +zmq_proxy_steerable (frontend, backend, NULL, control); +.fi +.if n \{\ +.RE +.\} +.PP +\fBSet up a controller in another node, process or whatever\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +void *control = zmq_socket (context, ZMQ_PUB); +assert (control); +assert (zmq_bind (control, "tcp://*:5557") == 0); + +// pause the proxy +assert (zmq_send (control, "PAUSE", 5, 0) == 0); + +// resume the proxy +assert (zmq_send (control, "RESUME", 6, 0) == 0); + +// terminate the proxy +assert (zmq_send (control, "TERMINATE", 9, 0) == 0); +\-\-\- + + +SEE ALSO +.fi +.if n \{\ +.RE +.\} +.sp +\fBzmq_proxy\fR(3) \fBzmq_bind\fR(3) \fBzmq_connect\fR(3) \fBzmq_socket\fR(3) \fBzmq\fR(7) +.SH "AUTHORS" +.sp +This page was written by the 0MQ community\&. To make a change please read the 0MQ Contribution Policy at \m[blue]\fBhttp://www\&.zeromq\&.org/docs:contributing\fR\m[]\&. diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_recv.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_recv.3 new file mode 100644 index 00000000000000..f90366ae309170 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_recv.3 @@ -0,0 +1,122 @@ +'\" t +.\" Title: zmq_recv +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.78.1 +.\" Date: 02/18/2017 +.\" Manual: 0MQ Manual +.\" Source: 0MQ 4.2.2 +.\" Language: English +.\" +.TH "ZMQ_RECV" "3" "02/18/2017" "0MQ 4\&.2\&.2" "0MQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zmq_recv \- receive a message part from a socket +.SH "SYNOPSIS" +.sp +\fBint zmq_recv (void \fR\fB\fI*socket\fR\fR\fB, void \fR\fB\fI*buf\fR\fR\fB, size_t \fR\fB\fIlen\fR\fR\fB, int \fR\fB\fIflags\fR\fR\fB);\fR +.SH "DESCRIPTION" +.sp +The \fIzmq_recv()\fR function shall receive a message from the socket referenced by the \fIsocket\fR argument and store it in the buffer referenced by the \fIbuf\fR argument\&. Any bytes exceeding the length specified by the \fIlen\fR argument shall be truncated\&. If there are no messages available on the specified \fIsocket\fR the \fIzmq_recv()\fR function shall block until the request can be satisfied\&. The \fIflags\fR argument is a combination of the flags defined below: The \fIbuf\fR argument may be null if len is zero\&. +.PP +\fBZMQ_DONTWAIT\fR +.RS 4 +Specifies that the operation should be performed in non\-blocking mode\&. If there are no messages available on the specified +\fIsocket\fR, the +\fIzmq_recv()\fR +function shall fail with +\fIerrno\fR +set to EAGAIN\&. +.RE +.SS "Multi\-part messages" +.sp +A 0MQ message is composed of 1 or more message parts\&. 0MQ ensures atomic delivery of messages: peers shall receive either all \fImessage parts\fR of a message or none at all\&. The total number of message parts is unlimited except by available memory\&. +.sp +An application that processes multi\-part messages must use the \fIZMQ_RCVMORE\fR \fBzmq_getsockopt\fR(3) option after calling \fIzmq_recv()\fR to determine if there are further parts to receive\&. +.SH "RETURN VALUE" +.sp +The \fIzmq_recv()\fR function shall return number of bytes in the message if successful\&. Note that the value can exceed the value of the \fIlen\fR parameter in case the message was truncated\&. If not successful the function shall return \-1 and set \fIerrno\fR to one of the values defined below\&. +.SH "ERRORS" +.PP +\fBEAGAIN\fR +.RS 4 +Non\-blocking mode was requested and no messages are available at the moment\&. +.RE +.PP +\fBENOTSUP\fR +.RS 4 +The +\fIzmq_recv()\fR +operation is not supported by this socket type\&. +.RE +.PP +\fBEFSM\fR +.RS 4 +The +\fIzmq_recv()\fR +operation cannot be performed on this socket at the moment due to the socket not being in the appropriate state\&. This error may occur with socket types that switch between several states, such as ZMQ_REP\&. See the +\fImessaging patterns\fR +section of +\fBzmq_socket\fR(3) +for more information\&. +.RE +.PP +\fBETERM\fR +.RS 4 +The 0MQ +\fIcontext\fR +associated with the specified +\fIsocket\fR +was terminated\&. +.RE +.PP +\fBENOTSOCK\fR +.RS 4 +The provided +\fIsocket\fR +was invalid\&. +.RE +.PP +\fBEINTR\fR +.RS 4 +The operation was interrupted by delivery of a signal before a message was available\&. +.RE +.SH "EXAMPLE" +.PP +\fBReceiving a message from a socket\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +char buf [256]; +nbytes = zmq_recv (socket, buf, 256, 0); +assert (nbytes != \-1); +.fi +.if n \{\ +.RE +.\} +.sp +.SH "SEE ALSO" +.sp +\fBzmq_send\fR(3) \fBzmq_getsockopt\fR(3) \fBzmq_socket\fR(7) \fBzmq\fR(7) +.SH "AUTHORS" +.sp +This page was written by the 0MQ community\&. To make a change please read the 0MQ Contribution Policy at \m[blue]\fBhttp://www\&.zeromq\&.org/docs:contributing\fR\m[]\&. diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_recvmsg.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_recvmsg.3 new file mode 100644 index 00000000000000..c3b0b44bb10e3f --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_recvmsg.3 @@ -0,0 +1,175 @@ +'\" t +.\" Title: zmq_recvmsg +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.78.1 +.\" Date: 02/18/2017 +.\" Manual: 0MQ Manual +.\" Source: 0MQ 4.2.2 +.\" Language: English +.\" +.TH "ZMQ_RECVMSG" "3" "02/18/2017" "0MQ 4\&.2\&.2" "0MQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zmq_recvmsg \- receive a message part from a socket +.SH "SYNOPSIS" +.sp +\fBint zmq_recvmsg (void \fR\fB\fI*socket\fR\fR\fB, zmq_msg_t \fR\fB\fI*msg\fR\fR\fB, int \fR\fB\fIflags\fR\fR\fB);\fR +.SH "DESCRIPTION" +.sp +The \fIzmq_recvmsg()\fR function shall receive a message part from the socket referenced by the \fIsocket\fR argument and store it in the message referenced by the \fImsg\fR argument\&. Any content previously stored in \fImsg\fR shall be properly deallocated\&. If there are no message parts available on the specified \fIsocket\fR the \fIzmq_recvmsg()\fR function shall block until the request can be satisfied\&. The \fIflags\fR argument is a combination of the flags defined below: +.PP +\fBZMQ_DONTWAIT\fR +.RS 4 +Specifies that the operation should be performed in non\-blocking mode\&. If there are no messages available on the specified +\fIsocket\fR, the +\fIzmq_recvmsg()\fR +function shall fail with +\fIerrno\fR +set to EAGAIN\&. +.RE +.if n \{\ +.sp +.\} +.RS 4 +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBNote\fR +.ps -1 +.br +.sp +this API method is deprecated in favor of zmq_msg_recv(3)\&. +.sp .5v +.RE +.SS "Multi\-part messages" +.sp +A 0MQ message is composed of 1 or more message parts\&. Each message part is an independent \fIzmq_msg_t\fR in its own right\&. 0MQ ensures atomic delivery of messages: peers shall receive either all \fImessage parts\fR of a message or none at all\&. The total number of message parts is unlimited except by available memory\&. +.sp +An application that processes multi\-part messages must use the \fIZMQ_RCVMORE\fR \fBzmq_getsockopt\fR(3) option after calling \fIzmq_recvmsg()\fR to determine if there are further parts to receive\&. +.SH "RETURN VALUE" +.sp +The \fIzmq_recvmsg()\fR function shall return number of bytes in the message if successful\&. Otherwise it shall return \-1 and set \fIerrno\fR to one of the values defined below\&. +.SH "ERRORS" +.PP +\fBEAGAIN\fR +.RS 4 +Non\-blocking mode was requested and no messages are available at the moment\&. +.RE +.PP +\fBENOTSUP\fR +.RS 4 +The +\fIzmq_recvmsg()\fR +operation is not supported by this socket type\&. +.RE +.PP +\fBEFSM\fR +.RS 4 +The +\fIzmq_recvmsg()\fR +operation cannot be performed on this socket at the moment due to the socket not being in the appropriate state\&. This error may occur with socket types that switch between several states, such as ZMQ_REP\&. See the +\fImessaging patterns\fR +section of +\fBzmq_socket\fR(3) +for more information\&. +.RE +.PP +\fBETERM\fR +.RS 4 +The 0MQ +\fIcontext\fR +associated with the specified +\fIsocket\fR +was terminated\&. +.RE +.PP +\fBENOTSOCK\fR +.RS 4 +The provided +\fIsocket\fR +was invalid\&. +.RE +.PP +\fBEINTR\fR +.RS 4 +The operation was interrupted by delivery of a signal before a message was available\&. +.RE +.PP +\fBEFAULT\fR +.RS 4 +The message passed to the function was invalid\&. +.RE +.SH "EXAMPLE" +.PP +\fBReceiving a message from a socket\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +/* Create an empty 0MQ message */ +zmq_msg_t msg; +int rc = zmq_msg_init (&msg); +assert (rc == 0); +/* Block until a message is available to be received from socket */ +rc = zmq_recvmsg (socket, &msg, 0); +assert (rc != \-1); +/* Release message */ +zmq_msg_close (&msg); +.fi +.if n \{\ +.RE +.\} +.PP +\fBReceiving a multi-part message\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +int more; +size_t more_size = sizeof (more); +do { + /* Create an empty 0MQ message to hold the message part */ + zmq_msg_t part; + int rc = zmq_msg_init (&part); + assert (rc == 0); + /* Block until a message is available to be received from socket */ + rc = zmq_recvmsg (socket, &part, 0); + assert (rc != \-1); + /* Determine if more message parts are to follow */ + rc = zmq_getsockopt (socket, ZMQ_RCVMORE, &more, &more_size); + assert (rc == 0); + zmq_msg_close (&part); +} while (more); +.fi +.if n \{\ +.RE +.\} +.sp +.SH "SEE ALSO" +.sp +\fBzmq_recv\fR(3) \fBzmq_send\fR(3) \fBzmq_getsockopt\fR(3) \fBzmq_socket\fR(7) \fBzmq\fR(7) +.SH "AUTHORS" +.sp +This page was written by the 0MQ community\&. To make a change please read the 0MQ Contribution Policy at \m[blue]\fBhttp://www\&.zeromq\&.org/docs:contributing\fR\m[]\&. diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_send.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_send.3 new file mode 100644 index 00000000000000..f0bb2adadb310b --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_send.3 @@ -0,0 +1,158 @@ +'\" t +.\" Title: zmq_send +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.78.1 +.\" Date: 02/18/2017 +.\" Manual: 0MQ Manual +.\" Source: 0MQ 4.2.2 +.\" Language: English +.\" +.TH "ZMQ_SEND" "3" "02/18/2017" "0MQ 4\&.2\&.2" "0MQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zmq_send \- send a message part on a socket +.SH "SYNOPSIS" +.sp +\fBint zmq_send (void \fR\fB\fI*socket\fR\fR\fB, void \fR\fB\fI*buf\fR\fR\fB, size_t \fR\fB\fIlen\fR\fR\fB, int \fR\fB\fIflags\fR\fR\fB);\fR +.SH "DESCRIPTION" +.sp +The \fIzmq_send()\fR function shall queue a message created from the buffer referenced by the \fIbuf\fR and \fIlen\fR arguments\&. The \fIflags\fR argument is a combination of the flags defined below: +.PP +\fBZMQ_DONTWAIT\fR +.RS 4 +For socket types (DEALER, PUSH) that block when there are no available peers (or all peers have full high\-water mark), specifies that the operation should be performed in non\-blocking mode\&. If the message cannot be queued on the +\fIsocket\fR, the +\fIzmq_send()\fR +function shall fail with +\fIerrno\fR +set to EAGAIN\&. +.RE +.PP +\fBZMQ_SNDMORE\fR +.RS 4 +Specifies that the message being sent is a multi\-part message, and that further message parts are to follow\&. Refer to the section regarding multi\-part messages below for a detailed description\&. +.RE +.if n \{\ +.sp +.\} +.RS 4 +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBNote\fR +.ps -1 +.br +.sp +A successful invocation of \fIzmq_send()\fR does not indicate that the message has been transmitted to the network, only that it has been queued on the \fIsocket\fR and 0MQ has assumed responsibility for the message\&. +.sp .5v +.RE +.SS "Multi\-part messages" +.sp +A 0MQ message is composed of 1 or more message parts\&. 0MQ ensures atomic delivery of messages: peers shall receive either all \fImessage parts\fR of a message or none at all\&. The total number of message parts is unlimited except by available memory\&. +.sp +An application that sends multi\-part messages must use the \fIZMQ_SNDMORE\fR flag when sending each message part except the final one\&. +.SH "RETURN VALUE" +.sp +The \fIzmq_send()\fR function shall return number of bytes in the message if successful\&. Otherwise it shall return \-1 and set \fIerrno\fR to one of the values defined below\&. +.SH "ERRORS" +.PP +\fBEAGAIN\fR +.RS 4 +Non\-blocking mode was requested and the message cannot be sent at the moment\&. +.RE +.PP +\fBENOTSUP\fR +.RS 4 +The +\fIzmq_send()\fR +operation is not supported by this socket type\&. +.RE +.PP +\fBEINVAL\fR +.RS 4 +The sender tried to send multipart data, which the socket type does not allow\&. +.RE +.PP +\fBEFSM\fR +.RS 4 +The +\fIzmq_send()\fR +operation cannot be performed on this socket at the moment due to the socket not being in the appropriate state\&. This error may occur with socket types that switch between several states, such as ZMQ_REP\&. See the +\fImessaging patterns\fR +section of +\fBzmq_socket\fR(3) +for more information\&. +.RE +.PP +\fBETERM\fR +.RS 4 +The 0MQ +\fIcontext\fR +associated with the specified +\fIsocket\fR +was terminated\&. +.RE +.PP +\fBENOTSOCK\fR +.RS 4 +The provided +\fIsocket\fR +was invalid\&. +.RE +.PP +\fBEINTR\fR +.RS 4 +The operation was interrupted by delivery of a signal before the message was sent\&. +.RE +.PP +\fBEHOSTUNREACH\fR +.RS 4 +The message cannot be routed\&. +.RE +.SH "EXAMPLE" +.PP +\fBSending a multi-part message\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +/* Send a multi\-part message consisting of three parts to socket */ +rc = zmq_send (socket, "ABC", 3, ZMQ_SNDMORE); +assert (rc == 3); +rc = zmq_send (socket, "DEFGH", 5, ZMQ_SNDMORE); +assert (rc == 5); +/* Final part; no more parts to follow */ +rc = zmq_send (socket, "JK", 2, 0); +assert (rc == 2); +.fi +.if n \{\ +.RE +.\} +.sp +.SH "SEE ALSO" +.sp +\fBzmq_send_const\fR(3) \fBzmq_recv\fR(3) \fBzmq_socket\fR(7) \fBzmq\fR(7) +.SH "AUTHORS" +.sp +This page was written by the 0MQ community\&. To make a change please read the 0MQ Contribution Policy at \m[blue]\fBhttp://www\&.zeromq\&.org/docs:contributing\fR\m[]\&. diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_send_const.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_send_const.3 new file mode 100644 index 00000000000000..11175ff3267475 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_send_const.3 @@ -0,0 +1,153 @@ +'\" t +.\" Title: zmq_send_const +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.78.1 +.\" Date: 02/18/2017 +.\" Manual: 0MQ Manual +.\" Source: 0MQ 4.2.2 +.\" Language: English +.\" +.TH "ZMQ_SEND_CONST" "3" "02/18/2017" "0MQ 4\&.2\&.2" "0MQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zmq_send_const \- send a constant\-memory message part on a socket +.SH "SYNOPSIS" +.sp +\fBint zmq_send_const (void \fR\fB\fI*socket\fR\fR\fB, void \fR\fB\fI*buf\fR\fR\fB, size_t \fR\fB\fIlen\fR\fR\fB, int \fR\fB\fIflags\fR\fR\fB);\fR +.SH "DESCRIPTION" +.sp +The \fIzmq_send_const()\fR function shall queue a message created from the buffer referenced by the \fIbuf\fR and \fIlen\fR arguments\&. The message buffer is assumed to be constant\-memory and will therefore not be copied or deallocated in any way\&. The \fIflags\fR argument is a combination of the flags defined below: +.PP +\fBZMQ_DONTWAIT\fR +.RS 4 +For socket types (DEALER, PUSH) that block when there are no available peers (or all peers have full high\-water mark), specifies that the operation should be performed in non\-blocking mode\&. If the message cannot be queued on the +\fIsocket\fR, the +\fIzmq_send_const()\fR +function shall fail with +\fIerrno\fR +set to EAGAIN\&. +.RE +.PP +\fBZMQ_SNDMORE\fR +.RS 4 +Specifies that the message being sent is a multi\-part message, and that further message parts are to follow\&. Refer to the section regarding multi\-part messages below for a detailed description\&. +.RE +.if n \{\ +.sp +.\} +.RS 4 +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBNote\fR +.ps -1 +.br +.sp +A successful invocation of \fIzmq_send_const()\fR does not indicate that the message has been transmitted to the network, only that it has been queued on the \fIsocket\fR and 0MQ has assumed responsibility for the message\&. +.sp .5v +.RE +.SS "Multi\-part messages" +.sp +A 0MQ message is composed of 1 or more message parts\&. 0MQ ensures atomic delivery of messages: peers shall receive either all \fImessage parts\fR of a message or none at all\&. The total number of message parts is unlimited except by available memory\&. +.sp +An application that sends multi\-part messages must use the \fIZMQ_SNDMORE\fR flag when sending each message part except the final one\&. +.SH "RETURN VALUE" +.sp +The \fIzmq_send_const()\fR function shall return number of bytes in the message if successful\&. Otherwise it shall return \-1 and set \fIerrno\fR to one of the values defined below\&. +.SH "ERRORS" +.PP +\fBEAGAIN\fR +.RS 4 +Non\-blocking mode was requested and the message cannot be sent at the moment\&. +.RE +.PP +\fBENOTSUP\fR +.RS 4 +The +\fIzmq_send_const()\fR +operation is not supported by this socket type\&. +.RE +.PP +\fBEFSM\fR +.RS 4 +The +\fIzmq_send_const()\fR +operation cannot be performed on this socket at the moment due to the socket not being in the appropriate state\&. This error may occur with socket types that switch between several states, such as ZMQ_REP\&. See the +\fImessaging patterns\fR +section of +\fBzmq_socket\fR(3) +for more information\&. +.RE +.PP +\fBETERM\fR +.RS 4 +The 0MQ +\fIcontext\fR +associated with the specified +\fIsocket\fR +was terminated\&. +.RE +.PP +\fBENOTSOCK\fR +.RS 4 +The provided +\fIsocket\fR +was invalid\&. +.RE +.PP +\fBEINTR\fR +.RS 4 +The operation was interrupted by delivery of a signal before the message was sent\&. +.RE +.PP +\fBEHOSTUNREACH\fR +.RS 4 +The message cannot be routed\&. +.RE +.SH "EXAMPLE" +.PP +\fBSending a multi-part message\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +/* Send a multi\-part message consisting of three parts to socket */ +rc = zmq_send_const (socket, "ABC", 3, ZMQ_SNDMORE); +assert (rc == 3); +rc = zmq_send_const (socket, "DEFGH", 5, ZMQ_SNDMORE); +assert (rc == 5); +/* Final part; no more parts to follow */ +rc = zmq_send_const (socket, "JK", 2, 0); +assert (rc == 2); +.fi +.if n \{\ +.RE +.\} +.sp +.SH "SEE ALSO" +.sp +\fBzmq_send\fR(3) \fBzmq_recv\fR(3) \fBzmq_socket\fR(7) \fBzmq\fR(7) +.SH "AUTHORS" +.sp +This page was written by the 0MQ community\&. To make a change please read the 0MQ Contribution Policy at \m[blue]\fBhttp://www\&.zeromq\&.org/docs:contributing\fR\m[]\&. diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_sendmsg.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_sendmsg.3 new file mode 100644 index 00000000000000..4074be3a45056a --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_sendmsg.3 @@ -0,0 +1,198 @@ +'\" t +.\" Title: zmq_sendmsg +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.78.1 +.\" Date: 02/18/2017 +.\" Manual: 0MQ Manual +.\" Source: 0MQ 4.2.2 +.\" Language: English +.\" +.TH "ZMQ_SENDMSG" "3" "02/18/2017" "0MQ 4\&.2\&.2" "0MQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zmq_sendmsg \- send a message part on a socket +.SH "SYNOPSIS" +.sp +\fBint zmq_sendmsg (void \fR\fB\fI*socket\fR\fR\fB, zmq_msg_t \fR\fB\fI*msg\fR\fR\fB, int \fR\fB\fIflags\fR\fR\fB);\fR +.SH "DESCRIPTION" +.sp +The \fIzmq_sendmsg()\fR function shall queue the message referenced by the \fImsg\fR argument to be sent to the socket referenced by the \fIsocket\fR argument\&. The \fIflags\fR argument is a combination of the flags defined below: +.PP +\fBZMQ_DONTWAIT\fR +.RS 4 +For socket types (DEALER, PUSH) that block when there are no available peers (or all peers have full high\-water mark), specifies that the operation should be performed in non\-blocking mode\&. If the message cannot be queued on the +\fIsocket\fR, the +\fIzmq_sendmsg()\fR +function shall fail with +\fIerrno\fR +set to EAGAIN\&. +.RE +.PP +\fBZMQ_SNDMORE\fR +.RS 4 +Specifies that the message being sent is a multi\-part message, and that further message parts are to follow\&. Refer to the section regarding multi\-part messages below for a detailed description\&. +.RE +.sp +The \fIzmq_msg_t\fR structure passed to \fIzmq_sendmsg()\fR is nullified during the call\&. If you want to send the same message to multiple sockets you have to copy it (e\&.g\&. using \fIzmq_msg_copy()\fR)\&. +.if n \{\ +.sp +.\} +.RS 4 +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBNote\fR +.ps -1 +.br +.sp +A successful invocation of \fIzmq_sendmsg()\fR does not indicate that the message has been transmitted to the network, only that it has been queued on the \fIsocket\fR and 0MQ has assumed responsibility for the message\&. +.sp .5v +.RE +.if n \{\ +.sp +.\} +.RS 4 +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBNote\fR +.ps -1 +.br +.sp +this API method is deprecated in favor of zmq_msg_send(3)\&. +.sp .5v +.RE +.SS "Multi\-part messages" +.sp +A 0MQ message is composed of 1 or more message parts\&. Each message part is an independent \fIzmq_msg_t\fR in its own right\&. 0MQ ensures atomic delivery of messages: peers shall receive either all \fImessage parts\fR of a message or none at all\&. The total number of message parts is unlimited except by available memory\&. +.sp +An application that sends multi\-part messages must use the \fIZMQ_SNDMORE\fR flag when sending each message part except the final one\&. +.SH "RETURN VALUE" +.sp +The \fIzmq_sendmsg()\fR function shall return number of bytes in the message if successful\&. Otherwise it shall return \-1 and set \fIerrno\fR to one of the values defined below\&. +.SH "ERRORS" +.PP +\fBEAGAIN\fR +.RS 4 +Non\-blocking mode was requested and the message cannot be sent at the moment\&. +.RE +.PP +\fBENOTSUP\fR +.RS 4 +The +\fIzmq_sendmsg()\fR +operation is not supported by this socket type\&. +.RE +.PP +\fBEINVAL\fR +.RS 4 +The sender tried to send multipart data, which the socket type does not allow\&. +.RE +.PP +\fBEFSM\fR +.RS 4 +The +\fIzmq_sendmsg()\fR +operation cannot be performed on this socket at the moment due to the socket not being in the appropriate state\&. This error may occur with socket types that switch between several states, such as ZMQ_REP\&. See the +\fImessaging patterns\fR +section of +\fBzmq_socket\fR(3) +for more information\&. +.RE +.PP +\fBETERM\fR +.RS 4 +The 0MQ +\fIcontext\fR +associated with the specified +\fIsocket\fR +was terminated\&. +.RE +.PP +\fBENOTSOCK\fR +.RS 4 +The provided +\fIsocket\fR +was invalid\&. +.RE +.PP +\fBEINTR\fR +.RS 4 +The operation was interrupted by delivery of a signal before the message was sent\&. +.RE +.PP +\fBEFAULT\fR +.RS 4 +Invalid message\&. +.RE +.PP +\fBEHOSTUNREACH\fR +.RS 4 +The message cannot be routed\&. +.RE +.SH "EXAMPLE" +.PP +\fBFilling in a message and sending it to a socket\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +/* Create a new message, allocating 6 bytes for message content */ +zmq_msg_t msg; +int rc = zmq_msg_init_size (&msg, 6); +assert (rc == 0); +/* Fill in message content with \*(AqAAAAAA\*(Aq */ +memset (zmq_msg_data (&msg), \*(AqA\*(Aq, 6); +/* Send the message to the socket */ +rc = zmq_sendmsg (socket, &msg, 0); +assert (rc == 6); +.fi +.if n \{\ +.RE +.\} +.PP +\fBSending a multi-part message\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +/* Send a multi\-part message consisting of three parts to socket */ +rc = zmq_sendmsg (socket, &part1, ZMQ_SNDMORE); +rc = zmq_sendmsg (socket, &part2, ZMQ_SNDMORE); +/* Final part; no more parts to follow */ +rc = zmq_sendmsg (socket, &part3, 0); +.fi +.if n \{\ +.RE +.\} +.sp +.SH "SEE ALSO" +.sp +\fBzmq_recv\fR(3) \fBzmq_socket\fR(7) \fBzmq\fR(7) +.SH "AUTHORS" +.sp +This page was written by the 0MQ community\&. To make a change please read the 0MQ Contribution Policy at \m[blue]\fBhttp://www\&.zeromq\&.org/docs:contributing\fR\m[]\&. diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_setsockopt.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_setsockopt.3 new file mode 100644 index 00000000000000..af381286e8fb3d --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_setsockopt.3 @@ -0,0 +1,3201 @@ +'\" t +.\" Title: zmq_setsockopt +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.78.1 +.\" Date: 02/18/2017 +.\" Manual: 0MQ Manual +.\" Source: 0MQ 4.2.2 +.\" Language: English +.\" +.TH "ZMQ_SETSOCKOPT" "3" "02/18/2017" "0MQ 4\&.2\&.2" "0MQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zmq_setsockopt \- set 0MQ socket options +.SH "SYNOPSIS" +.sp +\fBint zmq_setsockopt (void \fR\fB\fI*socket\fR\fR\fB, int \fR\fB\fIoption_name\fR\fR\fB, const void \fR\fB\fI*option_value\fR\fR\fB, size_t \fR\fB\fIoption_len\fR\fR\fB);\fR +.sp +Caution: All options, with the exception of ZMQ_SUBSCRIBE, ZMQ_UNSUBSCRIBE, ZMQ_LINGER, ZMQ_ROUTER_HANDOVER, ZMQ_ROUTER_MANDATORY, ZMQ_PROBE_ROUTER, ZMQ_XPUB_VERBOSE, ZMQ_XPUB_VERBOSER, ZMQ_REQ_CORRELATE, ZMQ_REQ_RELAXED, ZMQ_SNDHWM and ZMQ_RCVHWM, only take effect for subsequent socket bind/connects\&. +.sp +Specifically, security options take effect for subsequent bind/connect calls, and can be changed at any time to affect subsequent binds and/or connects\&. +.SH "DESCRIPTION" +.sp +The \fIzmq_setsockopt()\fR function shall set the option specified by the \fIoption_name\fR argument to the value pointed to by the \fIoption_value\fR argument for the 0MQ socket pointed to by the \fIsocket\fR argument\&. The \fIoption_len\fR argument is the size of the option value in bytes\&. For options taking a value of type "character string", the provided byte data should either contain no zero bytes, or end in a single zero byte (terminating ASCII NUL character)\&. +.sp +The following socket options can be set with the \fIzmq_setsockopt()\fR function: +.SS "ZMQ_AFFINITY: Set I/O thread affinity" +.sp +The \fIZMQ_AFFINITY\fR option shall set the I/O thread affinity for newly created connections on the specified \fIsocket\fR\&. +.sp +Affinity determines which threads from the 0MQ I/O thread pool associated with the socket\(cqs \fIcontext\fR shall handle newly created connections\&. A value of zero specifies no affinity, meaning that work shall be distributed fairly among all 0MQ I/O threads in the thread pool\&. For non\-zero values, the lowest bit corresponds to thread 1, second lowest bit to thread 2 and so on\&. For example, a value of 3 specifies that subsequent connections on \fIsocket\fR shall be handled exclusively by I/O threads 1 and 2\&. +.sp +See also \fBzmq_init\fR(3) for details on allocating the number of I/O threads for a specific \fIcontext\fR\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +uint64_t +T} +T{ +.sp +Option value unit +T}:T{ +.sp +N/A (bitmap) +T} +T{ +.sp +Default value +T}:T{ +.sp +0 +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +N/A +T} +.TE +.sp 1 +.SS "ZMQ_BACKLOG: Set maximum length of the queue of outstanding connections" +.sp +The \fIZMQ_BACKLOG\fR option shall set the maximum length of the queue of outstanding peer connections for the specified \fIsocket\fR; this only applies to connection\-oriented transports\&. For details refer to your operating system documentation for the \fIlisten\fR function\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +connections +T} +T{ +.sp +Default value +T}:T{ +.sp +100 +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, only for connection\-oriented transports\&. +T} +.TE +.sp 1 +.SS "ZMQ_CONNECT_RID: Assign the next outbound connection id" +.sp +The \fIZMQ_CONNECT_RID\fR option sets the peer id of the next host connected via the zmq_connect() call, and immediately readies that connection for data transfer with the named id\&. This option applies only to the first subsequent call to zmq_connect(), calls thereafter use default connection behaviour\&. +.sp +Typical use is to set this socket option ahead of each zmq_connect() attempt to a new host\&. Each connection MUST be assigned a unique name\&. Assigning a name that is already in use is not allowed\&. +.sp +Useful when connecting ROUTER to ROUTER, or STREAM to STREAM, as it allows for immediate sending to peers\&. Outbound id framing requirements for ROUTER and STREAM sockets apply\&. +.sp +The peer id should be from 1 to 255 bytes long and MAY NOT start with binary zero\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +binary data +T} +T{ +.sp +Option value unit +T}:T{ +.sp +N/A +T} +T{ +.sp +Default value +T}:T{ +.sp +NULL +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +ZMQ_ROUTER, ZMQ_STREAM +T} +.TE +.sp 1 +.SS "ZMQ_CONFLATE: Keep only last message" +.sp +If set, a socket shall keep only one message in its inbound/outbound queue, this message being the last message received/the last message to be sent\&. Ignores \fIZMQ_RCVHWM\fR and \fIZMQ_SNDHWM\fR options\&. Does not support multi\-part messages, in particular, only one part of it is kept in the socket internal queue\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +boolean +T} +T{ +.sp +Default value +T}:T{ +.sp +0 (false) +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +ZMQ_PULL, ZMQ_PUSH, ZMQ_SUB, ZMQ_PUB, ZMQ_DEALER +T} +.TE +.sp 1 +.SS "ZMQ_CONNECT_TIMEOUT: Set connect() timeout" +.sp +Sets how long to wait before timing\-out a connect() system call\&. The connect() system call normally takes a long time before it returns a time out error\&. Setting this option allows the library to time out the call at an earlier interval\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +milliseconds +T} +T{ +.sp +Default value +T}:T{ +.sp +0 (disabled) +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, when using TCP transports\&. +T} +.TE +.sp 1 +.SS "ZMQ_CURVE_PUBLICKEY: Set CURVE public key" +.sp +Sets the socket\(cqs long term public key\&. You must set this on CURVE client sockets, see \fBzmq_curve\fR(7)\&. You can provide the key as 32 binary bytes, or as a 40\-character string encoded in the Z85 encoding format and terminated in a null byte\&. The public key must always be used with the matching secret key\&. To generate a public/secret key pair, use \fBzmq_curve_keypair\fR(3)\&. To derive the public key from a secret key, use \fBzmq_curve_public\fR(3)\&. +.if n \{\ +.sp +.\} +.RS 4 +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBNote\fR +.ps -1 +.br +.sp +an option value size of 40 is supported for backwards compatibility, though is deprecated\&. +.sp .5v +.RE +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +binary data or Z85 text string +T} +T{ +.sp +Option value size +T}:T{ +.sp +32 or 41 +T} +T{ +.sp +Default value +T}:T{ +.sp +NULL +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, when using TCP transport +T} +.TE +.sp 1 +.SS "ZMQ_CURVE_SECRETKEY: Set CURVE secret key" +.sp +Sets the socket\(cqs long term secret key\&. You must set this on both CURVE client and server sockets, see \fBzmq_curve\fR(7)\&. You can provide the key as 32 binary bytes, or as a 40\-character string encoded in the Z85 encoding format and terminated in a null byte\&. To generate a public/secret key pair, use \fBzmq_curve_keypair\fR(3)\&. To derive the public key from a secret key, use \fBzmq_curve_public\fR(3)\&. +.if n \{\ +.sp +.\} +.RS 4 +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBNote\fR +.ps -1 +.br +.sp +an option value size of 40 is supported for backwards compatibility, though is deprecated\&. +.sp .5v +.RE +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +binary data or Z85 text string +T} +T{ +.sp +Option value size +T}:T{ +.sp +32 or 41 +T} +T{ +.sp +Default value +T}:T{ +.sp +NULL +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, when using TCP transport +T} +.TE +.sp 1 +.SS "ZMQ_CURVE_SERVER: Set CURVE server role" +.sp +Defines whether the socket will act as server for CURVE security, see \fBzmq_curve\fR(7)\&. A value of \fI1\fR means the socket will act as CURVE server\&. A value of \fI0\fR means the socket will not act as CURVE server, and its security role then depends on other option settings\&. Setting this to \fI0\fR shall reset the socket security to NULL\&. When you set this you must also set the server\(cqs secret key using the ZMQ_CURVE_SECRETKEY option\&. A server socket does not need to know its own public key\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +0, 1 +T} +T{ +.sp +Default value +T}:T{ +.sp +0 +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, when using TCP transport +T} +.TE +.sp 1 +.SS "ZMQ_CURVE_SERVERKEY: Set CURVE server key" +.sp +Sets the socket\(cqs long term server key\&. You must set this on CURVE client sockets, see \fBzmq_curve\fR(7)\&. You can provide the key as 32 binary bytes, or as a 40\-character string encoded in the Z85 encoding format and terminated in a null byte\&. This key must have been generated together with the server\(cqs secret key\&. To generate a public/secret key pair, use \fBzmq_curve_keypair\fR(3)\&. +.if n \{\ +.sp +.\} +.RS 4 +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBNote\fR +.ps -1 +.br +.sp +an option value size of 40 is supported for backwards compatibility, though is deprecated\&. +.sp .5v +.RE +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +binary data or Z85 text string +T} +T{ +.sp +Option value size +T}:T{ +.sp +32 or 41 +T} +T{ +.sp +Default value +T}:T{ +.sp +NULL +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, when using TCP transport +T} +.TE +.sp 1 +.SS "ZMQ_GSSAPI_PLAINTEXT: Disable GSSAPI encryption" +.sp +Defines whether communications on the socket will be encrypted, see \fBzmq_gssapi\fR(7)\&. A value of \fI1\fR means that communications will be plaintext\&. A value of \fI0\fR means communications will be encrypted\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +0, 1 +T} +T{ +.sp +Default value +T}:T{ +.sp +0 (false) +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, when using TCP transport +T} +.TE +.sp 1 +.SS "ZMQ_GSSAPI_PRINCIPAL: Set name of GSSAPI principal" +.sp +Sets the name of the principal for whom GSSAPI credentials should be acquired\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +character string +T} +T{ +.sp +Option value unit +T}:T{ +.sp +N/A +T} +T{ +.sp +Default value +T}:T{ +.sp +not set +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, when using TCP transport +T} +.TE +.sp 1 +.SS "ZMQ_GSSAPI_SERVER: Set GSSAPI server role" +.sp +Defines whether the socket will act as server for GSSAPI security, see \fBzmq_gssapi\fR(7)\&. A value of \fI1\fR means the socket will act as GSSAPI server\&. A value of \fI0\fR means the socket will act as GSSAPI client\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +0, 1 +T} +T{ +.sp +Default value +T}:T{ +.sp +0 (false) +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, when using TCP transport +T} +.TE +.sp 1 +.SS "ZMQ_GSSAPI_SERVICE_PRINCIPAL: Set name of GSSAPI service principal" +.sp +Sets the name of the principal of the GSSAPI server to which a GSSAPI client intends to connect\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +character string +T} +T{ +.sp +Option value unit +T}:T{ +.sp +N/A +T} +T{ +.sp +Default value +T}:T{ +.sp +not set +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, when using TCP transport +T} +.TE +.sp 1 +.SS "ZMQ_HANDSHAKE_IVL: Set maximum handshake interval" +.sp +The \fIZMQ_HANDSHAKE_IVL\fR option shall set the maximum handshake interval for the specified \fIsocket\fR\&. Handshaking is the exchange of socket configuration information (socket type, identity, security) that occurs when a connection is first opened, only for connection\-oriented transports\&. If handshaking does not complete within the configured time, the connection shall be closed\&. The value 0 means no handshake time limit\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +milliseconds +T} +T{ +.sp +Default value +T}:T{ +.sp +30000 +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all but ZMQ_STREAM, only for connection\-oriented transports +T} +.TE +.sp 1 +.SS "ZMQ_HEARTBEAT_IVL: Set interval between sending ZMTP heartbeats" +.sp +The \fIZMQ_HEARTBEAT_IVL\fR option shall set the interval between sending ZMTP heartbeats for the specified \fIsocket\fR\&. If this option is set and is greater than 0, then a \fIPING\fR ZMTP command will be sent every \fIZMQ_HEARTBEAT_IVL\fR milliseconds\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +milliseconds +T} +T{ +.sp +Default value +T}:T{ +.sp +0 +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, when using connection\-oriented transports +T} +.TE +.sp 1 +.SS "ZMQ_HEARTBEAT_TIMEOUT: Set timeout for ZMTP heartbeats" +.sp +The \fIZMQ_HEARTBEAT_TIMEOUT\fR option shall set how long to wait before timing\-out a connection after sending a \fIPING\fR ZMTP command and not receiving any traffic\&. This option is only valid if \fIZMQ_HEARTBEAT_IVL\fR is also set, and is greater than 0\&. The connection will time out if there is no traffic received after sending the \fIPING\fR command, but the received traffic does not have to be a \fIPONG\fR command \- any received traffic will cancel the timeout\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +milliseconds +T} +T{ +.sp +Default value +T}:T{ +.sp +0 +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, when using connection\-oriented transports +T} +.TE +.sp 1 +.SS "ZMQ_HEARTBEAT_TTL: Set the TTL value for ZMTP heartbeats" +.sp +The \fIZMQ_HEARTBEAT_TTL\fR option shall set the timeout on the remote peer for ZMTP heartbeats\&. If this option is greater than 0, the remote side shall time out the connection if it does not receive any more traffic within the TTL period\&. This option does not have any effect if \fIZMQ_HEARTBEAT_IVL\fR is not set or is 0\&. Internally, this value is rounded down to the nearest decisecond, any value less than 100 will have no effect\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +milliseconds +T} +T{ +.sp +Default value +T}:T{ +.sp +0 +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, when using connection\-oriented transports +T} +.TE +.sp 1 +.SS "ZMQ_IDENTITY: Set socket identity" +.sp +The \fIZMQ_IDENTITY\fR option shall set the identity of the specified \fIsocket\fR when connecting to a ROUTER socket\&. The identity should be from 1 to 255 bytes long and may contain any values\&. +.sp +If two clients use the same identity when connecting to a ROUTER, the results shall depend on the ZMQ_ROUTER_HANDOVER option setting\&. If that is not set (or set to the default of zero), the ROUTER socket shall reject clients trying to connect with an already\-used identity\&. If that option is set to 1, the ROUTER socket shall hand\-over the connection to the new client and disconnect the existing one\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +binary data +T} +T{ +.sp +Option value unit +T}:T{ +.sp +N/A +T} +T{ +.sp +Default value +T}:T{ +.sp +NULL +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +ZMQ_REQ, ZMQ_REP, ZMQ_ROUTER, ZMQ_DEALER\&. +T} +.TE +.sp 1 +.SS "ZMQ_IMMEDIATE: Queue messages only to completed connections" +.sp +By default queues will fill on outgoing connections even if the connection has not completed\&. This can lead to "lost" messages on sockets with round\-robin routing (REQ, PUSH, DEALER)\&. If this option is set to 1, messages shall be queued only to completed connections\&. This will cause the socket to block if there are no other connections, but will prevent queues from filling on pipes awaiting connection\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +boolean +T} +T{ +.sp +Default value +T}:T{ +.sp +0 (false) +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, only for connection\-oriented transports\&. +T} +.TE +.sp 1 +.SS "ZMQ_INVERT_MATCHING: Invert message filtering" +.sp +Reverses the filtering behavior of PUB\-SUB sockets, when set to 1\&. +.sp +On \fIPUB\fR and \fIXPUB\fR sockets, this causes messages to be sent to all connected sockets \fIexcept\fR those subscribed to a prefix that matches the message\&. On \fISUB\fR sockets, this causes only incoming messages that do \fInot\fR match any of the socket\(cqs subscriptions to be received by the user\&. +.sp +Whenever \fIZMQ_INVERT_MATCHING\fR is set to 1 on a \fIPUB\fR socket, all \fISUB\fR sockets connecting to it must also have the option set to 1\&. Failure to do so will have the \fISUB\fR sockets reject everything the \fIPUB\fR socket sends them\&. \fIXSUB\fR sockets do not need to do this because they do not filter incoming messages\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +0,1 +T} +T{ +.sp +Default value +T}:T{ +.sp +0 +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +ZMQ_PUB, ZMQ_XPUB, ZMQ_SUB +T} +.TE +.sp 1 +.SS "ZMQ_IPV6: Enable IPv6 on socket" +.sp +Set the IPv6 option for the socket\&. A value of 1 means IPv6 is enabled on the socket, while 0 means the socket will use only IPv4\&. When IPv6 is enabled the socket will connect to, or accept connections from, both IPv4 and IPv6 hosts\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +boolean +T} +T{ +.sp +Default value +T}:T{ +.sp +0 (false) +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, when using TCP transports\&. +T} +.TE +.sp 1 +.SS "ZMQ_LINGER: Set linger period for socket shutdown" +.sp +The \fIZMQ_LINGER\fR option shall set the linger period for the specified \fIsocket\fR\&. The linger period determines how long pending messages which have yet to be sent to a peer shall linger in memory after a socket is disconnected with \fBzmq_disconnect\fR(3) or closed with \fBzmq_close\fR(3), and further affects the termination of the socket\(cqs context with \fBzmq_ctx_term\fR(3)\&. The following outlines the different behaviours: +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +A value of +\fI\-1\fR +specifies an infinite linger period\&. Pending messages shall not be discarded after a call to +\fIzmq_disconnect()\fR +or +\fIzmq_close()\fR; attempting to terminate the socket\(cqs context with +\fIzmq_ctx_term()\fR +shall block until all pending messages have been sent to a peer\&. +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +The value of +\fI0\fR +specifies no linger period\&. Pending messages shall be discarded immediately after a call to +\fIzmq_disconnect()\fR +or +\fIzmq_close()\fR\&. +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +Positive values specify an upper bound for the linger period in milliseconds\&. Pending messages shall not be discarded after a call to +\fIzmq_disconnect()\fR +or +\fIzmq_close()\fR; attempting to terminate the socket\(cqs context with +\fIzmq_ctx_term()\fR +shall block until either all pending messages have been sent to a peer, or the linger period expires, after which any pending messages shall be discarded\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +Option value type +T}:T{ +int +T} +T{ +Option value unit +T}:T{ +milliseconds +T} +T{ +Default value +T}:T{ +30000 (thirty seconds) +T} +T{ +Applicable socket types +T}:T{ +all +T} +.TE +.sp 1 +.RE +.SS "ZMQ_MAXMSGSIZE: Maximum acceptable inbound message size" +.sp +Limits the size of the inbound message\&. If a peer sends a message larger than ZMQ_MAXMSGSIZE it is disconnected\&. Value of \-1 means \fIno limit\fR\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int64_t +T} +T{ +.sp +Option value unit +T}:T{ +.sp +bytes +T} +T{ +.sp +Default value +T}:T{ +.sp +\-1 +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all +T} +.TE +.sp 1 +.SS "ZMQ_MULTICAST_HOPS: Maximum network hops for multicast packets" +.sp +Sets the time\-to\-live field in every multicast packet sent from this socket\&. The default is 1 which means that the multicast packets don\(cqt leave the local network\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +network hops +T} +T{ +.sp +Default value +T}:T{ +.sp +1 +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, when using multicast transports +T} +.TE +.sp 1 +.SS "ZMQ_MULTICAST_MAXTPDU: Maximum transport data unit size for multicast packets" +.sp +Sets the maximum transport data unit size used for outbound multicast packets\&. +.sp +This must be set at or below the minimum Maximum Transmission Unit (MTU) for all network paths over which multicast reception is required\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +bytes +T} +T{ +.sp +Default value +T}:T{ +.sp +1500 +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, when using multicast transports +T} +.TE +.sp 1 +.SS "ZMQ_PLAIN_PASSWORD: Set PLAIN security password" +.sp +Sets the password for outgoing connections over TCP or IPC\&. If you set this to a non\-null value, the security mechanism used for connections shall be PLAIN, see \fBzmq_plain\fR(7)\&. If you set this to a null value, the security mechanism used for connections shall be NULL, see \fBzmq_null\fR(3)\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +character string +T} +T{ +.sp +Option value unit +T}:T{ +.sp +N/A +T} +T{ +.sp +Default value +T}:T{ +.sp +not set +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, when using TCP transport +T} +.TE +.sp 1 +.SS "ZMQ_PLAIN_SERVER: Set PLAIN server role" +.sp +Defines whether the socket will act as server for PLAIN security, see \fBzmq_plain\fR(7)\&. A value of \fI1\fR means the socket will act as PLAIN server\&. A value of \fI0\fR means the socket will not act as PLAIN server, and its security role then depends on other option settings\&. Setting this to \fI0\fR shall reset the socket security to NULL\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +0, 1 +T} +T{ +.sp +Default value +T}:T{ +.sp +0 +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, when using TCP transport +T} +.TE +.sp 1 +.SS "ZMQ_PLAIN_USERNAME: Set PLAIN security username" +.sp +Sets the username for outgoing connections over TCP or IPC\&. If you set this to a non\-null value, the security mechanism used for connections shall be PLAIN, see \fBzmq_plain\fR(7)\&. If you set this to a null value, the security mechanism used for connections shall be NULL, see \fBzmq_null\fR(3)\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +character string +T} +T{ +.sp +Option value unit +T}:T{ +.sp +N/A +T} +T{ +.sp +Default value +T}:T{ +.sp +not set +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, when using TCP transport +T} +.TE +.sp 1 +.SS "ZMQ_USE_FD: Set the pre\-allocated socket file descriptor" +.sp +When set to a positive integer value before zmq_bind is called on the socket, the socket shall use the corresponding file descriptor for connections over TCP or IPC instead of allocating a new file descriptor\&. Useful for writing systemd socket activated services\&. If set to \-1 (default), a new file descriptor will be allocated instead (default behaviour)\&. +.if n \{\ +.sp +.\} +.RS 4 +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBNote\fR +.ps -1 +.br +.sp +if set after calling zmq_bind, this option shall have no effect\&. NOTE: the file descriptor passed through MUST have been ran through the "bind" and "listen" system calls beforehand\&. Also, socket option that would normally be passed through zmq_setsockopt like TCP buffers length, IP_TOS or SO_REUSEADDR MUST be set beforehand by the caller, as they must be set before the socket is bound\&. +.sp .5v +.RE +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +file descriptor +T} +T{ +.sp +Default value +T}:T{ +.sp +\-1 +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all bound sockets, when using IPC or TCP transport +T} +.TE +.sp 1 +.SS "ZMQ_PROBE_ROUTER: bootstrap connections to ROUTER sockets" +.sp +When set to 1, the socket will automatically send an empty message when a new connection is made or accepted\&. You may set this on REQ, DEALER, or ROUTER sockets connected to a ROUTER socket\&. The application must filter such empty messages\&. The ZMQ_PROBE_ROUTER option in effect provides the ROUTER application with an event signaling the arrival of a new peer\&. +.if n \{\ +.sp +.\} +.RS 4 +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBNote\fR +.ps -1 +.br +.sp +do not set this option on a socket that talks to any other socket types: the results are undefined\&. +.sp .5v +.RE +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +0, 1 +T} +T{ +.sp +Default value +T}:T{ +.sp +0 +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +ZMQ_ROUTER, ZMQ_DEALER, ZMQ_REQ +T} +.TE +.sp 1 +.SS "ZMQ_RATE: Set multicast data rate" +.sp +The \fIZMQ_RATE\fR option shall set the maximum send or receive data rate for multicast transports such as \fBzmq_pgm\fR(7) using the specified \fIsocket\fR\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +kilobits per second +T} +T{ +.sp +Default value +T}:T{ +.sp +100 +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, when using multicast transports +T} +.TE +.sp 1 +.SS "ZMQ_RCVBUF: Set kernel receive buffer size" +.sp +The \fIZMQ_RCVBUF\fR option shall set the underlying kernel receive buffer size for the \fIsocket\fR to the specified size in bytes\&. A value of \-1 means leave the OS default unchanged\&. For details refer to your operating system documentation for the \fISO_RCVBUF\fR socket option\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +bytes +T} +T{ +.sp +Default value +T}:T{ +.sp +\-1 +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all +T} +.TE +.sp 1 +.SS "ZMQ_RCVHWM: Set high water mark for inbound messages" +.sp +The \fIZMQ_RCVHWM\fR option shall set the high water mark for inbound messages on the specified \fIsocket\fR\&. The high water mark is a hard limit on the maximum number of outstanding messages 0MQ shall queue in memory for any single peer that the specified \fIsocket\fR is communicating with\&. A value of zero means no limit\&. +.sp +If this limit has been reached the socket shall enter an exceptional state and depending on the socket type, 0MQ shall take appropriate action such as blocking or dropping sent messages\&. Refer to the individual socket descriptions in \fBzmq_socket\fR(3) for details on the exact action taken for each socket type\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +messages +T} +T{ +.sp +Default value +T}:T{ +.sp +1000 +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all +T} +.TE +.sp 1 +.SS "ZMQ_RCVTIMEO: Maximum time before a recv operation returns with EAGAIN" +.sp +Sets the timeout for receive operation on the socket\&. If the value is 0, \fIzmq_recv(3)\fR will return immediately, with a EAGAIN error if there is no message to receive\&. If the value is \-1, it will block until a message is available\&. For all other values, it will wait for a message for that amount of time before returning with an EAGAIN error\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +milliseconds +T} +T{ +.sp +Default value +T}:T{ +.sp +\-1 (infinite) +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all +T} +.TE +.sp 1 +.SS "ZMQ_RECONNECT_IVL: Set reconnection interval" +.sp +The \fIZMQ_RECONNECT_IVL\fR option shall set the initial reconnection interval for the specified \fIsocket\fR\&. The reconnection interval is the period 0MQ shall wait between attempts to reconnect disconnected peers when using connection\-oriented transports\&. The value \-1 means no reconnection\&. +.if n \{\ +.sp +.\} +.RS 4 +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBNote\fR +.ps -1 +.br +.sp +The reconnection interval may be randomized by 0MQ to prevent reconnection storms in topologies with a large number of peers per socket\&. +.sp .5v +.RE +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +milliseconds +T} +T{ +.sp +Default value +T}:T{ +.sp +100 +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, only for connection\-oriented transports +T} +.TE +.sp 1 +.SS "ZMQ_RECONNECT_IVL_MAX: Set maximum reconnection interval" +.sp +The \fIZMQ_RECONNECT_IVL_MAX\fR option shall set the maximum reconnection interval for the specified \fIsocket\fR\&. This is the maximum period 0MQ shall wait between attempts to reconnect\&. On each reconnect attempt, the previous interval shall be doubled untill ZMQ_RECONNECT_IVL_MAX is reached\&. This allows for exponential backoff strategy\&. Default value means no exponential backoff is performed and reconnect interval calculations are only based on ZMQ_RECONNECT_IVL\&. +.if n \{\ +.sp +.\} +.RS 4 +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBNote\fR +.ps -1 +.br +.sp +Values less than ZMQ_RECONNECT_IVL will be ignored\&. +.sp .5v +.RE +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +milliseconds +T} +T{ +.sp +Default value +T}:T{ +.sp +0 (only use ZMQ_RECONNECT_IVL) +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, only for connection\-oriented transports +T} +.TE +.sp 1 +.SS "ZMQ_RECOVERY_IVL: Set multicast recovery interval" +.sp +The \fIZMQ_RECOVERY_IVL\fR option shall set the recovery interval for multicast transports using the specified \fIsocket\fR\&. The recovery interval determines the maximum time in milliseconds that a receiver can be absent from a multicast group before unrecoverable data loss will occur\&. +.if n \{\ +.sp +.\} +.RS 4 +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBCaution\fR +.ps -1 +.br +.sp +Exercise care when setting large recovery intervals as the data needed for recovery will be held in memory\&. For example, a 1 minute recovery interval at a data rate of 1Gbps requires a 7GB in\-memory buffer\&. +.sp .5v +.RE +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +milliseconds +T} +T{ +.sp +Default value +T}:T{ +.sp +10000 +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, when using multicast transports +T} +.TE +.sp 1 +.SS "ZMQ_REQ_CORRELATE: match replies with requests" +.sp +The default behaviour of REQ sockets is to rely on the ordering of messages to match requests and responses and that is usually sufficient\&. When this option is set to 1, the REQ socket will prefix outgoing messages with an extra frame containing a request id\&. That means the full message is (request id, 0, user frames\&...)\&. The REQ socket will discard all incoming messages that don\(cqt begin with these two frames\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +0, 1 +T} +T{ +.sp +Default value +T}:T{ +.sp +0 +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +ZMQ_REQ +T} +.TE +.sp 1 +.SS "ZMQ_REQ_RELAXED: relax strict alternation between request and reply" +.sp +By default, a REQ socket does not allow initiating a new request with \fIzmq_send(3)\fR until the reply to the previous one has been received\&. When set to 1, sending another message is allowed and previous replies will be discarded if any\&. The request\-reply state machine is reset and a new request is sent to the next available peer\&. +.sp +If set to 1, also enable ZMQ_REQ_CORRELATE to ensure correct matching of requests and replies\&. Otherwise a late reply to an aborted request can be reported as the reply to the superseding request\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +0, 1 +T} +T{ +.sp +Default value +T}:T{ +.sp +0 +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +ZMQ_REQ +T} +.TE +.sp 1 +.SS "ZMQ_ROUTER_HANDOVER: handle duplicate client identities on ROUTER sockets" +.sp +If two clients use the same identity when connecting to a ROUTER, the results shall depend on the ZMQ_ROUTER_HANDOVER option setting\&. If that is not set (or set to the default of zero), the ROUTER socket shall reject clients trying to connect with an already\-used identity\&. If that option is set to 1, the ROUTER socket shall hand\-over the connection to the new client and disconnect the existing one\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +0, 1 +T} +T{ +.sp +Default value +T}:T{ +.sp +0 +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +ZMQ_ROUTER +T} +.TE +.sp 1 +.SS "ZMQ_ROUTER_MANDATORY: accept only routable messages on ROUTER sockets" +.sp +Sets the ROUTER socket behaviour when an unroutable message is encountered\&. A value of 0 is the default and discards the message silently when it cannot be routed or the peers SNDHWM is reached\&. A value of 1 returns an \fIEHOSTUNREACH\fR error code if the message cannot be routed or \fIEAGAIN\fR error code if the SNDHWM is reached and ZMQ_DONTWAIT was used\&. Without ZMQ_DONTWAIT it will block until the SNDTIMEO is reached or a spot in the send queue opens up\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +0, 1 +T} +T{ +.sp +Default value +T}:T{ +.sp +0 +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +ZMQ_ROUTER +T} +.TE +.sp 1 +.SS "ZMQ_ROUTER_RAW: switch ROUTER socket to raw mode" +.sp +Sets the raw mode on the ROUTER, when set to 1\&. When the ROUTER socket is in raw mode, and when using the tcp:// transport, it will read and write TCP data without 0MQ framing\&. This lets 0MQ applications talk to non\-0MQ applications\&. When using raw mode, you cannot set explicit identities, and the ZMQ_SNDMORE flag is ignored when sending data messages\&. In raw mode you can close a specific connection by sending it a zero\-length message (following the identity frame)\&. +.if n \{\ +.sp +.\} +.RS 4 +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBNote\fR +.ps -1 +.br +.sp +This option is deprecated, please use ZMQ_STREAM sockets instead\&. +.sp .5v +.RE +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +0, 1 +T} +T{ +.sp +Default value +T}:T{ +.sp +0 +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +ZMQ_ROUTER +T} +.TE +.sp 1 +.SS "ZMQ_SNDBUF: Set kernel transmit buffer size" +.sp +The \fIZMQ_SNDBUF\fR option shall set the underlying kernel transmit buffer size for the \fIsocket\fR to the specified size in bytes\&. A value of \-1 means leave the OS default unchanged\&. For details please refer to your operating system documentation for the \fISO_SNDBUF\fR socket option\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +bytes +T} +T{ +.sp +Default value +T}:T{ +.sp +\-1 +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all +T} +.TE +.sp 1 +.SS "ZMQ_SNDHWM: Set high water mark for outbound messages" +.sp +The \fIZMQ_SNDHWM\fR option shall set the high water mark for outbound messages on the specified \fIsocket\fR\&. The high water mark is a hard limit on the maximum number of outstanding messages 0MQ shall queue in memory for any single peer that the specified \fIsocket\fR is communicating with\&. A value of zero means no limit\&. +.sp +If this limit has been reached the socket shall enter an exceptional state and depending on the socket type, 0MQ shall take appropriate action such as blocking or dropping sent messages\&. Refer to the individual socket descriptions in \fBzmq_socket\fR(3) for details on the exact action taken for each socket type\&. +.if n \{\ +.sp +.\} +.RS 4 +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBNote\fR +.ps -1 +.br +.sp +0MQ does not guarantee that the socket will accept as many as ZMQ_SNDHWM messages, and the actual limit may be as much as 60\-70% lower depending on the flow of messages on the socket\&. +.sp .5v +.RE +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +messages +T} +T{ +.sp +Default value +T}:T{ +.sp +1000 +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all +T} +.TE +.sp 1 +.SS "ZMQ_SNDTIMEO: Maximum time before a send operation returns with EAGAIN" +.sp +Sets the timeout for send operation on the socket\&. If the value is 0, \fIzmq_send(3)\fR will return immediately, with a EAGAIN error if the message cannot be sent\&. If the value is \-1, it will block until the message is sent\&. For all other values, it will try to send the message for that amount of time before returning with an EAGAIN error\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +milliseconds +T} +T{ +.sp +Default value +T}:T{ +.sp +\-1 (infinite) +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all +T} +.TE +.sp 1 +.SS "ZMQ_SOCKS_PROXY: Set SOCKS5 proxy address" +.sp +Sets the SOCKS5 proxy address that shall be used by the socket for the TCP connection(s)\&. Does not support SOCKS5 authentication\&. If the endpoints are domain names instead of addresses they shall not be resolved and they shall be forwarded unchanged to the SOCKS proxy service in the client connection request message (address type 0x03 domain name)\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +character string +T} +T{ +.sp +Option value unit +T}:T{ +.sp +N/A +T} +T{ +.sp +Default value +T}:T{ +.sp +not set +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, when using TCP transport +T} +.TE +.sp 1 +.SS "ZMQ_STREAM_NOTIFY: send connect and disconnect notifications" +.sp +Enables connect and disconnect notifications on a STREAM socket, when set to 1\&. When notifications are enabled, the socket delivers a zero\-length message when a peer connects or disconnects\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +0, 1 +T} +T{ +.sp +Default value +T}:T{ +.sp +1 +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +ZMQ_STREAM +T} +.TE +.sp 1 +.SS "ZMQ_SUBSCRIBE: Establish message filter" +.sp +The \fIZMQ_SUBSCRIBE\fR option shall establish a new message filter on a \fIZMQ_SUB\fR socket\&. Newly created \fIZMQ_SUB\fR sockets shall filter out all incoming messages, therefore you should call this option to establish an initial message filter\&. +.sp +An empty \fIoption_value\fR of length zero shall subscribe to all incoming messages\&. A non\-empty \fIoption_value\fR shall subscribe to all messages beginning with the specified prefix\&. Multiple filters may be attached to a single \fIZMQ_SUB\fR socket, in which case a message shall be accepted if it matches at least one filter\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +binary data +T} +T{ +.sp +Option value unit +T}:T{ +.sp +N/A +T} +T{ +.sp +Default value +T}:T{ +.sp +N/A +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +ZMQ_SUB +T} +.TE +.sp 1 +.SS "ZMQ_TCP_KEEPALIVE: Override SO_KEEPALIVE socket option" +.sp +Override \fISO_KEEPALIVE\fR socket option (where supported by OS)\&. The default value of \-1 means to skip any overrides and leave it to OS default\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +\-1,0,1 +T} +T{ +.sp +Default value +T}:T{ +.sp +\-1 (leave to OS default) +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, when using TCP transports\&. +T} +.TE +.sp 1 +.SS "ZMQ_TCP_KEEPALIVE_CNT: Override TCP_KEEPCNT socket option" +.sp +Override \fITCP_KEEPCNT\fR socket option (where supported by OS)\&. The default value of \-1 means to skip any overrides and leave it to OS default\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +\-1,>0 +T} +T{ +.sp +Default value +T}:T{ +.sp +\-1 (leave to OS default) +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, when using TCP transports\&. +T} +.TE +.sp 1 +.SS "ZMQ_TCP_KEEPALIVE_IDLE: Override TCP_KEEPIDLE (or TCP_KEEPALIVE on some OS)" +.sp +Override \fITCP_KEEPIDLE\fR (or \fITCP_KEEPALIVE\fR on some OS) socket option (where supported by OS)\&. The default value of \-1 means to skip any overrides and leave it to OS default\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +\-1,>0 +T} +T{ +.sp +Default value +T}:T{ +.sp +\-1 (leave to OS default) +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, when using TCP transports\&. +T} +.TE +.sp 1 +.SS "ZMQ_TCP_KEEPALIVE_INTVL: Override TCP_KEEPINTVL socket option" +.sp +Override \fITCP_KEEPINTVL\fR socket option(where supported by OS)\&. The default value of \-1 means to skip any overrides and leave it to OS default\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +\-1,>0 +T} +T{ +.sp +Default value +T}:T{ +.sp +\-1 (leave to OS default) +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, when using TCP transports\&. +T} +.TE +.sp 1 +.SS "ZMQ_TCP_MAXRT: Set TCP Maximum Retransmit Timeout" +.sp +On OSes where it is supported, sets how long before an unacknowledged TCP retransmit times out\&. The system normally attempts many TCP retransmits following an exponential backoff strategy\&. This means that after a network outage, it may take a long time before the session can be re\-established\&. Setting this option allows the timeout to happen at a shorter interval\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +milliseconds +T} +T{ +.sp +Default value +T}:T{ +.sp +0 (leave to OS default) +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, when using TCP transports\&. +T} +.TE +.sp 1 +.SS "ZMQ_TOS: Set the Type\-of\-Service on socket" +.sp +Sets the ToS fields (Differentiated services (DS) and Explicit Congestion Notification (ECN) field of the IP header\&. The ToS field is typically used to specify a packets priority\&. The availability of this option is dependent on intermediate network equipment that inspect the ToS field and provide a path for low\-delay, high\-throughput, highly\-reliable service, etc\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +>0 +T} +T{ +.sp +Default value +T}:T{ +.sp +0 +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, only for connection\-oriented transports +T} +.TE +.sp 1 +.SS "ZMQ_UNSUBSCRIBE: Remove message filter" +.sp +The \fIZMQ_UNSUBSCRIBE\fR option shall remove an existing message filter on a \fIZMQ_SUB\fR socket\&. The filter specified must match an existing filter previously established with the \fIZMQ_SUBSCRIBE\fR option\&. If the socket has several instances of the same filter attached the \fIZMQ_UNSUBSCRIBE\fR option shall remove only one instance, leaving the rest in place and functional\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +binary data +T} +T{ +.sp +Option value unit +T}:T{ +.sp +N/A +T} +T{ +.sp +Default value +T}:T{ +.sp +N/A +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +ZMQ_SUB +T} +.TE +.sp 1 +.SS "ZMQ_XPUB_VERBOSE: pass subscribe messages on XPUB socket" +.sp +Sets the \fIXPUB\fR socket behaviour on new subscriptions\&. If enabled, the socket passes all subscribe messages to the caller\&. If disabled, these are not visible to the caller\&. The default is 0 (disabled)\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +0, 1 +T} +T{ +.sp +Default value +T}:T{ +.sp +0 +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +ZMQ_XPUB +T} +.TE +.sp 1 +.SS "ZMQ_XPUB_VERBOSER: pass subscribe and unsubscribe messages on XPUB socket" +.sp +Sets the \fIXPUB\fR socket behaviour on new subscriptions and ubsubscriptions\&. If enabled, the socket passes all subscribe and unsubscribe messages to the caller\&. If disabled, these are not visible to the caller\&. The default is 0 (disabled)\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +0, 1 +T} +T{ +.sp +Default value +T}:T{ +.sp +0 +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +ZMQ_XPUB +T} +.TE +.sp 1 +.SS "ZMQ_XPUB_MANUAL: change the subscription handling to manual" +.sp +Sets the \fIXPUB\fR socket subscription handling mode manual/automatic\&. A value of \fI0\fR is the default and subscription requests will be handled automatically\&. A value of \fI1\fR will change the subscription requests handling to manual, with manual mode subscription requests are not added to the subscription list\&. To add subscription the user need to call setsockopt with ZMQ_SUBSCRIBE on XPUB socket\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +0, 1 +T} +T{ +.sp +Default value +T}:T{ +.sp +0 +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +ZMQ_XPUB +T} +.TE +.sp 1 +.SS "ZMQ_XPUB_NODROP: do not silently drop messages if SENDHWM is reached" +.sp +Sets the \fIXPUB\fR socket behaviour to return error EAGAIN if SENDHWM is reached and the message could not be send\&. +.sp +A value of 0 is the default and drops the message silently when the peers SNDHWM is reached\&. A value of 1 returns an \fIEAGAIN\fR error code if the SNDHWM is reached and ZMQ_DONTWAIT was used\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +0, 1 +T} +T{ +.sp +Default value +T}:T{ +.sp +0 +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +ZMQ_XPUB, ZMQ_PUB +T} +.TE +.sp 1 +.SS "ZMQ_XPUB_WELCOME_MSG: set welcome message that will be received by subscriber when connecting" +.sp +Sets a welcome message the will be recieved by subscriber when connecting\&. Subscriber must subscribe to the Welcome message before connecting\&. Welcome message will also be sent on reconnecting\&. For welcome message to work well user must poll on incoming subscription messages on the XPUB socket and handle them\&. +.sp +Use NULL and lenght of zero to disable welcome message\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +binary data +T} +T{ +.sp +Option value unit +T}:T{ +.sp +N/A +T} +T{ +.sp +Default value +T}:T{ +.sp +NULL +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +ZMQ_XPUB +T} +.TE +.sp 1 +.SS "ZMQ_ZAP_DOMAIN: Set RFC 27 authentication domain" +.sp +Sets the domain for ZAP (ZMQ RFC 27) authentication\&. For NULL security (the default on all tcp:// connections), ZAP authentication only happens if you set a non\-empty domain\&. For PLAIN and CURVE security, ZAP requests are always made, if there is a ZAP handler present\&. See \m[blue]\fBhttp://rfc\&.zeromq\&.org/spec:27\fR\m[] for more details\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +character string +T} +T{ +.sp +Option value unit +T}:T{ +.sp +N/A +T} +T{ +.sp +Default value +T}:T{ +.sp +not set +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, when using TCP transport +T} +.TE +.sp 1 +.SS "ZMQ_TCP_ACCEPT_FILTER: Assign filters to allow new TCP connections" +.sp +Assign an arbitrary number of filters that will be applied for each new TCP transport connection on a listening socket\&. If no filters are applied, then the TCP transport allows connections from any IP address\&. If at least one filter is applied then new connection source ip should be matched\&. To clear all filters call zmq_setsockopt(socket, ZMQ_TCP_ACCEPT_FILTER, NULL, 0)\&. Filter is a null\-terminated string with ipv6 or ipv4 CIDR\&. +.if n \{\ +.sp +.\} +.RS 4 +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBNote\fR +.ps -1 +.br +.sp +This option is deprecated, please use authentication via the ZAP API and IP address whitelisting / blacklisting\&. +.sp .5v +.RE +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +binary data +T} +T{ +.sp +Option value unit +T}:T{ +.sp +N/A +T} +T{ +.sp +Default value +T}:T{ +.sp +no filters (allow from all) +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all listening sockets, when using TCP transports\&. +T} +.TE +.sp 1 +.SS "ZMQ_IPC_FILTER_GID: Assign group ID filters to allow new IPC connections" +.sp +Assign an arbitrary number of filters that will be applied for each new IPC transport connection on a listening socket\&. If no IPC filters are applied, then the IPC transport allows connections from any process\&. If at least one UID, GID, or PID filter is applied then new connection credentials should be matched\&. To clear all GID filters call zmq_setsockopt(socket, ZMQ_IPC_FILTER_GID, NULL, 0)\&. +.if n \{\ +.sp +.\} +.RS 4 +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBNote\fR +.ps -1 +.br +.sp +GID filters are only available on platforms supporting SO_PEERCRED or LOCAL_PEERCRED socket options (currently only Linux and later versions of OS X)\&. +.sp .5v +.RE +.if n \{\ +.sp +.\} +.RS 4 +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBNote\fR +.ps -1 +.br +.sp +This option is deprecated, please use authentication via the ZAP API and IPC whitelisting / blacklisting\&. +.sp .5v +.RE +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +gid_t +T} +T{ +.sp +Option value unit +T}:T{ +.sp +N/A +T} +T{ +.sp +Default value +T}:T{ +.sp +no filters (allow from all) +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all listening sockets, when using IPC transports\&. +T} +.TE +.sp 1 +.SS "ZMQ_IPC_FILTER_PID: Assign process ID filters to allow new IPC connections" +.sp +Assign an arbitrary number of filters that will be applied for each new IPC transport connection on a listening socket\&. If no IPC filters are applied, then the IPC transport allows connections from any process\&. If at least one UID, GID, or PID filter is applied then new connection credentials should be matched\&. To clear all PID filters call zmq_setsockopt(socket, ZMQ_IPC_FILTER_PID, NULL, 0)\&. +.if n \{\ +.sp +.\} +.RS 4 +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBNote\fR +.ps -1 +.br +.sp +PID filters are only available on platforms supporting the SO_PEERCRED socket option (currently only Linux)\&. +.sp .5v +.RE +.if n \{\ +.sp +.\} +.RS 4 +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBNote\fR +.ps -1 +.br +.sp +This option is deprecated, please use authentication via the ZAP API and IPC whitelisting / blacklisting\&. +.sp .5v +.RE +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +pid_t +T} +T{ +.sp +Option value unit +T}:T{ +.sp +N/A +T} +T{ +.sp +Default value +T}:T{ +.sp +no filters (allow from all) +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all listening sockets, when using IPC transports\&. +T} +.TE +.sp 1 +.SS "ZMQ_IPC_FILTER_UID: Assign user ID filters to allow new IPC connections" +.sp +Assign an arbitrary number of filters that will be applied for each new IPC transport connection on a listening socket\&. If no IPC filters are applied, then the IPC transport allows connections from any process\&. If at least one UID, GID, or PID filter is applied then new connection credentials should be matched\&. To clear all UID filters call zmq_setsockopt(socket, ZMQ_IPC_FILTER_UID, NULL, 0)\&. +.if n \{\ +.sp +.\} +.RS 4 +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBNote\fR +.ps -1 +.br +.sp +UID filters are only available on platforms supporting SO_PEERCRED or LOCAL_PEERCRED socket options (currently only Linux and later versions of OS X)\&. +.sp .5v +.RE +.if n \{\ +.sp +.\} +.RS 4 +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBNote\fR +.ps -1 +.br +.sp +This option is deprecated, please use authentication via the ZAP API and IPC whitelisting / blacklisting\&. +.sp .5v +.RE +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +uid_t +T} +T{ +.sp +Option value unit +T}:T{ +.sp +N/A +T} +T{ +.sp +Default value +T}:T{ +.sp +no filters (allow from all) +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all listening sockets, when using IPC transports\&. +T} +.TE +.sp 1 +.SS "ZMQ_IPV4ONLY: Use IPv4\-only on socket" +.sp +Set the IPv4\-only option for the socket\&. This option is deprecated\&. Please use the ZMQ_IPV6 option\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +boolean +T} +T{ +.sp +Default value +T}:T{ +.sp +1 (true) +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, when using TCP transports\&. +T} +.TE +.sp 1 +.SS "ZMQ_VMCI_BUFFER_SIZE: Set buffer size of the VMCI socket" +.sp +The ZMQ_VMCI_BUFFER_SIZE option shall set the size of the underlying buffer for the socket\&. Used during negotiation before the connection is established\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +uint64_t +T} +T{ +.sp +Option value unit +T}:T{ +.sp +bytes +T} +T{ +.sp +Default value +T}:T{ +.sp +65546 +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, when using VMCI transport +T} +.TE +.sp 1 +.SS "ZMQ_VMCI_BUFFER_MIN_SIZE: Set min buffer size of the VMCI socket" +.sp +The ZMQ_VMCI_BUFFER_MIN_SIZE option shall set the min size of the underlying buffer for the socket\&. Used during negotiation before the connection is established\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +uint64_t +T} +T{ +.sp +Option value unit +T}:T{ +.sp +bytes +T} +T{ +.sp +Default value +T}:T{ +.sp +128 +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, when using VMCI transport +T} +.TE +.sp 1 +.SS "ZMQ_VMCI_BUFFER_MAX_SIZE: Set max buffer size of the VMCI socket" +.sp +The ZMQ_VMCI_BUFFER_MAX_SIZE option shall set the max size of the underlying buffer for the socket\&. Used during negotiation before the connection is established\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +uint64_t +T} +T{ +.sp +Option value unit +T}:T{ +.sp +bytes +T} +T{ +.sp +Default value +T}:T{ +.sp +262144 +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, when using VMCI transport +T} +.TE +.sp 1 +.SS "ZMQ_VMCI_CONNECT_TIMEOUT: Set connection timeout of the VMCI socket" +.sp +The ZMQ_VMCI_CONNECT_TIMEOUT option shall set connection timeout for the socket\&. +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Option value type +T}:T{ +.sp +int +T} +T{ +.sp +Option value unit +T}:T{ +.sp +milliseconds +T} +T{ +.sp +Default value +T}:T{ +.sp +\-1 +T} +T{ +.sp +Applicable socket types +T}:T{ +.sp +all, when using VMCI transport +T} +.TE +.sp 1 +.SH "RETURN VALUE" +.sp +The \fIzmq_setsockopt()\fR function shall return zero if successful\&. Otherwise it shall return \-1 and set \fIerrno\fR to one of the values defined below\&. +.SH "ERRORS" +.PP +\fBEINVAL\fR +.RS 4 +The requested option +\fIoption_name\fR +is unknown, or the requested +\fIoption_len\fR +or +\fIoption_value\fR +is invalid\&. +.RE +.PP +\fBETERM\fR +.RS 4 +The 0MQ +\fIcontext\fR +associated with the specified +\fIsocket\fR +was terminated\&. +.RE +.PP +\fBENOTSOCK\fR +.RS 4 +The provided +\fIsocket\fR +was invalid\&. +.RE +.PP +\fBEINTR\fR +.RS 4 +The operation was interrupted by delivery of a signal\&. +.RE +.SH "EXAMPLE" +.PP +\fBSubscribing to messages on a ZMQ_SUB socket\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +/* Subscribe to all messages */ +rc = zmq_setsockopt (socket, ZMQ_SUBSCRIBE, "", 0); +assert (rc == 0); +/* Subscribe to messages prefixed with "ANIMALS\&.CATS" */ +rc = zmq_setsockopt (socket, ZMQ_SUBSCRIBE, "ANIMALS\&.CATS", 12); +.fi +.if n \{\ +.RE +.\} +.PP +\fBSetting I/O thread affinity\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +int64_t affinity; +/* Incoming connections on TCP port 5555 shall be handled by I/O thread 1 */ +affinity = 1; +rc = zmq_setsockopt (socket, ZMQ_AFFINITY, &affinity, sizeof (affinity)); +assert (rc); +rc = zmq_bind (socket, "tcp://lo:5555"); +assert (rc); +/* Incoming connections on TCP port 5556 shall be handled by I/O thread 2 */ +affinity = 2; +rc = zmq_setsockopt (socket, ZMQ_AFFINITY, &affinity, sizeof (affinity)); +assert (rc); +rc = zmq_bind (socket, "tcp://lo:5556"); +assert (rc); +.fi +.if n \{\ +.RE +.\} +.sp +.SH "SEE ALSO" +.sp +\fBzmq_getsockopt\fR(3) \fBzmq_socket\fR(3) \fBzmq_plain\fR(7) \fBzmq_curve\fR(7) \fBzmq\fR(7) +.SH "AUTHORS" +.sp +This page was written by the 0MQ community\&. To make a change please read the 0MQ Contribution Policy at \m[blue]\fBhttp://www\&.zeromq\&.org/docs:contributing\fR\m[]\&. diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_socket.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_socket.3 new file mode 100644 index 00000000000000..eaf039a03f9533 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_socket.3 @@ -0,0 +1,1403 @@ +'\" t +.\" Title: zmq_socket +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.78.1 +.\" Date: 02/18/2017 +.\" Manual: 0MQ Manual +.\" Source: 0MQ 4.2.2 +.\" Language: English +.\" +.TH "ZMQ_SOCKET" "3" "02/18/2017" "0MQ 4\&.2\&.2" "0MQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zmq_socket \- create 0MQ socket +.SH "SYNOPSIS" +.sp +\fBvoid *zmq_socket (void \fR\fB\fI*context\fR\fR\fB, int \fR\fB\fItype\fR\fR\fB);\fR +.SH "DESCRIPTION" +.sp +The \fIzmq_socket()\fR function shall create a 0MQ socket within the specified \fIcontext\fR and return an opaque handle to the newly created socket\&. The \fItype\fR argument specifies the socket type, which determines the semantics of communication over the socket\&. +.sp +The newly created socket is initially unbound, and not associated with any endpoints\&. In order to establish a message flow a socket must first be connected to at least one endpoint with \fBzmq_connect\fR(3), or at least one endpoint must be created for accepting incoming connections with \fBzmq_bind\fR(3)\&. +.PP +\fBKey differences to conventional sockets\fR. Generally speaking, conventional sockets present a +\fIsynchronous\fR +interface to either connection\-oriented reliable byte streams (SOCK_STREAM), or connection\-less unreliable datagrams (SOCK_DGRAM)\&. In comparison, 0MQ sockets present an abstraction of an asynchronous +\fImessage queue\fR, with the exact queueing semantics depending on the socket type in use\&. Where conventional sockets transfer streams of bytes or discrete datagrams, 0MQ sockets transfer discrete +\fImessages\fR\&. +.sp +0MQ sockets being \fIasynchronous\fR means that the timings of the physical connection setup and tear down, reconnect and effective delivery are transparent to the user and organized by 0MQ itself\&. Further, messages may be \fIqueued\fR in the event that a peer is unavailable to receive them\&. +.sp +Conventional sockets allow only strict one\-to\-one (two peers), many\-to\-one (many clients, one server), or in some cases one\-to\-many (multicast) relationships\&. With the exception of \fIZMQ_PAIR\fR, 0MQ sockets may be connected \fBto multiple endpoints\fR using \fIzmq_connect()\fR, while simultaneously accepting incoming connections \fBfrom multiple endpoints\fR bound to the socket using \fIzmq_bind()\fR, thus allowing many\-to\-many relationships\&. +.PP +\fBThread safety\fR. 0MQ has both thread safe socket type and +\fInot\fR +thread safe socket types\&. Applications MUST NOT use a +\fInot\fR +thread safe socket from multiple threads except after migrating a socket from one thread to another with a "full fence" memory barrier\&. +.sp +Following are the thread safe sockets: * ZMQ_CLIENT * ZMQ_SERVER * ZMQ_DISH * ZMQ_RADIO * ZMQ_SCATTER * ZMQ_GATHER +.PP +\fBSocket types\fR. The following sections present the socket types defined by 0MQ, grouped by the general +\fImessaging pattern\fR +which is built from related socket types\&. +.SS "Client\-server pattern" +.sp +The client\-server pattern is used to allow a single \fIZMQ_SERVER\fR \fIserver\fR talk to one or more \fIZMQ_CLIENT\fR \fIclients\fR\&. The client always starts the conversation, after which either peer can send messages asynchronously, to the other\&. +.sp +The client\-server pattern is formally defined by \m[blue]\fBhttp://rfc\&.zeromq\&.org/spec:41\fR\m[]\&. +.sp +Note: this pattern is meant to eventually deprecate the use of \fIZMQ_DEALER\fR and \fIZMQ_ROUTER\fR to build client\-server architectures, as well as \fIZMQ_REP\fR and \fIZMQ_REQ\fR for request\-reply\&. +.sp +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBZMQ_CLIENT\fR +.RS 4 +.sp +A \fIZMQ_CLIENT\fR socket talks to a \fIZMQ_SERVER\fR socket\&. Either peer can connect, though the usual and recommended model is to bind the \fIZMQ_SERVER\fR and connect the \fIZMQ_CLIENT\fR\&. +.sp +If the \fIZMQ_CLIENT\fR socket has established a connection, \fBzmq_send\fR(3) will accept messages, queue them, and send them as rapidly as the network allows\&. The outgoing buffer limit is defined by the high water mark for the socket\&. If the outgoing buffer is full, or if there is no connected peer, \fBzmq_send\fR(3) will block, by default\&. The \fIZMQ_CLIENT\fR socket will not drop messages\&. +.sp +When a \fIZMQ_CLIENT\fR socket is connected to multiple \fIZMQ_SERVER\fR sockets, outgoing messages are distributed between connected peers on a round\-robin basis\&. Likewise, the \fIZMQ_CLIENT\fR socket receives messages fairly from each connected peer\&. This usage is sensible only for stateless protocols\&. +.sp +\fIZMQ_CLIENT\fR sockets are threadsafe and can be used from multiple threads at the same time\&. Note that replies from a \fIZMQ_SERVER\fR socket will go to the first client thread that calls libzmq:zmq_msg_recv\&. If you need to get replies back to the originating thread, use one \fIZMQ_CLIENT\fR socket per thread\&. +.if n \{\ +.sp +.\} +.RS 4 +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBNote\fR +.ps -1 +.br +.sp +\fIZMQ_CLIENT\fR sockets are threadsafe\&. They do not accept the ZMQ_SNDMORE option on sends not ZMQ_RCVMORE on receives\&. This limits them to single part data\&. The intention is to extend the API to allow scatter/gather of multi\-part data\&. +.sp .5v +.RE +.sp +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.B Table\ \&1.\ \&Summary of ZMQ_CLIENT characteristics +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Compatible peer sockets +T}:T{ +.sp +\fIZMQ_SERVER\fR +T} +T{ +.sp +Direction +T}:T{ +.sp +Bidirectional +T} +T{ +.sp +Send/receive pattern +T}:T{ +.sp +Unrestricted +T} +T{ +.sp +Outgoing routing strategy +T}:T{ +.sp +Round\-robin +T} +T{ +.sp +Incoming routing strategy +T}:T{ +.sp +Fair\-queued +T} +T{ +.sp +Action in mute state +T}:T{ +.sp +Block +T} +.TE +.sp 1 +.RE +.sp +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBZMQ_SERVER\fR +.RS 4 +.sp +A \fIZMQ_SERVER\fR socket talks to a set of \fIZMQ_CLIENT\fR sockets\&. A \fIZMQ_SERVER\fR socket can only reply to an incoming message: the \fIZMQ_CLIENT\fR peer must always initiate a conversation\&. +.sp +Each received message has a \fIrouting_id\fR that is a 32\-bit unsigned integer\&. The application can fetch this with \fBzmq_msg_routing_id\fR(3)\&. To send a message to a given \fIZMQ_CLIENT\fR peer the application must set the peer\(cqs \fIrouting_id\fR on the message, using \fBzmq_msg_set_routing_id\fR(3)\&. +.sp +If the \fIrouting_id\fR is not specified, or does not refer to a connected client peer, the send call will fail with EHOSTUNREACH\&. If the outgoing buffer for the client peer is full, the send call shall block, unless ZMQ_DONT_WAIT is used in the send, in which case it shall fail with EAGAIN\&. The \fIZMQ_SERVER\fR socket shall not drop messages in any case\&. +.if n \{\ +.sp +.\} +.RS 4 +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBNote\fR +.ps -1 +.br +.sp +\fIZMQ_SERVER\fR sockets are threadsafe\&. They do not accept the ZMQ_SNDMORE option on sends not ZMQ_RCVMORE on receives\&. This limits them to single part data\&. The intention is to extend the API to allow scatter/gather of multi\-part data\&. +.sp .5v +.RE +.sp +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.B Table\ \&2.\ \&Summary of ZMQ_SERVER characteristics +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Compatible peer sockets +T}:T{ +.sp +\fIZMQ_CLIENT\fR +T} +T{ +.sp +Direction +T}:T{ +.sp +Bidirectional +T} +T{ +.sp +Send/receive pattern +T}:T{ +.sp +Unrestricted +T} +T{ +.sp +Outgoing routing strategy +T}:T{ +.sp +See text +T} +T{ +.sp +Incoming routing strategy +T}:T{ +.sp +Fair\-queued +T} +T{ +.sp +Action in mute state +T}:T{ +.sp +Return EAGAIN +T} +.TE +.sp 1 +.RE +.SS "Radio\-dish pattern" +.sp +The radio\-dish pattern is used for one\-to\-many distribution of data from a single \fIpublisher\fR to multiple \fIsubscribers\fR in a fan out fashion\&. +.sp +Radio\-dish is using groups (vs Pub\-sub topics), Dish sockets can join a group and each message sent by Radio sockets belong to a group\&. +.sp +Groups are null terminated strings limited to 16 chars length (including null)\&. The intention is to increase the length to 40 chars (including null)\&. +.sp +Groups are matched using exact matching (vs prefix matching of PubSub)\&. +.if n \{\ +.sp +.\} +.RS 4 +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBNote\fR +.ps -1 +.br +.sp +Radio\-dish is still in draft phase\&. +.sp .5v +.RE +.sp +Note: this pattern is meant to eventually deprecate the use of \fIZMQ_PUB\fR and \fIZMQ_SUB\fR to build pub\-sub architectures\&. +.sp +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBZMQ_RADIO\fR +.RS 4 +.sp +A socket of type \fIZMQ_RADIO\fR is used by a \fIpublisher\fR to distribute data\&. Each message belong to a group, a group is specified with linkzmq_zmq_msg_set_group[3]\&. Messages are distributed to all members of a group\&. The \fBzmq_recv\fR(3) function is not implemented for this socket type\&. +.sp +When a \fIZMQ_RADIO\fR socket enters the \fImute\fR state due to having reached the high water mark for a \fIsubscriber\fR, then any messages that would be sent to the \fIsubscriber\fR in question shall instead be dropped until the mute state ends\&. The \fIzmq_send()\fR function shall never block for this socket type\&. +.if n \{\ +.sp +.\} +.RS 4 +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBNote\fR +.ps -1 +.br +.sp +\fIZMQ_RADIO\fR sockets are threadsafe\&. They do not accept the ZMQ_SNDMORE option on sends\&. This limits them to single part data\&. +.sp .5v +.RE +.sp +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.B Table\ \&3.\ \&Summary of ZMQ_RADIO characteristics +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Compatible peer sockets +T}:T{ +.sp +\fIZMQ_DISH\fR +T} +T{ +.sp +Direction +T}:T{ +.sp +Unidirectional +T} +T{ +.sp +Send/receive pattern +T}:T{ +.sp +Send only +T} +T{ +.sp +Incoming routing strategy +T}:T{ +.sp +N/A +T} +T{ +.sp +Outgoing routing strategy +T}:T{ +.sp +Fan out +T} +T{ +.sp +Action in mute state +T}:T{ +.sp +Drop +T} +.TE +.sp 1 +.RE +.sp +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBZMQ_DISH\fR +.RS 4 +.sp +A socket of type \fIZMQ_DISH\fR is used by a \fIsubscriber\fR to subscribe to groups distributed by a \fIradio\fR\&. Initially a \fIZMQ_DISH\fR socket is not subscribed to any groups, use \fBzmq_join\fR(3) to join a group\&. To get the group the message belong to call \fBzmq_msg_group\fR(3)\&. The \fIzmq_send()\fR function is not implemented for this socket type\&. +.if n \{\ +.sp +.\} +.RS 4 +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBNote\fR +.ps -1 +.br +.sp +\fIZMQ_DISH\fR sockets are threadsafe\&. They do not accept ZMQ_RCVMORE on receives\&. This limits them to single part data\&. +.sp .5v +.RE +.sp +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.B Table\ \&4.\ \&Summary of ZMQ_DISH characteristics +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Compatible peer sockets +T}:T{ +.sp +\fIZMQ_RADIO\fR +T} +T{ +.sp +Direction +T}:T{ +.sp +Unidirectional +T} +T{ +.sp +Send/receive pattern +T}:T{ +.sp +Receive only +T} +T{ +.sp +Incoming routing strategy +T}:T{ +.sp +Fair\-queued +T} +T{ +.sp +Outgoing routing strategy +T}:T{ +.sp +N/A +T} +.TE +.sp 1 +.RE +.SS "Publish\-subscribe pattern" +.sp +The publish\-subscribe pattern is used for one\-to\-many distribution of data from a single \fIpublisher\fR to multiple \fIsubscribers\fR in a fan out fashion\&. +.sp +The publish\-subscribe pattern is formally defined by \m[blue]\fBhttp://rfc\&.zeromq\&.org/spec:29\fR\m[]\&. +.sp +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBZMQ_PUB\fR +.RS 4 +.sp +A socket of type \fIZMQ_PUB\fR is used by a \fIpublisher\fR to distribute data\&. Messages sent are distributed in a fan out fashion to all connected peers\&. The \fBzmq_recv\fR(3) function is not implemented for this socket type\&. +.sp +When a \fIZMQ_PUB\fR socket enters the \fImute\fR state due to having reached the high water mark for a \fIsubscriber\fR, then any messages that would be sent to the \fIsubscriber\fR in question shall instead be dropped until the mute state ends\&. The \fIzmq_send()\fR function shall never block for this socket type\&. +.sp +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.B Table\ \&5.\ \&Summary of ZMQ_PUB characteristics +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Compatible peer sockets +T}:T{ +.sp +\fIZMQ_SUB\fR, \fIZMQ_XSUB\fR +T} +T{ +.sp +Direction +T}:T{ +.sp +Unidirectional +T} +T{ +.sp +Send/receive pattern +T}:T{ +.sp +Send only +T} +T{ +.sp +Incoming routing strategy +T}:T{ +.sp +N/A +T} +T{ +.sp +Outgoing routing strategy +T}:T{ +.sp +Fan out +T} +T{ +.sp +Action in mute state +T}:T{ +.sp +Drop +T} +.TE +.sp 1 +.RE +.sp +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBZMQ_SUB\fR +.RS 4 +.sp +A socket of type \fIZMQ_SUB\fR is used by a \fIsubscriber\fR to subscribe to data distributed by a \fIpublisher\fR\&. Initially a \fIZMQ_SUB\fR socket is not subscribed to any messages, use the \fIZMQ_SUBSCRIBE\fR option of \fBzmq_setsockopt\fR(3) to specify which messages to subscribe to\&. The \fIzmq_send()\fR function is not implemented for this socket type\&. +.sp +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.B Table\ \&6.\ \&Summary of ZMQ_SUB characteristics +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Compatible peer sockets +T}:T{ +.sp +\fIZMQ_PUB\fR, \fIZMQ_XPUB\fR +T} +T{ +.sp +Direction +T}:T{ +.sp +Unidirectional +T} +T{ +.sp +Send/receive pattern +T}:T{ +.sp +Receive only +T} +T{ +.sp +Incoming routing strategy +T}:T{ +.sp +Fair\-queued +T} +T{ +.sp +Outgoing routing strategy +T}:T{ +.sp +N/A +T} +.TE +.sp 1 +.RE +.sp +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBZMQ_XPUB\fR +.RS 4 +.sp +Same as ZMQ_PUB except that you can receive subscriptions from the peers in form of incoming messages\&. Subscription message is a byte 1 (for subscriptions) or byte 0 (for unsubscriptions) followed by the subscription body\&. Messages without a sub/unsub prefix are also received, but have no effect on subscription status\&. +.sp +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.B Table\ \&7.\ \&Summary of ZMQ_XPUB characteristics +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Compatible peer sockets +T}:T{ +.sp +\fIZMQ_SUB\fR, \fIZMQ_XSUB\fR +T} +T{ +.sp +Direction +T}:T{ +.sp +Unidirectional +T} +T{ +.sp +Send/receive pattern +T}:T{ +.sp +Send messages, receive subscriptions +T} +T{ +.sp +Incoming routing strategy +T}:T{ +.sp +N/A +T} +T{ +.sp +Outgoing routing strategy +T}:T{ +.sp +Fan out +T} +T{ +.sp +Action in mute state +T}:T{ +.sp +Drop +T} +.TE +.sp 1 +.RE +.sp +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBZMQ_XSUB\fR +.RS 4 +.sp +Same as ZMQ_SUB except that you subscribe by sending subscription messages to the socket\&. Subscription message is a byte 1 (for subscriptions) or byte 0 (for unsubscriptions) followed by the subscription body\&. Messages without a sub/unsub prefix may also be sent, but have no effect on subscription status\&. +.sp +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.B Table\ \&8.\ \&Summary of ZMQ_XSUB characteristics +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Compatible peer sockets +T}:T{ +.sp +\fIZMQ_PUB\fR, \fIZMQ_XPUB\fR +T} +T{ +.sp +Direction +T}:T{ +.sp +Unidirectional +T} +T{ +.sp +Send/receive pattern +T}:T{ +.sp +Receive messages, send subscriptions +T} +T{ +.sp +Incoming routing strategy +T}:T{ +.sp +Fair\-queued +T} +T{ +.sp +Outgoing routing strategy +T}:T{ +.sp +N/A +T} +T{ +.sp +Action in mute state +T}:T{ +.sp +Drop +T} +.TE +.sp 1 +.RE +.SS "Pipeline pattern" +.sp +The pipeline pattern is used for distributing data to \fInodes\fR arranged in a pipeline\&. Data always flows down the pipeline, and each stage of the pipeline is connected to at least one \fInode\fR\&. When a pipeline stage is connected to multiple \fInodes\fR data is round\-robined among all connected \fInodes\fR\&. +.sp +The pipeline pattern is formally defined by \m[blue]\fBhttp://rfc\&.zeromq\&.org/spec:30\fR\m[]\&. +.sp +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBZMQ_PUSH\fR +.RS 4 +.sp +A socket of type \fIZMQ_PUSH\fR is used by a pipeline \fInode\fR to send messages to downstream pipeline \fInodes\fR\&. Messages are round\-robined to all connected downstream \fInodes\fR\&. The \fIzmq_recv()\fR function is not implemented for this socket type\&. +.sp +When a \fIZMQ_PUSH\fR socket enters the \fImute\fR state due to having reached the high water mark for all downstream \fInodes\fR, or if there are no downstream \fInodes\fR at all, then any \fBzmq_send\fR(3) operations on the socket shall block until the mute state ends or at least one downstream \fInode\fR becomes available for sending; messages are not discarded\&. +.sp +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.B Table\ \&9.\ \&Summary of ZMQ_PUSH characteristics +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Compatible peer sockets +T}:T{ +.sp +\fIZMQ_PULL\fR +T} +T{ +.sp +Direction +T}:T{ +.sp +Unidirectional +T} +T{ +.sp +Send/receive pattern +T}:T{ +.sp +Send only +T} +T{ +.sp +Incoming routing strategy +T}:T{ +.sp +N/A +T} +T{ +.sp +Outgoing routing strategy +T}:T{ +.sp +Round\-robin +T} +T{ +.sp +Action in mute state +T}:T{ +.sp +Block +T} +.TE +.sp 1 +.RE +.sp +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBZMQ_PULL\fR +.RS 4 +.sp +A socket of type \fIZMQ_PULL\fR is used by a pipeline \fInode\fR to receive messages from upstream pipeline \fInodes\fR\&. Messages are fair\-queued from among all connected upstream \fInodes\fR\&. The \fIzmq_send()\fR function is not implemented for this socket type\&. +.sp +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.B Table\ \&10.\ \&Summary of ZMQ_PULL characteristics +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Compatible peer sockets +T}:T{ +.sp +\fIZMQ_PUSH\fR +T} +T{ +.sp +Direction +T}:T{ +.sp +Unidirectional +T} +T{ +.sp +Send/receive pattern +T}:T{ +.sp +Receive only +T} +T{ +.sp +Incoming routing strategy +T}:T{ +.sp +Fair\-queued +T} +T{ +.sp +Outgoing routing strategy +T}:T{ +.sp +N/A +T} +T{ +.sp +Action in mute state +T}:T{ +.sp +Block +T} +.TE +.sp 1 +.RE +.SS "Exclusive pair pattern" +.sp +The exclusive pair pattern is used to connect a peer to precisely one other peer\&. This pattern is used for inter\-thread communication across the inproc transport\&. +.sp +The exclusive pair pattern is formally defined by \m[blue]\fBhttp://rfc\&.zeromq\&.org/spec:31\fR\m[]\&. +.sp +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBZMQ_PAIR\fR +.RS 4 +.sp +A socket of type \fIZMQ_PAIR\fR can only be connected to a single peer at any one time\&. No message routing or filtering is performed on messages sent over a \fIZMQ_PAIR\fR socket\&. +.sp +When a \fIZMQ_PAIR\fR socket enters the \fImute\fR state due to having reached the high water mark for the connected peer, or if no peer is connected, then any \fBzmq_send\fR(3) operations on the socket shall block until the peer becomes available for sending; messages are not discarded\&. +.if n \{\ +.sp +.\} +.RS 4 +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBNote\fR +.ps -1 +.br +.sp +\fIZMQ_PAIR\fR sockets are designed for inter\-thread communication across the \fBzmq_inproc\fR(7) transport and do not implement functionality such as auto\-reconnection\&. +.sp .5v +.RE +.sp +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.B Table\ \&11.\ \&Summary of ZMQ_PAIR characteristics +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Compatible peer sockets +T}:T{ +.sp +\fIZMQ_PAIR\fR +T} +T{ +.sp +Direction +T}:T{ +.sp +Bidirectional +T} +T{ +.sp +Send/receive pattern +T}:T{ +.sp +Unrestricted +T} +T{ +.sp +Incoming routing strategy +T}:T{ +.sp +N/A +T} +T{ +.sp +Outgoing routing strategy +T}:T{ +.sp +N/A +T} +T{ +.sp +Action in mute state +T}:T{ +.sp +Block +T} +.TE +.sp 1 +.RE +.SS "Native Pattern" +.sp +The native pattern is used for communicating with TCP peers and allows asynchronous requests and replies in either direction\&. +.sp +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBZMQ_STREAM\fR +.RS 4 +.sp +A socket of type \fIZMQ_STREAM\fR is used to send and receive TCP data from a non\-0MQ peer, when using the tcp:// transport\&. A \fIZMQ_STREAM\fR socket can act as client and/or server, sending and/or receiving TCP data asynchronously\&. +.sp +When receiving TCP data, a \fIZMQ_STREAM\fR socket shall prepend a message part containing the \fIidentity\fR of the originating peer to the message before passing it to the application\&. Messages received are fair\-queued from among all connected peers\&. +.sp +When sending TCP data, a \fIZMQ_STREAM\fR socket shall remove the first part of the message and use it to determine the \fIidentity\fR of the peer the message shall be routed to, and unroutable messages shall cause an EHOSTUNREACH or EAGAIN error\&. +.sp +To open a connection to a server, use the zmq_connect call, and then fetch the socket identity using the ZMQ_IDENTITY zmq_getsockopt call\&. +.sp +To close a specific connection, send the identity frame followed by a zero\-length message (see EXAMPLE section)\&. +.sp +When a connection is made, a zero\-length message will be received by the application\&. Similarly, when the peer disconnects (or the connection is lost), a zero\-length message will be received by the application\&. +.sp +You must send one identity frame followed by one data frame\&. The ZMQ_SNDMORE flag is required for identity frames but is ignored on data frames\&. +.sp +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.B Table\ \&12.\ \&Summary of ZMQ_STREAM characteristics +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Compatible peer sockets +T}:T{ +.sp +none\&. +T} +T{ +.sp +Direction +T}:T{ +.sp +Bidirectional +T} +T{ +.sp +Send/receive pattern +T}:T{ +.sp +Unrestricted +T} +T{ +.sp +Outgoing routing strategy +T}:T{ +.sp +See text +T} +T{ +.sp +Incoming routing strategy +T}:T{ +.sp +Fair\-queued +T} +T{ +.sp +Action in mute state +T}:T{ +.sp +EAGAIN +T} +.TE +.sp 1 +.RE +.SS "Request\-reply pattern" +.sp +The request\-reply pattern is used for sending requests from a ZMQ_REQ \fIclient\fR to one or more ZMQ_REP \fIservices\fR, and receiving subsequent replies to each request sent\&. +.sp +The request\-reply pattern is formally defined by \m[blue]\fBhttp://rfc\&.zeromq\&.org/spec:28\fR\m[]\&. +.sp +Note: this pattern will be deprecated in favor of the client\-server pattern\&. +.sp +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBZMQ_REQ\fR +.RS 4 +.sp +A socket of type \fIZMQ_REQ\fR is used by a \fIclient\fR to send requests to and receive replies from a \fIservice\fR\&. This socket type allows only an alternating sequence of \fIzmq_send(request)\fR and subsequent \fIzmq_recv(reply)\fR calls\&. Each request sent is round\-robined among all \fIservices\fR, and each reply received is matched with the last issued request\&. +.sp +If no services are available, then any send operation on the socket shall block until at least one \fIservice\fR becomes available\&. The REQ socket shall not discard messages\&. +.sp +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.B Table\ \&13.\ \&Summary of ZMQ_REQ characteristics +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Compatible peer sockets +T}:T{ +.sp +\fIZMQ_REP\fR, \fIZMQ_ROUTER\fR +T} +T{ +.sp +Direction +T}:T{ +.sp +Bidirectional +T} +T{ +.sp +Send/receive pattern +T}:T{ +.sp +Send, Receive, Send, Receive, \&... +T} +T{ +.sp +Outgoing routing strategy +T}:T{ +.sp +Round\-robin +T} +T{ +.sp +Incoming routing strategy +T}:T{ +.sp +Last peer +T} +T{ +.sp +Action in mute state +T}:T{ +.sp +Block +T} +.TE +.sp 1 +.RE +.sp +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBZMQ_REP\fR +.RS 4 +.sp +A socket of type \fIZMQ_REP\fR is used by a \fIservice\fR to receive requests from and send replies to a \fIclient\fR\&. This socket type allows only an alternating sequence of \fIzmq_recv(request)\fR and subsequent \fIzmq_send(reply)\fR calls\&. Each request received is fair\-queued from among all \fIclients\fR, and each reply sent is routed to the \fIclient\fR that issued the last request\&. If the original requester does not exist any more the reply is silently discarded\&. +.sp +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.B Table\ \&14.\ \&Summary of ZMQ_REP characteristics +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Compatible peer sockets +T}:T{ +.sp +\fIZMQ_REQ\fR, \fIZMQ_DEALER\fR +T} +T{ +.sp +Direction +T}:T{ +.sp +Bidirectional +T} +T{ +.sp +Send/receive pattern +T}:T{ +.sp +Receive, Send, Receive, Send, \&... +T} +T{ +.sp +Incoming routing strategy +T}:T{ +.sp +Fair\-queued +T} +T{ +.sp +Outgoing routing strategy +T}:T{ +.sp +Last peer +T} +.TE +.sp 1 +.RE +.sp +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBZMQ_DEALER\fR +.RS 4 +.sp +A socket of type \fIZMQ_DEALER\fR is an advanced pattern used for extending request/reply sockets\&. Each message sent is round\-robined among all connected peers, and each message received is fair\-queued from all connected peers\&. +.sp +When a \fIZMQ_DEALER\fR socket enters the \fImute\fR state due to having reached the high water mark for all peers, or if there are no peers at all, then any \fBzmq_send\fR(3) operations on the socket shall block until the mute state ends or at least one peer becomes available for sending; messages are not discarded\&. +.sp +When a \fIZMQ_DEALER\fR socket is connected to a \fIZMQ_REP\fR socket each message sent must consist of an empty message part, the \fIdelimiter\fR, followed by one or more \fIbody parts\fR\&. +.sp +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.B Table\ \&15.\ \&Summary of ZMQ_DEALER characteristics +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Compatible peer sockets +T}:T{ +.sp +\fIZMQ_ROUTER\fR, \fIZMQ_REP\fR, \fIZMQ_DEALER\fR +T} +T{ +.sp +Direction +T}:T{ +.sp +Bidirectional +T} +T{ +.sp +Send/receive pattern +T}:T{ +.sp +Unrestricted +T} +T{ +.sp +Outgoing routing strategy +T}:T{ +.sp +Round\-robin +T} +T{ +.sp +Incoming routing strategy +T}:T{ +.sp +Fair\-queued +T} +T{ +.sp +Action in mute state +T}:T{ +.sp +Block +T} +.TE +.sp 1 +.RE +.sp +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBZMQ_ROUTER\fR +.RS 4 +.sp +A socket of type \fIZMQ_ROUTER\fR is an advanced socket type used for extending request/reply sockets\&. When receiving messages a \fIZMQ_ROUTER\fR socket shall prepend a message part containing the \fIidentity\fR of the originating peer to the message before passing it to the application\&. Messages received are fair\-queued from among all connected peers\&. When sending messages a \fIZMQ_ROUTER\fR socket shall remove the first part of the message and use it to determine the \fIidentity\fR of the peer the message shall be routed to\&. If the peer does not exist anymore the message shall be silently discarded by default, unless \fIZMQ_ROUTER_MANDATORY\fR socket option is set to \fI1\fR\&. +.sp +When a \fIZMQ_ROUTER\fR socket enters the \fImute\fR state due to having reached the high water mark for all peers, then any messages sent to the socket shall be dropped until the mute state ends\&. Likewise, any messages routed to a peer for which the individual high water mark has been reached shall also be dropped, unless \fIZMQ_ROUTER_MANDATORY\fR socket option is set\&. +.sp +When a \fIZMQ_REQ\fR socket is connected to a \fIZMQ_ROUTER\fR socket, in addition to the \fIidentity\fR of the originating peer each message received shall contain an empty \fIdelimiter\fR message part\&. Hence, the entire structure of each received message as seen by the application becomes: one or more \fIidentity\fR parts, \fIdelimiter\fR part, one or more \fIbody parts\fR\&. When sending replies to a \fIZMQ_REQ\fR socket the application must include the \fIdelimiter\fR part\&. +.sp +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.B Table\ \&16.\ \&Summary of ZMQ_ROUTER characteristics +.TS +tab(:); +lt lt +lt lt +lt lt +lt lt +lt lt +lt lt. +T{ +.sp +Compatible peer sockets +T}:T{ +.sp +\fIZMQ_DEALER\fR, \fIZMQ_REQ\fR, \fIZMQ_ROUTER\fR +T} +T{ +.sp +Direction +T}:T{ +.sp +Bidirectional +T} +T{ +.sp +Send/receive pattern +T}:T{ +.sp +Unrestricted +T} +T{ +.sp +Outgoing routing strategy +T}:T{ +.sp +See text +T} +T{ +.sp +Incoming routing strategy +T}:T{ +.sp +Fair\-queued +T} +T{ +.sp +Action in mute state +T}:T{ +.sp +Drop (see text) +T} +.TE +.sp 1 +.RE +.SH "RETURN VALUE" +.sp +The \fIzmq_socket()\fR function shall return an opaque handle to the newly created socket if successful\&. Otherwise, it shall return NULL and set \fIerrno\fR to one of the values defined below\&. +.SH "ERRORS" +.PP +\fBEINVAL\fR +.RS 4 +The requested socket +\fItype\fR +is invalid\&. +.RE +.PP +\fBEFAULT\fR +.RS 4 +The provided +\fIcontext\fR +is invalid\&. +.RE +.PP +\fBEMFILE\fR +.RS 4 +The limit on the total number of open 0MQ sockets has been reached\&. +.RE +.PP +\fBETERM\fR +.RS 4 +The context specified was terminated\&. +.RE +.SH "EXAMPLE" +.PP +\fBCreating a simple HTTP server using ZMQ_STREAM\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +void *ctx = zmq_ctx_new (); +assert (ctx); +/* Create ZMQ_STREAM socket */ +void *socket = zmq_socket (ctx, ZMQ_STREAM); +assert (socket); +int rc = zmq_bind (socket, "tcp://*:8080"); +assert (rc == 0); +/* Data structure to hold the ZMQ_STREAM ID */ +uint8_t id [256]; +size_t id_size = 256; +/* Data structure to hold the ZMQ_STREAM received data */ +uint8_t raw [256]; +size_t raw_size = 256; +while (1) { + /* Get HTTP request; ID frame and then request */ + id_size = zmq_recv (socket, id, 256, 0); + assert (id_size > 0); + do { + raw_size = zmq_recv (socket, raw, 256, 0); + assert (raw_size >= 0); + } while (raw_size == 256); + /* Prepares the response */ + char http_response [] = + "HTTP/1\&.0 200 OK\er\en" + "Content\-Type: text/plain\er\en" + "\er\en" + "Hello, World!"; + /* Sends the ID frame followed by the response */ + zmq_send (socket, id, id_size, ZMQ_SNDMORE); + zmq_send (socket, http_response, strlen (http_response), 0); + /* Closes the connection by sending the ID frame followed by a zero response */ + zmq_send (socket, id, id_size, ZMQ_SNDMORE); + zmq_send (socket, 0, 0, 0); +} +zmq_close (socket); +zmq_ctx_destroy (ctx); +.fi +.if n \{\ +.RE +.\} +.sp +.SH "SEE ALSO" +.sp +\fBzmq_init\fR(3) \fBzmq_setsockopt\fR(3) \fBzmq_bind\fR(3) \fBzmq_connect\fR(3) \fBzmq_send\fR(3) \fBzmq_recv\fR(3) \fBzmq_inproc\fR(7) \fBzmq\fR(7) +.SH "AUTHORS" +.sp +This page was written by the 0MQ community\&. To make a change please read the 0MQ Contribution Policy at \m[blue]\fBhttp://www\&.zeromq\&.org/docs:contributing\fR\m[]\&. diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_socket_monitor.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_socket_monitor.3 new file mode 100644 index 00000000000000..26664be708ad3e --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_socket_monitor.3 @@ -0,0 +1,241 @@ +'\" t +.\" Title: zmq_socket_monitor +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.78.1 +.\" Date: 02/18/2017 +.\" Manual: 0MQ Manual +.\" Source: 0MQ 4.2.2 +.\" Language: English +.\" +.TH "ZMQ_SOCKET_MONITOR" "3" "02/18/2017" "0MQ 4\&.2\&.2" "0MQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zmq_socket_monitor \- monitor socket events +.SH "SYNOPSIS" +.sp +\fBint zmq_socket_monitor (void \fR\fB\fI*socket\fR\fR\fB, char \fR\fB\fI*endpoint\fR\fR\fB, int \fR\fB\fIevents\fR\fR\fB);\fR +.SH "DESCRIPTION" +.sp +The \fIzmq_socket_monitor()\fR method lets an application thread track socket events (like connects) on a ZeroMQ socket\&. Each call to this method creates a \fIZMQ_PAIR\fR socket and binds that to the specified inproc:// \fIendpoint\fR\&. To collect the socket events, you must create your own \fIZMQ_PAIR\fR socket, and connect that to the endpoint\&. +.sp +The \fIevents\fR argument is a bitmask of the socket events you wish to monitor, see \fISupported events\fR below\&. To monitor all events, use the event value ZMQ_EVENT_ALL\&. NOTE: as new events are added, the catch\-all value will start returning them\&. An application that relies on a strict and fixed sequence of events must not use ZMQ_EVENT_ALL in order to guarantee compatibility with future versions\&. +.sp +Each event is sent as two frames\&. The first frame contains an event number (16 bits), and an event value (32 bits) that provides additional data according to the event number\&. The second frame contains a string that specifies the affected TCP or IPC endpoint\&. +.sp +.if n \{\ +.RS 4 +.\} +.nf +The _zmq_socket_monitor()_ method supports only connection\-oriented +transports, that is, TCP, IPC, and TIPC\&. +.fi +.if n \{\ +.RE +.\} +.SH "SUPPORTED EVENTS" +.SS "ZMQ_EVENT_CONNECTED" +.sp +The socket has successfully connected to a remote peer\&. The event value is the file descriptor (FD) of the underlying network socket\&. Warning: there is no guarantee that the FD is still valid by the time your code receives this event\&. +.SS "ZMQ_EVENT_CONNECT_DELAYED" +.sp +A connect request on the socket is pending\&. The event value is unspecified\&. +.SS "ZMQ_EVENT_CONNECT_RETRIED" +.sp +A connect request failed, and is now being retried\&. The event value is the reconnect interval in milliseconds\&. Note that the reconnect interval is recalculated at each retry\&. +.SS "ZMQ_EVENT_LISTENING" +.sp +The socket was successfully bound to a network interface\&. The event value is the FD of the underlying network socket\&. Warning: there is no guarantee that the FD is still valid by the time your code receives this event\&. +.SS "ZMQ_EVENT_BIND_FAILED" +.sp +The socket could not bind to a given interface\&. The event value is the errno generated by the system bind call\&. +.SS "ZMQ_EVENT_ACCEPTED" +.sp +The socket has accepted a connection from a remote peer\&. The event value is the FD of the underlying network socket\&. Warning: there is no guarantee that the FD is still valid by the time your code receives this event\&. +.SS "ZMQ_EVENT_ACCEPT_FAILED" +.sp +The socket has rejected a connection from a remote peer\&. The event value is the errno generated by the accept call\&. +.SS "ZMQ_EVENT_CLOSED" +.sp +The socket was closed\&. The event value is the FD of the (now closed) network socket\&. +.SS "ZMQ_EVENT_CLOSE_FAILED" +.sp +The socket close failed\&. The event value is the errno returned by the system call\&. Note that this event occurs only on IPC transports\&. +.SS "ZMQ_EVENT_DISCONNECTED" +.sp +The socket was disconnected unexpectedly\&. The event value is the FD of the underlying network socket\&. Warning: this socket will be closed\&. +.SS "ZMQ_EVENT_MONITOR_STOPPED" +.sp +Monitoring on this socket ended\&. +.SS "ZMQ_EVENT_HANDSHAKE_FAILED" +.sp +The ZMTP security mechanism handshake failed\&. The event value is unspecified\&. NOTE: in DRAFT state, not yet available in stable releases\&. +.SS "ZMQ_EVENT_HANDSHAKE_SUCCEED" +.sp +The ZMTP security mechanism handshake succeeded\&. The event value is unspecified\&. NOTE: in DRAFT state, not yet available in stable releases\&. +.SH "RETURN VALUE" +.sp +The \fIzmq_socket_monitor()\fR function returns a value of 0 or greater if successful\&. Otherwise it returns \-1 and sets \fIerrno\fR to one of the values defined below\&. +.SH "ERRORS" +.PP +\fBETERM\fR +.RS 4 +The 0MQ +\fIcontext\fR +associated with the specified +\fIsocket\fR +was terminated\&. +.RE +.PP +\fBEPROTONOSUPPORT\fR +.RS 4 +The requested +\fItransport\fR +protocol is not supported\&. Monitor sockets are required to use the inproc:// transport\&. +.RE +.PP +\fBEINVAL\fR +.RS 4 +The endpoint supplied is invalid\&. +.RE +.SH "EXAMPLE" +.PP +\fBMonitoring client and server sockets\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +// Read one event off the monitor socket; return value and address +// by reference, if not null, and event number by value\&. Returns \-1 +// in case of error\&. + +static int +get_monitor_event (void *monitor, int *value, char **address) +{ + // First frame in message contains event number and value + zmq_msg_t msg; + zmq_msg_init (&msg); + if (zmq_msg_recv (&msg, monitor, 0) == \-1) + return \-1; // Interrupted, presumably + assert (zmq_msg_more (&msg)); + + uint8_t *data = (uint8_t *) zmq_msg_data (&msg); + uint16_t event = *(uint16_t *) (data); + if (value) + *value = *(uint32_t *) (data + 2); + + // Second frame in message contains event address + zmq_msg_init (&msg); + if (zmq_msg_recv (&msg, monitor, 0) == \-1) + return \-1; // Interrupted, presumably + assert (!zmq_msg_more (&msg)); + + if (address) { + uint8_t *data = (uint8_t *) zmq_msg_data (&msg); + size_t size = zmq_msg_size (&msg); + *address = (char *) malloc (size + 1); + memcpy (*address, data, size); + (*address)[size] = 0; + } + return event; +} + +int main (void) +{ + void *ctx = zmq_ctx_new (); + assert (ctx); + + // We\*(Aqll monitor these two sockets + void *client = zmq_socket (ctx, ZMQ_DEALER); + assert (client); + void *server = zmq_socket (ctx, ZMQ_DEALER); + assert (server); + + // Socket monitoring only works over inproc:// + int rc = zmq_socket_monitor (client, "tcp://127\&.0\&.0\&.1:9999", 0); + assert (rc == \-1); + assert (zmq_errno () == EPROTONOSUPPORT); + + // Monitor all events on client and server sockets + rc = zmq_socket_monitor (client, "inproc://monitor\-client", ZMQ_EVENT_ALL); + assert (rc == 0); + rc = zmq_socket_monitor (server, "inproc://monitor\-server", ZMQ_EVENT_ALL); + assert (rc == 0); + + // Create two sockets for collecting monitor events + void *client_mon = zmq_socket (ctx, ZMQ_PAIR); + assert (client_mon); + void *server_mon = zmq_socket (ctx, ZMQ_PAIR); + assert (server_mon); + + // Connect these to the inproc endpoints so they\*(Aqll get events + rc = zmq_connect (client_mon, "inproc://monitor\-client"); + assert (rc == 0); + rc = zmq_connect (server_mon, "inproc://monitor\-server"); + assert (rc == 0); + + // Now do a basic ping test + rc = zmq_bind (server, "tcp://127\&.0\&.0\&.1:9998"); + assert (rc == 0); + rc = zmq_connect (client, "tcp://127\&.0\&.0\&.1:9998"); + assert (rc == 0); + bounce (client, server); + + // Close client and server + close_zero_linger (client); + close_zero_linger (server); + + // Now collect and check events from both sockets + int event = get_monitor_event (client_mon, NULL, NULL); + if (event == ZMQ_EVENT_CONNECT_DELAYED) + event = get_monitor_event (client_mon, NULL, NULL); + assert (event == ZMQ_EVENT_CONNECTED); + event = get_monitor_event (client_mon, NULL, NULL); + assert (event == ZMQ_EVENT_MONITOR_STOPPED); + + // This is the flow of server events + event = get_monitor_event (server_mon, NULL, NULL); + assert (event == ZMQ_EVENT_LISTENING); + event = get_monitor_event (server_mon, NULL, NULL); + assert (event == ZMQ_EVENT_ACCEPTED); + event = get_monitor_event (server_mon, NULL, NULL); + assert (event == ZMQ_EVENT_CLOSED); + event = get_monitor_event (server_mon, NULL, NULL); + assert (event == ZMQ_EVENT_MONITOR_STOPPED); + + // Close down the sockets + close_zero_linger (client_mon); + close_zero_linger (server_mon); + zmq_ctx_term (ctx); + + return 0 ; +} +.fi +.if n \{\ +.RE +.\} +.sp +.SH "SEE ALSO" +.sp +\fBzmq\fR(7) +.SH "AUTHORS" +.sp +This page was written by the 0MQ community\&. To make a change please read the 0MQ Contribution Policy at \m[blue]\fBhttp://www\&.zeromq\&.org/docs:contributing\fR\m[]\&. diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_strerror.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_strerror.3 new file mode 100644 index 00000000000000..f77803861e7def --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_strerror.3 @@ -0,0 +1,67 @@ +'\" t +.\" Title: zmq_strerror +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.78.1 +.\" Date: 02/18/2017 +.\" Manual: 0MQ Manual +.\" Source: 0MQ 4.2.2 +.\" Language: English +.\" +.TH "ZMQ_STRERROR" "3" "02/18/2017" "0MQ 4\&.2\&.2" "0MQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zmq_strerror \- get 0MQ error message string +.SH "SYNOPSIS" +.sp +\fBconst char *zmq_strerror (int \fR\fB\fIerrnum\fR\fR\fB);\fR +.SH "DESCRIPTION" +.sp +The \fIzmq_strerror()\fR function shall return a pointer to an error message string corresponding to the error number specified by the \fIerrnum\fR argument\&. As 0MQ defines additional error numbers over and above those defined by the operating system, applications should use \fIzmq_strerror()\fR in preference to the standard \fIstrerror()\fR function\&. +.SH "RETURN VALUE" +.sp +The \fIzmq_strerror()\fR function shall return a pointer to an error message string\&. +.SH "ERRORS" +.sp +No errors are defined\&. +.SH "EXAMPLE" +.PP +\fBDisplaying an error message when a 0MQ context cannot be initialised\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +void *ctx = zmq_init (1, 1, 0); +if (!ctx) { + printf ("Error occurred during zmq_init(): %s\en", zmq_strerror (errno)); + abort (); +} +.fi +.if n \{\ +.RE +.\} +.sp +.SH "SEE ALSO" +.sp +\fBzmq\fR(7) +.SH "AUTHORS" +.sp +This page was written by the 0MQ community\&. To make a change please read the 0MQ Contribution Policy at \m[blue]\fBhttp://www\&.zeromq\&.org/docs:contributing\fR\m[]\&. diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_unbind.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_unbind.3 new file mode 100644 index 00000000000000..bef9c5002bb461 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_unbind.3 @@ -0,0 +1,125 @@ +'\" t +.\" Title: zmq_unbind +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.78.1 +.\" Date: 02/18/2017 +.\" Manual: 0MQ Manual +.\" Source: 0MQ 4.2.2 +.\" Language: English +.\" +.TH "ZMQ_UNBIND" "3" "02/18/2017" "0MQ 4\&.2\&.2" "0MQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zmq_unbind \- Stop accepting connections on a socket +.SH "SYNOPSIS" +.sp +int zmq_unbind (void \fI*socket\fR, const char \fI*endpoint\fR); +.SH "DESCRIPTION" +.sp +The \fIzmq_unbind()\fR function shall unbind a socket specified by the \fIsocket\fR argument from the endpoint specified by the \fIendpoint\fR argument\&. +.sp +The \fIendpoint\fR argument is as described in \fBzmq_bind\fR(3) +.SS "Unbinding wild\-card address from a socket" +.sp +When wild\-card * \fIendpoint\fR (described in \fBzmq_tcp\fR(7), \fBzmq_ipc\fR(7) and \fBzmq_vmci\fR(7)) was used in \fIzmq_bind()\fR, the caller should use real \fIendpoint\fR obtained from the ZMQ_LAST_ENDPOINT socket option to unbind this \fIendpoint\fR from a socket\&. +.SH "RETURN VALUE" +.sp +The \fIzmq_unbind()\fR function shall return zero if successful\&. Otherwise it shall return \-1 and set \fIerrno\fR to one of the values defined below\&. +.SH "ERRORS" +.PP +\fBEINVAL\fR +.RS 4 +The endpoint supplied is invalid\&. +.RE +.PP +\fBETERM\fR +.RS 4 +The 0MQ +\fIcontext\fR +associated with the specified +\fIsocket\fR +was terminated\&. +.RE +.PP +\fBENOTSOCK\fR +.RS 4 +The provided +\fIsocket\fR +was invalid\&. +.RE +.PP +\fBENOENT\fR +.RS 4 +The endpoint supplied was not previously bound\&. +.RE +.SH "EXAMPLES" +.PP +\fBUnbind a subscriber socket from a TCP transport\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +/* Create a ZMQ_SUB socket */ +void *socket = zmq_socket (context, ZMQ_SUB); +assert (socket); +/* Connect it to the host server001, port 5555 using a TCP transport */ +rc = zmq_bind (socket, "tcp://127\&.0\&.0\&.1:5555"); +assert (rc == 0); +/* Disconnect from the previously connected endpoint */ +rc = zmq_unbind (socket, "tcp://127\&.0\&.0\&.1:5555"); +assert (rc == 0); +.fi +.if n \{\ +.RE +.\} +.PP +\fBUnbind wild-card * binded socket\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +/* Create a ZMQ_SUB socket */ +void *socket = zmq_socket (context, ZMQ_SUB); +assert (socket); +/* Bind it to the system\-assigned ephemeral port using a TCP transport */ +rc = zmq_bind (socket, "tcp://127\&.0\&.0\&.1:*"); +assert (rc == 0); +/* Obtain real endpoint */ +const size_t buf_size = 32; +char buf[buf_size]; +rc = zmq_getsockopt (socket, ZMQ_LAST_ENDPOINT, buf, (size_t *)&buf_size); +assert (rc == 0); +/* Unbind socket by real endpoint */ +rc = zmq_unbind (socket, buf); +assert (rc == 0); +.fi +.if n \{\ +.RE +.\} +.sp +.SH "SEE ALSO" +.sp +\fBzmq_bind\fR(3) \fBzmq_socket\fR(3) \fBzmq\fR(7) +.SH "AUTHORS" +.sp +This page was written by the 0MQ community\&. To make a change please read the 0MQ Contribution Policy at \m[blue]\fBhttp://www\&.zeromq\&.org/docs:contributing\fR\m[]\&. diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_version.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_version.3 new file mode 100644 index 00000000000000..2b0316947e6d20 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_version.3 @@ -0,0 +1,67 @@ +'\" t +.\" Title: zmq_version +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.78.1 +.\" Date: 02/18/2017 +.\" Manual: 0MQ Manual +.\" Source: 0MQ 4.2.2 +.\" Language: English +.\" +.TH "ZMQ_VERSION" "3" "02/18/2017" "0MQ 4\&.2\&.2" "0MQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zmq_version \- report 0MQ library version +.SH "SYNOPSIS" +.sp +\fBvoid zmq_version (int \fR\fB\fI*major\fR\fR\fB, int \fR\fB\fI*minor\fR\fR\fB, int \fR\fB\fI*patch\fR\fR\fB);\fR +.SH "DESCRIPTION" +.sp +The \fIzmq_version()\fR function shall fill in the integer variables pointed to by the \fImajor\fR, \fIminor\fR and \fIpatch\fR arguments with the major, minor and patch level components of the 0MQ library version\&. +.sp +This functionality is intended for applications or language bindings dynamically linking to the 0MQ library that wish to determine the actual version of the 0MQ library they are using\&. +.SH "RETURN VALUE" +.sp +There is no return value\&. +.SH "ERRORS" +.sp +No errors are defined\&. +.SH "EXAMPLE" +.PP +\fBPrinting out the version of the 0MQ library\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +int major, minor, patch; +zmq_version (&major, &minor, &patch); +printf ("Current 0MQ version is %d\&.%d\&.%d\en", major, minor, patch); +.fi +.if n \{\ +.RE +.\} +.sp +.SH "SEE ALSO" +.sp +\fBzmq\fR(7) +.SH "AUTHORS" +.sp +This page was written by the 0MQ community\&. To make a change please read the 0MQ Contribution Policy at \m[blue]\fBhttp://www\&.zeromq\&.org/docs:contributing\fR\m[]\&. diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_z85_decode.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_z85_decode.3 new file mode 100644 index 00000000000000..a8c054b8f3e228 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_z85_decode.3 @@ -0,0 +1,64 @@ +'\" t +.\" Title: zmq_z85_decode +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.78.1 +.\" Date: 02/18/2017 +.\" Manual: 0MQ Manual +.\" Source: 0MQ 4.2.2 +.\" Language: English +.\" +.TH "ZMQ_Z85_DECODE" "3" "02/18/2017" "0MQ 4\&.2\&.2" "0MQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zmq_z85_decode \- decode a binary key from Z85 printable text +.SH "SYNOPSIS" +.sp +\fBuint8_t *zmq_z85_decode (uint8_t *dest, const char *string);\fR +.SH "DESCRIPTION" +.sp +The \fIzmq_z85_decode()\fR function shall decode \fIstring\fR into \fIdest\fR\&. The length of \fIstring\fR shall be divisible by 5\&. \fIdest\fR must be large enough for the decoded value (0\&.8 x strlen (string))\&. +.sp +The encoding shall follow the ZMQ RFC 32 specification\&. +.SH "RETURN VALUE" +.sp +The \fIzmq_z85_decode()\fR function shall return \fIdest\fR if successful, else it shall return NULL\&. +.SH "EXAMPLE" +.PP +\fBDecoding a CURVE key\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +const char decoded [] = "rq:rM>}U?@Lns47E1%kR\&.o@n%FcmmsL/@{H8]yf7"; +uint8_t public_key [32]; +zmq_z85_decode (public_key, decoded); +.fi +.if n \{\ +.RE +.\} +.sp +.SH "SEE ALSO" +.sp +\fBzmq_z85_decode\fR(3) \fBzmq_curve_keypair\fR(3) \fBzmq_curve_public\fR(3) \fBzmq_curve\fR(7) +.SH "AUTHORS" +.sp +This page was written by the 0MQ community\&. To make a change please read the 0MQ Contribution Policy at \m[blue]\fBhttp://www\&.zeromq\&.org/docs:contributing\fR\m[]\&. diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_z85_encode.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_z85_encode.3 new file mode 100644 index 00000000000000..442f6bb827833a --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zmq_z85_encode.3 @@ -0,0 +1,69 @@ +'\" t +.\" Title: zmq_z85_encode +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.78.1 +.\" Date: 02/18/2017 +.\" Manual: 0MQ Manual +.\" Source: 0MQ 4.2.2 +.\" Language: English +.\" +.TH "ZMQ_Z85_ENCODE" "3" "02/18/2017" "0MQ 4\&.2\&.2" "0MQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zmq_z85_encode \- encode a binary key as Z85 printable text +.SH "SYNOPSIS" +.sp +\fBchar *zmq_z85_encode (char *dest, const uint8_t *data, size_t size);\fR +.SH "DESCRIPTION" +.sp +The \fIzmq_z85_encode()\fR function shall encode the binary block specified by \fIdata\fR and \fIsize\fR into a string in \fIdest\fR\&. The size of the binary block must be divisible by 4\&. The \fIdest\fR must have sufficient space for size * 1\&.25 plus 1 for a null terminator\&. A 32\-byte CURVE key is encoded as 40 ASCII characters plus a null terminator\&. +.sp +The encoding shall follow the ZMQ RFC 32 specification\&. +.SH "RETURN VALUE" +.sp +The \fIzmq_z85_encode()\fR function shall return \fIdest\fR if successful, else it shall return NULL\&. +.SH "EXAMPLE" +.PP +\fBEncoding a CURVE key\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +#include +uint8_t public_key [32]; +uint8_t secret_key [32]; +int rc = crypto_box_keypair (public_key, secret_key); +assert (rc == 0); +char encoded [41]; +zmq_z85_encode (encoded, public_key, 32); +puts (encoded); +.fi +.if n \{\ +.RE +.\} +.sp +.SH "SEE ALSO" +.sp +\fBzmq_z85_decode\fR(3) \fBzmq_curve_keypair\fR(3) \fBzmq_curve_public\fR(3) \fBzmq_curve\fR(7) +.SH "AUTHORS" +.sp +This page was written by the 0MQ community\&. To make a change please read the 0MQ Contribution Policy at \m[blue]\fBhttp://www\&.zeromq\&.org/docs:contributing\fR\m[]\&. diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zmsg.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zmsg.3 new file mode 100644 index 00000000000000..0be48b58cf5ac0 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zmsg.3 @@ -0,0 +1,545 @@ +'\" t +.\" Title: zmsg +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.76.1 +.\" Date: 12/31/2016 +.\" Manual: CZMQ Manual +.\" Source: CZMQ 4.0.2 +.\" Language: English +.\" +.TH "ZMSG" "3" "12/31/2016" "CZMQ 4\&.0\&.2" "CZMQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zmsg \- working with multipart messages +.SH "SYNOPSIS" +.sp +.nf +// This is a stable class, and may not change except for emergencies\&. It +// is provided in stable builds\&. +// This class has draft methods, which may change over time\&. They are not +// in stable releases, by default\&. Use \-\-enable\-drafts to enable\&. +// Create a new empty message object +CZMQ_EXPORT zmsg_t * + zmsg_new (void); + +// Receive message from socket, returns zmsg_t object or NULL if the recv +// was interrupted\&. Does a blocking recv\&. If you want to not block then use +// the zloop class or zmsg_recv_nowait or zmq_poll to check for socket input +// before receiving\&. +CZMQ_EXPORT zmsg_t * + zmsg_recv (void *source); + +// Load/append an open file into new message, return the message\&. +// Returns NULL if the message could not be loaded\&. +CZMQ_EXPORT zmsg_t * + zmsg_load (FILE *file); + +// Decodes a serialized message frame created by zmsg_encode () and returns +// a new zmsg_t object\&. Returns NULL if the frame was badly formatted or +// there was insufficient memory to work\&. +CZMQ_EXPORT zmsg_t * + zmsg_decode (zframe_t *frame); + +// Generate a signal message encoding the given status\&. A signal is a short +// message carrying a 1\-byte success/failure code (by convention, 0 means +// OK)\&. Signals are encoded to be distinguishable from "normal" messages\&. +CZMQ_EXPORT zmsg_t * + zmsg_new_signal (byte status); + +// Destroy a message object and all frames it contains +CZMQ_EXPORT void + zmsg_destroy (zmsg_t **self_p); + +// Send message to destination socket, and destroy the message after sending +// it successfully\&. If the message has no frames, sends nothing but destroys +// the message anyhow\&. Nullifies the caller\*(Aqs reference to the message (as +// it is a destructor)\&. +CZMQ_EXPORT int + zmsg_send (zmsg_t **self_p, void *dest); + +// Send message to destination socket as part of a multipart sequence, and +// destroy the message after sending it successfully\&. Note that after a +// zmsg_sendm, you must call zmsg_send or another method that sends a final +// message part\&. If the message has no frames, sends nothing but destroys +// the message anyhow\&. Nullifies the caller\*(Aqs reference to the message (as +// it is a destructor)\&. +CZMQ_EXPORT int + zmsg_sendm (zmsg_t **self_p, void *dest); + +// Return size of message, i\&.e\&. number of frames (0 or more)\&. +CZMQ_EXPORT size_t + zmsg_size (zmsg_t *self); + +// Return total size of all frames in message\&. +CZMQ_EXPORT size_t + zmsg_content_size (zmsg_t *self); + +// Push frame to the front of the message, i\&.e\&. before all other frames\&. +// Message takes ownership of frame, will destroy it when message is sent\&. +// Returns 0 on success, \-1 on error\&. Deprecates zmsg_push, which did not +// nullify the caller\*(Aqs frame reference\&. +CZMQ_EXPORT int + zmsg_prepend (zmsg_t *self, zframe_t **frame_p); + +// Add frame to the end of the message, i\&.e\&. after all other frames\&. +// Message takes ownership of frame, will destroy it when message is sent\&. +// Returns 0 on success\&. Deprecates zmsg_add, which did not nullify the +// caller\*(Aqs frame reference\&. +CZMQ_EXPORT int + zmsg_append (zmsg_t *self, zframe_t **frame_p); + +// Remove first frame from message, if any\&. Returns frame, or NULL\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT zframe_t * + zmsg_pop (zmsg_t *self); + +// Push block of memory to front of message, as a new frame\&. +// Returns 0 on success, \-1 on error\&. +CZMQ_EXPORT int + zmsg_pushmem (zmsg_t *self, const void *data, size_t size); + +// Add block of memory to the end of the message, as a new frame\&. +// Returns 0 on success, \-1 on error\&. +CZMQ_EXPORT int + zmsg_addmem (zmsg_t *self, const void *data, size_t size); + +// Push string as new frame to front of message\&. +// Returns 0 on success, \-1 on error\&. +CZMQ_EXPORT int + zmsg_pushstr (zmsg_t *self, const char *string); + +// Push string as new frame to end of message\&. +// Returns 0 on success, \-1 on error\&. +CZMQ_EXPORT int + zmsg_addstr (zmsg_t *self, const char *string); + +// Push formatted string as new frame to front of message\&. +// Returns 0 on success, \-1 on error\&. +CZMQ_EXPORT int + zmsg_pushstrf (zmsg_t *self, const char *format, \&.\&.\&.) CHECK_PRINTF (2); + +// Push formatted string as new frame to end of message\&. +// Returns 0 on success, \-1 on error\&. +CZMQ_EXPORT int + zmsg_addstrf (zmsg_t *self, const char *format, \&.\&.\&.) CHECK_PRINTF (2); + +// Pop frame off front of message, return as fresh string\&. If there were +// no more frames in the message, returns NULL\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT char * + zmsg_popstr (zmsg_t *self); + +// Push encoded message as a new frame\&. Message takes ownership of +// submessage, so the original is destroyed in this call\&. Returns 0 on +// success, \-1 on error\&. +CZMQ_EXPORT int + zmsg_addmsg (zmsg_t *self, zmsg_t **msg_p); + +// Remove first submessage from message, if any\&. Returns zmsg_t, or NULL if +// decoding was not successful\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT zmsg_t * + zmsg_popmsg (zmsg_t *self); + +// Remove specified frame from list, if present\&. Does not destroy frame\&. +CZMQ_EXPORT void + zmsg_remove (zmsg_t *self, zframe_t *frame); + +// Set cursor to first frame in message\&. Returns frame, or NULL, if the +// message is empty\&. Use this to navigate the frames as a list\&. +CZMQ_EXPORT zframe_t * + zmsg_first (zmsg_t *self); + +// Return the next frame\&. If there are no more frames, returns NULL\&. To move +// to the first frame call zmsg_first()\&. Advances the cursor\&. +CZMQ_EXPORT zframe_t * + zmsg_next (zmsg_t *self); + +// Return the last frame\&. If there are no frames, returns NULL\&. +CZMQ_EXPORT zframe_t * + zmsg_last (zmsg_t *self); + +// Save message to an open file, return 0 if OK, else \-1\&. The message is +// saved as a series of frames, each with length and data\&. Note that the +// file is NOT guaranteed to be portable between operating systems, not +// versions of CZMQ\&. The file format is at present undocumented and liable +// to arbitrary change\&. +CZMQ_EXPORT int + zmsg_save (zmsg_t *self, FILE *file); + +// Serialize multipart message to a single message frame\&. Use this method +// to send structured messages across transports that do not support +// multipart data\&. Allocates and returns a new frame containing the +// serialized message\&. To decode a serialized message frame, use +// zmsg_decode ()\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT zframe_t * + zmsg_encode (zmsg_t *self); + +// Create copy of message, as new message object\&. Returns a fresh zmsg_t +// object\&. If message is null, or memory was exhausted, returns null\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT zmsg_t * + zmsg_dup (zmsg_t *self); + +// Send message to zsys log sink (may be stdout, or system facility as +// configured by zsys_set_logstream)\&. +CZMQ_EXPORT void + zmsg_print (zmsg_t *self); + +// Return true if the two messages have the same number of frames and each +// frame in the first message is identical to the corresponding frame in the +// other message\&. As with zframe_eq, return false if either message is NULL\&. +CZMQ_EXPORT bool + zmsg_eq (zmsg_t *self, zmsg_t *other); + +// Return signal value, 0 or greater, if message is a signal, \-1 if not\&. +CZMQ_EXPORT int + zmsg_signal (zmsg_t *self); + +// Probe the supplied object, and report if it looks like a zmsg_t\&. +CZMQ_EXPORT bool + zmsg_is (void *self); + +// Self test of this class\&. +CZMQ_EXPORT void + zmsg_test (bool verbose); + +#ifdef CZMQ_BUILD_DRAFT_API +// *** Draft method, for development use, may change without warning *** +// Return message routing ID, if the message came from a ZMQ_SERVER socket\&. +// Else returns zero\&. +CZMQ_EXPORT uint32_t + zmsg_routing_id (zmsg_t *self); + +// *** Draft method, for development use, may change without warning *** +// Set routing ID on message\&. This is used if/when the message is sent to a +// ZMQ_SERVER socket\&. +CZMQ_EXPORT void + zmsg_set_routing_id (zmsg_t *self, uint32_t routing_id); + +#endif // CZMQ_BUILD_DRAFT_API +Please add \*(Aq@interface\*(Aq section in \*(Aq\&./\&.\&./src/zmsg\&.c\*(Aq\&. +.fi +.SH "DESCRIPTION" +.sp +The zmsg class provides methods to send and receive multipart messages across 0MQ sockets\&. This class provides a list\-like container interface, with methods to work with the overall container\&. zmsg_t messages are composed of zero or more zframe_t frames\&. +.sp +Please add \fI@discuss\fR section in \fI\&./\&.\&./src/zmsg\&.c\fR\&. +.SH "EXAMPLE" +.PP +\fBFrom zmsg_test method\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +// Create two PAIR sockets and connect over inproc +zsock_t *output = zsock_new_pair ("@inproc://zmsg\&.test"); +assert (output); +zsock_t *input = zsock_new_pair (">inproc://zmsg\&.test"); +assert (input); + +// Test send and receive of single\-frame message +zmsg_t *msg = zmsg_new (); +assert (msg); +zframe_t *frame = zframe_new ("Hello", 5); +assert (frame); +zmsg_prepend (msg, &frame); +assert (zmsg_size (msg) == 1); +assert (zmsg_content_size (msg) == 5); +rc = zmsg_send (&msg, output); +assert (msg == NULL); +assert (rc == 0); + +msg = zmsg_recv (input); +assert (msg); +assert (zmsg_size (msg) == 1); +assert (zmsg_content_size (msg) == 5); +zmsg_destroy (&msg); + +// Test send and receive of multi\-frame message +msg = zmsg_new (); +assert (msg); +rc = zmsg_addmem (msg, "Frame0", 6); +assert (rc == 0); +rc = zmsg_addmem (msg, "Frame1", 6); +assert (rc == 0); +rc = zmsg_addmem (msg, "Frame2", 6); +assert (rc == 0); +rc = zmsg_addmem (msg, "Frame3", 6); +assert (rc == 0); +rc = zmsg_addmem (msg, "Frame4", 6); +assert (rc == 0); +rc = zmsg_addmem (msg, "Frame5", 6); +assert (rc == 0); +rc = zmsg_addmem (msg, "Frame6", 6); +assert (rc == 0); +rc = zmsg_addmem (msg, "Frame7", 6); +assert (rc == 0); +rc = zmsg_addmem (msg, "Frame8", 6); +assert (rc == 0); +rc = zmsg_addmem (msg, "Frame9", 6); +assert (rc == 0); +zmsg_t *copy = zmsg_dup (msg); +assert (copy); +rc = zmsg_send (©, output); +assert (rc == 0); +rc = zmsg_send (&msg, output); +assert (rc == 0); + +copy = zmsg_recv (input); +assert (copy); +assert (zmsg_size (copy) == 10); +assert (zmsg_content_size (copy) == 60); +zmsg_destroy (©); + +msg = zmsg_recv (input); +assert (msg); +assert (zmsg_size (msg) == 10); +assert (zmsg_content_size (msg) == 60); + +// Save to a file, read back +FILE *file = fopen ("zmsg\&.test", "w"); +assert (file); +rc = zmsg_save (msg, file); +assert (rc == 0); +fclose (file); + +file = fopen ("zmsg\&.test", "r"); +rc = zmsg_save (msg, file); +assert (rc == \-1); +fclose (file); +zmsg_destroy (&msg); + +file = fopen ("zmsg\&.test", "r"); +msg = zmsg_load (file); +assert (msg); +fclose (file); +remove ("zmsg\&.test"); +assert (zmsg_size (msg) == 10); +assert (zmsg_content_size (msg) == 60); + +// Remove all frames except first and last +int frame_nbr; +for (frame_nbr = 0; frame_nbr < 8; frame_nbr++) { + zmsg_first (msg); + frame = zmsg_next (msg); + zmsg_remove (msg, frame); + zframe_destroy (&frame); +} +// Test message frame manipulation +assert (zmsg_size (msg) == 2); +frame = zmsg_last (msg); +assert (zframe_streq (frame, "Frame9")); +assert (zmsg_content_size (msg) == 12); +frame = zframe_new ("Address", 7); +assert (frame); +zmsg_prepend (msg, &frame); +assert (zmsg_size (msg) == 3); +rc = zmsg_addstr (msg, "Body"); +assert (rc == 0); +assert (zmsg_size (msg) == 4); +frame = zmsg_pop (msg); +zframe_destroy (&frame); +assert (zmsg_size (msg) == 3); +char *body = zmsg_popstr (msg); +assert (streq (body, "Frame0")); +free (body); +zmsg_destroy (&msg); + +// Test encoding/decoding +msg = zmsg_new (); +assert (msg); +byte *blank = (byte *) zmalloc (100000); +assert (blank); +rc = zmsg_addmem (msg, blank, 0); +assert (rc == 0); +rc = zmsg_addmem (msg, blank, 1); +assert (rc == 0); +rc = zmsg_addmem (msg, blank, 253); +assert (rc == 0); +rc = zmsg_addmem (msg, blank, 254); +assert (rc == 0); +rc = zmsg_addmem (msg, blank, 255); +assert (rc == 0); +rc = zmsg_addmem (msg, blank, 256); +assert (rc == 0); +rc = zmsg_addmem (msg, blank, 65535); +assert (rc == 0); +rc = zmsg_addmem (msg, blank, 65536); +assert (rc == 0); +rc = zmsg_addmem (msg, blank, 65537); +assert (rc == 0); +free (blank); +assert (zmsg_size (msg) == 9); +frame = zmsg_encode (msg); +zmsg_destroy (&msg); +msg = zmsg_decode (frame); +assert (msg); +zmsg_destroy (&msg); +zframe_destroy (&frame); + +// Test submessages +msg = zmsg_new (); +assert (msg); +zmsg_t *submsg = zmsg_new (); +zmsg_pushstr (msg, "matr"); +zmsg_pushstr (submsg, "joska"); +rc = zmsg_addmsg (msg, &submsg); +assert (rc == 0); +assert (submsg == NULL); +submsg = zmsg_popmsg (msg); +assert (submsg == NULL); // string "matr" is not encoded zmsg_t, so was discarded +submsg = zmsg_popmsg (msg); +assert (submsg); +body = zmsg_popstr (submsg); +assert (streq (body, "joska")); +free (body); +zmsg_destroy (&submsg); +frame = zmsg_pop (msg); +assert (frame == NULL); +zmsg_destroy (&msg); + +// Test comparison of two messages +msg = zmsg_new (); +zmsg_addstr (msg, "One"); +zmsg_addstr (msg, "Two"); +zmsg_addstr (msg, "Three"); +zmsg_t *msg_other = zmsg_new (); +zmsg_addstr (msg_other, "One"); +zmsg_addstr (msg_other, "Two"); +zmsg_addstr (msg_other, "One\-Hundred"); +zmsg_t *msg_dup = zmsg_dup (msg); +zmsg_t *empty_msg = zmsg_new (); +zmsg_t *empty_msg_2 = zmsg_new (); +assert (zmsg_eq (msg, msg_dup)); +assert (!zmsg_eq (msg, msg_other)); +assert (zmsg_eq (empty_msg, empty_msg_2)); +assert (!zmsg_eq (msg, NULL)); +assert (!zmsg_eq (NULL, empty_msg)); +assert (!zmsg_eq (NULL, NULL)); +zmsg_destroy (&msg); +zmsg_destroy (&msg_other); +zmsg_destroy (&msg_dup); +zmsg_destroy (&empty_msg); +zmsg_destroy (&empty_msg_2); + +// Test signal messages +msg = zmsg_new_signal (0); +assert (zmsg_signal (msg) == 0); +zmsg_destroy (&msg); +msg = zmsg_new_signal (\-1); +assert (zmsg_signal (msg) == 255); +zmsg_destroy (&msg); + +// Now try methods on an empty message +msg = zmsg_new (); +assert (msg); +assert (zmsg_size (msg) == 0); +assert (zmsg_unwrap (msg) == NULL); +assert (zmsg_first (msg) == NULL); +assert (zmsg_last (msg) == NULL); +assert (zmsg_next (msg) == NULL); +assert (zmsg_pop (msg) == NULL); +// Sending an empty message is valid and destroys the message +assert (zmsg_send (&msg, output) == 0); +assert (!msg); + +zsock_destroy (&input); +zsock_destroy (&output); + +#if defined (ZMQ_SERVER) +// Create server and client sockets and connect over inproc +zsock_t *server = zsock_new_server ("inproc://zmsg\-test\-routing"); +assert (server); +zsock_t *client = zsock_new_client ("inproc://zmsg\-test\-routing"); +assert (client); + +// Send request from client to server +zmsg_t *request = zmsg_new (); +assert (request); +zmsg_addstr (request, "Hello"); +rc = zmsg_send (&request, client); +assert (rc == 0); +assert (!request); + +// Read request and send reply +request = zmsg_recv (server); +assert (request); +char *string = zmsg_popstr (request); +assert (streq (string, "Hello")); +assert (zmsg_routing_id (request)); +zstr_free (&string); + +zmsg_t *reply = zmsg_new (); +assert (reply); +zmsg_addstr (reply, "World"); +zmsg_set_routing_id (reply, zmsg_routing_id (request)); +rc = zmsg_send (&reply, server); +assert (rc == 0); +zmsg_destroy (&request); + +// Read reply +reply = zmsg_recv (client); +string = zmsg_popstr (reply); +assert (streq (string, "World")); +assert (zmsg_routing_id (reply) == 0); +zmsg_destroy (&reply); +zstr_free (&string); + +// Client and server disallow multipart +msg = zmsg_new (); +zmsg_addstr (msg, "One"); +zmsg_addstr (msg, "Two"); +rc = zmsg_send (&msg, client); +assert (rc == \-1); +assert (zmsg_size (msg) == 2); +rc = zmsg_send (&msg, server); +assert (rc == \-1); +assert (zmsg_size (msg) == 2); +zmsg_destroy (&msg); + +zsock_destroy (&client); +zsock_destroy (&server); +#endif +.fi +.if n \{\ +.RE +.\} +.sp +.SH "AUTHORS" +.sp +The czmq manual was written by the authors in the AUTHORS file\&. +.SH "RESOURCES" +.sp +Main web site: \m[blue]\fB\%\fR\m[] +.sp +Report bugs to the email <\m[blue]\fBzeromq\-dev@lists\&.zeromq\&.org\fR\m[]\&\s-2\u[1]\d\s+2> +.SH "COPYRIGHT" +.sp +Copyright (c) the Contributors as noted in the AUTHORS file\&. This file is part of CZMQ, the high\-level C binding for 0MQ: http://czmq\&.zeromq\&.org\&. This Source Code Form is subject to the terms of the Mozilla Public License, v\&. 2\&.0\&. If a copy of the MPL was not distributed with this file, You can obtain one at http://mozilla\&.org/MPL/2\&.0/\&. LICENSE included with the czmq distribution\&. +.SH "NOTES" +.IP " 1." 4 +zeromq-dev@lists.zeromq.org +.RS 4 +\%mailto:zeromq-dev@lists.zeromq.org +.RE diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zpoller.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zpoller.3 new file mode 100644 index 00000000000000..33e0170d5e8a86 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zpoller.3 @@ -0,0 +1,216 @@ +'\" t +.\" Title: zpoller +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.76.1 +.\" Date: 12/31/2016 +.\" Manual: CZMQ Manual +.\" Source: CZMQ 4.0.2 +.\" Language: English +.\" +.TH "ZPOLLER" "3" "12/31/2016" "CZMQ 4\&.0\&.2" "CZMQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zpoller \- trivial socket poller class +.SH "SYNOPSIS" +.sp +.nf +// This is a stable class, and may not change except for emergencies\&. It +// is provided in stable builds\&. +// Create new poller, specifying zero or more readers\&. The list of +// readers ends in a NULL\&. Each reader can be a zsock_t instance, a +// zactor_t instance, a libzmq socket (void *), or a file handle\&. +CZMQ_EXPORT zpoller_t * + zpoller_new (void *reader, \&.\&.\&.); + +// Destroy a poller +CZMQ_EXPORT void + zpoller_destroy (zpoller_t **self_p); + +// Add a reader to be polled\&. Returns 0 if OK, \-1 on failure\&. The reader may +// be a libzmq void * socket, a zsock_t instance, or a zactor_t instance\&. +CZMQ_EXPORT int + zpoller_add (zpoller_t *self, void *reader); + +// Remove a reader from the poller; returns 0 if OK, \-1 on failure\&. The reader +// must have been passed during construction, or in an zpoller_add () call\&. +CZMQ_EXPORT int + zpoller_remove (zpoller_t *self, void *reader); + +// By default the poller stops if the process receives a SIGINT or SIGTERM +// signal\&. This makes it impossible to shut\-down message based architectures +// like zactors\&. This method lets you switch off break handling\&. The default +// nonstop setting is off (false)\&. +CZMQ_EXPORT void + zpoller_set_nonstop (zpoller_t *self, bool nonstop); + +// Poll the registered readers for I/O, return first reader that has input\&. +// The reader will be a libzmq void * socket, or a zsock_t or zactor_t +// instance as specified in zpoller_new/zpoller_add\&. The timeout should be +// zero or greater, or \-1 to wait indefinitely\&. Socket priority is defined +// by their order in the poll list\&. If you need a balanced poll, use the low +// level zmq_poll method directly\&. If the poll call was interrupted (SIGINT), +// or the ZMQ context was destroyed, or the timeout expired, returns NULL\&. +// You can test the actual exit condition by calling zpoller_expired () and +// zpoller_terminated ()\&. The timeout is in msec\&. +CZMQ_EXPORT void * + zpoller_wait (zpoller_t *self, int timeout); + +// Return true if the last zpoller_wait () call ended because the timeout +// expired, without any error\&. +CZMQ_EXPORT bool + zpoller_expired (zpoller_t *self); + +// Return true if the last zpoller_wait () call ended because the process +// was interrupted, or the parent context was destroyed\&. +CZMQ_EXPORT bool + zpoller_terminated (zpoller_t *self); + +// Self test of this class\&. +CZMQ_EXPORT void + zpoller_test (bool verbose); + +Please add \*(Aq@interface\*(Aq section in \*(Aq\&./\&.\&./src/zpoller\&.c\*(Aq\&. +.fi +.SH "DESCRIPTION" +.sp +The zpoller class provides a minimalist interface to ZeroMQ\(cqs zmq_poll API, for the very common case of reading from a number of sockets\&. It does not provide polling for output, nor polling on file handles\&. If you need either of these, use the zmq_poll API directly\&. +.sp +The class implements the poller using the zmq_poller API if that exists, else does the work itself\&. +.SH "EXAMPLE" +.PP +\fBFrom zpoller_test method\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +// Create a few sockets +zsock_t *vent = zsock_new (ZMQ_PUSH); +assert (vent); +int port_nbr = zsock_bind (vent, "tcp://127\&.0\&.0\&.1:*"); +assert (port_nbr != \-1); +zsock_t *sink = zsock_new (ZMQ_PULL); +assert (sink); +int rc = zsock_connect (sink, "tcp://127\&.0\&.0\&.1:%d", port_nbr); +assert (rc != \-1); +zsock_t *bowl = zsock_new (ZMQ_PULL); +assert (bowl); +zsock_t *dish = zsock_new (ZMQ_PULL); +assert (dish); + +// Set up poller +zpoller_t *poller = zpoller_new (bowl, dish, NULL); +assert (poller); + +// Add a reader to the existing poller +rc = zpoller_add (poller, sink); +assert (rc == 0); + +zstr_send (vent, "Hello, World"); + +// We expect a message only on the sink +zsock_t *which = (zsock_t *) zpoller_wait (poller, \-1); +assert (which == sink); +assert (zpoller_expired (poller) == false); +assert (zpoller_terminated (poller) == false); +char *message = zstr_recv (which); +assert (streq (message, "Hello, World")); +zstr_free (&message); + +// Stop polling reader +rc = zpoller_remove (poller, sink); +assert (rc == 0); + +// Check we can poll an FD +rc = zsock_connect (bowl, "tcp://127\&.0\&.0\&.1:%d", port_nbr); +assert (rc != \-1); +SOCKET fd = zsock_fd (bowl); +rc = zpoller_add (poller, (void *) &fd); +assert (rc != \-1); +zstr_send (vent, "Hello again, world"); +assert (zpoller_wait (poller, 500) == &fd); + +// Check zpoller_set_nonstop () +zsys_interrupted = 1; +zpoller_wait (poller, 0); +assert (zpoller_terminated (poller)); +zpoller_set_nonstop (poller, true); +zpoller_wait (poller, 0); +assert (!zpoller_terminated (poller)); +zsys_interrupted = 0; + +zpoller_destroy (&poller); +zsock_destroy (&vent); +zsock_destroy (&sink); +zsock_destroy (&bowl); +zsock_destroy (&dish); + +#ifdef ZMQ_SERVER +// Check thread safe sockets +zpoller_destroy (&poller); +zsock_t *client = zsock_new (ZMQ_CLIENT); +assert (client); +zsock_t *server = zsock_new (ZMQ_SERVER); +assert (server); +poller = zpoller_new (client, server, NULL); +assert (poller); +port_nbr = zsock_bind (server, "tcp://127\&.0\&.0\&.1:*"); +assert (port_nbr != \-1); +rc = zsock_connect (client, "tcp://127\&.0\&.0\&.1:%d", port_nbr); +assert (rc != \-1); + +zstr_send (client, "Hello, World"); + +// We expect a message only on the server +which = (zsock_t *) zpoller_wait (poller, \-1); +assert (which == server); +assert (zpoller_expired (poller) == false); +assert (zpoller_terminated (poller) == false); +message = zstr_recv (which); +assert (streq (message, "Hello, World")); +zstr_free (&message); + +zpoller_destroy (&poller); +zsock_destroy (&client); +zsock_destroy (&server); +#endif +.fi +.if n \{\ +.RE +.\} +.sp +.SH "AUTHORS" +.sp +The czmq manual was written by the authors in the AUTHORS file\&. +.SH "RESOURCES" +.sp +Main web site: \m[blue]\fB\%\fR\m[] +.sp +Report bugs to the email <\m[blue]\fBzeromq\-dev@lists\&.zeromq\&.org\fR\m[]\&\s-2\u[1]\d\s+2> +.SH "COPYRIGHT" +.sp +Copyright (c) the Contributors as noted in the AUTHORS file\&. This file is part of CZMQ, the high\-level C binding for 0MQ: http://czmq\&.zeromq\&.org\&. This Source Code Form is subject to the terms of the Mozilla Public License, v\&. 2\&.0\&. If a copy of the MPL was not distributed with this file, You can obtain one at http://mozilla\&.org/MPL/2\&.0/\&. LICENSE included with the czmq distribution\&. +.SH "NOTES" +.IP " 1." 4 +zeromq-dev@lists.zeromq.org +.RS 4 +\%mailto:zeromq-dev@lists.zeromq.org +.RE diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zproc.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zproc.3 new file mode 100644 index 00000000000000..9bfcfa9c84b840 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zproc.3 @@ -0,0 +1,208 @@ +'\" t +.\" Title: zproc +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.76.1 +.\" Date: 12/31/2016 +.\" Manual: CZMQ Manual +.\" Source: CZMQ 4.0.2 +.\" Language: English +.\" +.TH "ZPROC" "3" "12/31/2016" "CZMQ 4\&.0\&.2" "CZMQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zproc \- process configuration and status +.SH "SYNOPSIS" +.sp +.nf +// This is a draft class, and may change without notice\&. It is disabled in +// stable builds by default\&. If you use this in applications, please ask +// for it to be pushed to stable state\&. Use \-\-enable\-drafts to enable\&. +#ifdef CZMQ_BUILD_DRAFT_API +// *** Draft method, for development use, may change without warning *** +// Returns CZMQ version as a single 6\-digit integer encoding the major +// version (x 10000), the minor version (x 100) and the patch\&. +CZMQ_EXPORT int + zproc_czmq_version (void); + +// *** Draft method, for development use, may change without warning *** +// Returns true if the process received a SIGINT or SIGTERM signal\&. +// It is good practice to use this method to exit any infinite loop +// processing messages\&. +CZMQ_EXPORT bool + zproc_interrupted (void); + +// *** Draft method, for development use, may change without warning *** +// Returns true if the underlying libzmq supports CURVE security\&. +CZMQ_EXPORT bool + zproc_has_curve (void); + +// *** Draft method, for development use, may change without warning *** +// Return current host name, for use in public tcp:// endpoints\&. +// If the host name is not resolvable, returns NULL\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT char * + zproc_hostname (void); + +// *** Draft method, for development use, may change without warning *** +// Move the current process into the background\&. The precise effect +// depends on the operating system\&. On POSIX boxes, moves to a specified +// working directory (if specified), closes all file handles, reopens +// stdin, stdout, and stderr to the null device, and sets the process to +// ignore SIGHUP\&. On Windows, does nothing\&. Returns 0 if OK, \-1 if there +// was an error\&. +CZMQ_EXPORT void + zproc_daemonize (const char *workdir); + +// *** Draft method, for development use, may change without warning *** +// Drop the process ID into the lockfile, with exclusive lock, and +// switch the process to the specified group and/or user\&. Any of the +// arguments may be null, indicating a no\-op\&. Returns 0 on success, +// \-1 on failure\&. Note if you combine this with zsys_daemonize, run +// after, not before that method, or the lockfile will hold the wrong +// process ID\&. +CZMQ_EXPORT void + zproc_run_as (const char *lockfile, const char *group, const char *user); + +// *** Draft method, for development use, may change without warning *** +// Configure the number of I/O threads that ZeroMQ will use\&. A good +// rule of thumb is one thread per gigabit of traffic in or out\&. The +// default is 1, sufficient for most applications\&. If the environment +// variable ZSYS_IO_THREADS is defined, that provides the default\&. +// Note that this method is valid only before any socket is created\&. +CZMQ_EXPORT void + zproc_set_io_threads (size_t io_threads); + +// *** Draft method, for development use, may change without warning *** +// Configure the number of sockets that ZeroMQ will allow\&. The default +// is 1024\&. The actual limit depends on the system, and you can query it +// by using zsys_socket_limit ()\&. A value of zero means "maximum"\&. +// Note that this method is valid only before any socket is created\&. +CZMQ_EXPORT void + zproc_set_max_sockets (size_t max_sockets); + +// *** Draft method, for development use, may change without warning *** +// Set network interface name to use for broadcasts, particularly zbeacon\&. +// This lets the interface be configured for test environments where required\&. +// For example, on Mac OS X, zbeacon cannot bind to 255\&.255\&.255\&.255 which is +// the default when there is no specified interface\&. If the environment +// variable ZSYS_INTERFACE is set, use that as the default interface name\&. +// Setting the interface to "*" means "use all available interfaces"\&. +CZMQ_EXPORT void + zproc_set_biface (const char *value); + +// *** Draft method, for development use, may change without warning *** +// Return network interface to use for broadcasts, or "" if none was set\&. +CZMQ_EXPORT const char * + zproc_biface (void); + +// *** Draft method, for development use, may change without warning *** +// Set log identity, which is a string that prefixes all log messages sent +// by this process\&. The log identity defaults to the environment variable +// ZSYS_LOGIDENT, if that is set\&. +CZMQ_EXPORT void + zproc_set_log_ident (const char *value); + +// *** Draft method, for development use, may change without warning *** +// Sends log output to a PUB socket bound to the specified endpoint\&. To +// collect such log output, create a SUB socket, subscribe to the traffic +// you care about, and connect to the endpoint\&. Log traffic is sent as a +// single string frame, in the same format as when sent to stdout\&. The +// log system supports a single sender; multiple calls to this method will +// bind the same sender to multiple endpoints\&. To disable the sender, call +// this method with a null argument\&. +CZMQ_EXPORT void + zproc_set_log_sender (const char *endpoint); + +// *** Draft method, for development use, may change without warning *** +// Enable or disable logging to the system facility (syslog on POSIX boxes, +// event log on Windows)\&. By default this is disabled\&. +CZMQ_EXPORT void + zproc_set_log_system (bool logsystem); + +// *** Draft method, for development use, may change without warning *** +// Log error condition \- highest priority +CZMQ_EXPORT void + zproc_log_error (const char *format, \&.\&.\&.) CHECK_PRINTF (1); + +// *** Draft method, for development use, may change without warning *** +// Log warning condition \- high priority +CZMQ_EXPORT void + zproc_log_warning (const char *format, \&.\&.\&.) CHECK_PRINTF (1); + +// *** Draft method, for development use, may change without warning *** +// Log normal, but significant, condition \- normal priority +CZMQ_EXPORT void + zproc_log_notice (const char *format, \&.\&.\&.) CHECK_PRINTF (1); + +// *** Draft method, for development use, may change without warning *** +// Log informational message \- low priority +CZMQ_EXPORT void + zproc_log_info (const char *format, \&.\&.\&.) CHECK_PRINTF (1); + +// *** Draft method, for development use, may change without warning *** +// Log debug\-level message \- lowest priority +CZMQ_EXPORT void + zproc_log_debug (const char *format, \&.\&.\&.) CHECK_PRINTF (1); + +// *** Draft method, for development use, may change without warning *** +// Self test of this class\&. +CZMQ_EXPORT void + zproc_test (bool verbose); + +#endif // CZMQ_BUILD_DRAFT_API +Please add \*(Aq@interface\*(Aq section in \*(Aq\&./\&.\&./src/zproc\&.c\*(Aq\&. +.fi +.SH "DESCRIPTION" +.sp +zproc \- process configuration and status +.sp +Please add \fI@discuss\fR section in \fI\&./\&.\&./src/zproc\&.c\fR\&. +.SH "EXAMPLE" +.PP +\fBFrom zproc_test method\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +Please add \*(Aq@selftest\*(Aq section in \*(Aq\&./\&.\&./src/zproc\&.c\*(Aq\&. +.fi +.if n \{\ +.RE +.\} +.sp +.SH "AUTHORS" +.sp +The czmq manual was written by the authors in the AUTHORS file\&. +.SH "RESOURCES" +.sp +Main web site: \m[blue]\fB\%\fR\m[] +.sp +Report bugs to the email <\m[blue]\fBzeromq\-dev@lists\&.zeromq\&.org\fR\m[]\&\s-2\u[1]\d\s+2> +.SH "COPYRIGHT" +.sp +Copyright (c) the Contributors as noted in the AUTHORS file\&. This file is part of CZMQ, the high\-level C binding for 0MQ: http://czmq\&.zeromq\&.org\&. This Source Code Form is subject to the terms of the Mozilla Public License, v\&. 2\&.0\&. If a copy of the MPL was not distributed with this file, You can obtain one at http://mozilla\&.org/MPL/2\&.0/\&. LICENSE included with the czmq distribution\&. +.SH "NOTES" +.IP " 1." 4 +zeromq-dev@lists.zeromq.org +.RS 4 +\%mailto:zeromq-dev@lists.zeromq.org +.RE diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zproxy.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zproxy.3 new file mode 100644 index 00000000000000..037d3da6bb92bd --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zproxy.3 @@ -0,0 +1,402 @@ +'\" t +.\" Title: zproxy +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.76.1 +.\" Date: 12/31/2016 +.\" Manual: CZMQ Manual +.\" Source: CZMQ 4.0.2 +.\" Language: English +.\" +.TH "ZPROXY" "3" "12/31/2016" "CZMQ 4\&.0\&.2" "CZMQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zproxy \- run a steerable proxy in the background +.SH "SYNOPSIS" +.sp +.nf +// Create new zproxy actor instance\&. The proxy switches messages between +// a frontend socket and a backend socket; use the FRONTEND and BACKEND +// commands to configure these: +// +// zactor_t *proxy = zactor_new (zproxy, NULL); +// +// Destroy zproxy instance\&. This destroys the two sockets and stops any +// message flow between them: +// +// zactor_destroy (&proxy); +// +// Note that all zproxy commands are synchronous, so your application always +// waits for a signal from the actor after each command\&. +// +// Enable verbose logging of commands and activity: +// +// zstr_send (proxy, "VERBOSE"); +// zsock_wait (proxy); +// +// Specify frontend socket type \-\- see zsock_type_str () \-\- and attach to +// endpoints, see zsock_attach ()\&. Note that a proxy socket is always +// serverish: +// +// zstr_sendx (proxy, "FRONTEND", "XSUB", endpoints, NULL); +// zsock_wait (proxy); +// +// Specify backend socket type \-\- see zsock_type_str () \-\- and attach to +// endpoints, see zsock_attach ()\&. Note that a proxy socket is always +// serverish: +// +// zstr_sendx (proxy, "BACKEND", "XPUB", endpoints, NULL); +// zsock_wait (proxy); +// +// Capture all proxied messages; these are delivered to the application +// via an inproc PULL socket that you have already bound to the specified +// endpoint: +// +// zstr_sendx (proxy, "CAPTURE", endpoint, NULL); +// zsock_wait (proxy); +// +// Pause the proxy\&. A paused proxy will cease processing messages, causing +// them to be queued up and potentially hit the high\-water mark on the +// frontend or backend socket, causing messages to be dropped, or writing +// applications to block: +// +// zstr_sendx (proxy, "PAUSE", NULL); +// zsock_wait (proxy); +// +// Resume the proxy\&. Note that the proxy starts automatically as soon as it +// has a properly attached frontend and backend socket: +// +// zstr_sendx (proxy, "RESUME", NULL); +// zsock_wait (proxy); +// +// Configure an authentication domain for the "FRONTEND" or "BACKEND" proxy +// socket \-\- see zsock_set_zap_domain ()\&. Call before binding socket: +// +// zstr_sendx (proxy, "DOMAIN", "FRONTEND", "global", NULL); +// zsock_wait (proxy); +// +// Configure PLAIN authentication for the "FRONTEND" or "BACKEND" proxy +// socket \-\- see zsock_set_plain_server ()\&. Call before binding socket: +// +// zstr_sendx (proxy, "PLAIN", "BACKEND", NULL); +// zsock_wait (proxy); +// +// Configure CURVE authentication for the "FRONTEND" or "BACKEND" proxy +// socket \-\- see zsock_set_curve_server () \-\- specifying both the public and +// secret keys of a certificate as Z85 armored strings \-\- see +// zcert_public_txt () and zcert_secret_txt ()\&. Call before binding socket: +// +// zstr_sendx (proxy, "CURVE", "FRONTEND", public_txt, secret_txt, NULL); +// zsock_wait (proxy); +// +// This is the zproxy constructor as a zactor_fn; the argument is a +// character string specifying frontend and backend socket types as two +// uppercase strings separated by a hyphen: +CZMQ_EXPORT void + zproxy (zsock_t *pipe, void *unused); + +// Selftest +CZMQ_EXPORT void + zproxy_test (bool verbose); +Please add \*(Aq@interface\*(Aq section in \*(Aq\&./\&.\&./src/zproxy\&.c\*(Aq\&. +.fi +.SH "DESCRIPTION" +.sp +A zproxy actor switches messages between a frontend and a backend socket\&. It acts much like the zmq_proxy_steerable method, though it makes benefit of CZMQ\(cqs facilities, to be somewhat simpler to set\-up\&. +.sp +This class replaces zproxy_v2, and is meant for applications that use the CZMQ v3 API (meaning, zsock)\&. +.SH "EXAMPLE" +.PP +\fBFrom zproxy_test method\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +// Create and configure our proxy +zactor_t *proxy = zactor_new (zproxy, NULL); +assert (proxy); +if (verbose) { + zstr_sendx (proxy, "VERBOSE", NULL); + zsock_wait (proxy); +} +zstr_sendx (proxy, "FRONTEND", "PULL", "inproc://frontend", NULL); +zsock_wait (proxy); +zstr_sendx (proxy, "BACKEND", "PUSH", "inproc://backend", NULL); +zsock_wait (proxy); + +// Connect application sockets to proxy +zsock_t *faucet = zsock_new_push (">inproc://frontend"); +assert (faucet); +zsock_t *sink = zsock_new_pull (">inproc://backend"); +assert (sink); + +// Send some messages and check they arrived +char *hello, *world; +zstr_sendx (faucet, "Hello", "World", NULL); +zstr_recvx (sink, &hello, &world, NULL); +assert (streq (hello, "Hello")); +assert (streq (world, "World")); +zstr_free (&hello); +zstr_free (&world); + +// Test pause/resume functionality +zstr_sendx (proxy, "PAUSE", NULL); +zsock_wait (proxy); +zstr_sendx (faucet, "Hello", "World", NULL); +zsock_set_rcvtimeo (sink, 100); +zstr_recvx (sink, &hello, &world, NULL); +assert (!hello && !world); + +zstr_sendx (proxy, "RESUME", NULL); +zsock_wait (proxy); +zstr_recvx (sink, &hello, &world, NULL); +assert (streq (hello, "Hello")); +assert (streq (world, "World")); +zstr_free (&hello); +zstr_free (&world); + +// Test capture functionality +zsock_t *capture = zsock_new_pull ("inproc://capture"); +assert (capture); + +// Switch on capturing, check that it works +zstr_sendx (proxy, "CAPTURE", "inproc://capture", NULL); +zsock_wait (proxy); +zstr_sendx (faucet, "Hello", "World", NULL); +zstr_recvx (sink, &hello, &world, NULL); +assert (streq (hello, "Hello")); +assert (streq (world, "World")); +zstr_free (&hello); +zstr_free (&world); + +zstr_recvx (capture, &hello, &world, NULL); +assert (streq (hello, "Hello")); +assert (streq (world, "World")); +zstr_free (&hello); +zstr_free (&world); + +zsock_destroy (&faucet); +zsock_destroy (&sink); +zsock_destroy (&capture); +zactor_destroy (&proxy); + +// Test socket creation dependency +proxy = zactor_new (zproxy, NULL); +assert (proxy); + +sink = zsock_new_sub (">ipc://backend", "whatever"); +assert (sink); + +zstr_sendx (proxy, "BACKEND", "XPUB", "ipc://backend", NULL); +zsock_wait (proxy); + +zsock_destroy(&sink); +zactor_destroy(&proxy); + +#if (ZMQ_VERSION_MAJOR == 4) +// Test authentication functionality +# define TESTDIR "\&.test_zproxy" + +// Create temporary directory for test files +zsys_dir_create (TESTDIR); + +char *frontend = NULL; +char *backend = NULL; + +// Check there\*(Aqs no authentication +s_create_test_sockets (&proxy, &faucet, &sink, verbose); +s_bind_test_sockets (proxy, &frontend, &backend); +bool success = s_can_connect (&proxy, &faucet, &sink, frontend, backend, verbose); +assert (success); + +// Install the authenticator +zactor_t *auth = zactor_new (zauth, NULL); +assert (auth); +if (verbose) { + zstr_sendx (auth, "VERBOSE", NULL); + zsock_wait (auth); +} + +// Check there\*(Aqs no authentication on a default NULL server +s_bind_test_sockets (proxy, &frontend, &backend); +success = s_can_connect (&proxy, &faucet, &sink, frontend, backend, verbose); +assert (success); + +// When we set a domain on the server, we switch on authentication +// for NULL sockets, but with no policies, the client connection +// will be allowed\&. +zstr_sendx (proxy, "DOMAIN", "FRONTEND", "global", NULL); +zsock_wait (proxy); +s_bind_test_sockets (proxy, &frontend, &backend); +success = s_can_connect (&proxy, &faucet, &sink, frontend, backend, verbose); +assert (success); + +// Blacklist 127\&.0\&.0\&.1, connection should fail +zstr_sendx (proxy, "DOMAIN", "FRONTEND", "global", NULL); +zsock_wait (proxy); +s_bind_test_sockets (proxy, &frontend, &backend); +zstr_sendx (auth, "DENY", "127\&.0\&.0\&.1", NULL); +zsock_wait (auth); +success = s_can_connect (&proxy, &faucet, &sink, frontend, backend, verbose); +assert (!success); + +// Whitelist our address, which overrides the blacklist +zstr_sendx (proxy, "DOMAIN", "FRONTEND", "global", NULL); +zsock_wait (proxy); +zstr_sendx (proxy, "DOMAIN", "BACKEND", "global", NULL); +zsock_wait (proxy); +s_bind_test_sockets (proxy, &frontend, &backend); +zstr_sendx (auth, "ALLOW", "127\&.0\&.0\&.1", NULL); +zsock_wait (auth); +success = s_can_connect (&proxy, &faucet, &sink, frontend, backend, verbose); +assert (success); + +// Try PLAIN authentication + +// Test negative case (no server\-side passwords defined) +zstr_sendx (proxy, "PLAIN", "FRONTEND", NULL); +zsock_wait (proxy); +s_bind_test_sockets (proxy, &frontend, &backend); +zsock_set_plain_username (faucet, "admin"); +zsock_set_plain_password (faucet, "Password"); +success = s_can_connect (&proxy, &faucet, &sink, frontend, backend, verbose); +assert (!success); + +// Test positive case (server\-side passwords defined) +FILE *password = fopen (TESTDIR "/password\-file", "w"); +assert (password); +fprintf (password, "admin=Password\en"); +fclose (password); +zstr_sendx (proxy, "PLAIN", "FRONTEND", NULL); +zsock_wait (proxy); +zstr_sendx (proxy, "PLAIN", "BACKEND", NULL); +zsock_wait (proxy); +s_bind_test_sockets (proxy, &frontend, &backend); +zsock_set_plain_username (faucet, "admin"); +zsock_set_plain_password (faucet, "Password"); +zsock_set_plain_username (sink, "admin"); +zsock_set_plain_password (sink, "Password"); +zstr_sendx (auth, "PLAIN", TESTDIR "/password\-file", NULL); +zsock_wait (auth); +success = s_can_connect (&proxy, &faucet, &sink, frontend, backend, verbose); +assert (success); + +// Test negative case (bad client password) +zstr_sendx (proxy, "PLAIN", "FRONTEND", NULL); +zsock_wait (proxy); +s_bind_test_sockets (proxy, &frontend, &backend); +zsock_set_plain_username (faucet, "admin"); +zsock_set_plain_password (faucet, "Bogus"); +success = s_can_connect (&proxy, &faucet, &sink, frontend, backend, verbose); +assert (!success); + +if (zsys_has_curve ()) { + // We\*(Aqll create two new certificates and save the client public + // certificate on disk + zcert_t *server_cert = zcert_new (); + assert (server_cert); + zcert_t *client_cert = zcert_new (); + assert (client_cert); + const char *public_key = zcert_public_txt (server_cert); + const char *secret_key = zcert_secret_txt (server_cert); + + // Try CURVE authentication + + // Test without setting\-up any authentication + zstr_sendx (proxy, "CURVE", "FRONTEND", public_key, secret_key, NULL); + zsock_wait (proxy); + s_bind_test_sockets (proxy, &frontend, &backend); + zcert_apply (client_cert, faucet); + zsock_set_curve_serverkey (faucet, public_key); + success = s_can_connect (&proxy, &faucet, &sink, frontend, backend, verbose); + assert (!success); + + // Test CURVE_ALLOW_ANY + zstr_sendx (proxy, "CURVE", "FRONTEND", public_key, secret_key, NULL); + zsock_wait (proxy); + s_bind_test_sockets (proxy, &frontend, &backend); + zcert_apply (client_cert, faucet); + zsock_set_curve_serverkey (faucet, public_key); + zstr_sendx (auth, "CURVE", CURVE_ALLOW_ANY, NULL); + zsock_wait (auth); + success = s_can_connect (&proxy, &faucet, &sink, frontend, backend, verbose); + assert (success); + + // Test with client certificate file in authentication folder + zstr_sendx (proxy, "CURVE", "FRONTEND", public_key, secret_key, NULL); + zsock_wait (proxy); + zstr_sendx (proxy, "CURVE", "BACKEND", public_key, secret_key, NULL); + zsock_wait (proxy); + s_bind_test_sockets (proxy, &frontend, &backend); + zcert_apply (client_cert, faucet); + zsock_set_curve_serverkey (faucet, public_key); + zcert_apply (client_cert, sink); + zsock_set_curve_serverkey (sink, public_key); + zcert_save_public (client_cert, TESTDIR "/mycert\&.txt"); + zstr_sendx (auth, "CURVE", TESTDIR, NULL); + zsock_wait (auth); + success = s_can_connect (&proxy, &faucet, &sink, frontend, backend, verbose); + assert (success); + + zcert_destroy (&server_cert); + zcert_destroy (&client_cert); +} + +// Remove the authenticator and check a normal connection works +zactor_destroy (&auth); +s_bind_test_sockets (proxy, &frontend, &backend); +success = s_can_connect (&proxy, &faucet, &sink, frontend, backend, verbose); +assert (success); + +// Cleanup +zsock_destroy (&faucet); +zsock_destroy (&sink); +zactor_destroy (&proxy); +zstr_free (&frontend); +zstr_free (&backend); + +// Delete temporary directory and test files +zsys_file_delete (TESTDIR "/password\-file"); +zsys_file_delete (TESTDIR "/mycert\&.txt"); +zsys_dir_delete (TESTDIR); +#endif +.fi +.if n \{\ +.RE +.\} +.sp +.SH "AUTHORS" +.sp +The czmq manual was written by the authors in the AUTHORS file\&. +.SH "RESOURCES" +.sp +Main web site: \m[blue]\fB\%\fR\m[] +.sp +Report bugs to the email <\m[blue]\fBzeromq\-dev@lists\&.zeromq\&.org\fR\m[]\&\s-2\u[1]\d\s+2> +.SH "COPYRIGHT" +.sp +Copyright (c) the Contributors as noted in the AUTHORS file\&. This file is part of CZMQ, the high\-level C binding for 0MQ: http://czmq\&.zeromq\&.org\&. This Source Code Form is subject to the terms of the Mozilla Public License, v\&. 2\&.0\&. If a copy of the MPL was not distributed with this file, You can obtain one at http://mozilla\&.org/MPL/2\&.0/\&. LICENSE included with the czmq distribution\&. +.SH "NOTES" +.IP " 1." 4 +zeromq-dev@lists.zeromq.org +.RS 4 +\%mailto:zeromq-dev@lists.zeromq.org +.RE diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zrex.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zrex.3 new file mode 100644 index 00000000000000..99c7337d403609 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zrex.3 @@ -0,0 +1,199 @@ +'\" t +.\" Title: zrex +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.76.1 +.\" Date: 12/31/2016 +.\" Manual: CZMQ Manual +.\" Source: CZMQ 4.0.2 +.\" Language: English +.\" +.TH "ZREX" "3" "12/31/2016" "CZMQ 4\&.0\&.2" "CZMQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zrex \- work with regular expressions +.SH "SYNOPSIS" +.sp +.nf +// Constructor\&. Optionally, sets an expression against which we can match +// text and capture hits\&. If there is an error in the expression, reports +// zrex_valid() as false and provides the error in zrex_strerror()\&. If you +// set a pattern, you can call zrex_matches() to test it against text\&. +CZMQ_EXPORT zrex_t * + zrex_new (const char *expression); + +// Destructor +CZMQ_EXPORT void + zrex_destroy (zrex_t **self_p); + +// Return true if the expression was valid and compiled without errors\&. +CZMQ_EXPORT bool + zrex_valid (zrex_t *self); + +// Return the error message generated during compilation of the expression\&. +CZMQ_EXPORT const char * + zrex_strerror (zrex_t *self); + +// Returns true if the text matches the previously compiled expression\&. +// Use this method to compare one expression against many strings\&. +CZMQ_EXPORT bool + zrex_matches (zrex_t *self, const char *text); + +// Returns true if the text matches the supplied expression\&. Use this +// method to compare one string against several expressions\&. +CZMQ_EXPORT bool + zrex_eq (zrex_t *self, const char *text, const char *expression); + +// Returns number of hits from last zrex_matches or zrex_eq\&. If the text +// matched, returns 1 plus the number of capture groups\&. If the text did +// not match, returns zero\&. To retrieve individual capture groups, call +// zrex_hit ()\&. +CZMQ_EXPORT int + zrex_hits (zrex_t *self); + +// Returns the Nth capture group from the last expression match, where +// N is 0 to the value returned by zrex_hits()\&. Capture group 0 is the +// whole matching string\&. Sequence 1 is the first capture group, if any, +// and so on\&. +CZMQ_EXPORT const char * + zrex_hit (zrex_t *self, uint index); + +// Fetches hits into string variables provided by caller; this makes for +// nicer code than accessing hits by index\&. Caller should not modify nor +// free the returned values\&. Returns number of strings returned\&. This +// method starts at hit 1, i\&.e\&. first capture group, as hit 0 is always +// the original matched string\&. +CZMQ_EXPORT int + zrex_fetch (zrex_t *self, const char **string_p, \&.\&.\&.); + +// Self test of this class +CZMQ_EXPORT void + zrex_test (bool verbose); +Please add \*(Aq@interface\*(Aq section in \*(Aq\&./\&.\&./src/zrex\&.c\*(Aq\&. +.fi +.SH "DESCRIPTION" +.sp +Wraps a very simple regular expression library (SLRE) as a CZMQ class\&. Supports this syntax: +.sp +.if n \{\ +.RS 4 +.\} +.nf +^ Match beginning of a buffer +$ Match end of a buffer +() Grouping and substring capturing +[\&.\&.\&.] Match any character from set +[^\&.\&.\&.] Match any character but ones from set +\&. Match any character +\es Match whitespace +\eS Match non\-whitespace +\ed Match decimal digit +\eD Match non decimal digit +\ea Match alphabetic character +\eA Match non\-alphabetic character +\ew Match alphanumeric character +\eW Match non\-alphanumeric character +\er Match carriage return +\en Match newline ++ Match one or more times (greedy) ++? Match one or more times (non\-greedy) +* Match zero or more times (greedy) +*? Match zero or more times (non\-greedy) +? Match zero or once +\exDD Match byte with hex value 0xDD +\emeta Match one of the meta character: ^$()\&.[*+?\e +.fi +.if n \{\ +.RE +.\} +.sp +Please add \fI@discuss\fR section in \fI\&./\&.\&./src/zrex\&.c\fR\&. +.SH "EXAMPLE" +.PP +\fBFrom zrex_test method\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +// This shows the pattern of matching many lines to a single pattern +zrex_t *rex = zrex_new ("\e\ed+\-\e\ed+\-\e\ed+"); +assert (rex); +assert (zrex_valid (rex)); +bool matches = zrex_matches (rex, "123\-456\-789"); +assert (matches); +assert (zrex_hits (rex) == 1); +assert (streq (zrex_hit (rex, 0), "123\-456\-789")); +assert (zrex_hit (rex, 1) == NULL); +zrex_destroy (&rex); + +// Here we pick out hits using capture groups +rex = zrex_new ("(\e\ed+)\-(\e\ed+)\-(\e\ed+)"); +assert (rex); +assert (zrex_valid (rex)); +matches = zrex_matches (rex, "123\-456\-ABC"); +assert (!matches); +matches = zrex_matches (rex, "123\-456\-789"); +assert (matches); +assert (zrex_hits (rex) == 4); +assert (streq (zrex_hit (rex, 0), "123\-456\-789")); +assert (streq (zrex_hit (rex, 1), "123")); +assert (streq (zrex_hit (rex, 2), "456")); +assert (streq (zrex_hit (rex, 3), "789")); +zrex_destroy (&rex); + +// This shows the pattern of matching one line against many +// patterns and then handling the case when it hits +rex = zrex_new (NULL); // No initial pattern +assert (rex); +char *input = "Mechanism: CURVE"; +matches = zrex_eq (rex, input, "Version: (\&.+)"); +assert (!matches); +assert (zrex_hits (rex) == 0); +matches = zrex_eq (rex, input, "Mechanism: (\&.+)"); +assert (matches); +assert (zrex_hits (rex) == 2); +const char *mechanism; +zrex_fetch (rex, &mechanism, NULL); +assert (streq (zrex_hit (rex, 1), "CURVE")); +assert (streq (mechanism, "CURVE")); +zrex_destroy (&rex); +.fi +.if n \{\ +.RE +.\} +.sp +.SH "AUTHORS" +.sp +The czmq manual was written by the authors in the AUTHORS file\&. +.SH "RESOURCES" +.sp +Main web site: \m[blue]\fB\%\fR\m[] +.sp +Report bugs to the email <\m[blue]\fBzeromq\-dev@lists\&.zeromq\&.org\fR\m[]\&\s-2\u[1]\d\s+2> +.SH "COPYRIGHT" +.sp +Copyright (c) the Contributors as noted in the AUTHORS file\&. This file is part of CZMQ, the high\-level C binding for 0MQ: http://czmq\&.zeromq\&.org\&. This Source Code Form is subject to the terms of the Mozilla Public License, v\&. 2\&.0\&. If a copy of the MPL was not distributed with this file, You can obtain one at http://mozilla\&.org/MPL/2\&.0/\&. LICENSE included with the czmq distribution\&. +.SH "NOTES" +.IP " 1." 4 +zeromq-dev@lists.zeromq.org +.RS 4 +\%mailto:zeromq-dev@lists.zeromq.org +.RE diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zsock.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zsock.3 new file mode 100644 index 00000000000000..fc4a7e8b44c21b --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zsock.3 @@ -0,0 +1,1469 @@ +'\" t +.\" Title: zsock +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.76.1 +.\" Date: 12/31/2016 +.\" Manual: CZMQ Manual +.\" Source: CZMQ 4.0.2 +.\" Language: English +.\" +.TH "ZSOCK" "3" "12/31/2016" "CZMQ 4\&.0\&.2" "CZMQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zsock \- high\-level socket API that hides libzmq contexts and sockets +.SH "SYNOPSIS" +.sp +.nf +// This is a stable class, and may not change except for emergencies\&. It +// is provided in stable builds\&. +// This class has draft methods, which may change over time\&. They are not +// in stable releases, by default\&. Use \-\-enable\-drafts to enable\&. +// Create a new socket\&. Returns the new socket, or NULL if the new socket +// could not be created\&. Note that the symbol zsock_new (and other +// constructors/destructors for zsock) are redirected to the *_checked +// variant, enabling intelligent socket leak detection\&. This can have +// performance implications if you use a LOT of sockets\&. To turn off this +// redirection behaviour, define ZSOCK_NOCHECK\&. +CZMQ_EXPORT zsock_t * + zsock_new (int type); + +// Create a PUB socket\&. Default action is bind\&. +CZMQ_EXPORT zsock_t * + zsock_new_pub (const char *endpoint); + +// Create a SUB socket, and optionally subscribe to some prefix string\&. Default +// action is connect\&. +CZMQ_EXPORT zsock_t * + zsock_new_sub (const char *endpoint, const char *subscribe); + +// Create a REQ socket\&. Default action is connect\&. +CZMQ_EXPORT zsock_t * + zsock_new_req (const char *endpoint); + +// Create a REP socket\&. Default action is bind\&. +CZMQ_EXPORT zsock_t * + zsock_new_rep (const char *endpoint); + +// Create a DEALER socket\&. Default action is connect\&. +CZMQ_EXPORT zsock_t * + zsock_new_dealer (const char *endpoint); + +// Create a ROUTER socket\&. Default action is bind\&. +CZMQ_EXPORT zsock_t * + zsock_new_router (const char *endpoint); + +// Create a PUSH socket\&. Default action is connect\&. +CZMQ_EXPORT zsock_t * + zsock_new_push (const char *endpoint); + +// Create a PULL socket\&. Default action is bind\&. +CZMQ_EXPORT zsock_t * + zsock_new_pull (const char *endpoint); + +// Create an XPUB socket\&. Default action is bind\&. +CZMQ_EXPORT zsock_t * + zsock_new_xpub (const char *endpoint); + +// Create an XSUB socket\&. Default action is connect\&. +CZMQ_EXPORT zsock_t * + zsock_new_xsub (const char *endpoint); + +// Create a PAIR socket\&. Default action is connect\&. +CZMQ_EXPORT zsock_t * + zsock_new_pair (const char *endpoint); + +// Create a STREAM socket\&. Default action is connect\&. +CZMQ_EXPORT zsock_t * + zsock_new_stream (const char *endpoint); + +// Destroy the socket\&. You must use this for any socket created via the +// zsock_new method\&. +CZMQ_EXPORT void + zsock_destroy (zsock_t **self_p); + +// Bind a socket to a formatted endpoint\&. For tcp:// endpoints, supports +// ephemeral ports, if you specify the port number as "*"\&. By default +// zsock uses the IANA designated range from C000 (49152) to FFFF (65535)\&. +// To override this range, follow the "*" with "[first\-last]"\&. Either or +// both first and last may be empty\&. To bind to a random port within the +// range, use "!" in place of "*"\&. +// +// Examples: +// tcp://127\&.0\&.0\&.1:* bind to first free port from C000 up +// tcp://127\&.0\&.0\&.1:! bind to random port from C000 to FFFF +// tcp://127\&.0\&.0\&.1:*[60000\-] bind to first free port from 60000 up +// tcp://127\&.0\&.0\&.1:![\-60000] bind to random port from C000 to 60000 +// tcp://127\&.0\&.0\&.1:![55000\-55999] +// bind to random port from 55000 to 55999 +// +// On success, returns the actual port number used, for tcp:// endpoints, +// and 0 for other transports\&. On failure, returns \-1\&. Note that when using +// ephemeral ports, a port may be reused by different services without +// clients being aware\&. Protocols that run on ephemeral ports should take +// this into account\&. +CZMQ_EXPORT int + zsock_bind (zsock_t *self, const char *format, \&.\&.\&.) CHECK_PRINTF (2); + +// Returns last bound endpoint, if any\&. +CZMQ_EXPORT const char * + zsock_endpoint (zsock_t *self); + +// Unbind a socket from a formatted endpoint\&. +// Returns 0 if OK, \-1 if the endpoint was invalid or the function +// isn\*(Aqt supported\&. +CZMQ_EXPORT int + zsock_unbind (zsock_t *self, const char *format, \&.\&.\&.) CHECK_PRINTF (2); + +// Connect a socket to a formatted endpoint +// Returns 0 if OK, \-1 if the endpoint was invalid\&. +CZMQ_EXPORT int + zsock_connect (zsock_t *self, const char *format, \&.\&.\&.) CHECK_PRINTF (2); + +// Disconnect a socket from a formatted endpoint +// Returns 0 if OK, \-1 if the endpoint was invalid or the function +// isn\*(Aqt supported\&. +CZMQ_EXPORT int + zsock_disconnect (zsock_t *self, const char *format, \&.\&.\&.) CHECK_PRINTF (2); + +// Attach a socket to zero or more endpoints\&. If endpoints is not null, +// parses as list of ZeroMQ endpoints, separated by commas, and prefixed by +// \*(Aq@\*(Aq (to bind the socket) or \*(Aq>\*(Aq (to connect the socket)\&. Returns 0 if all +// endpoints were valid, or \-1 if there was a syntax error\&. If the endpoint +// does not start with \*(Aq@\*(Aq or \*(Aq>\*(Aq, the serverish argument defines whether +// it is used to bind (serverish = true) or connect (serverish = false)\&. +CZMQ_EXPORT int + zsock_attach (zsock_t *self, const char *endpoints, bool serverish); + +// Returns socket type as printable constant string\&. +CZMQ_EXPORT const char * + zsock_type_str (zsock_t *self); + +// Send a \*(Aqpicture\*(Aq message to the socket (or actor)\&. The picture is a +// string that defines the type of each frame\&. This makes it easy to send +// a complex multiframe message in one call\&. The picture can contain any +// of these characters, each corresponding to one or two arguments: +// +// i = int (signed) +// 1 = uint8_t +// 2 = uint16_t +// 4 = uint32_t +// 8 = uint64_t +// s = char * +// b = byte *, size_t (2 arguments) +// c = zchunk_t * +// f = zframe_t * +// h = zhashx_t * +// U = zuuid_t * +// p = void * (sends the pointer value, only meaningful over inproc) +// m = zmsg_t * (sends all frames in the zmsg) +// z = sends zero\-sized frame (0 arguments) +// u = uint (deprecated) +// +// Note that s, b, c, and f are encoded the same way and the choice is +// offered as a convenience to the sender, which may or may not already +// have data in a zchunk or zframe\&. Does not change or take ownership of +// any arguments\&. Returns 0 if successful, \-1 if sending failed for any +// reason\&. +CZMQ_EXPORT int + zsock_send (void *self, const char *picture, \&.\&.\&.); + +// Send a \*(Aqpicture\*(Aq message to the socket (or actor)\&. This is a va_list +// version of zsock_send (), so please consult its documentation for the +// details\&. +CZMQ_EXPORT int + zsock_vsend (void *self, const char *picture, va_list argptr); + +// Receive a \*(Aqpicture\*(Aq message to the socket (or actor)\&. See zsock_send for +// the format and meaning of the picture\&. Returns the picture elements into +// a series of pointers as provided by the caller: +// +// i = int * (stores signed integer) +// 4 = uint32_t * (stores 32\-bit unsigned integer) +// 8 = uint64_t * (stores 64\-bit unsigned integer) +// s = char ** (allocates new string) +// b = byte **, size_t * (2 arguments) (allocates memory) +// c = zchunk_t ** (creates zchunk) +// f = zframe_t ** (creates zframe) +// U = zuuid_t * (creates a zuuid with the data) +// h = zhashx_t ** (creates zhashx) +// p = void ** (stores pointer) +// m = zmsg_t ** (creates a zmsg with the remaing frames) +// z = null, asserts empty frame (0 arguments) +// u = uint * (stores unsigned integer, deprecated) +// +// Note that zsock_recv creates the returned objects, and the caller must +// destroy them when finished with them\&. The supplied pointers do not need +// to be initialized\&. Returns 0 if successful, or \-1 if it failed to recv +// a message, in which case the pointers are not modified\&. When message +// frames are truncated (a short message), sets return values to zero/null\&. +// If an argument pointer is NULL, does not store any value (skips it)\&. +// An \*(Aqn\*(Aq picture matches an empty frame; if the message does not match, +// the method will return \-1\&. +CZMQ_EXPORT int + zsock_recv (void *self, const char *picture, \&.\&.\&.); + +// Receive a \*(Aqpicture\*(Aq message from the socket (or actor)\&. This is a +// va_list version of zsock_recv (), so please consult its documentation +// for the details\&. +CZMQ_EXPORT int + zsock_vrecv (void *self, const char *picture, va_list argptr); + +// Send a binary encoded \*(Aqpicture\*(Aq message to the socket (or actor)\&. This +// method is similar to zsock_send, except the arguments are encoded in a +// binary format that is compatible with zproto, and is designed to reduce +// memory allocations\&. The pattern argument is a string that defines the +// type of each argument\&. Supports these argument types: +// +// pattern C type zproto type: +// 1 uint8_t type = "number" size = "1" +// 2 uint16_t type = "number" size = "2" +// 4 uint32_t type = "number" size = "3" +// 8 uint64_t type = "number" size = "4" +// s char *, 0\-255 chars type = "string" +// S char *, 0\-2^32\-1 chars type = "longstr" +// c zchunk_t * type = "chunk" +// f zframe_t * type = "frame" +// u zuuid_t * type = "uuid" +// m zmsg_t * type = "msg" +// p void *, sends pointer value, only over inproc +// +// Does not change or take ownership of any arguments\&. Returns 0 if +// successful, \-1 if sending failed for any reason\&. +CZMQ_EXPORT int + zsock_bsend (void *self, const char *picture, \&.\&.\&.); + +// Receive a binary encoded \*(Aqpicture\*(Aq message from the socket (or actor)\&. +// This method is similar to zsock_recv, except the arguments are encoded +// in a binary format that is compatible with zproto, and is designed to +// reduce memory allocations\&. The pattern argument is a string that defines +// the type of each argument\&. See zsock_bsend for the supported argument +// types\&. All arguments must be pointers; this call sets them to point to +// values held on a per\-socket basis\&. +// Note that zsock_brecv creates the returned objects, and the caller must +// destroy them when finished with them\&. The supplied pointers do not need +// to be initialized\&. Returns 0 if successful, or \-1 if it failed to read +// a message\&. +CZMQ_EXPORT int + zsock_brecv (void *self, const char *picture, \&.\&.\&.); + +// Set socket to use unbounded pipes (HWM=0); use this in cases when you are +// totally certain the message volume can fit in memory\&. This method works +// across all versions of ZeroMQ\&. Takes a polymorphic socket reference\&. +CZMQ_EXPORT void + zsock_set_unbounded (void *self); + +// Send a signal over a socket\&. A signal is a short message carrying a +// success/failure code (by convention, 0 means OK)\&. Signals are encoded +// to be distinguishable from "normal" messages\&. Accepts a zsock_t or a +// zactor_t argument, and returns 0 if successful, \-1 if the signal could +// not be sent\&. Takes a polymorphic socket reference\&. +CZMQ_EXPORT int + zsock_signal (void *self, byte status); + +// Wait on a signal\&. Use this to coordinate between threads, over pipe +// pairs\&. Blocks until the signal is received\&. Returns \-1 on error, 0 or +// greater on success\&. Accepts a zsock_t or a zactor_t as argument\&. +// Takes a polymorphic socket reference\&. +CZMQ_EXPORT int + zsock_wait (void *self); + +// If there is a partial message still waiting on the socket, remove and +// discard it\&. This is useful when reading partial messages, to get specific +// message types\&. +CZMQ_EXPORT void + zsock_flush (void *self); + +// Probe the supplied object, and report if it looks like a zsock_t\&. +// Takes a polymorphic socket reference\&. +CZMQ_EXPORT bool + zsock_is (void *self); + +// Probe the supplied reference\&. If it looks like a zsock_t instance, return +// the underlying libzmq socket handle; else if it looks like a file +// descriptor, return NULL; else if it looks like a libzmq socket handle, +// return the supplied value\&. Takes a polymorphic socket reference\&. +CZMQ_EXPORT void * + zsock_resolve (void *self); + +// Get socket option `heartbeat_ivl`\&. +// Available from libzmq 4\&.2\&.0\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT int + zsock_heartbeat_ivl (void *self); + +// Set socket option `heartbeat_ivl`\&. +// Available from libzmq 4\&.2\&.0\&. +CZMQ_EXPORT void + zsock_set_heartbeat_ivl (void *self, int heartbeat_ivl); + +// Get socket option `heartbeat_ttl`\&. +// Available from libzmq 4\&.2\&.0\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT int + zsock_heartbeat_ttl (void *self); + +// Set socket option `heartbeat_ttl`\&. +// Available from libzmq 4\&.2\&.0\&. +CZMQ_EXPORT void + zsock_set_heartbeat_ttl (void *self, int heartbeat_ttl); + +// Get socket option `heartbeat_timeout`\&. +// Available from libzmq 4\&.2\&.0\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT int + zsock_heartbeat_timeout (void *self); + +// Set socket option `heartbeat_timeout`\&. +// Available from libzmq 4\&.2\&.0\&. +CZMQ_EXPORT void + zsock_set_heartbeat_timeout (void *self, int heartbeat_timeout); + +// Get socket option `use_fd`\&. +// Available from libzmq 4\&.2\&.0\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT int + zsock_use_fd (void *self); + +// Set socket option `use_fd`\&. +// Available from libzmq 4\&.2\&.0\&. +CZMQ_EXPORT void + zsock_set_use_fd (void *self, int use_fd); + +// Set socket option `xpub_manual`\&. +// Available from libzmq 4\&.2\&.0\&. +CZMQ_EXPORT void + zsock_set_xpub_manual (void *self, int xpub_manual); + +// Set socket option `xpub_welcome_msg`\&. +// Available from libzmq 4\&.2\&.0\&. +CZMQ_EXPORT void + zsock_set_xpub_welcome_msg (void *self, const char *xpub_welcome_msg); + +// Set socket option `stream_notify`\&. +// Available from libzmq 4\&.2\&.0\&. +CZMQ_EXPORT void + zsock_set_stream_notify (void *self, int stream_notify); + +// Get socket option `invert_matching`\&. +// Available from libzmq 4\&.2\&.0\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT int + zsock_invert_matching (void *self); + +// Set socket option `invert_matching`\&. +// Available from libzmq 4\&.2\&.0\&. +CZMQ_EXPORT void + zsock_set_invert_matching (void *self, int invert_matching); + +// Set socket option `xpub_verboser`\&. +// Available from libzmq 4\&.2\&.0\&. +CZMQ_EXPORT void + zsock_set_xpub_verboser (void *self, int xpub_verboser); + +// Get socket option `connect_timeout`\&. +// Available from libzmq 4\&.2\&.0\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT int + zsock_connect_timeout (void *self); + +// Set socket option `connect_timeout`\&. +// Available from libzmq 4\&.2\&.0\&. +CZMQ_EXPORT void + zsock_set_connect_timeout (void *self, int connect_timeout); + +// Get socket option `tcp_maxrt`\&. +// Available from libzmq 4\&.2\&.0\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT int + zsock_tcp_maxrt (void *self); + +// Set socket option `tcp_maxrt`\&. +// Available from libzmq 4\&.2\&.0\&. +CZMQ_EXPORT void + zsock_set_tcp_maxrt (void *self, int tcp_maxrt); + +// Get socket option `thread_safe`\&. +// Available from libzmq 4\&.2\&.0\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT int + zsock_thread_safe (void *self); + +// Get socket option `multicast_maxtpdu`\&. +// Available from libzmq 4\&.2\&.0\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT int + zsock_multicast_maxtpdu (void *self); + +// Set socket option `multicast_maxtpdu`\&. +// Available from libzmq 4\&.2\&.0\&. +CZMQ_EXPORT void + zsock_set_multicast_maxtpdu (void *self, int multicast_maxtpdu); + +// Get socket option `vmci_buffer_size`\&. +// Available from libzmq 4\&.2\&.0\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT int + zsock_vmci_buffer_size (void *self); + +// Set socket option `vmci_buffer_size`\&. +// Available from libzmq 4\&.2\&.0\&. +CZMQ_EXPORT void + zsock_set_vmci_buffer_size (void *self, int vmci_buffer_size); + +// Get socket option `vmci_buffer_min_size`\&. +// Available from libzmq 4\&.2\&.0\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT int + zsock_vmci_buffer_min_size (void *self); + +// Set socket option `vmci_buffer_min_size`\&. +// Available from libzmq 4\&.2\&.0\&. +CZMQ_EXPORT void + zsock_set_vmci_buffer_min_size (void *self, int vmci_buffer_min_size); + +// Get socket option `vmci_buffer_max_size`\&. +// Available from libzmq 4\&.2\&.0\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT int + zsock_vmci_buffer_max_size (void *self); + +// Set socket option `vmci_buffer_max_size`\&. +// Available from libzmq 4\&.2\&.0\&. +CZMQ_EXPORT void + zsock_set_vmci_buffer_max_size (void *self, int vmci_buffer_max_size); + +// Get socket option `vmci_connect_timeout`\&. +// Available from libzmq 4\&.2\&.0\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT int + zsock_vmci_connect_timeout (void *self); + +// Set socket option `vmci_connect_timeout`\&. +// Available from libzmq 4\&.2\&.0\&. +CZMQ_EXPORT void + zsock_set_vmci_connect_timeout (void *self, int vmci_connect_timeout); + +// Get socket option `tos`\&. +// Available from libzmq 4\&.1\&.0\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT int + zsock_tos (void *self); + +// Set socket option `tos`\&. +// Available from libzmq 4\&.1\&.0\&. +CZMQ_EXPORT void + zsock_set_tos (void *self, int tos); + +// Set socket option `router_handover`\&. +// Available from libzmq 4\&.1\&.0\&. +CZMQ_EXPORT void + zsock_set_router_handover (void *self, int router_handover); + +// Set socket option `connect_rid`\&. +// Available from libzmq 4\&.1\&.0\&. +CZMQ_EXPORT void + zsock_set_connect_rid (void *self, const char *connect_rid); + +// Set socket option `connect_rid` from 32\-octet binary +// Available from libzmq 4\&.1\&.0\&. +CZMQ_EXPORT void + zsock_set_connect_rid_bin (void *self, const byte *connect_rid); + +// Get socket option `handshake_ivl`\&. +// Available from libzmq 4\&.1\&.0\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT int + zsock_handshake_ivl (void *self); + +// Set socket option `handshake_ivl`\&. +// Available from libzmq 4\&.1\&.0\&. +CZMQ_EXPORT void + zsock_set_handshake_ivl (void *self, int handshake_ivl); + +// Get socket option `socks_proxy`\&. +// Available from libzmq 4\&.1\&.0\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT char * + zsock_socks_proxy (void *self); + +// Set socket option `socks_proxy`\&. +// Available from libzmq 4\&.1\&.0\&. +CZMQ_EXPORT void + zsock_set_socks_proxy (void *self, const char *socks_proxy); + +// Set socket option `xpub_nodrop`\&. +// Available from libzmq 4\&.1\&.0\&. +CZMQ_EXPORT void + zsock_set_xpub_nodrop (void *self, int xpub_nodrop); + +// Set socket option `router_mandatory`\&. +// Available from libzmq 4\&.0\&.0\&. +CZMQ_EXPORT void + zsock_set_router_mandatory (void *self, int router_mandatory); + +// Set socket option `probe_router`\&. +// Available from libzmq 4\&.0\&.0\&. +CZMQ_EXPORT void + zsock_set_probe_router (void *self, int probe_router); + +// Set socket option `req_relaxed`\&. +// Available from libzmq 4\&.0\&.0\&. +CZMQ_EXPORT void + zsock_set_req_relaxed (void *self, int req_relaxed); + +// Set socket option `req_correlate`\&. +// Available from libzmq 4\&.0\&.0\&. +CZMQ_EXPORT void + zsock_set_req_correlate (void *self, int req_correlate); + +// Set socket option `conflate`\&. +// Available from libzmq 4\&.0\&.0\&. +CZMQ_EXPORT void + zsock_set_conflate (void *self, int conflate); + +// Get socket option `zap_domain`\&. +// Available from libzmq 4\&.0\&.0\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT char * + zsock_zap_domain (void *self); + +// Set socket option `zap_domain`\&. +// Available from libzmq 4\&.0\&.0\&. +CZMQ_EXPORT void + zsock_set_zap_domain (void *self, const char *zap_domain); + +// Get socket option `mechanism`\&. +// Available from libzmq 4\&.0\&.0\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT int + zsock_mechanism (void *self); + +// Get socket option `plain_server`\&. +// Available from libzmq 4\&.0\&.0\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT int + zsock_plain_server (void *self); + +// Set socket option `plain_server`\&. +// Available from libzmq 4\&.0\&.0\&. +CZMQ_EXPORT void + zsock_set_plain_server (void *self, int plain_server); + +// Get socket option `plain_username`\&. +// Available from libzmq 4\&.0\&.0\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT char * + zsock_plain_username (void *self); + +// Set socket option `plain_username`\&. +// Available from libzmq 4\&.0\&.0\&. +CZMQ_EXPORT void + zsock_set_plain_username (void *self, const char *plain_username); + +// Get socket option `plain_password`\&. +// Available from libzmq 4\&.0\&.0\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT char * + zsock_plain_password (void *self); + +// Set socket option `plain_password`\&. +// Available from libzmq 4\&.0\&.0\&. +CZMQ_EXPORT void + zsock_set_plain_password (void *self, const char *plain_password); + +// Get socket option `curve_server`\&. +// Available from libzmq 4\&.0\&.0\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT int + zsock_curve_server (void *self); + +// Set socket option `curve_server`\&. +// Available from libzmq 4\&.0\&.0\&. +CZMQ_EXPORT void + zsock_set_curve_server (void *self, int curve_server); + +// Get socket option `curve_publickey`\&. +// Available from libzmq 4\&.0\&.0\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT char * + zsock_curve_publickey (void *self); + +// Set socket option `curve_publickey`\&. +// Available from libzmq 4\&.0\&.0\&. +CZMQ_EXPORT void + zsock_set_curve_publickey (void *self, const char *curve_publickey); + +// Set socket option `curve_publickey` from 32\-octet binary +// Available from libzmq 4\&.0\&.0\&. +CZMQ_EXPORT void + zsock_set_curve_publickey_bin (void *self, const byte *curve_publickey); + +// Get socket option `curve_secretkey`\&. +// Available from libzmq 4\&.0\&.0\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT char * + zsock_curve_secretkey (void *self); + +// Set socket option `curve_secretkey`\&. +// Available from libzmq 4\&.0\&.0\&. +CZMQ_EXPORT void + zsock_set_curve_secretkey (void *self, const char *curve_secretkey); + +// Set socket option `curve_secretkey` from 32\-octet binary +// Available from libzmq 4\&.0\&.0\&. +CZMQ_EXPORT void + zsock_set_curve_secretkey_bin (void *self, const byte *curve_secretkey); + +// Get socket option `curve_serverkey`\&. +// Available from libzmq 4\&.0\&.0\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT char * + zsock_curve_serverkey (void *self); + +// Set socket option `curve_serverkey`\&. +// Available from libzmq 4\&.0\&.0\&. +CZMQ_EXPORT void + zsock_set_curve_serverkey (void *self, const char *curve_serverkey); + +// Set socket option `curve_serverkey` from 32\-octet binary +// Available from libzmq 4\&.0\&.0\&. +CZMQ_EXPORT void + zsock_set_curve_serverkey_bin (void *self, const byte *curve_serverkey); + +// Get socket option `gssapi_server`\&. +// Available from libzmq 4\&.0\&.0\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT int + zsock_gssapi_server (void *self); + +// Set socket option `gssapi_server`\&. +// Available from libzmq 4\&.0\&.0\&. +CZMQ_EXPORT void + zsock_set_gssapi_server (void *self, int gssapi_server); + +// Get socket option `gssapi_plaintext`\&. +// Available from libzmq 4\&.0\&.0\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT int + zsock_gssapi_plaintext (void *self); + +// Set socket option `gssapi_plaintext`\&. +// Available from libzmq 4\&.0\&.0\&. +CZMQ_EXPORT void + zsock_set_gssapi_plaintext (void *self, int gssapi_plaintext); + +// Get socket option `gssapi_principal`\&. +// Available from libzmq 4\&.0\&.0\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT char * + zsock_gssapi_principal (void *self); + +// Set socket option `gssapi_principal`\&. +// Available from libzmq 4\&.0\&.0\&. +CZMQ_EXPORT void + zsock_set_gssapi_principal (void *self, const char *gssapi_principal); + +// Get socket option `gssapi_service_principal`\&. +// Available from libzmq 4\&.0\&.0\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT char * + zsock_gssapi_service_principal (void *self); + +// Set socket option `gssapi_service_principal`\&. +// Available from libzmq 4\&.0\&.0\&. +CZMQ_EXPORT void + zsock_set_gssapi_service_principal (void *self, const char *gssapi_service_principal); + +// Get socket option `ipv6`\&. +// Available from libzmq 4\&.0\&.0\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT int + zsock_ipv6 (void *self); + +// Set socket option `ipv6`\&. +// Available from libzmq 4\&.0\&.0\&. +CZMQ_EXPORT void + zsock_set_ipv6 (void *self, int ipv6); + +// Get socket option `immediate`\&. +// Available from libzmq 4\&.0\&.0\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT int + zsock_immediate (void *self); + +// Set socket option `immediate`\&. +// Available from libzmq 4\&.0\&.0\&. +CZMQ_EXPORT void + zsock_set_immediate (void *self, int immediate); + +// Get socket option `type`\&. +// Available from libzmq 3\&.0\&.0\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT int + zsock_type (void *self); + +// Get socket option `sndhwm`\&. +// Available from libzmq 3\&.0\&.0\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT int + zsock_sndhwm (void *self); + +// Set socket option `sndhwm`\&. +// Available from libzmq 3\&.0\&.0\&. +CZMQ_EXPORT void + zsock_set_sndhwm (void *self, int sndhwm); + +// Get socket option `rcvhwm`\&. +// Available from libzmq 3\&.0\&.0\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT int + zsock_rcvhwm (void *self); + +// Set socket option `rcvhwm`\&. +// Available from libzmq 3\&.0\&.0\&. +CZMQ_EXPORT void + zsock_set_rcvhwm (void *self, int rcvhwm); + +// Get socket option `affinity`\&. +// Available from libzmq 3\&.0\&.0\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT int + zsock_affinity (void *self); + +// Set socket option `affinity`\&. +// Available from libzmq 3\&.0\&.0\&. +CZMQ_EXPORT void + zsock_set_affinity (void *self, int affinity); + +// Set socket option `subscribe`\&. +// Available from libzmq 3\&.0\&.0\&. +CZMQ_EXPORT void + zsock_set_subscribe (void *self, const char *subscribe); + +// Set socket option `unsubscribe`\&. +// Available from libzmq 3\&.0\&.0\&. +CZMQ_EXPORT void + zsock_set_unsubscribe (void *self, const char *unsubscribe); + +// Get socket option `identity`\&. +// Available from libzmq 3\&.0\&.0\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT char * + zsock_identity (void *self); + +// Set socket option `identity`\&. +// Available from libzmq 3\&.0\&.0\&. +CZMQ_EXPORT void + zsock_set_identity (void *self, const char *identity); + +// Get socket option `rate`\&. +// Available from libzmq 3\&.0\&.0\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT int + zsock_rate (void *self); + +// Set socket option `rate`\&. +// Available from libzmq 3\&.0\&.0\&. +CZMQ_EXPORT void + zsock_set_rate (void *self, int rate); + +// Get socket option `recovery_ivl`\&. +// Available from libzmq 3\&.0\&.0\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT int + zsock_recovery_ivl (void *self); + +// Set socket option `recovery_ivl`\&. +// Available from libzmq 3\&.0\&.0\&. +CZMQ_EXPORT void + zsock_set_recovery_ivl (void *self, int recovery_ivl); + +// Get socket option `sndbuf`\&. +// Available from libzmq 3\&.0\&.0\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT int + zsock_sndbuf (void *self); + +// Set socket option `sndbuf`\&. +// Available from libzmq 3\&.0\&.0\&. +CZMQ_EXPORT void + zsock_set_sndbuf (void *self, int sndbuf); + +// Get socket option `rcvbuf`\&. +// Available from libzmq 3\&.0\&.0\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT int + zsock_rcvbuf (void *self); + +// Set socket option `rcvbuf`\&. +// Available from libzmq 3\&.0\&.0\&. +CZMQ_EXPORT void + zsock_set_rcvbuf (void *self, int rcvbuf); + +// Get socket option `linger`\&. +// Available from libzmq 3\&.0\&.0\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT int + zsock_linger (void *self); + +// Set socket option `linger`\&. +// Available from libzmq 3\&.0\&.0\&. +CZMQ_EXPORT void + zsock_set_linger (void *self, int linger); + +// Get socket option `reconnect_ivl`\&. +// Available from libzmq 3\&.0\&.0\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT int + zsock_reconnect_ivl (void *self); + +// Set socket option `reconnect_ivl`\&. +// Available from libzmq 3\&.0\&.0\&. +CZMQ_EXPORT void + zsock_set_reconnect_ivl (void *self, int reconnect_ivl); + +// Get socket option `reconnect_ivl_max`\&. +// Available from libzmq 3\&.0\&.0\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT int + zsock_reconnect_ivl_max (void *self); + +// Set socket option `reconnect_ivl_max`\&. +// Available from libzmq 3\&.0\&.0\&. +CZMQ_EXPORT void + zsock_set_reconnect_ivl_max (void *self, int reconnect_ivl_max); + +// Get socket option `backlog`\&. +// Available from libzmq 3\&.0\&.0\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT int + zsock_backlog (void *self); + +// Set socket option `backlog`\&. +// Available from libzmq 3\&.0\&.0\&. +CZMQ_EXPORT void + zsock_set_backlog (void *self, int backlog); + +// Get socket option `maxmsgsize`\&. +// Available from libzmq 3\&.0\&.0\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT int + zsock_maxmsgsize (void *self); + +// Set socket option `maxmsgsize`\&. +// Available from libzmq 3\&.0\&.0\&. +CZMQ_EXPORT void + zsock_set_maxmsgsize (void *self, int maxmsgsize); + +// Get socket option `multicast_hops`\&. +// Available from libzmq 3\&.0\&.0\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT int + zsock_multicast_hops (void *self); + +// Set socket option `multicast_hops`\&. +// Available from libzmq 3\&.0\&.0\&. +CZMQ_EXPORT void + zsock_set_multicast_hops (void *self, int multicast_hops); + +// Get socket option `rcvtimeo`\&. +// Available from libzmq 3\&.0\&.0\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT int + zsock_rcvtimeo (void *self); + +// Set socket option `rcvtimeo`\&. +// Available from libzmq 3\&.0\&.0\&. +CZMQ_EXPORT void + zsock_set_rcvtimeo (void *self, int rcvtimeo); + +// Get socket option `sndtimeo`\&. +// Available from libzmq 3\&.0\&.0\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT int + zsock_sndtimeo (void *self); + +// Set socket option `sndtimeo`\&. +// Available from libzmq 3\&.0\&.0\&. +CZMQ_EXPORT void + zsock_set_sndtimeo (void *self, int sndtimeo); + +// Set socket option `xpub_verbose`\&. +// Available from libzmq 3\&.0\&.0\&. +CZMQ_EXPORT void + zsock_set_xpub_verbose (void *self, int xpub_verbose); + +// Get socket option `tcp_keepalive`\&. +// Available from libzmq 3\&.0\&.0\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT int + zsock_tcp_keepalive (void *self); + +// Set socket option `tcp_keepalive`\&. +// Available from libzmq 3\&.0\&.0\&. +CZMQ_EXPORT void + zsock_set_tcp_keepalive (void *self, int tcp_keepalive); + +// Get socket option `tcp_keepalive_idle`\&. +// Available from libzmq 3\&.0\&.0\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT int + zsock_tcp_keepalive_idle (void *self); + +// Set socket option `tcp_keepalive_idle`\&. +// Available from libzmq 3\&.0\&.0\&. +CZMQ_EXPORT void + zsock_set_tcp_keepalive_idle (void *self, int tcp_keepalive_idle); + +// Get socket option `tcp_keepalive_cnt`\&. +// Available from libzmq 3\&.0\&.0\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT int + zsock_tcp_keepalive_cnt (void *self); + +// Set socket option `tcp_keepalive_cnt`\&. +// Available from libzmq 3\&.0\&.0\&. +CZMQ_EXPORT void + zsock_set_tcp_keepalive_cnt (void *self, int tcp_keepalive_cnt); + +// Get socket option `tcp_keepalive_intvl`\&. +// Available from libzmq 3\&.0\&.0\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT int + zsock_tcp_keepalive_intvl (void *self); + +// Set socket option `tcp_keepalive_intvl`\&. +// Available from libzmq 3\&.0\&.0\&. +CZMQ_EXPORT void + zsock_set_tcp_keepalive_intvl (void *self, int tcp_keepalive_intvl); + +// Get socket option `tcp_accept_filter`\&. +// Available from libzmq 3\&.0\&.0\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT char * + zsock_tcp_accept_filter (void *self); + +// Set socket option `tcp_accept_filter`\&. +// Available from libzmq 3\&.0\&.0\&. +CZMQ_EXPORT void + zsock_set_tcp_accept_filter (void *self, const char *tcp_accept_filter); + +// Get socket option `rcvmore`\&. +// Available from libzmq 3\&.0\&.0\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT int + zsock_rcvmore (void *self); + +// Get socket option `fd`\&. +// Available from libzmq 3\&.0\&.0\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT SOCKET + zsock_fd (void *self); + +// Get socket option `events`\&. +// Available from libzmq 3\&.0\&.0\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT int + zsock_events (void *self); + +// Get socket option `last_endpoint`\&. +// Available from libzmq 3\&.0\&.0\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT char * + zsock_last_endpoint (void *self); + +// Set socket option `router_raw`\&. +// Available from libzmq 3\&.0\&.0\&. +CZMQ_EXPORT void + zsock_set_router_raw (void *self, int router_raw); + +// Get socket option `ipv4only`\&. +// Available from libzmq 3\&.0\&.0\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT int + zsock_ipv4only (void *self); + +// Set socket option `ipv4only`\&. +// Available from libzmq 3\&.0\&.0\&. +CZMQ_EXPORT void + zsock_set_ipv4only (void *self, int ipv4only); + +// Set socket option `delay_attach_on_connect`\&. +// Available from libzmq 3\&.0\&.0\&. +CZMQ_EXPORT void + zsock_set_delay_attach_on_connect (void *self, int delay_attach_on_connect); + +// Self test of this class\&. +CZMQ_EXPORT void + zsock_test (bool verbose); + +#ifdef CZMQ_BUILD_DRAFT_API +// *** Draft method, for development use, may change without warning *** +// Create a SERVER socket\&. Default action is bind\&. +CZMQ_EXPORT zsock_t * + zsock_new_server (const char *endpoint); + +// *** Draft method, for development use, may change without warning *** +// Create a CLIENT socket\&. Default action is connect\&. +CZMQ_EXPORT zsock_t * + zsock_new_client (const char *endpoint); + +// *** Draft method, for development use, may change without warning *** +// Create a RADIO socket\&. Default action is bind\&. +CZMQ_EXPORT zsock_t * + zsock_new_radio (const char *endpoint); + +// *** Draft method, for development use, may change without warning *** +// Create a DISH socket\&. Default action is connect\&. +CZMQ_EXPORT zsock_t * + zsock_new_dish (const char *endpoint); + +// *** Draft method, for development use, may change without warning *** +// Create a GATHER socket\&. Default action is bind\&. +CZMQ_EXPORT zsock_t * + zsock_new_gather (const char *endpoint); + +// *** Draft method, for development use, may change without warning *** +// Create a SCATTER socket\&. Default action is connect\&. +CZMQ_EXPORT zsock_t * + zsock_new_scatter (const char *endpoint); + +// *** Draft method, for development use, may change without warning *** +// Return socket routing ID if any\&. This returns 0 if the socket is not +// of type ZMQ_SERVER or if no request was already received on it\&. +CZMQ_EXPORT uint32_t + zsock_routing_id (zsock_t *self); + +// *** Draft method, for development use, may change without warning *** +// Set routing ID on socket\&. The socket MUST be of type ZMQ_SERVER\&. +// This will be used when sending messages on the socket via the zsock API\&. +CZMQ_EXPORT void + zsock_set_routing_id (zsock_t *self, uint32_t routing_id); + +// *** Draft method, for development use, may change without warning *** +// Join a group for the RADIO\-DISH pattern\&. Call only on ZMQ_DISH\&. +// Returns 0 if OK, \-1 if failed\&. +CZMQ_EXPORT int + zsock_join (void *self, const char *group); + +// *** Draft method, for development use, may change without warning *** +// Leave a group for the RADIO\-DISH pattern\&. Call only on ZMQ_DISH\&. +// Returns 0 if OK, \-1 if failed\&. +CZMQ_EXPORT int + zsock_leave (void *self, const char *group); + +#endif // CZMQ_BUILD_DRAFT_API +Please add \*(Aq@interface\*(Aq section in \*(Aq\&./\&.\&./src/zsock\&.c\*(Aq\&. +.fi +.SH "DESCRIPTION" +.sp +The zsock class wraps the libzmq socket handle (a void *) with a proper structure that follows the CLASS rules for construction and destruction\&. Some zsock methods take a void * "polymorphic" reference, which can be either a zsock_t or a zactor_t reference, or a libzmq void *\&. +.sp +Please add \fI@discuss\fR section in \fI\&./\&.\&./src/zsock\&.c\fR\&. +.SH "EXAMPLE" +.PP +\fBFrom zsock_test method\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +zsock_t *writer = zsock_new_push ("@tcp://127\&.0\&.0\&.1:5560"); +assert (writer); +assert (zsock_resolve (writer) != writer); +assert (streq (zsock_type_str (writer), "PUSH")); + +int rc; +#if (ZMQ_VERSION >= ZMQ_MAKE_VERSION (3, 2, 0)) +// Check unbind +rc = zsock_unbind (writer, "tcp://127\&.0\&.0\&.1:%d", 5560); +assert (rc == 0); + +// In some cases and especially when running under Valgrind, doing +// a bind immediately after an unbind causes an EADDRINUSE error\&. +// Even a short sleep allows the OS to release the port for reuse\&. +zclock_sleep (100); + +// Bind again +rc = zsock_bind (writer, "tcp://127\&.0\&.0\&.1:%d", 5560); +assert (rc == 5560); +assert (streq (zsock_endpoint (writer), "tcp://127\&.0\&.0\&.1:5560")); +#endif + +zsock_t *reader = zsock_new_pull (">tcp://127\&.0\&.0\&.1:5560"); +assert (reader); +assert (zsock_resolve (reader) != reader); +assert (streq (zsock_type_str (reader), "PULL")); + +// Basic Hello, World +zstr_send (writer, "Hello, World"); +zmsg_t *msg = zmsg_recv (reader); +assert (msg); +char *string = zmsg_popstr (msg); +assert (streq (string, "Hello, World")); +free (string); +zmsg_destroy (&msg); + +// Test resolve libzmq socket +#if (ZMQ_VERSION >= ZMQ_MAKE_VERSION (3, 2, 0)) +void *zmq_ctx = zmq_ctx_new (); +#else +void *zmq_ctx = zmq_ctx_new (1); +#endif +assert (zmq_ctx); +void *zmq_sock = zmq_socket (zmq_ctx, ZMQ_PUB); +assert (zmq_sock); +assert (zsock_resolve (zmq_sock) == zmq_sock); +zmq_close (zmq_sock); +zmq_ctx_term (zmq_ctx); + +// Test resolve zsock +zsock_t *resolve = zsock_new_pub("@tcp://127\&.0\&.0\&.1:5561"); +assert (resolve); +assert (zsock_resolve (resolve) == resolve\->handle); +zsock_destroy (&resolve); + +// Test resolve FD +SOCKET fd = zsock_fd (reader); +assert (zsock_resolve ((void *) &fd) == NULL); + +// Test binding to ephemeral ports, sequential and random +int port = zsock_bind (writer, "tcp://127\&.0\&.0\&.1:*"); +assert (port >= DYNAMIC_FIRST && port <= DYNAMIC_LAST); +port = zsock_bind (writer, "tcp://127\&.0\&.0\&.1:*[50000\-]"); +assert (port >= 50000 && port <= DYNAMIC_LAST); +port = zsock_bind (writer, "tcp://127\&.0\&.0\&.1:*[\-50001]"); +assert (port >= DYNAMIC_FIRST && port <= 50001); +port = zsock_bind (writer, "tcp://127\&.0\&.0\&.1:*[60000\-60050]"); +assert (port >= 60000 && port <= 60050); + +port = zsock_bind (writer, "tcp://127\&.0\&.0\&.1:!"); +assert (port >= DYNAMIC_FIRST && port <= DYNAMIC_LAST); +port = zsock_bind (writer, "tcp://127\&.0\&.0\&.1:![50000\-]"); +assert (port >= 50000 && port <= DYNAMIC_LAST); +port = zsock_bind (writer, "tcp://127\&.0\&.0\&.1:![\-50001]"); +assert (port >= DYNAMIC_FIRST && port <= 50001); +port = zsock_bind (writer, "tcp://127\&.0\&.0\&.1:![60000\-60050]"); +assert (port >= 60000 && port <= 60050); + +// Test zsock_attach method +zsock_t *server = zsock_new (ZMQ_DEALER); +assert (server); +rc = zsock_attach (server, "@inproc://myendpoint,tcp://127\&.0\&.0\&.1:5556,inproc://others", true); +assert (rc == 0); +rc = zsock_attach (server, "", false); +assert (rc == 0); +rc = zsock_attach (server, NULL, true); +assert (rc == 0); +rc = zsock_attach (server, ">a,@b, c,, ", false); +assert (rc == \-1); +zsock_destroy (&server); + +// Test zsock_endpoint method +rc = zsock_bind (writer, "inproc://test\&.%s", "writer"); +assert (rc == 0); +assert (streq (zsock_endpoint (writer), "inproc://test\&.writer")); + +// Test error state when connecting to an invalid socket type +// (\*(Aqtxp://\*(Aq instead of \*(Aqtcp://\*(Aq, typo intentional) +rc = zsock_connect (reader, "txp://127\&.0\&.0\&.1:5560"); +assert (rc == \-1); + +// Test signal/wait methods +rc = zsock_signal (writer, 123); +assert (rc == 0); +rc = zsock_wait (reader); +assert (rc == 123); + +// Test zsock_send/recv pictures +uint8_t number1 = 123; +uint16_t number2 = 123 * 123; +uint32_t number4 = 123 * 123; +number4 *= 123; +uint32_t number4_MAX = UINT32_MAX; +uint64_t number8 = 123 * 123; +number8 *= 123; +number8 *= 123; +uint64_t number8_MAX = UINT64_MAX; + +zchunk_t *chunk = zchunk_new ("HELLO", 5); +assert (chunk); +zframe_t *frame = zframe_new ("WORLD", 5); +assert (frame); +zhashx_t *hash = zhashx_new (); +assert (hash); +zuuid_t *uuid = zuuid_new (); +assert (uuid); +zhashx_set_destructor (hash, (zhashx_destructor_fn *) zstr_free); +zhashx_set_duplicator (hash, (zhashx_duplicator_fn *) strdup); +zhashx_insert (hash, "1", "value A"); +zhashx_insert (hash, "2", "value B"); +char *original = "pointer"; + +// Test zsock_recv into each supported type +zsock_send (writer, "i124488zsbcfUhp", + \-12345, number1, number2, number4, number4_MAX, + number8, number8_MAX, + "This is a string", "ABCDE", 5, + chunk, frame, uuid, hash, original); +char *uuid_str = strdup (zuuid_str (uuid)); +zchunk_destroy (&chunk); +zframe_destroy (&frame); +zuuid_destroy (&uuid); +zhashx_destroy (&hash); + +int integer; +byte *data; +size_t size; +char *pointer; +number8_MAX = number8 = number4_MAX = number4 = number2 = number1 = 0ULL; +rc = zsock_recv (reader, "i124488zsbcfUhp", + &integer, &number1, &number2, &number4, &number4_MAX, + &number8, &number8_MAX, &string, &data, &size, &chunk, + &frame, &uuid, &hash, &pointer); +assert (rc == 0); +assert (integer == \-12345); +assert (number1 == 123); +assert (number2 == 123 * 123); +assert (number4 == 123 * 123 * 123); +assert (number4_MAX == UINT32_MAX); +assert (number8 == 123 * 123 * 123 * 123); +assert (number8_MAX == UINT64_MAX); +assert (streq (string, "This is a string")); +assert (memcmp (data, "ABCDE", 5) == 0); +assert (size == 5); +assert (memcmp (zchunk_data (chunk), "HELLO", 5) == 0); +assert (zchunk_size (chunk) == 5); +assert (streq (uuid_str, zuuid_str (uuid))); +assert (memcmp (zframe_data (frame), "WORLD", 5) == 0); +assert (zframe_size (frame) == 5); +char *value = (char *) zhashx_lookup (hash, "1"); +assert (streq (value, "value A")); +value = (char *) zhashx_lookup (hash, "2"); +assert (streq (value, "value B")); +assert (original == pointer); +free (string); +free (data); +free (uuid_str); +zframe_destroy (&frame); +zchunk_destroy (&chunk); +zhashx_destroy (&hash); +zuuid_destroy (&uuid); + +// Test zsock_recv of short message; this lets us return a failure +// with a status code and then nothing else; the receiver will get +// the status code and NULL/zero for all other values +zsock_send (writer, "i", \-1); +zsock_recv (reader, "izsbcfp", + &integer, &string, &data, &size, &chunk, &frame, &pointer); +assert (integer == \-1); +assert (string == NULL); +assert (data == NULL); +assert (size == 0); +assert (chunk == NULL); +assert (frame == NULL); +assert (pointer == NULL); + +msg = zmsg_new (); +zmsg_addstr (msg, "frame 1"); +zmsg_addstr (msg, "frame 2"); +zsock_send (writer, "szm", "header", msg); +zmsg_destroy (&msg); + +zsock_recv (reader, "szm", &string, &msg); + +assert (streq ("header", string)); +assert (zmsg_size (msg) == 2); +assert (zframe_streq (zmsg_first (msg), "frame 1")); +assert (zframe_streq (zmsg_next (msg), "frame 2")); +zstr_free (&string); +zmsg_destroy (&msg); + +// Test zsock_recv with null arguments +chunk = zchunk_new ("HELLO", 5); +assert (chunk); +frame = zframe_new ("WORLD", 5); +assert (frame); +zsock_send (writer, "izsbcfp", + \-12345, "This is a string", "ABCDE", 5, chunk, frame, original); +zframe_destroy (&frame); +zchunk_destroy (&chunk); +zsock_recv (reader, "izsbcfp", &integer, NULL, NULL, NULL, &chunk, NULL, NULL); +assert (integer == \-12345); +assert (memcmp (zchunk_data (chunk), "HELLO", 5) == 0); +assert (zchunk_size (chunk) == 5); +zchunk_destroy (&chunk); + +// Test zsock_bsend/brecv pictures with binary encoding +frame = zframe_new ("Hello", 5); +chunk = zchunk_new ("World", 5); + +msg = zmsg_new (); +zmsg_addstr (msg, "Hello"); +zmsg_addstr (msg, "World"); + +zsock_bsend (writer, "1248sSpcfm", + number1, number2, number4, number8, + "Hello, World", + "Goodbye cruel World!", + original, + chunk, frame, msg); +zchunk_destroy (&chunk); +zframe_destroy (&frame); +zmsg_destroy (&msg); + +number8 = number4 = number2 = number1 = 0; +char *longstr; +zsock_brecv (reader, "1248sSpcfm", + &number1, &number2, &number4, &number8, + &string, &longstr, + &pointer, + &chunk, &frame, &msg); +assert (number1 == 123); +assert (number2 == 123 * 123); +assert (number4 == 123 * 123 * 123); +assert (number8 == 123 * 123 * 123 * 123); +assert (streq (string, "Hello, World")); +assert (streq (longstr, "Goodbye cruel World!")); +assert (pointer == original); +zstr_free (&longstr); +zchunk_destroy (&chunk); +zframe_destroy (&frame); +zmsg_destroy (&msg); + +#ifdef ZMQ_SERVER + +// Test zsock_bsend/brecv pictures with binary encoding on SERVER and CLIENT sockets +server = zsock_new_server ("tcp://127\&.0\&.0\&.1:5561"); +assert (server); +zsock_t* client = zsock_new_client ("tcp://127\&.0\&.0\&.1:5561"); +assert (client); + +// From client to server +chunk = zchunk_new ("World", 5); +zsock_bsend (client, "1248sSpc", + number1, number2, number4, number8, + "Hello, World", + "Goodbye cruel World!", + original, + chunk); +zchunk_destroy (&chunk); + +number8 = number4 = number2 = number1 = 0; +zsock_brecv (server, "1248sSpc", + &number1, &number2, &number4, &number8, + &string, &longstr, + &pointer, + &chunk); +assert (number1 == 123); +assert (number2 == 123 * 123); +assert (number4 == 123 * 123 * 123); +assert (number8 == 123 * 123 * 123 * 123); +assert (streq (string, "Hello, World")); +assert (streq (longstr, "Goodbye cruel World!")); +assert (pointer == original); +assert (zsock_routing_id (server)); +zstr_free (&longstr); +zchunk_destroy (&chunk); + +// From server to client +chunk = zchunk_new ("World", 5); +zsock_bsend (server, "1248sSpc", + number1, number2, number4, number8, + "Hello, World", + "Goodbye cruel World!", + original, + chunk); +zchunk_destroy (&chunk); + +number8 = number4 = number2 = number1 = 0; +zsock_brecv (client, "1248sSpc", + &number1, &number2, &number4, &number8, + &string, &longstr, + &pointer, + &chunk); +assert (number1 == 123); +assert (number2 == 123 * 123); +assert (number4 == 123 * 123 * 123); +assert (number8 == 123 * 123 * 123 * 123); +assert (streq (string, "Hello, World")); +assert (streq (longstr, "Goodbye cruel World!")); +assert (pointer == original); +assert (zsock_routing_id (client) == 0); +zstr_free (&longstr); +zchunk_destroy (&chunk); + +zsock_destroy (&client); +zsock_destroy (&server); + +#endif + +#ifdef ZMQ_SCATTER + +zsock_t* gather = zsock_new_gather ("inproc://test\-gather\-scatter"); +assert (gather); +zsock_t* scatter = zsock_new_scatter ("inproc://test\-gather\-scatter"); +assert (scatter); + +rc = zstr_send (scatter, "HELLO"); +assert (rc == 0); + +char* message; +message = zstr_recv (gather); +assert (streq(message, "HELLO")); +zstr_free (&message); + +zsock_destroy (&gather); +zsock_destroy (&scatter); + +#endif + +// Check that we can send a zproto format message +zsock_bsend (writer, "1111sS4", 0xAA, 0xA0, 0x02, 0x01, "key", "value", 1234); +zgossip_msg_t *gossip = zgossip_msg_new (); +zgossip_msg_recv (gossip, reader); +assert (zgossip_msg_id (gossip) == ZGOSSIP_MSG_PUBLISH); +zgossip_msg_destroy (&gossip); + +zsock_destroy (&reader); +zsock_destroy (&writer); +.fi +.if n \{\ +.RE +.\} +.sp +.SH "AUTHORS" +.sp +The czmq manual was written by the authors in the AUTHORS file\&. +.SH "RESOURCES" +.sp +Main web site: \m[blue]\fB\%\fR\m[] +.sp +Report bugs to the email <\m[blue]\fBzeromq\-dev@lists\&.zeromq\&.org\fR\m[]\&\s-2\u[1]\d\s+2> +.SH "COPYRIGHT" +.sp +Copyright (c) the Contributors as noted in the AUTHORS file\&. This file is part of CZMQ, the high\-level C binding for 0MQ: http://czmq\&.zeromq\&.org\&. This Source Code Form is subject to the terms of the Mozilla Public License, v\&. 2\&.0\&. If a copy of the MPL was not distributed with this file, You can obtain one at http://mozilla\&.org/MPL/2\&.0/\&. LICENSE included with the czmq distribution\&. +.SH "NOTES" +.IP " 1." 4 +zeromq-dev@lists.zeromq.org +.RS 4 +\%mailto:zeromq-dev@lists.zeromq.org +.RE diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zstr.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zstr.3 new file mode 100644 index 00000000000000..c4ea4275458c67 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zstr.3 @@ -0,0 +1,242 @@ +'\" t +.\" Title: zstr +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.76.1 +.\" Date: 12/31/2016 +.\" Manual: CZMQ Manual +.\" Source: CZMQ 4.0.2 +.\" Language: English +.\" +.TH "ZSTR" "3" "12/31/2016" "CZMQ 4\&.0\&.2" "CZMQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zstr \- sending and receiving strings +.SH "SYNOPSIS" +.sp +.nf +// This is a stable class, and may not change except for emergencies\&. It +// is provided in stable builds\&. +// This class has draft methods, which may change over time\&. They are not +// in stable releases, by default\&. Use \-\-enable\-drafts to enable\&. +// Receive C string from socket\&. Caller must free returned string using +// zstr_free()\&. Returns NULL if the context is being terminated or the +// process was interrupted\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT char * + zstr_recv (void *source); + +// Receive a series of strings (until NULL) from multipart data\&. +// Each string is allocated and filled with string data; if there +// are not enough frames, unallocated strings are set to NULL\&. +// Returns \-1 if the message could not be read, else returns the +// number of strings filled, zero or more\&. Free each returned string +// using zstr_free()\&. If not enough strings are provided, remaining +// multipart frames in the message are dropped\&. +CZMQ_EXPORT int + zstr_recvx (void *source, char **string_p, \&.\&.\&.); + +// Send a C string to a socket, as a frame\&. The string is sent without +// trailing null byte; to read this you can use zstr_recv, or a similar +// method that adds a null terminator on the received string\&. String +// may be NULL, which is sent as ""\&. +CZMQ_EXPORT int + zstr_send (void *dest, const char *string); + +// Send a C string to a socket, as zstr_send(), with a MORE flag, so that +// you can send further strings in the same multi\-part message\&. +CZMQ_EXPORT int + zstr_sendm (void *dest, const char *string); + +// Send a formatted string to a socket\&. Note that you should NOT use +// user\-supplied strings in the format (they may contain \*(Aq%\*(Aq which +// will create security holes)\&. +CZMQ_EXPORT int + zstr_sendf (void *dest, const char *format, \&.\&.\&.) CHECK_PRINTF (2); + +// Send a formatted string to a socket, as for zstr_sendf(), with a +// MORE flag, so that you can send further strings in the same multi\-part +// message\&. +CZMQ_EXPORT int + zstr_sendfm (void *dest, const char *format, \&.\&.\&.) CHECK_PRINTF (2); + +// Send a series of strings (until NULL) as multipart data +// Returns 0 if the strings could be sent OK, or \-1 on error\&. +CZMQ_EXPORT int + zstr_sendx (void *dest, const char *string, \&.\&.\&.); + +// Free a provided string, and nullify the parent pointer\&. Safe to call on +// a null pointer\&. +CZMQ_EXPORT void + zstr_free (char **string_p); + +// Self test of this class\&. +CZMQ_EXPORT void + zstr_test (bool verbose); + +#ifdef CZMQ_BUILD_DRAFT_API +// *** Draft method, for development use, may change without warning *** +// Accepts a void pointer and returns a fresh character string\&. If source +// is null, returns an empty string\&. +// Caller owns return value and must destroy it when done\&. +CZMQ_EXPORT char * + zstr_str (void *source); + +#endif // CZMQ_BUILD_DRAFT_API +Please add \*(Aq@interface\*(Aq section in \*(Aq\&./\&.\&./src/zstr\&.c\*(Aq\&. +.fi +.SH "DESCRIPTION" +.sp +The zstr class provides utility functions for sending and receiving C strings across 0MQ sockets\&. It sends strings without a terminating null, and appends a null byte on received strings\&. This class is for simple message sending\&. +.sp +.if n \{\ +.RS 4 +.\} +.nf + Memory Wire + +\-\-\-\-\-\-\-\-\-\-\-\-\-+\-\-\-+ +\-\-\-+\-\-\-\-\-\-\-\-\-\-\-\-\-+ +Send | S t r i n g | 0 | \-\-\-\-> | 6 | S t r i n g | + +\-\-\-\-\-\-\-\-\-\-\-\-\-+\-\-\-+ +\-\-\-+\-\-\-\-\-\-\-\-\-\-\-\-\-+ +.fi +.if n \{\ +.RE +.\} +.sp +.if n \{\ +.RS 4 +.\} +.nf + Wire Heap + +\-\-\-+\-\-\-\-\-\-\-\-\-\-\-\-\-+ +\-\-\-\-\-\-\-\-\-\-\-\-\-+\-\-\-+ +Recv | 6 | S t r i n g | \-\-\-\-> | S t r i n g | 0 | + +\-\-\-+\-\-\-\-\-\-\-\-\-\-\-\-\-+ +\-\-\-\-\-\-\-\-\-\-\-\-\-+\-\-\-+ +.fi +.if n \{\ +.RE +.\} +.SH "EXAMPLE" +.PP +\fBFrom zstr_test method\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +// Create two PAIR sockets and connect over inproc +zsock_t *output = zsock_new_pair ("@inproc://zstr\&.test"); +assert (output); +zsock_t *input = zsock_new_pair (">inproc://zstr\&.test"); +assert (input); + +// Send ten strings, five strings with MORE flag and then END +int string_nbr; +for (string_nbr = 0; string_nbr < 10; string_nbr++) + zstr_sendf (output, "this is string %d", string_nbr); +zstr_sendx (output, "This", "is", "almost", "the", "very", "END", NULL); + +// Read and count until we receive END +string_nbr = 0; +for (string_nbr = 0;; string_nbr++) { + char *string = zstr_recv (input); + assert (string); + if (streq (string, "END")) { + zstr_free (&string); + break; + } + zstr_free (&string); +} +assert (string_nbr == 15); + +zsock_destroy (&input); +zsock_destroy (&output); + +#if defined (ZMQ_SERVER) +// Test SERVER/CLIENT over zstr +zsock_t *server = zsock_new_server ("inproc://zstr\-test\-routing"); +zsock_t *client = zsock_new_client ("inproc://zstr\-test\-routing");; +assert (server); +assert (client); + +// Try normal ping\-pong to check reply routing ID +int rc = zstr_send (client, "Hello"); +assert (rc == 0); +char *request = zstr_recv (server); +assert (streq (request, "Hello")); +assert (zsock_routing_id (server)); +free (request); + +rc = zstr_send (server, "World"); +assert (rc == 0); +char *reply = zstr_recv (client); +assert (streq (reply, "World")); +free (reply); + +rc = zstr_sendf (server, "%s", "World"); +assert (rc == 0); +reply = zstr_recv (client); +assert (streq (reply, "World")); +free (reply); + +// Try ping\-pong using sendx and recx +rc = zstr_sendx (client, "Hello", NULL); +assert (rc == 0); +rc = zstr_recvx (server, &request, NULL); +assert (rc >= 0); +assert (streq (request, "Hello")); +free (request); + +rc = zstr_sendx (server, "World", NULL); +assert (rc == 0); +rc = zstr_recvx (client, &reply, NULL); +assert (rc >= 0); +assert (streq (reply, "World")); +free (reply); + +// Client and server disallow multipart +rc = zstr_sendm (client, "Hello"); +assert (rc == \-1); +rc = zstr_sendm (server, "World"); +assert (rc == \-1); + +zsock_destroy (&client); +zsock_destroy (&server); +#endif +.fi +.if n \{\ +.RE +.\} +.sp +.SH "AUTHORS" +.sp +The czmq manual was written by the authors in the AUTHORS file\&. +.SH "RESOURCES" +.sp +Main web site: \m[blue]\fB\%\fR\m[] +.sp +Report bugs to the email <\m[blue]\fBzeromq\-dev@lists\&.zeromq\&.org\fR\m[]\&\s-2\u[1]\d\s+2> +.SH "COPYRIGHT" +.sp +Copyright (c) the Contributors as noted in the AUTHORS file\&. This file is part of CZMQ, the high\-level C binding for 0MQ: http://czmq\&.zeromq\&.org\&. This Source Code Form is subject to the terms of the Mozilla Public License, v\&. 2\&.0\&. If a copy of the MPL was not distributed with this file, You can obtain one at http://mozilla\&.org/MPL/2\&.0/\&. LICENSE included with the czmq distribution\&. +.SH "NOTES" +.IP " 1." 4 +zeromq-dev@lists.zeromq.org +.RS 4 +\%mailto:zeromq-dev@lists.zeromq.org +.RE diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zsys.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zsys.3 new file mode 100644 index 00000000000000..2d4f5c2e45616d --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zsys.3 @@ -0,0 +1,539 @@ +'\" t +.\" Title: zsys +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.76.1 +.\" Date: 12/31/2016 +.\" Manual: CZMQ Manual +.\" Source: CZMQ 4.0.2 +.\" Language: English +.\" +.TH "ZSYS" "3" "12/31/2016" "CZMQ 4\&.0\&.2" "CZMQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zsys \- system\-level methods +.SH "SYNOPSIS" +.sp +.nf +#define UDP_FRAME_MAX 255 // Max size of UDP frame + +// Callback for interrupt signal handler +typedef void (zsys_handler_fn) (int signal_value); + +// Initialize CZMQ zsys layer; this happens automatically when you create +// a socket or an actor; however this call lets you force initialization +// earlier, so e\&.g\&. logging is properly set\-up before you start working\&. +// Not threadsafe, so call only from main thread\&. Safe to call multiple +// times\&. Returns global CZMQ context\&. +CZMQ_EXPORT void * + zsys_init (void); + +// Optionally shut down the CZMQ zsys layer; this normally happens automatically +// when the process exits; however this call lets you force a shutdown +// earlier, avoiding any potential problems with atexit() ordering, especially +// with Windows dlls\&. +CZMQ_EXPORT void + zsys_shutdown (void); + +// Get a new ZMQ socket, automagically creating a ZMQ context if this is +// the first time\&. Caller is responsible for destroying the ZMQ socket +// before process exits, to avoid a ZMQ deadlock\&. Note: you should not use +// this method in CZMQ apps, use zsock_new() instead\&. +// *** This is for CZMQ internal use only and may change arbitrarily *** +CZMQ_EXPORT void * + zsys_socket (int type, const char *filename, size_t line_nbr); + +// Destroy/close a ZMQ socket\&. You should call this for every socket you +// create using zsys_socket()\&. +// *** This is for CZMQ internal use only and may change arbitrarily *** +CZMQ_EXPORT int + zsys_close (void *handle, const char *filename, size_t line_nbr); + +// Return ZMQ socket name for socket type +// *** This is for CZMQ internal use only and may change arbitrarily *** +CZMQ_EXPORT char * + zsys_sockname (int socktype); + +// Create a pipe, which consists of two PAIR sockets connected over inproc\&. +// The pipe is configured to use the zsys_pipehwm setting\&. Returns the +// frontend socket successful, NULL if failed\&. +CZMQ_EXPORT zsock_t * + zsys_create_pipe (zsock_t **backend_p); + +// Set interrupt handler; this saves the default handlers so that a +// zsys_handler_reset () can restore them\&. If you call this multiple times +// then the last handler will take affect\&. If handler_fn is NULL, disables +// default SIGINT/SIGTERM handling in CZMQ\&. +CZMQ_EXPORT void + zsys_handler_set (zsys_handler_fn *handler_fn); + +// Reset interrupt handler, call this at exit if needed +CZMQ_EXPORT void + zsys_handler_reset (void); + +// Set default interrupt handler, so Ctrl\-C or SIGTERM will set +// zsys_interrupted\&. Idempotent; safe to call multiple times\&. +// *** This is for CZMQ internal use only and may change arbitrarily *** +CZMQ_EXPORT void + zsys_catch_interrupts (void); + +// Return 1 if file exists, else zero +CZMQ_EXPORT bool + zsys_file_exists (const char *filename); + +// Return size of file, or \-1 if not found +CZMQ_EXPORT ssize_t + zsys_file_size (const char *filename); + +// Return file modification time\&. Returns 0 if the file does not exist\&. +CZMQ_EXPORT time_t + zsys_file_modified (const char *filename); + +// Return file mode; provides at least support for the POSIX S_ISREG(m) +// and S_ISDIR(m) macros and the S_IRUSR and S_IWUSR bits, on all boxes\&. +// Returns a mode_t cast to int, or \-1 in case of error\&. +CZMQ_EXPORT int + zsys_file_mode (const char *filename); + +// Delete file\&. Does not complain if the file is absent +CZMQ_EXPORT int + zsys_file_delete (const char *filename); + +// Check if file is \*(Aqstable\*(Aq +CZMQ_EXPORT bool + zsys_file_stable (const char *filename); + +// Create a file path if it doesn\*(Aqt exist\&. The file path is treated as a +// printf format\&. +CZMQ_EXPORT int + zsys_dir_create (const char *pathname, \&.\&.\&.); + +// Remove a file path if empty; the pathname is treated as printf format\&. +CZMQ_EXPORT int + zsys_dir_delete (const char *pathname, \&.\&.\&.); + +// Move to a specified working directory\&. Returns 0 if OK, \-1 if this failed\&. +CZMQ_EXPORT int + zsys_dir_change (const char *pathname); + +// Set private file creation mode; all files created from here will be +// readable/writable by the owner only\&. +CZMQ_EXPORT void + zsys_file_mode_private (void); + +// Reset default file creation mode; all files created from here will use +// process file mode defaults\&. +CZMQ_EXPORT void + zsys_file_mode_default (void); + +// Return the CZMQ version for run\-time API detection; returns version +// number into provided fields, providing reference isn\*(Aqt null in each case\&. +CZMQ_EXPORT void + zsys_version (int *major, int *minor, int *patch); + +// Format a string using printf formatting, returning a freshly allocated +// buffer\&. If there was insufficient memory, returns NULL\&. Free the returned +// string using zstr_free()\&. +CZMQ_EXPORT char * + zsys_sprintf (const char *format, \&.\&.\&.); + +// Format a string with a va_list argument, returning a freshly allocated +// buffer\&. If there was insufficient memory, returns NULL\&. Free the returned +// string using zstr_free()\&. +CZMQ_EXPORT char * + zsys_vprintf (const char *format, va_list argptr); + +// Create UDP beacon socket; if the routable option is true, uses +// multicast (not yet implemented), else uses broadcast\&. This method +// and related ones might _eventually_ be moved to a zudp class\&. +// *** This is for CZMQ internal use only and may change arbitrarily *** +CZMQ_EXPORT SOCKET + zsys_udp_new (bool routable); + +// Close a UDP socket +// *** This is for CZMQ internal use only and may change arbitrarily *** +CZMQ_EXPORT int + zsys_udp_close (SOCKET handle); + +// Send zframe to UDP socket, return \-1 if sending failed due to +// interface having disappeared (happens easily with WiFi) +// *** This is for CZMQ internal use only and may change arbitrarily *** +CZMQ_EXPORT int + zsys_udp_send (SOCKET udpsock, zframe_t *frame, inaddr_t *address, int addrlen); + +// Receive zframe from UDP socket, and set address of peer that sent it +// The peername must be a char [INET_ADDRSTRLEN] array\&. +// *** This is for CZMQ internal use only and may change arbitrarily *** +CZMQ_EXPORT zframe_t * + zsys_udp_recv (SOCKET udpsock, char *peername, int peerlen); + +// Handle an I/O error on some socket operation; will report and die on +// fatal errors, and continue silently on "try again" errors\&. +// *** This is for CZMQ internal use only and may change arbitrarily *** +CZMQ_EXPORT void + zsys_socket_error (const char *reason); + +// Return current host name, for use in public tcp:// endpoints\&. Caller gets +// a freshly allocated string, should free it using zstr_free()\&. If the host +// name is not resolvable, returns NULL\&. +CZMQ_EXPORT char * + zsys_hostname (void); + +// Move the current process into the background\&. The precise effect depends +// on the operating system\&. On POSIX boxes, moves to a specified working +// directory (if specified), closes all file handles, reopens stdin, stdout, +// and stderr to the null device, and sets the process to ignore SIGHUP\&. On +// Windows, does nothing\&. Returns 0 if OK, \-1 if there was an error\&. +CZMQ_EXPORT int + zsys_daemonize (const char *workdir); + +// Drop the process ID into the lockfile, with exclusive lock, and switch +// the process to the specified group and/or user\&. Any of the arguments +// may be null, indicating a no\-op\&. Returns 0 on success, \-1 on failure\&. +// Note if you combine this with zsys_daemonize, run after, not before +// that method, or the lockfile will hold the wrong process ID\&. +CZMQ_EXPORT int + zsys_run_as (const char *lockfile, const char *group, const char *user); + +// Returns true if the underlying libzmq supports CURVE security\&. +// Uses a heuristic probe according to the version of libzmq being used\&. +CZMQ_EXPORT bool + zsys_has_curve (void); + +// Configure the number of I/O threads that ZeroMQ will use\&. A good +// rule of thumb is one thread per gigabit of traffic in or out\&. The +// default is 1, sufficient for most applications\&. If the environment +// variable ZSYS_IO_THREADS is defined, that provides the default\&. +// Note that this method is valid only before any socket is created\&. +CZMQ_EXPORT void + zsys_set_io_threads (size_t io_threads); + +// Configure the number of sockets that ZeroMQ will allow\&. The default +// is 1024\&. The actual limit depends on the system, and you can query it +// by using zsys_socket_limit ()\&. A value of zero means "maximum"\&. +// Note that this method is valid only before any socket is created\&. +CZMQ_EXPORT void + zsys_set_max_sockets (size_t max_sockets); + +// Return maximum number of ZeroMQ sockets that the system will support\&. +CZMQ_EXPORT size_t + zsys_socket_limit (void); + +// Configure the maximum allowed size of a message sent\&. +// The default is INT_MAX\&. +CZMQ_EXPORT void + zsys_set_max_msgsz (int max_msgsz); + +// Return maximum message size\&. +CZMQ_EXPORT int + zsys_max_msgsz (void); + +// Configure the default linger timeout in msecs for new zsock instances\&. +// You can also set this separately on each zsock_t instance\&. The default +// linger time is zero, i\&.e\&. any pending messages will be dropped\&. If the +// environment variable ZSYS_LINGER is defined, that provides the default\&. +// Note that process exit will typically be delayed by the linger time\&. +CZMQ_EXPORT void + zsys_set_linger (size_t linger); + +// Configure the default outgoing pipe limit (HWM) for new zsock instances\&. +// You can also set this separately on each zsock_t instance\&. The default +// HWM is 1,000, on all versions of ZeroMQ\&. If the environment variable +// ZSYS_SNDHWM is defined, that provides the default\&. Note that a value of +// zero means no limit, i\&.e\&. infinite memory consumption\&. +CZMQ_EXPORT void + zsys_set_sndhwm (size_t sndhwm); + +// Configure the default incoming pipe limit (HWM) for new zsock instances\&. +// You can also set this separately on each zsock_t instance\&. The default +// HWM is 1,000, on all versions of ZeroMQ\&. If the environment variable +// ZSYS_RCVHWM is defined, that provides the default\&. Note that a value of +// zero means no limit, i\&.e\&. infinite memory consumption\&. +CZMQ_EXPORT void + zsys_set_rcvhwm (size_t rcvhwm); + +// Configure the default HWM for zactor internal pipes; this is set on both +// ends of the pipe, for outgoing messages only (sndhwm)\&. The default HWM is +// 1,000, on all versions of ZeroMQ\&. If the environment var ZSYS_ACTORHWM is +// defined, that provides the default\&. Note that a value of zero means no +// limit, i\&.e\&. infinite memory consumption\&. +CZMQ_EXPORT void + zsys_set_pipehwm (size_t pipehwm); + +// Return the HWM for zactor internal pipes\&. +CZMQ_EXPORT size_t + zsys_pipehwm (void); + +// Configure use of IPv6 for new zsock instances\&. By default sockets accept +// and make only IPv4 connections\&. When you enable IPv6, sockets will accept +// and connect to both IPv4 and IPv6 peers\&. You can override the setting on +// each zsock_t instance\&. The default is IPv4 only (ipv6 set to 0)\&. If the +// environment variable ZSYS_IPV6 is defined (as 1 or 0), this provides the +// default\&. Note: has no effect on ZMQ v2\&. +CZMQ_EXPORT void + zsys_set_ipv6 (int ipv6); + +// Return use of IPv6 for zsock instances\&. +CZMQ_EXPORT int + zsys_ipv6 (void); + +// Set network interface name to use for broadcasts, particularly zbeacon\&. +// This lets the interface be configured for test environments where required\&. +// For example, on Mac OS X, zbeacon cannot bind to 255\&.255\&.255\&.255 which is +// the default when there is no specified interface\&. If the environment +// variable ZSYS_INTERFACE is set, use that as the default interface name\&. +// Setting the interface to "*" means "use all available interfaces"\&. +CZMQ_EXPORT void + zsys_set_interface (const char *value); + +// Return network interface to use for broadcasts, or "" if none was set\&. +CZMQ_EXPORT const char * + zsys_interface (void); + +// Set IPv6 address to use zbeacon socket, particularly for receiving zbeacon\&. +// This needs to be set IPv6 is enabled as IPv6 can have multiple addresses +// on a given interface\&. If the environment variable ZSYS_IPV6_ADDRESS is set, +// use that as the default IPv6 address\&. +CZMQ_EXPORT void + zsys_set_ipv6_address (const char *value); + +// Return IPv6 address to use for zbeacon reception, or "" if none was set\&. +CZMQ_EXPORT const char * + zsys_ipv6_address (void); + +// Set IPv6 milticast address to use for sending zbeacon messages\&. This needs +// to be set if IPv6 is enabled\&. If the environment variable +// ZSYS_IPV6_MCAST_ADDRESS is set, use that as the default IPv6 multicast +// address\&. +CZMQ_EXPORT void + zsys_set_ipv6_mcast_address (const char *value); + +// Return IPv6 multicast address to use for sending zbeacon, or "" if none was +// set\&. +CZMQ_EXPORT const char * + zsys_ipv6_mcast_address (void); + +// Configure the automatic use of pre\-allocated FDs when creating new sockets\&. +// If 0 (default), nothing will happen\&. Else, when a new socket is bound, the +// system API will be used to check if an existing pre\-allocated FD with a +// matching port (if TCP) or path (if IPC) exists, and if it does it will be +// set via the ZMQ_USE_FD socket option so that the library will use it +// instead of creating a new socket\&. +CZMQ_EXPORT void + zsys_set_auto_use_fd (int auto_use_fd); + +// Return use of automatic pre\-allocated FDs for zsock instances\&. +CZMQ_EXPORT int + zsys_auto_use_fd (void); + +// Set log identity, which is a string that prefixes all log messages sent +// by this process\&. The log identity defaults to the environment variable +// ZSYS_LOGIDENT, if that is set\&. +CZMQ_EXPORT void + zsys_set_logident (const char *value); + +// Set stream to receive log traffic\&. By default, log traffic is sent to +// stdout\&. If you set the stream to NULL, no stream will receive the log +// traffic (it may still be sent to the system facility)\&. +CZMQ_EXPORT void + zsys_set_logstream (FILE *stream); + +// Sends log output to a PUB socket bound to the specified endpoint\&. To +// collect such log output, create a SUB socket, subscribe to the traffic +// you care about, and connect to the endpoint\&. Log traffic is sent as a +// single string frame, in the same format as when sent to stdout\&. The +// log system supports a single sender; multiple calls to this method will +// bind the same sender to multiple endpoints\&. To disable the sender, call +// this method with a null argument\&. +CZMQ_EXPORT void + zsys_set_logsender (const char *endpoint); + +// Enable or disable logging to the system facility (syslog on POSIX boxes, +// event log on Windows)\&. By default this is disabled\&. +CZMQ_EXPORT void + zsys_set_logsystem (bool logsystem); + +// Log error condition \- highest priority +CZMQ_EXPORT void + zsys_error (const char *format, \&.\&.\&.); + +// Log warning condition \- high priority +CZMQ_EXPORT void + zsys_warning (const char *format, \&.\&.\&.); + +// Log normal, but significant, condition \- normal priority +CZMQ_EXPORT void + zsys_notice (const char *format, \&.\&.\&.); + +// Log informational message \- low priority +CZMQ_EXPORT void + zsys_info (const char *format, \&.\&.\&.); + +// Log debug\-level message \- lowest priority +CZMQ_EXPORT void + zsys_debug (const char *format, \&.\&.\&.); + +// Self test of this class +CZMQ_EXPORT void + zsys_test (bool verbose); + +// Global signal indicator, TRUE when user presses Ctrl\-C or the process +// gets a SIGTERM signal\&. +CZMQ_EXPORT extern volatile int zsys_interrupted; +// Deprecated name for this variable +CZMQ_EXPORT extern volatile int zctx_interrupted; +Please add \*(Aq@interface\*(Aq section in \*(Aq\&./\&.\&./src/zsys\&.c\*(Aq\&. +.fi +.SH "DESCRIPTION" +.sp +The zsys class provides a portable wrapper for system calls\&. We collect them here to reduce the number of weird #ifdefs in other classes\&. As far as possible, the bulk of CZMQ classes are fully portable\&. +.sp +Please add \fI@discuss\fR section in \fI\&./\&.\&./src/zsys\&.c\fR\&. +.SH "EXAMPLE" +.PP +\fBFrom zsys_test method\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +zsys_catch_interrupts (); + +// Check capabilities without using the return value +int rc = zsys_has_curve (); + +if (verbose) { + char *hostname = zsys_hostname (); + zsys_info ("host name is %s", hostname); + free (hostname); + zsys_info ("system limit is %zu ZeroMQ sockets", zsys_socket_limit ()); +} +zsys_set_linger (0); +zsys_set_sndhwm (1000); +zsys_set_rcvhwm (1000); +zsys_set_pipehwm (2500); +assert (zsys_pipehwm () == 2500); +zsys_set_ipv6 (0); + +// Test pipe creation +zsock_t *pipe_back; +zsock_t *pipe_front = zsys_create_pipe (&pipe_back); +zstr_send (pipe_front, "Hello"); +char *string = zstr_recv (pipe_back); +assert (streq (string, "Hello")); +free (string); +zsock_destroy (&pipe_back); +zsock_destroy (&pipe_front); + +// Test file manipulation +rc = zsys_file_delete ("nosuchfile"); +assert (rc == \-1); + +bool rc_bool = zsys_file_exists ("nosuchfile"); +assert (rc_bool != true); + +rc = (int) zsys_file_size ("nosuchfile"); +assert (rc == \-1); + +time_t when = zsys_file_modified ("\&."); +assert (when > 0); + +int mode = zsys_file_mode ("\&."); +assert (S_ISDIR (mode)); +assert (mode & S_IRUSR); +assert (mode & S_IWUSR); + +zsys_file_mode_private (); +rc = zsys_dir_create ("%s/%s", "\&.", "\&.testsys/subdir"); +assert (rc == 0); +when = zsys_file_modified ("\&./\&.testsys/subdir"); +assert (when > 0); +assert (!zsys_file_stable ("\&./\&.testsys/subdir")); +rc = zsys_dir_delete ("%s/%s", "\&.", "\&.testsys/subdir"); +assert (rc == 0); +rc = zsys_dir_delete ("%s/%s", "\&.", "\&.testsys"); +assert (rc == 0); +zsys_file_mode_default (); +assert (zsys_dir_change ("\&.") == 0); + +int major, minor, patch; +zsys_version (&major, &minor, &patch); +assert (major == CZMQ_VERSION_MAJOR); +assert (minor == CZMQ_VERSION_MINOR); +assert (patch == CZMQ_VERSION_PATCH); + +string = zsys_sprintf ("%s %02x", "Hello", 16); +assert (streq (string, "Hello 10")); +free (string); + +char *str64 = "ABCDEFGHIJKLMNOPQRSTUVWXYZabcdefghijklmnopqrstuvwxyz1234567890,\&."; +int num10 = 1234567890; +string = zsys_sprintf ("%s%s%s%s%d", str64, str64, str64, str64, num10); +assert (strlen (string) == (4 * 64 + 10)); +free (string); + +// Test logging system +zsys_set_logident ("czmq_selftest"); +zsys_set_logsender ("inproc://logging"); +void *logger = zsys_socket (ZMQ_SUB, NULL, 0); +assert (logger); +rc = zmq_connect (logger, "inproc://logging"); +assert (rc == 0); +rc = zmq_setsockopt (logger, ZMQ_SUBSCRIBE, "", 0); +assert (rc == 0); + +if (verbose) { + zsys_error ("This is an %s message", "error"); + zsys_warning ("This is a %s message", "warning"); + zsys_notice ("This is a %s message", "notice"); + zsys_info ("This is a %s message", "info"); + zsys_debug ("This is a %s message", "debug"); + zsys_set_logident ("hello, world"); + zsys_info ("This is a %s message", "info"); + zsys_debug ("This is a %s message", "debug"); + + // Check that logsender functionality is working + char *received = zstr_recv (logger); + assert (received); + zstr_free (&received); +} +zsys_close (logger, NULL, 0); +.fi +.if n \{\ +.RE +.\} +.sp +.SH "AUTHORS" +.sp +The czmq manual was written by the authors in the AUTHORS file\&. +.SH "RESOURCES" +.sp +Main web site: \m[blue]\fB\%\fR\m[] +.sp +Report bugs to the email <\m[blue]\fBzeromq\-dev@lists\&.zeromq\&.org\fR\m[]\&\s-2\u[1]\d\s+2> +.SH "COPYRIGHT" +.sp +Copyright (c) the Contributors as noted in the AUTHORS file\&. This file is part of CZMQ, the high\-level C binding for 0MQ: http://czmq\&.zeromq\&.org\&. This Source Code Form is subject to the terms of the Mozilla Public License, v\&. 2\&.0\&. If a copy of the MPL was not distributed with this file, You can obtain one at http://mozilla\&.org/MPL/2\&.0/\&. LICENSE included with the czmq distribution\&. +.SH "NOTES" +.IP " 1." 4 +zeromq-dev@lists.zeromq.org +.RS 4 +\%mailto:zeromq-dev@lists.zeromq.org +.RE diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/ztimerset.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/ztimerset.3 new file mode 100644 index 00000000000000..1eaa5ab949caaf --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/ztimerset.3 @@ -0,0 +1,180 @@ +'\" t +.\" Title: ztimerset +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.76.1 +.\" Date: 12/31/2016 +.\" Manual: CZMQ Manual +.\" Source: CZMQ 4.0.2 +.\" Language: English +.\" +.TH "ZTIMERSET" "3" "12/31/2016" "CZMQ 4\&.0\&.2" "CZMQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +ztimerset \- timer set +.SH "SYNOPSIS" +.sp +.nf +// This is a draft class, and may change without notice\&. It is disabled in +// stable builds by default\&. If you use this in applications, please ask +// for it to be pushed to stable state\&. Use \-\-enable\-drafts to enable\&. +#ifdef CZMQ_BUILD_DRAFT_API +// Callback function for timer event\&. +typedef void (ztimerset_fn) ( + int timer_id, void *arg); + +// *** Draft method, for development use, may change without warning *** +// Create new timer set\&. +CZMQ_EXPORT ztimerset_t * + ztimerset_new (void); + +// *** Draft method, for development use, may change without warning *** +// Destroy a timer set +CZMQ_EXPORT void + ztimerset_destroy (ztimerset_t **self_p); + +// *** Draft method, for development use, may change without warning *** +// Add a timer to the set\&. Returns timer id if OK, \-1 on failure\&. +CZMQ_EXPORT int + ztimerset_add (ztimerset_t *self, size_t interval, ztimerset_fn handler, void *arg); + +// *** Draft method, for development use, may change without warning *** +// Cancel a timer\&. Returns 0 if OK, \-1 on failure\&. +CZMQ_EXPORT int + ztimerset_cancel (ztimerset_t *self, int timer_id); + +// *** Draft method, for development use, may change without warning *** +// Set timer interval\&. Returns 0 if OK, \-1 on failure\&. +// This method is slow, canceling the timer and adding a new one yield better performance\&. +CZMQ_EXPORT int + ztimerset_set_interval (ztimerset_t *self, int timer_id, size_t interval); + +// *** Draft method, for development use, may change without warning *** +// Reset timer to start interval counting from current time\&. Returns 0 if OK, \-1 on failure\&. +// This method is slow, canceling the timer and adding a new one yield better performance\&. +CZMQ_EXPORT int + ztimerset_reset (ztimerset_t *self, int timer_id); + +// *** Draft method, for development use, may change without warning *** +// Return the time until the next interval\&. +// Should be used as timeout parameter for the zpoller wait method\&. +// The timeout is in msec\&. +CZMQ_EXPORT int + ztimerset_timeout (ztimerset_t *self); + +// *** Draft method, for development use, may change without warning *** +// Invoke callback function of all timers which their interval has elapsed\&. +// Should be call after zpoller wait method\&. +// Returns 0 if OK, \-1 on failure\&. +CZMQ_EXPORT int + ztimerset_execute (ztimerset_t *self); + +// *** Draft method, for development use, may change without warning *** +// Self test of this class\&. +CZMQ_EXPORT void + ztimerset_test (bool verbose); + +#endif // CZMQ_BUILD_DRAFT_API +Please add \*(Aq@interface\*(Aq section in \*(Aq\&./\&.\&./src/ztimerset\&.c\*(Aq\&. +.fi +.SH "DESCRIPTION" +.sp +ztimerset \- timer set +.sp +Please add \fI@discuss\fR section in \fI\&./\&.\&./src/ztimerset\&.c\fR\&. +.SH "EXAMPLE" +.PP +\fBFrom ztimerset_test method\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +// Simple create/destroy test +ztimerset_t *self = ztimerset_new (); +assert (self); + +// Adding timer +bool timer_invoked = false; +int timer_id = ztimerset_add (self, 100, handler, &timer_invoked); +assert (timer_id != \-1); +int rc = ztimerset_execute (self); +assert (rc == 0); +assert (!timer_invoked); +int timeout = ztimerset_timeout (self); +assert (timeout > 0); +zclock_sleep (timeout); +rc = ztimerset_execute (self); +assert (rc == 0); +assert (timer_invoked); + +// Cancel timer +timeout = ztimerset_timeout (self); +assert (timeout > 0); +rc = ztimerset_cancel (self, timer_id); +assert (rc == 0); +timeout = ztimerset_timeout (self); +assert(timeout == \-1); + +// Reset a timer +timer_id = ztimerset_add (self, 100, handler, &timer_invoked); +assert (timer_id != \-1); +timeout = ztimerset_timeout (self); +assert (timeout > 0); +zclock_sleep (timeout / 2); +timeout = ztimerset_timeout (self); +rc = ztimerset_reset(self, timer_id); +assert (rc == 0); +int timeout2 = ztimerset_timeout (self); +assert (timeout2 > timeout); +rc = ztimerset_cancel (self, timer_id); +assert (rc == 0); + +// Set interval +timer_id = ztimerset_add (self, 100, handler, &timer_invoked); +assert (timer_id != \-1); +timeout = ztimerset_timeout (self); +rc = ztimerset_set_interval(self, timer_id, 200); +timeout2 = ztimerset_timeout (self); +assert (timeout2 > timeout); + +ztimerset_destroy (&self); +.fi +.if n \{\ +.RE +.\} +.sp +.SH "AUTHORS" +.sp +The czmq manual was written by the authors in the AUTHORS file\&. +.SH "RESOURCES" +.sp +Main web site: \m[blue]\fB\%\fR\m[] +.sp +Report bugs to the email <\m[blue]\fBzeromq\-dev@lists\&.zeromq\&.org\fR\m[]\&\s-2\u[1]\d\s+2> +.SH "COPYRIGHT" +.sp +Copyright (c) the Contributors as noted in the AUTHORS file\&. This file is part of CZMQ, the high\-level C binding for 0MQ: http://czmq\&.zeromq\&.org\&. This Source Code Form is subject to the terms of the Mozilla Public License, v\&. 2\&.0\&. If a copy of the MPL was not distributed with this file, You can obtain one at http://mozilla\&.org/MPL/2\&.0/\&. LICENSE included with the czmq distribution\&. +.SH "NOTES" +.IP " 1." 4 +zeromq-dev@lists.zeromq.org +.RS 4 +\%mailto:zeromq-dev@lists.zeromq.org +.RE diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/ztrie.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/ztrie.3 new file mode 100644 index 00000000000000..6cfb401a344658 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/ztrie.3 @@ -0,0 +1,292 @@ +'\" t +.\" Title: ztrie +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.76.1 +.\" Date: 12/31/2016 +.\" Manual: CZMQ Manual +.\" Source: CZMQ 4.0.2 +.\" Language: English +.\" +.TH "ZTRIE" "3" "12/31/2016" "CZMQ 4\&.0\&.2" "CZMQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +ztrie \- simple trie for tokenizable strings +.SH "SYNOPSIS" +.sp +.nf +// This is a draft class, and may change without notice\&. It is disabled in +// stable builds by default\&. If you use this in applications, please ask +// for it to be pushed to stable state\&. Use \-\-enable\-drafts to enable\&. +#ifdef CZMQ_BUILD_DRAFT_API +// Callback function for ztrie_node to destroy node data\&. +typedef void (ztrie_destroy_data_fn) ( + void **data); + +// *** Draft method, for development use, may change without warning *** +// Creates a new ztrie\&. +CZMQ_EXPORT ztrie_t * + ztrie_new (char delimiter); + +// *** Draft method, for development use, may change without warning *** +// Destroy the ztrie\&. +CZMQ_EXPORT void + ztrie_destroy (ztrie_t **self_p); + +// *** Draft method, for development use, may change without warning *** +// Inserts a new route into the tree and attaches the data\&. Returns \-1 +// if the route already exists, otherwise 0\&. This method takes ownership of +// the provided data if a destroy_data_fn is provided\&. +CZMQ_EXPORT int + ztrie_insert_route (ztrie_t *self, const char *path, void *data, ztrie_destroy_data_fn destroy_data_fn); + +// *** Draft method, for development use, may change without warning *** +// Removes a route from the trie and destroys its data\&. Returns \-1 if the +// route does not exists, otherwise 0\&. +// the start of the list call zlist_first ()\&. Advances the cursor\&. +CZMQ_EXPORT int + ztrie_remove_route (ztrie_t *self, const char *path); + +// *** Draft method, for development use, may change without warning *** +// Returns true if the path matches a route in the tree, otherwise false\&. +CZMQ_EXPORT bool + ztrie_matches (ztrie_t *self, const char *path); + +// *** Draft method, for development use, may change without warning *** +// Returns the data of a matched route from last ztrie_matches\&. If the path +// did not match, returns NULL\&. Do not delete the data as it\*(Aqs owned by +// ztrie\&. +CZMQ_EXPORT void * + ztrie_hit_data (ztrie_t *self); + +// *** Draft method, for development use, may change without warning *** +// Returns the count of parameters that a matched route has\&. +CZMQ_EXPORT size_t + ztrie_hit_parameter_count (ztrie_t *self); + +// *** Draft method, for development use, may change without warning *** +// Returns the parameters of a matched route with named regexes from last +// ztrie_matches\&. If the path did not match or the route did not contain any +// named regexes, returns NULL\&. +CZMQ_EXPORT zhashx_t * + ztrie_hit_parameters (ztrie_t *self); + +// *** Draft method, for development use, may change without warning *** +// Returns the asterisk matched part of a route, if there has been no match +// or no asterisk match, returns NULL\&. +CZMQ_EXPORT const char * + ztrie_hit_asterisk_match (ztrie_t *self); + +// *** Draft method, for development use, may change without warning *** +// Print the trie +CZMQ_EXPORT void + ztrie_print (ztrie_t *self); + +// *** Draft method, for development use, may change without warning *** +// Self test of this class\&. +CZMQ_EXPORT void + ztrie_test (bool verbose); + +#endif // CZMQ_BUILD_DRAFT_API +Please add \*(Aq@interface\*(Aq section in \*(Aq\&./\&.\&./src/ztrie\&.c\*(Aq\&. +.fi +.SH "DESCRIPTION" +.sp +This is a variant of a trie or prefix tree where all the descendants of a node have a common prefix of the string associated with that node\&. This implementation is specialized for strings that can be tokenized by a delimiter like a URL, URI or URN\&. Routes in the tree can be matched by regular expressions and by using capturing groups parts of a matched route can be easily obtained\&. +.sp +Note that the performance for pure string based matching is okay but on short strings zhash and zhashx are 3\-4 times faster\&. +.SH "EXAMPLE" +.PP +\fBFrom ztrie_test method\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +// Create a new trie for matching strings that can be tokenized by a slash +// (e\&.g\&. URLs minus the protocol, address and port)\&. +ztrie_t *self = ztrie_new (\*(Aq/\*(Aq); +assert (self); + +int ret = 0; + +// Let\*(Aqs start by inserting a couple of routes into the trie\&. +// This one is for the route \*(Aq/foo/bar\*(Aq the slash at the beginning of the +// route is important because everything before the first delimiter will be +// discarded\&. A slash at the end of a route is optional though\&. The data +// associated with this node is passed without destroy function which means +// it must be destroyed by the caller\&. +int foo_bar_data = 10; +ret = ztrie_insert_route (self, "/foo/bar", &foo_bar_data, NULL); +assert (ret == 0); + +// Now suppose we like to match all routes with two tokens that start with +// \*(Aq/foo/\*(Aq but aren\*(Aqt \*(Aq/foo/bar\*(Aq\&. This is possible by using regular +// expressions which are enclosed in an opening and closing curly bracket\&. +// Tokens that contain regular expressions are always match after string +// based tokens\&. +// Note: There is no order in which regular expressions are sorted thus +// if you enter multiple expressions for a route you will have to make +// sure they don\*(Aqt have overlapping results\&. For example \*(Aq/foo/{[^/]+}\*(Aq +// and \*(Aq/foo/{\ed+} having could turn out badly\&. +int foo_other_data = 100; +ret = ztrie_insert_route (self, "/foo/{[^/]+}", &foo_other_data, NULL); +assert (ret == 0); + +// Regular expression are only matched against tokens of the same level\&. +// This allows us to append to are route with a regular expression as if +// it were a string\&. +ret = ztrie_insert_route (self, "/foo/{[^/]+}/gulp", NULL, NULL); +assert (ret == 0); + +// Routes are identified by their endpoint, which is the last token of the route\&. +// It is possible to insert routes for a node that already exists but isn\*(Aqt an +// endpoint yet\&. The delimiter at the end of a route is optional and has no effect\&. +ret = ztrie_insert_route (self, "/foo/", NULL, NULL); +assert (ret == 0); + +// If you try to insert a route which already exists the method will return \-1\&. +ret = ztrie_insert_route (self, "/foo", NULL, NULL); +assert (ret == \-1); + +// It is not allowed to insert routes with empty tokens\&. +ret = ztrie_insert_route (self, "//foo", NULL, NULL); +assert (ret == \-1); + +// Everything before the first delimiter is ignored so \*(Aqfoo/bar/baz\*(Aq is equivalent +// to \*(Aq/bar/baz\*(Aq\&. +ret = ztrie_insert_route (self, "foo/bar/baz", NULL, NULL); +assert (ret == 0); +ret = ztrie_insert_route (self, "/bar/baz", NULL, NULL); +assert (ret == \-1); + +// Of course you are allowed to remove routes, in case there is data associated with a +// route and a destroy data function has been supplied that data will be destroyed\&. +ret = ztrie_remove_route (self, "/foo"); +assert (ret == 0); + +// Removing a non existent route will as well return \-1\&. +ret = ztrie_remove_route (self, "/foo"); +assert (ret == \-1); + +// Removing a route with a regular expression must exactly match the entered one\&. +ret = ztrie_remove_route (self, "/foo/{[^/]+}"); +assert (ret == 0); + +// Next we like to match a path by regular expressions and also extract matched +// parts of a route\&. This can be done by naming the regular expression\&. The name of a +// regular expression is entered at the beginning of the curly brackets and separated +// by a colon from the regular expression\&. The first one in this examples is named +// \*(Aqname\*(Aq and names the expression \*(Aq[^/]\*(Aq\&. If there is no capturing group defined in +// the expression the whole matched string will be associated with this parameter\&. In +// case you don\*(Aqt like the get the whole matched string use a capturing group, like +// it has been done for the \*(Aqid\*(Aq parameter\&. This is nice but you can even match as +// many parameter for a token as you like\&. Therefore simply put the parameter names +// separated by colons in front of the regular expression and make sure to add a +// capturing group for each parameter\&. The first parameter will be associated with +// the first capturing and so on\&. +char *data = (char *) malloc (80); +sprintf (data, "%s", "Hello World!"); +ret = ztrie_insert_route (self, "/baz/{name:[^/]+}/{id:\-\-(\e\ed+)}/{street:nr:(\e\ea+)(\e\ed+)}", data, NULL); +assert (ret == 0); + +// There is a lot you can do with regular expression but matching routes +// of arbitrary length wont work\&. Therefore we make use of the asterisk +// operator\&. Just place it at the end of your route, e\&.g\&. \*(Aq/config/bar/*\*(Aq\&. +ret = ztrie_insert_route (self, "/config/bar/*", NULL, NULL); +assert (ret == 0); + +// Appending to an asterisk as you would to with a regular expression +// isn\*(Aqt valid\&. +ret = ztrie_insert_route (self, "/config/bar/*/bar", NULL, NULL); +assert (ret == \-1); + +// The asterisk operator will only work as a leaf in the tree\&. If you +// enter an asterisk in the middle of your route it will simply be +// interpreted as a string\&. +ret = ztrie_insert_route (self, "/test/*/bar", NULL, NULL); +assert (ret == 0); + +// If a parent has an asterisk as child it is not allowed to have +// other siblings\&. +ret = ztrie_insert_route (self, "/config/bar/foo/glup", NULL, NULL); +assert (ret != 0); + +// Test matches +bool hasMatch = false; + +// The route \*(Aq/bar/foo\*(Aq will fail to match as this route has never been inserted\&. +hasMatch = ztrie_matches (self, "/bar/foo"); +assert (!hasMatch); + +// The route \*(Aq/foo/bar\*(Aq will match and we can obtain the data associated with it\&. +hasMatch = ztrie_matches (self, "/foo/bar"); +assert (hasMatch); +int foo_bar_hit_data = *((int *) ztrie_hit_data (self)); +assert (foo_bar_data == foo_bar_hit_data); + +// This route is part of another but is no endpoint itself thus the matches will fail\&. +hasMatch = ztrie_matches (self, "/baz/blub"); +assert (!hasMatch); + +// This route will match our named regular expressions route\&. Thus we can extract data +// from the route by their names\&. +hasMatch = ztrie_matches (self, "/baz/blub/\-\-11/abc23"); +assert (hasMatch); +char *match_data = (char *) ztrie_hit_data (self); +assert (streq ("Hello World!", match_data)); +zhashx_t *parameters = ztrie_hit_parameters (self); +assert (zhashx_size (parameters) == 4); +assert (streq ("blub", (char *) zhashx_lookup (parameters, "name"))); +assert (streq ("11", (char *) zhashx_lookup (parameters, "id"))); +assert (streq ("abc", (char *) zhashx_lookup (parameters, "street"))); +assert (streq ("23", (char *) zhashx_lookup (parameters, "nr"))); +zhashx_destroy (¶meters); + +// This will match our asterisk route \*(Aq/config/bar/*\*(Aq\&. As the result we +// can obtain the asterisk matched part of the route\&. +hasMatch = ztrie_matches (self, "/config/bar/foo/bar"); +assert (hasMatch); +assert (streq (ztrie_hit_asterisk_match (self), "foo/bar")); + +zstr_free (&data); +ztrie_destroy (&self); +.fi +.if n \{\ +.RE +.\} +.sp +.SH "AUTHORS" +.sp +The czmq manual was written by the authors in the AUTHORS file\&. +.SH "RESOURCES" +.sp +Main web site: \m[blue]\fB\%\fR\m[] +.sp +Report bugs to the email <\m[blue]\fBzeromq\-dev@lists\&.zeromq\&.org\fR\m[]\&\s-2\u[1]\d\s+2> +.SH "COPYRIGHT" +.sp +Copyright (c) the Contributors as noted in the AUTHORS file\&. This file is part of CZMQ, the high\-level C binding for 0MQ: http://czmq\&.zeromq\&.org\&. This Source Code Form is subject to the terms of the Mozilla Public License, v\&. 2\&.0\&. If a copy of the MPL was not distributed with this file, You can obtain one at http://mozilla\&.org/MPL/2\&.0/\&. LICENSE included with the czmq distribution\&. +.SH "NOTES" +.IP " 1." 4 +zeromq-dev@lists.zeromq.org +.RS 4 +\%mailto:zeromq-dev@lists.zeromq.org +.RE diff --git a/phonelibs/zmq/aarch64-linux/share/man/man3/zuuid.3 b/phonelibs/zmq/aarch64-linux/share/man/man3/zuuid.3 new file mode 100644 index 00000000000000..c5431245eb2de4 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man3/zuuid.3 @@ -0,0 +1,171 @@ +'\" t +.\" Title: zuuid +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.76.1 +.\" Date: 12/31/2016 +.\" Manual: CZMQ Manual +.\" Source: CZMQ 4.0.2 +.\" Language: English +.\" +.TH "ZUUID" "3" "12/31/2016" "CZMQ 4\&.0\&.2" "CZMQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zuuid \- UUID support class +.SH "SYNOPSIS" +.sp +.nf +// This is a stable class, and may not change except for emergencies\&. It +// is provided in stable builds\&. +// Create a new UUID object\&. +CZMQ_EXPORT zuuid_t * + zuuid_new (void); + +// Create UUID object from supplied ZUUID_LEN\-octet value\&. +CZMQ_EXPORT zuuid_t * + zuuid_new_from (const byte *source); + +// Destroy a specified UUID object\&. +CZMQ_EXPORT void + zuuid_destroy (zuuid_t **self_p); + +// Set UUID to new supplied ZUUID_LEN\-octet value\&. +CZMQ_EXPORT void + zuuid_set (zuuid_t *self, const byte *source); + +// Set UUID to new supplied string value skipping \*(Aq\-\*(Aq and \*(Aq{\*(Aq \*(Aq}\*(Aq +// optional delimiters\&. Return 0 if OK, else returns \-1\&. +CZMQ_EXPORT int + zuuid_set_str (zuuid_t *self, const char *source); + +// Return UUID binary data\&. +CZMQ_EXPORT const byte * + zuuid_data (zuuid_t *self); + +// Return UUID binary size +CZMQ_EXPORT size_t + zuuid_size (zuuid_t *self); + +// Returns UUID as string +CZMQ_EXPORT const char * + zuuid_str (zuuid_t *self); + +// Return UUID in the canonical string format: 8\-4\-4\-4\-12, in lower +// case\&. Caller does not modify or free returned value\&. See +// http://en\&.wikipedia\&.org/wiki/Universally_unique_identifier +CZMQ_EXPORT const char * + zuuid_str_canonical (zuuid_t *self); + +// Store UUID blob in target array +CZMQ_EXPORT void + zuuid_export (zuuid_t *self, byte *target); + +// Check if UUID is same as supplied value +CZMQ_EXPORT bool + zuuid_eq (zuuid_t *self, const byte *compare); + +// Check if UUID is different from supplied value +CZMQ_EXPORT bool + zuuid_neq (zuuid_t *self, const byte *compare); + +// Make copy of UUID object; if uuid is null, or memory was exhausted, +// returns null\&. +CZMQ_EXPORT zuuid_t * + zuuid_dup (zuuid_t *self); + +// Self test of this class\&. +CZMQ_EXPORT void + zuuid_test (bool verbose); + +Please add \*(Aq@interface\*(Aq section in \*(Aq\&./\&.\&./src/zuuid\&.c\*(Aq\&. +.fi +.SH "DESCRIPTION" +.sp +The zuuid class generates UUIDs and provides methods for working with them\&. If you build CZMQ with libuuid, on Unix/Linux, it will use that library\&. On Windows it will use UuidCreate()\&. Otherwise it will use a random number generator to produce convincing imitations of UUIDs\&. +.sp +Please add \fI@discuss\fR section in \fI\&./\&.\&./src/zuuid\&.c\fR\&. +.SH "EXAMPLE" +.PP +\fBFrom zuuid_test method\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +// Simple create/destroy test +assert (ZUUID_LEN == 16); +assert (ZUUID_STR_LEN == 32); + +zuuid_t *uuid = zuuid_new (); +assert (uuid); +assert (zuuid_size (uuid) == ZUUID_LEN); +assert (strlen (zuuid_str (uuid)) == ZUUID_STR_LEN); +zuuid_t *copy = zuuid_dup (uuid); +assert (streq (zuuid_str (uuid), zuuid_str (copy))); + +// Check set/set_str/export methods +const char *myuuid = "8CB3E9A9649B4BEF8DE225E9C2CEBB38"; +const char *myuuid2 = "8CB3E9A9\-649B\-4BEF\-8DE2\-25E9C2CEBB38"; +const char *myuuid3 = "{8CB3E9A9\-649B\-4BEF\-8DE2\-25E9C2CEBB38}"; +const char *myuuid4 = "8CB3E9A9649B4BEF8DE225E9C2CEBB3838"; +int rc = zuuid_set_str (uuid, myuuid); +assert (rc == 0); +assert (streq (zuuid_str (uuid), myuuid)); +rc = zuuid_set_str (uuid, myuuid2); +assert (rc == 0); +assert (streq (zuuid_str (uuid), myuuid)); +rc = zuuid_set_str (uuid, myuuid3); +assert (rc == 0); +assert (streq (zuuid_str (uuid), myuuid)); +rc = zuuid_set_str (uuid, myuuid4); +assert (rc == \-1); +byte copy_uuid [ZUUID_LEN]; +zuuid_export (uuid, copy_uuid); +zuuid_set (uuid, copy_uuid); +assert (streq (zuuid_str (uuid), myuuid)); + +// Check the canonical string format +assert (streq (zuuid_str_canonical (uuid), + "8cb3e9a9\-649b\-4bef\-8de2\-25e9c2cebb38")); + +zuuid_destroy (&uuid); +zuuid_destroy (©); +.fi +.if n \{\ +.RE +.\} +.sp +.SH "AUTHORS" +.sp +The czmq manual was written by the authors in the AUTHORS file\&. +.SH "RESOURCES" +.sp +Main web site: \m[blue]\fB\%\fR\m[] +.sp +Report bugs to the email <\m[blue]\fBzeromq\-dev@lists\&.zeromq\&.org\fR\m[]\&\s-2\u[1]\d\s+2> +.SH "COPYRIGHT" +.sp +Copyright (c) the Contributors as noted in the AUTHORS file\&. This file is part of CZMQ, the high\-level C binding for 0MQ: http://czmq\&.zeromq\&.org\&. This Source Code Form is subject to the terms of the Mozilla Public License, v\&. 2\&.0\&. If a copy of the MPL was not distributed with this file, You can obtain one at http://mozilla\&.org/MPL/2\&.0/\&. LICENSE included with the czmq distribution\&. +.SH "NOTES" +.IP " 1." 4 +zeromq-dev@lists.zeromq.org +.RS 4 +\%mailto:zeromq-dev@lists.zeromq.org +.RE diff --git a/phonelibs/zmq/aarch64-linux/share/man/man7/czmq.7 b/phonelibs/zmq/aarch64-linux/share/man/man7/czmq.7 new file mode 100644 index 00000000000000..6de419cb00d516 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man7/czmq.7 @@ -0,0 +1,1358 @@ +'\" t +.\" Title: czmq +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.76.1 +.\" Date: 12/31/2016 +.\" Manual: CZMQ Manual +.\" Source: CZMQ 4.0.2 +.\" Language: English +.\" +.TH "CZMQ" "7" "12/31/2016" "CZMQ 4\&.0\&.2" "CZMQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +czmq \- high\-level C binding for ZeroMQ +.SH "SYNOPSIS" +.sp +.nf +#include + +cc [\*(Aqflags\*(Aq] \*(Aqfiles\*(Aq \-lzmq \-lczmq [\*(Aqlibraries\*(Aq] +.fi +.SH "DESCRIPTION" +.SS "Classes" +.sp +These classes provide the main socket and message API: +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} + +\fBzsock\fR(3) +\- working with ZeroMQ sockets (high\-level) +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} + +\fBzstr\fR(3) +\- sending and receiving strings +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} + +\fBzmsg\fR(3) +\- working with multipart messages +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} + +\fBzframe\fR(3) +\- working with single message frames +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} + +\fBzactor\fR(3) +\- Actor class (socket + thread) +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} + +\fBzloop\fR(3) +\- event\-driven reactor +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} + +\fBzpoller\fR(3) +\- trivial socket poller class +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} + +\fBzproxy\fR(3) +\- proxy actor (like zmq_proxy_steerable) +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} + +\fBzmonitor\fR(3) +\- monitor events on ZeroMQ sockets +.RE +.sp +These classes support authentication and encryption: +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} + +\fBzauth\fR(3) +\- authentication actor for ZeroMQ servers +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} + +\fBzcert\fR(3) +\- work with CURVE security certificates +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} + +\fBzcertstore\fR(3) +\- work with CURVE security certificate stores +.RE +.sp +These classes provide generic containers: +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} + +\fBzhash\fR(3) +\- simple generic hash container +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} + +\fBzhashx\fR(3) +\- extended generic hash container +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} + +\fBzlist\fR(3) +\- simple generic list container +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} + +\fBzlistx\fR(3) +\- extended generic list container +.RE +.sp +These classes wrap\-up non\-portable functionality: +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} + +\fBzbeacon\fR(3) +\- LAN discovery and presence +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} + +\fBzclock\fR(3) +\- millisecond clocks and delays +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} + +\fBzdir\fR(3) +\- work with file\-system directories +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} + +\fBzdir_patch\fR(3) +\- work with directory differences +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} + +\fBzfile\fR(3) +\- work with file\-system files +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} + +\fBzsys\fR(3) +\- system\-level methods +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} + +\fBzuuid\fR(3) +\- UUID support class +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} + +\fBziflist\fR(3) +\- list available network interfaces +.RE +.sp +And these utility classes add value: +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} + +\fBzchunk\fR(3) +\- work with memory chunks +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} + +\fBzconfig\fR(3) +\- work with textual config files +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} + +\fBzrex\fR(3) +\- work with regular expressions +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} + +\fBzgossip\fR(3) +\- decentralized configuration management +.RE +.sp +These classes are deprecated: +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} + +\fBzctx\fR(3) +\- working with ZeroMQ contexts +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} + +\fBzsocket\fR(3) +\- working with ZeroMQ sockets (low\-level) +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} + +\fBzsockopt\fR(3) +\- get/set ZeroMQ socket options +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} + +\fBzthread\fR(3) +\- working with system threads +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} + +\fBzauth_v2\fR(3) +\- authentication for ZeroMQ servers +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} + +\fBzbeacon_v2\fR(3) +\- LAN discovery and presence +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} + +\fBzmonitor_v2\fR(3) +\- socket event monitor +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} + +\fBzproxy_v2\fR(3) +\- zmq_proxy wrapper +.RE +.SS "Scope and Goals" +.sp +CZMQ has these goals: +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +To wrap the \(/OMQ core API in semantics that are natural and lead to shorter, more readable applications\&. +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +To hide the differences between versions of \(/OMQ\&. +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +To provide a space for development of more sophisticated API semantics\&. +.RE +.SS "Ownership and License" +.sp +CZMQ is maintained by the ZeroMQ community at github\&.com/zeromq\&. Its other authors and contributors are listed in the AUTHORS file\&. +.sp +The contributors are listed in AUTHORS\&. This project uses the MPL v2 license, see LICENSE\&. +.SS "Contributing" +.sp +To submit an issue use the issue tracker at \m[blue]\fBhttp://github\&.com/zeromq/czmq/issues\fR\m[]\&. All discussion happens on the zeromq\-dev list or #zeromq IRC channel at irc\&.freenode\&.net\&. +.sp +The proper way to submit patches is to clone this repository, make your changes, and use git to create a patch or a pull request\&. See \m[blue]\fBhttp://www\&.zeromq\&.org/docs:contributing\fR\m[]\&. All contributors are listed in AUTHORS\&. +.sp +All classes are maintained by a single person, who is the responsible editor for that class and who is named in the header as such\&. This is usually the originator of the class\&. When several people collaborate on a class, one single person is always the lead maintainer and the one to blame when it breaks\&. +.sp +The general rule is, if you contribute code to CZMQ you must be willing to maintain it as long as there are users of it\&. Code with no active maintainer will in general be deprecated and/or removed\&. +.SH "USING CZMQ" +.SS "Building and Installing" +.sp +CZMQ uses autotools for packaging\&. To build from git (all example commands are for Linux): +.sp +.if n \{\ +.RS 4 +.\} +.nf + git clone git://github\&.com/zeromq/czmq\&.git + cd czmq + sh autogen\&.sh + \&./configure + make all + sudo make install + sudo ldconfig +.fi +.if n \{\ +.RE +.\} +.sp +You will need the pkg\-config, libtool, and autoreconf packages\&. Set the LD_LIBRARY_PATH to /usr/local/libs unless you install elsewhere\&. +.sp +After building, you can run the CZMQ selftests: +.sp +.if n \{\ +.RS 4 +.\} +.nf + cd src + \&./czmq_selftest +.fi +.if n \{\ +.RE +.\} +.SS "Linking with an Application" +.sp +Include czmq\&.h in your application and link with CZMQ\&. Here is a typical gcc link command: +.sp +.if n \{\ +.RS 4 +.\} +.nf + gcc \-lczmq \-lzmq myapp\&.c \-o myapp +.fi +.if n \{\ +.RE +.\} +.sp +You should read czmq\&.h\&. This file includes zmq\&.h and the system header files that typical \(/OMQ applications will need\&. The provided \fIc\fR shell script lets you write simple portable build scripts: +.sp +.if n \{\ +.RS 4 +.\} +.nf + c \-lczmq \-lzmq \-l myapp +.fi +.if n \{\ +.RE +.\} +.SS "The Class Model" +.sp +CZMQ consists of classes, each class consisting of a \&.h and a \&.c\&. Classes may depend on other classes\&. +.sp +czmq\&.h includes all classes header files, all the time\&. For the user, CZMQ forms one single package\&. All classes start by including czmq\&.h\&. All applications that use CZMQ start by including czmq\&.h\&. czmq\&.h also defines a limited number of small, useful macros and typedefs that have proven useful for writing clearer C code\&. +.sp +All classes (with some exceptions) are based on a flat C class system and follow these rules (where \fIzclass\fR is the class name): +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +Class typedef: +zclass_t +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +Constructor: +zclass_new +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +Destructor: +zclass_destroy +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +Property methods: +zclass_property_set, +zclass_property +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +Class structures are private (defined in the \&.c source but not the \&.h) +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +Properties are accessed only via methods named as described above\&. +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +In the class source code the object is always called +self\&. +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +The constructor may take arbitrary arguments, and returns NULL on failure, or a new object\&. +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +The destructor takes a pointer to an object reference and nullifies it\&. +.RE +.sp +Return values for methods are: +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +For methods that return an object reference, either the reference, or NULL on failure\&. +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +For methods that signal success/failure, a return value of 0 means success, \-1 failure\&. +.RE +.sp +Private/static functions in a class are named s_functionname and are not exported via the header file\&. +.sp +All classes (with some exceptions) have a test method called zclass_test\&. +.SH "DESIGN IDEOLOGY" +.SS "The Problem with C" +.sp +C has the significant advantage of being a small language that, if we take a little care with formatting and naming, can be easily interchanged between developers\&. Every C developer will use much the same 90% of the language\&. Larger languages like C++ provide powerful abstractions like STL containers but at the cost of interchange\&. +.sp +The huge problem with C is that any realistic application needs packages of functionality to bring the language up to the levels we expect for the 21st century\&. Much can be done by using external libraries but every additional library is a dependency that makes the resulting applications harder to build and port\&. While C itself is a highly portable language (and can be made more so by careful use of the preprocessor), most C libraries consider themselves part of the operating system, and as such do not attempt to be portable\&. +.sp +The answer to this, as we learned from building enterprise\-level C applications at iMatix from 1995\-2005, is to create our own fully portable, high\-quality libraries of pre\-packaged functionality, in C\&. Doing this right solves both the requirements of richness of the language, and of portability of the final applications\&. +.SS "A Simple Class Model" +.sp +C has no standard API style\&. It is one thing to write a useful component, but something else to provide an API that is consistent and obvious across many components\&. We learned from building OpenAMQ (\m[blue]\fBhttp://www\&.openamq\&.org\fR\m[]), a messaging client and server of 0\&.5M LoC, that a consistent model for extending C makes life for the application developer much easier\&. +.sp +The general model is that of a class (the source package) that provides objects (in fact C structures)\&. The application creates objects and then works with them\&. When done, the application destroys the object\&. In C, we tend to use the same name for the object as the class, when we can, and it looks like this (to take a fictitious CZMQ class): +.sp +.if n \{\ +.RS 4 +.\} +.nf + zregexp_t *regexp = zregexp_new (regexp_string); + if (!regexp) + printf ("E: invalid regular expression: %s\en", regexp_string); + else + if (zregexp_match (regexp, input_buffer)) + printf ("I: successful match for %s\en", input buffer); + zregexp_destroy (&regexp); +.fi +.if n \{\ +.RE +.\} +.sp +As far as the C program is concerned, the object is a reference to a structure (not a void pointer)\&. We pass the object reference to all methods, since this is still C\&. We could do weird stuff like put method addresses into the structure so that we can emulate a C++ syntax but it\(cqs not worthwhile\&. The goal is not to emulate an OO system, it\(cqs simply to gain consistency\&. The constructor returns an object reference, or NULL if it fails\&. The destructor nullifies the class pointer, and is idempotent\&. +.sp +What we aim at here is the simplest possible consistent syntax\&. +.sp +No model is fully consistent, and classes can define their own rules if it helps make a better result\&. For example: +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +Some classes may not be opaque\&. For example, we have cases of generated serialization classes that encode and decode structures to/from binary buffers\&. It feels clumsy to have to use methods to access the properties of these classes\&. +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +While every class has a new method that is the formal constructor, some methods may also act as constructors\&. For example, a "dup" method might take one object and return a second object\&. +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +While every class has a destroy method that is the formal destructor, some methods may also act as destructors\&. For example, a method that sends an object may also destroy the object (so that ownership of any buffers can passed to background threads)\&. Such methods take the same "pointer to a reference" argument as the destroy method\&. +.RE +.SS "Naming Style" +.sp +CZMQ aims for short, consistent names, following the theory that names we use most often should be shortest\&. Classes get one\-word names, unless they are part of a family of classes in which case they may be two words, the first being the family name\&. Methods, similarly, get one\-word names and we aim for consistency across classes (so a method that does something semantically similar in two classes will get the same name in both)\&. So the canonical name for any method is: +.sp +.if n \{\ +.RS 4 +.\} +.nf + zclassname_methodname +.fi +.if n \{\ +.RE +.\} +.sp +And the reader can easily parse this without needing special syntax to separate the class name from the method name\&. +.SS "Containers" +.sp +After a long experiment with containers, we\(cqve decided that we need exactly two containers: +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +A singly\-linked list\&. +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +A hash table using text keys\&. +.RE +.sp +These are zlist and zhash, respectively\&. Both store void pointers, with no attempt to manage the details of contained objects\&. You can use these containers to create lists of lists, hashes of lists, hashes of hashes, etc\&. +.sp +We assume that at some point we\(cqll need to switch to a doubly\-linked list\&. +.SS "Portability" +.sp +Creating a portable C application can be rewarding in terms of maintaining a single code base across many platforms, and keeping (expensive) system\-specific knowledge separate from application developers\&. In most projects (like \(/OMQ core), there is no portability layer and application code does conditional compilation for all mixes of platforms\&. This leads to quite messy code\&. +.sp +czmq acts as a portability layer, similar to but thinner than libraries like the [Apache Portable Runtime](\m[blue]\fBhttp://apr\&.apache\&.org\fR\m[]) (APR)\&. +.sp +These are the places a C application is subject to arbitrary system differences: +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +Different compilers may offer slightly different variants of the C language, often lacking specific types or using neat non\-portable names\&. Windows is a big culprit here\&. We solve this by +\fIpatching\fR +the language in czmq_prelude\&.h, e\&.g\&. defining int64_t on Windows\&. +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +System header files are inconsistent, i\&.e\&. you need to include different files depending on the OS type and version\&. We solve this by pulling in all necessary header files in czmq_prelude\&.h\&. This is a proven brute\-force approach that increases recompilation times but eliminates a major source of pain\&. +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +System libraries are inconsistent, i\&.e\&. you need to link with different libraries depending on the OS type and version\&. We solve this with an external compilation tool, +\fIC\fR, which detects the OS type and version (at runtime) and builds the necessary link commands\&. +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +System functions are inconsistent, i\&.e\&. you need to call different functions depending, again, on OS type and version\&. We solve this by building small abstract classes that handle specific areas of functionality, and doing conditional compilation in these\&. +.RE +.sp +An example of the last: +.sp +.if n \{\ +.RS 4 +.\} +.nf + #if (defined (__UNIX__)) + pid = GetCurrentProcessId(); + #elif (defined (__WINDOWS__)) + pid = getpid (); + #else + pid = 0; + #endif +.fi +.if n \{\ +.RE +.\} +.sp +CZMQ uses the GNU autotools system, so non\-portable code can use the macros this defines\&. It can also use macros defined by the czmq_prelude\&.h header file\&. +.SS "Technical Aspects" +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} + +\fBThread safety\fR: the use of opaque structures is thread safe, though \(/OMQ applications should not share state between threads in any case\&. +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} + +\fBName spaces\fR: we prefix class names with +z, which ensures that all exported functions are globally safe\&. +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} + +\fBLibrary versioning\fR: we don\(cqt make any attempt to version the library at this stage\&. Classes are in our experience highly stable once they are built and tested, the only changes typically being added methods\&. +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} + +\fBPerformance\fR: for critical path processing, you may want to avoid creating and destroying classes\&. However on modern Linux systems the heap allocator is very fast\&. Individual classes can choose whether or not to nullify their data on allocation\&. +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} + +\fBSelf\-testing\fR: every class has a +selftest +method that runs through the methods of the class\&. In theory, calling all selftest functions of all classes does a full unit test of the library\&. The +czmq_selftest +application does this\&. +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} + +\fBMemory management\fR: CZMQ classes do not use any special memory management techiques to detect leaks\&. We\(cqve done this in the past but it makes the code relatively complex\&. Instead, we do memory leak testing using tools like valgrind\&. +.RE +.SH "UNDER THE HOOD" +.SS "Adding a New Class" +.sp +If you define a new CZMQ class myclass you need to: +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +Write the +zmyclass\&.c +and +zmyclass\&.h +source files, in +src +and +include +respectively\&. +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +Add`#include ` to +include/czmq\&.h\&. +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +Add the myclass header and test call to +src/czmq_selftest\&.c\&. +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +Add a reference documentation to +\fIdoc/zmyclass\&.txt\fR\&. +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +Add myclass to \*(Aqsrc/Makefile\&.am` and +doc/Makefile\&.am\&. +.RE +.sp +The bin/newclass\&.sh shell script will automate these steps for you\&. +.SS "Coding Style" +.sp +In general the zctx class defines the style for the whole library\&. The overriding rules for coding style are consistency, clarity, and ease of maintenance\&. We use the C99 standard for syntax including principally: +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +The // comment style\&. +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +Variables definitions placed in or before the code that uses them\&. +.RE +.sp +So while ANSI C code might say: +.sp +.if n \{\ +.RS 4 +.\} +.nf + zblob_t *file_buffer; /* Buffer for our file */ + \&.\&.\&. (100 lines of code) + file_buffer = zblob_new (); + \&.\&.\&. +.fi +.if n \{\ +.RE +.\} +.sp +The style in CZMQ would be: +.sp +.if n \{\ +.RS 4 +.\} +.nf + zblob_t *file_buffer = zblob_new (); +.fi +.if n \{\ +.RE +.\} +.SS "Assertions" +.sp +We use assertions heavily to catch bad argument values\&. The CZMQ classes do not attempt to validate arguments and report errors; bad arguments are treated as fatal application programming errors\&. +.sp +We also use assertions heavily on calls to system functions that are never supposed to fail, where failure is to be treated as a fatal non\-recoverable error (e\&.g\&. running out of memory)\&. +.sp +Assertion code should always take this form: +.sp +.if n \{\ +.RS 4 +.\} +.nf + int rc = some_function (arguments); + assert (rc == 0); +.fi +.if n \{\ +.RE +.\} +.sp +Rather than the side\-effect form: +.sp +.if n \{\ +.RS 4 +.\} +.nf + assert (some_function (arguments) == 0); +.fi +.if n \{\ +.RE +.\} +.sp +Since assertions may be removed by an optimizing compiler\&. +.SS "Documentation" +.sp +Man pages are generated from the class header and source files via the doc/mkman tool, and similar functionality in the gitdown tool (\m[blue]\fBhttp://github\&.com/imatix/gitdown\fR\m[])\&. The header file for a class must wrap its interface as follows (example is from include/zclock\&.h): +.sp +.if n \{\ +.RS 4 +.\} +.nf + // @interface + // Sleep for a number of milliseconds + void + zclock_sleep (int msecs); + + // Return current system clock as milliseconds + int64_t + zclock_time (void); + + // Self test of this class + int + zclock_test (Bool verbose); + // @end +.fi +.if n \{\ +.RE +.\} +.sp +The source file for a class must provide documentation as follows: +.sp +.if n \{\ +.RS 4 +.\} +.nf + /* + @header + \&.\&.\&.short explanation of class\&.\&.\&. + @discuss + \&.\&.\&.longer discussion of how it works\&.\&.\&. + @end + */ +.fi +.if n \{\ +.RE +.\} +.sp +The source file for a class then provides the self test example as follows: +.sp +.if n \{\ +.RS 4 +.\} +.nf + // @selftest + int64_t start = zclock_time (); + zclock_sleep (10); + assert ((zclock_time () \- start) >= 10); + // @end +.fi +.if n \{\ +.RE +.\} +.sp +The template for man pages is in doc/mkman\&. +.SS "Development" +.sp +CZMQ is developed through a test\-driven process that guarantees no memory violations or leaks in the code: +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +Modify a class or method\&. +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +Update the test method for that class\&. +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +Run the +\fIselftest\fR +script, which uses the Valgrind memcheck tool\&. +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +Repeat until perfect\&. +.RE +.SS "Porting CZMQ" +.sp +When you try CZMQ on an OS that it\(cqs not been used on (ever, or for a while), you will hit code that does not compile\&. In some cases the patches are trivial, in other cases (usually when porting to Windows), the work needed to build equivalent functionality may be quite heavy\&. In any case, the benefit is that once ported, the functionality is available to all applications\&. +.sp +Before attempting to patch code for portability, please read the czmq_prelude\&.h header file\&. There are several typical types of changes you may need to make to get functionality working on a specific operating system: +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +Defining typedefs which are missing on that specific compiler: do this in czmq_prelude\&.h\&. +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +Defining macros that rename exotic library functions to more conventional names: do this in czmq_prelude\&.h\&. +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +Reimplementing specific methods to use a non\-standard API: this is typically needed on Windows\&. Do this in the relevant class, using #ifdefs to properly differentiate code for different platforms\&. +.RE +.sp +The canonical \fIstandard operating system\fR for all CZMQ code is Linux, gcc, POSIX\&. +.SH "AUTHORS" +.sp +The czmq manual was written by the authors in the AUTHORS file\&. +.SH "RESOURCES" +.sp +Main web site: \m[blue]\fB\%\fR\m[] +.sp +Report bugs to the email <\m[blue]\fBzeromq\-dev@lists\&.zeromq\&.org\fR\m[]\&\s-2\u[1]\d\s+2> +.SH "COPYRIGHT" +.sp +Copyright (c) the Contributors as noted in the AUTHORS file\&. This file is part of CZMQ, the high\-level C binding for 0MQ: http://czmq\&.zeromq\&.org\&. This Source Code Form is subject to the terms of the Mozilla Public License, v\&. 2\&.0\&. If a copy of the MPL was not distributed with this file, You can obtain one at http://mozilla\&.org/MPL/2\&.0/\&. LICENSE included with the czmq distribution\&. +.SH "NOTES" +.IP " 1." 4 +zeromq-dev@lists.zeromq.org +.RS 4 +\%mailto:zeromq-dev@lists.zeromq.org +.RE diff --git a/phonelibs/zmq/aarch64-linux/share/man/man7/zmq.7 b/phonelibs/zmq/aarch64-linux/share/man/man7/zmq.7 new file mode 100644 index 00000000000000..45224c4859df39 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man7/zmq.7 @@ -0,0 +1,275 @@ +'\" t +.\" Title: zmq +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.78.1 +.\" Date: 02/18/2017 +.\" Manual: 0MQ Manual +.\" Source: 0MQ 4.2.2 +.\" Language: English +.\" +.TH "ZMQ" "7" "02/18/2017" "0MQ 4\&.2\&.2" "0MQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zmq \- 0MQ lightweight messaging kernel +.SH "SYNOPSIS" +.sp +\fB#include \fR +.sp +\fBcc\fR [\fIflags\fR] \fIfiles\fR \fB\-lzmq\fR [\fIlibraries\fR] +.SH "DESCRIPTION" +.sp +The 0MQ lightweight messaging kernel is a library which extends the standard socket interfaces with features traditionally provided by specialised \fImessaging middleware\fR products\&. 0MQ sockets provide an abstraction of asynchronous \fImessage queues\fR, multiple \fImessaging patterns\fR, message filtering (\fIsubscriptions\fR), seamless access to multiple \fItransport protocols\fR and more\&. +.sp +This documentation presents an overview of 0MQ concepts, describes how 0MQ abstracts standard sockets and provides a reference manual for the functions provided by the 0MQ library\&. +.SS "Context" +.sp +The 0MQ \fIcontext\fR keeps the list of sockets and manages the async I/O thread and internal queries\&. +.sp +Before using any 0MQ library functions you must create a 0MQ \fIcontext\fR\&. When you exit your application you must destroy the \fIcontext\fR\&. These functions let you work with \fIcontexts\fR: +.PP +Create a new 0MQ context +.RS 4 +\fBzmq_ctx_new\fR(3) +.RE +.PP +Work with context properties +.RS 4 +\fBzmq_ctx_set\fR(3)\fBzmq_ctx_get\fR(3) +.RE +.PP +Destroy a 0MQ context +.RS 4 +\fBzmq_ctx_shutdown\fR(3)\fBzmq_ctx_term\fR(3) +.RE +.sp +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBThread safety\fR +.RS 4 +.sp +A 0MQ \fIcontext\fR is thread safe and may be shared among as many application threads as necessary, without any additional locking required on the part of the caller\&. +.sp +Individual 0MQ \fIsockets\fR are \fInot\fR thread safe except in the case where full memory barriers are issued when migrating a socket from one thread to another\&. In practice this means applications can create a socket in one thread with \fIzmq_socket()\fR and then pass it to a \fInewly created\fR thread as part of thread initialisation, for example via a structure passed as an argument to \fIpthread_create()\fR\&. +.RE +.sp +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBMultiple contexts\fR +.RS 4 +.sp +Multiple \fIcontexts\fR may coexist within a single application\&. Thus, an application can use 0MQ directly and at the same time make use of any number of additional libraries or components which themselves make use of 0MQ as long as the above guidelines regarding thread safety are adhered to\&. +.RE +.SS "Messages" +.sp +A 0MQ message is a discrete unit of data passed between applications or components of the same application\&. 0MQ messages have no internal structure and from the point of view of 0MQ itself they are considered to be opaque binary data\&. +.sp +The following functions are provided to work with messages: +.PP +Initialise a message +.RS 4 +\fBzmq_msg_init\fR(3)\fBzmq_msg_init_size\fR(3)\fBzmq_msg_init_data\fR(3) +.RE +.PP +Sending and receiving a message +.RS 4 +\fBzmq_msg_send\fR(3)\fBzmq_msg_recv\fR(3) +.RE +.PP +Release a message +.RS 4 +\fBzmq_msg_close\fR(3) +.RE +.PP +Access message content +.RS 4 +\fBzmq_msg_data\fR(3)\fBzmq_msg_size\fR(3)\fBzmq_msg_more\fR(3) +.RE +.PP +Work with message properties +.RS 4 +\fBzmq_msg_gets\fR(3)\fBzmq_msg_get\fR(3)\fBzmq_msg_set\fR(3) +.RE +.PP +Message manipulation +.RS 4 +\fBzmq_msg_copy\fR(3)\fBzmq_msg_move\fR(3) +.RE +.SS "Sockets" +.sp +0MQ sockets present an abstraction of a asynchronous \fImessage queue\fR, with the exact queueing semantics depending on the socket type in use\&. See \fBzmq_socket\fR(3) for the socket types provided\&. +.sp +The following functions are provided to work with sockets: +.PP +Creating a socket +.RS 4 +\fBzmq_socket\fR(3) +.RE +.PP +Closing a socket +.RS 4 +\fBzmq_close\fR(3) +.RE +.PP +Manipulating socket options +.RS 4 +\fBzmq_getsockopt\fR(3)\fBzmq_setsockopt\fR(3) +.RE +.PP +Establishing a message flow +.RS 4 +\fBzmq_bind\fR(3)\fBzmq_connect\fR(3) +.RE +.PP +Sending and receiving messages +.RS 4 +\fBzmq_msg_send\fR(3)\fBzmq_msg_recv\fR(3)\fBzmq_send\fR(3)\fBzmq_recv\fR(3)\fBzmq_send_const\fR(3) +.RE +.PP +Monitoring socket events +.RS 4 +\fBzmq_socket_monitor\fR(3) +.RE +.PP +\fBInput/output multiplexing\fR. 0MQ provides a mechanism for applications to multiplex input/output events over a set containing both 0MQ sockets and standard sockets\&. This mechanism mirrors the standard +\fIpoll()\fR +system call, and is described in detail in +\fBzmq_poll\fR(3)\&. +.SS "Transports" +.sp +A 0MQ socket can use multiple different underlying transport mechanisms\&. Each transport mechanism is suited to a particular purpose and has its own advantages and drawbacks\&. +.sp +The following transport mechanisms are provided: +.PP +Unicast transport using TCP +.RS 4 +\fBzmq_tcp\fR(7) +.RE +.PP +Reliable multicast transport using PGM +.RS 4 +\fBzmq_pgm\fR(7) +.RE +.PP +Local inter\-process communication transport +.RS 4 +\fBzmq_ipc\fR(7) +.RE +.PP +Local in\-process (inter\-thread) communication transport +.RS 4 +\fBzmq_inproc\fR(7) +.RE +.PP +Virtual Machine Communications Interface (VMC) transport +.RS 4 +\fBzmq_vmci\fR(7) +.RE +.PP +Unreliable unicast and multicast using UDP +.RS 4 +\fBzmq_udp\fR(7) +.RE +.SS "Proxies" +.sp +0MQ provides \fIproxies\fR to create fanout and fan\-in topologies\&. A proxy connects a \fIfrontend\fR socket to a \fIbackend\fR socket and switches all messages between the two sockets, opaquely\&. A proxy may optionally capture all traffic to a third socket\&. To start a proxy in an application thread, use \fBzmq_proxy\fR(3)\&. +.SS "Security" +.sp +A 0MQ socket can select a security mechanism\&. Both peers must use the same security mechanism\&. +.sp +The following security mechanisms are provided for IPC and TCP connections: +.PP +Null security +.RS 4 +\fBzmq_null\fR(7) +.RE +.PP +Plain\-text authentication using username and password +.RS 4 +\fBzmq_plain\fR(7) +.RE +.PP +Elliptic curve authentication and encryption +.RS 4 +\fBzmq_curve\fR(7) +.RE +.PP +Generate a CURVE keypair in armored text format +.RS 4 +\fBzmq_curve_keypair\fR(3) +.RE +.sp +Derive a CURVE public key from a secret key: \fBzmq_curve_public\fR(3) +.PP +Converting keys to/from armoured text strings +.RS 4 +\fBzmq_z85_decode\fR(3)\fBzmq_z85_encode\fR(3) +.RE +.SH "ERROR HANDLING" +.sp +The 0MQ library functions handle errors using the standard conventions found on POSIX systems\&. Generally, this means that upon failure a 0MQ library function shall return either a NULL value (if returning a pointer) or a negative value (if returning an integer), and the actual error code shall be stored in the \fIerrno\fR variable\&. +.sp +On non\-POSIX systems some users may experience issues with retrieving the correct value of the \fIerrno\fR variable\&. The \fIzmq_errno()\fR function is provided to assist in these cases; for details refer to \fBzmq_errno\fR(3)\&. +.sp +The \fIzmq_strerror()\fR function is provided to translate 0MQ\-specific error codes into error message strings; for details refer to \fBzmq_strerror\fR(3)\&. +.SH "UTILITY" +.sp +The following utility functions are provided: +.PP +Working with atomic counters +.RS 4 +\fBzmq_atomic_counter_new\fR(3)\fBzmq_atomic_counter_set\fR(3)\fBzmq_atomic_counter_inc\fR(3)\fBzmq_atomic_counter_dec\fR(3)\fBzmq_atomic_counter_value\fR(3)\fBzmq_atomic_counter_destroy\fR(3) +.RE +.SH "MISCELLANEOUS" +.sp +The following miscellaneous functions are provided: +.PP +Report 0MQ library version +.RS 4 +\fBzmq_version\fR(3) +.RE +.SH "LANGUAGE BINDINGS" +.sp +The 0MQ library provides interfaces suitable for calling from programs in any language; this documentation documents those interfaces as they would be used by C programmers\&. The intent is that programmers using 0MQ from other languages shall refer to this documentation alongside any documentation provided by the vendor of their language binding\&. +.sp +Language bindings (C++, Python, PHP, Ruby, Java and more) are provided by members of the 0MQ community and pointers can be found on the 0MQ website\&. +.SH "AUTHORS" +.sp +This page was written by the 0MQ community\&. To make a change please read the 0MQ Contribution Policy at \m[blue]\fBhttp://www\&.zeromq\&.org/docs:contributing\fR\m[]\&. +.SH "RESOURCES" +.sp +Main web site: \m[blue]\fBhttp://www\&.zeromq\&.org/\fR\m[] +.sp +Report bugs to the 0MQ development mailing list: <\m[blue]\fBzeromq\-dev@lists\&.zeromq\&.org\fR\m[]\&\s-2\u[1]\d\s+2> +.SH "COPYING" +.sp +Free use of this software is granted under the terms of the GNU Lesser General Public License (LGPL)\&. For details see the files COPYING and COPYING\&.LESSER included with the 0MQ distribution\&. +.SH "NOTES" +.IP " 1." 4 +zeromq-dev@lists.zeromq.org +.RS 4 +\%mailto:zeromq-dev@lists.zeromq.org +.RE diff --git a/phonelibs/zmq/aarch64-linux/share/man/man7/zmq_curve.7 b/phonelibs/zmq/aarch64-linux/share/man/man7/zmq_curve.7 new file mode 100644 index 00000000000000..675effc437045d --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man7/zmq_curve.7 @@ -0,0 +1,93 @@ +'\" t +.\" Title: zmq_curve +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.78.1 +.\" Date: 02/18/2017 +.\" Manual: 0MQ Manual +.\" Source: 0MQ 4.2.2 +.\" Language: English +.\" +.TH "ZMQ_CURVE" "7" "02/18/2017" "0MQ 4\&.2\&.2" "0MQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zmq_curve \- secure authentication and confidentiality +.SH "SYNOPSIS" +.sp +The CURVE mechanism defines a mechanism for secure authentication and confidentiality for communications between a client and a server\&. CURVE is intended for use on public networks\&. The CURVE mechanism is defined by this document: \m[blue]\fBhttp://rfc\&.zeromq\&.org/spec:25\fR\m[]\&. +.SH "CLIENT AND SERVER ROLES" +.sp +A socket using CURVE can be either client or server, at any moment, but not both\&. The role is independent of bind/connect direction\&. +.sp +A socket can change roles at any point by setting new options\&. The role affects all zmq_connect and zmq_bind calls that follow it\&. +.sp +To become a CURVE server, the application sets the ZMQ_CURVE_SERVER option on the socket, and then sets the ZMQ_CURVE_SECRETKEY option to provide the socket with its long\-term secret key\&. The application does not provide the socket with its long\-term public key, which is used only by clients\&. +.sp +To become a CURVE client, the application sets the ZMQ_CURVE_SERVERKEY option with the long\-term public key of the server it intends to connect to, or accept connections from, next\&. The application then sets the ZMQ_CURVE_PUBLICKEY and ZMQ_CURVE_SECRETKEY options with its client long\-term key pair\&. +.sp +If the server does authentication it will be based on the client\(cqs long term public key\&. +.SH "KEY ENCODING" +.sp +The standard representation for keys in source code is either 32 bytes of base 256 (binary) data, or 40 characters of base 85 data encoded using the Z85 algorithm defined by \m[blue]\fBhttp://rfc\&.zeromq\&.org/spec:32\fR\m[]\&. +.sp +The Z85 algorithm is designed to produce printable key strings for use in configuration files, the command line, and code\&. There is a reference implementation in C at \m[blue]\fBhttps://github\&.com/zeromq/rfc/tree/master/src\fR\m[]\&. +.SH "TEST KEY VALUES" +.sp +For test cases, the client shall use this long\-term key pair (specified as hexadecimal and in Z85): +.sp +.if n \{\ +.RS 4 +.\} +.nf +public: + BB88471D65E2659B30C55A5321CEBB5AAB2B70A398645C26DCA2B2FCB43FC518 + Yne@$w\-vo}U?@Lns47E1%kR\&.o@n%FcmmsL/@{H8]yf7 + +secret: + 8E0BDD697628B91D8F245587EE95C5B04D48963F79259877B49CD9063AEAD3B7 + JTKVSB%%)wK0E\&.X)V>+}o?pNmC{O&4W4b!Ni{Lh6 +.fi +.if n \{\ +.RE +.\} +.SH "SEE ALSO" +.sp +\fBzmq_z85_encode\fR(3) \fBzmq_z85_decode\fR(3) \fBzmq_setsockopt\fR(3) \fBzmq_null\fR(7) \fBzmq_plain\fR(7) \fBzmq\fR(7) +.SH "AUTHORS" +.sp +This page was written by the 0MQ community\&. To make a change please read the 0MQ Contribution Policy at \m[blue]\fBhttp://www\&.zeromq\&.org/docs:contributing\fR\m[]\&. diff --git a/phonelibs/zmq/aarch64-linux/share/man/man7/zmq_inproc.7 b/phonelibs/zmq/aarch64-linux/share/man/man7/zmq_inproc.7 new file mode 100644 index 00000000000000..a0b0e72d3f71d6 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man7/zmq_inproc.7 @@ -0,0 +1,103 @@ +'\" t +.\" Title: zmq_inproc +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.78.1 +.\" Date: 02/18/2017 +.\" Manual: 0MQ Manual +.\" Source: 0MQ 4.2.2 +.\" Language: English +.\" +.TH "ZMQ_INPROC" "7" "02/18/2017" "0MQ 4\&.2\&.2" "0MQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zmq_inproc \- 0MQ local in\-process (inter\-thread) communication transport +.SH "SYNOPSIS" +.sp +The in\-process transport passes messages via memory directly between threads sharing a single 0MQ \fIcontext\fR\&. +.if n \{\ +.sp +.\} +.RS 4 +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBNote\fR +.ps -1 +.br +.sp +No I/O threads are involved in passing messages using the \fIinproc\fR transport\&. Therefore, if you are using a 0MQ \fIcontext\fR for in\-process messaging only you can initialise the \fIcontext\fR with zero I/O threads\&. See \fBzmq_init\fR(3) for details\&. +.sp .5v +.RE +.SH "ADDRESSING" +.sp +A 0MQ endpoint is a string consisting of a \fItransport\fR:// followed by an \fIaddress\fR\&. The \fItransport\fR specifies the underlying protocol to use\&. The \fIaddress\fR specifies the transport\-specific address to connect to\&. +.sp +For the in\-process transport, the transport is inproc, and the meaning of the \fIaddress\fR part is defined below\&. +.SS "Assigning a local address to a socket" +.sp +When assigning a local address to a \fIsocket\fR using \fIzmq_bind()\fR with the \fIinproc\fR transport, the \fIendpoint\fR shall be interpreted as an arbitrary string identifying the \fIname\fR to create\&. The \fIname\fR must be unique within the 0MQ \fIcontext\fR associated with the \fIsocket\fR and may be up to 256 characters in length\&. No other restrictions are placed on the format of the \fIname\fR\&. +.SS "Connecting a socket" +.sp +When connecting a \fIsocket\fR to a peer address using \fIzmq_connect()\fR with the \fIinproc\fR transport, the \fIendpoint\fR shall be interpreted as an arbitrary string identifying the \fIname\fR to connect to\&. Before version 4\&.0 he \fIname\fR must have been previously created by assigning it to at least one \fIsocket\fR within the same 0MQ \fIcontext\fR as the \fIsocket\fR being connected\&. Since version 4\&.0 the order of \fIzmq_bind()\fR and \fIzmq_connect()\fR does not matter just like for the tcp transport type\&. +.SH "EXAMPLES" +.PP +\fBAssigning a local address to a socket\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +// Assign the in\-process name "#1" +rc = zmq_bind(socket, "inproc://#1"); +assert (rc == 0); +// Assign the in\-process name "my\-endpoint" +rc = zmq_bind(socket, "inproc://my\-endpoint"); +assert (rc == 0); +.fi +.if n \{\ +.RE +.\} +.PP +\fBConnecting a socket\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +// Connect to the in\-process name "#1" +rc = zmq_connect(socket, "inproc://#1"); +assert (rc == 0); +// Connect to the in\-process name "my\-endpoint" +rc = zmq_connect(socket, "inproc://my\-endpoint"); +assert (rc == 0); +.fi +.if n \{\ +.RE +.\} +.sp +.SH "SEE ALSO" +.sp +\fBzmq_bind\fR(3) \fBzmq_connect\fR(3) \fBzmq_ipc\fR(7) \fBzmq_tcp\fR(7) \fBzmq_pgm\fR(7) \fBzmq_vmci\fR(7) \fBzmq\fR(7) +.SH "AUTHORS" +.sp +This page was written by the 0MQ community\&. To make a change please read the 0MQ Contribution Policy at \m[blue]\fBhttp://www\&.zeromq\&.org/docs:contributing\fR\m[]\&. diff --git a/phonelibs/zmq/aarch64-linux/share/man/man7/zmq_ipc.7 b/phonelibs/zmq/aarch64-linux/share/man/man7/zmq_ipc.7 new file mode 100644 index 00000000000000..c190b6f1215f10 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man7/zmq_ipc.7 @@ -0,0 +1,166 @@ +'\" t +.\" Title: zmq_ipc +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.78.1 +.\" Date: 02/18/2017 +.\" Manual: 0MQ Manual +.\" Source: 0MQ 4.2.2 +.\" Language: English +.\" +.TH "ZMQ_IPC" "7" "02/18/2017" "0MQ 4\&.2\&.2" "0MQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zmq_ipc \- 0MQ local inter\-process communication transport +.SH "SYNOPSIS" +.sp +The inter\-process transport passes messages between local processes using a system\-dependent IPC mechanism\&. +.if n \{\ +.sp +.\} +.RS 4 +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBNote\fR +.ps -1 +.br +.sp +The inter\-process transport is currently only implemented on operating systems that provide UNIX domain sockets\&. +.sp .5v +.RE +.SH "ADDRESSING" +.sp +A 0MQ endpoint is a string consisting of a \fItransport\fR:// followed by an \fIaddress\fR\&. The \fItransport\fR specifies the underlying protocol to use\&. The \fIaddress\fR specifies the transport\-specific address to connect to\&. +.sp +For the inter\-process transport, the transport is ipc, and the meaning of the \fIaddress\fR part is defined below\&. +.SS "Binding a socket" +.sp +When binding a \fIsocket\fR to a local address using \fIzmq_bind()\fR with the \fIipc\fR transport, the \fIendpoint\fR shall be interpreted as an arbitrary string identifying the \fIpathname\fR to create\&. The \fIpathname\fR must be unique within the operating system namespace used by the \fIipc\fR implementation, and must fulfill any restrictions placed by the operating system on the format and length of a \fIpathname\fR\&. +.sp +When the address is wild\-card *, \fIzmq_bind()\fR shall generate a unique temporary pathname\&. The caller should retrieve this pathname using the ZMQ_LAST_ENDPOINT socket option\&. See \fBzmq_getsockopt\fR(3) for details\&. +.if n \{\ +.sp +.\} +.RS 4 +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBNote\fR +.ps -1 +.br +.sp +any existing binding to the same endpoint shall be overridden\&. That is, if a second process binds to an endpoint already bound by a process, this will succeed and the first process will lose its binding\&. In this behaviour, the \fIipc\fR transport is not consistent with the \fItcp\fR or \fIinproc\fR transports\&. +.sp .5v +.RE +.if n \{\ +.sp +.\} +.RS 4 +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBNote\fR +.ps -1 +.br +.sp +the endpoint pathname must be writable by the process\&. When the endpoint starts with \fI/\fR, e\&.g\&., ipc:///pathname, this will be an \fIabsolute\fR pathname\&. If the endpoint specifies a directory that does not exist, the bind shall fail\&. +.sp .5v +.RE +.if n \{\ +.sp +.\} +.RS 4 +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBNote\fR +.ps -1 +.br +.sp +on Linux only, when the endpoint pathname starts with @, the abstract namespace shall be used\&. The abstract namespace is independent of the filesystem and if a process attempts to bind an endpoint already bound by a process, it will fail\&. See unix(7) for details\&. +.sp .5v +.RE +.if n \{\ +.sp +.\} +.RS 4 +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBNote\fR +.ps -1 +.br +.sp +IPC pathnames have a maximum size that depends on the operating system\&. On Linux, the maximum is 113 characters including the "ipc://" prefix (107 characters for the real path name)\&. +.sp .5v +.RE +.SS "Unbinding wild\-card address from a socket" +.sp +When wild\-card * \fIendpoint\fR was used in \fIzmq_bind()\fR, the caller should use real \fIendpoint\fR obtained from the ZMQ_LAST_ENDPOINT socket option to unbind this \fIendpoint\fR from a socket using \fIzmq_unbind()\fR\&. +.SS "Connecting a socket" +.sp +When connecting a \fIsocket\fR to a peer address using \fIzmq_connect()\fR with the \fIipc\fR transport, the \fIendpoint\fR shall be interpreted as an arbitrary string identifying the \fIpathname\fR to connect to\&. The \fIpathname\fR must have been previously created within the operating system namespace by assigning it to a \fIsocket\fR with \fIzmq_bind()\fR\&. +.SH "EXAMPLES" +.PP +\fBAssigning a local address to a socket\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +// Assign the pathname "/tmp/feeds/0" +rc = zmq_bind(socket, "ipc:///tmp/feeds/0"); +assert (rc == 0); +.fi +.if n \{\ +.RE +.\} +.PP +\fBConnecting a socket\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +// Connect to the pathname "/tmp/feeds/0" +rc = zmq_connect(socket, "ipc:///tmp/feeds/0"); +assert (rc == 0); +.fi +.if n \{\ +.RE +.\} +.sp +.SH "SEE ALSO" +.sp +\fBzmq_bind\fR(3) \fBzmq_connect\fR(3) \fBzmq_inproc\fR(7) \fBzmq_tcp\fR(7) \fBzmq_pgm\fR(7) \fBzmq_vmci\fR(7) \fBzmq_getsockopt\fR(3) \fBzmq\fR(7) +.SH "AUTHORS" +.sp +This page was written by the 0MQ community\&. To make a change please read the 0MQ Contribution Policy at \m[blue]\fBhttp://www\&.zeromq\&.org/docs:contributing\fR\m[]\&. diff --git a/phonelibs/zmq/aarch64-linux/share/man/man7/zmq_null.7 b/phonelibs/zmq/aarch64-linux/share/man/man7/zmq_null.7 new file mode 100644 index 00000000000000..42497a11594113 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man7/zmq_null.7 @@ -0,0 +1,40 @@ +'\" t +.\" Title: zmq_null +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.78.1 +.\" Date: 02/18/2017 +.\" Manual: 0MQ Manual +.\" Source: 0MQ 4.2.2 +.\" Language: English +.\" +.TH "ZMQ_NULL" "7" "02/18/2017" "0MQ 4\&.2\&.2" "0MQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zmq_null \- no security or confidentiality +.SH "SYNOPSIS" +.sp +The NULL mechanism is defined by the ZMTP 3\&.0 specification: \m[blue]\fBhttp://rfc\&.zeromq\&.org/spec:23\fR\m[]\&. This is the default security mechanism for ZeroMQ sockets\&. +.SH "SEE ALSO" +.sp +\fBzmq_plain\fR(7) \fBzmq_curve\fR(7) \fBzmq\fR(7) +.SH "AUTHORS" +.sp +This page was written by the 0MQ community\&. To make a change please read the 0MQ Contribution Policy at \m[blue]\fBhttp://www\&.zeromq\&.org/docs:contributing\fR\m[]\&. diff --git a/phonelibs/zmq/aarch64-linux/share/man/man7/zmq_pgm.7 b/phonelibs/zmq/aarch64-linux/share/man/man7/zmq_pgm.7 new file mode 100644 index 00000000000000..ea8ca3fc155eb9 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man7/zmq_pgm.7 @@ -0,0 +1,200 @@ +'\" t +.\" Title: zmq_pgm +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.78.1 +.\" Date: 02/18/2017 +.\" Manual: 0MQ Manual +.\" Source: 0MQ 4.2.2 +.\" Language: English +.\" +.TH "ZMQ_PGM" "7" "02/18/2017" "0MQ 4\&.2\&.2" "0MQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zmq_pgm \- 0MQ reliable multicast transport using PGM +.SH "SYNOPSIS" +.sp +PGM (Pragmatic General Multicast) is a protocol for reliable multicast transport of data over IP networks\&. +.SH "DESCRIPTION" +.sp +0MQ implements two variants of PGM, the standard protocol where PGM datagrams are layered directly on top of IP datagrams as defined by RFC 3208 (the \fIpgm\fR transport) and "Encapsulated PGM" or EPGM where PGM datagrams are encapsulated inside UDP datagrams (the \fIepgm\fR transport)\&. +.sp +The \fIpgm\fR and \fIepgm\fR transports can only be used with the \fIZMQ_PUB\fR and \fIZMQ_SUB\fR socket types\&. +.sp +Further, PGM sockets are rate limited by default\&. For details, refer to the \fIZMQ_RATE\fR, and \fIZMQ_RECOVERY_IVL\fR options documented in \fBzmq_setsockopt\fR(3)\&. +.if n \{\ +.sp +.\} +.RS 4 +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBCaution\fR +.ps -1 +.br +.sp +The \fIpgm\fR transport implementation requires access to raw IP sockets\&. Additional privileges may be required on some operating systems for this operation\&. Applications not requiring direct interoperability with other PGM implementations are encouraged to use the \fIepgm\fR transport instead which does not require any special privileges\&. +.sp .5v +.RE +.SH "ADDRESSING" +.sp +A 0MQ endpoint is a string consisting of a \fItransport\fR:// followed by an \fIaddress\fR\&. The \fItransport\fR specifies the underlying protocol to use\&. The \fIaddress\fR specifies the transport\-specific address to connect to\&. +.sp +For the PGM transport, the transport is pgm, and for the EPGM protocol the transport is epgm\&. The meaning of the \fIaddress\fR part is defined below\&. +.SS "Connecting a socket" +.sp +When connecting a socket to a peer address using \fIzmq_connect()\fR with the \fIpgm\fR or \fIepgm\fR transport, the \fIendpoint\fR shall be interpreted as an \fIinterface\fR followed by a semicolon, followed by a \fImulticast address\fR, followed by a colon and a port number\&. +.sp +An \fIinterface\fR may be specified by either of the following: +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +The interface name as defined by the operating system\&. +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +The primary IPv4 address assigned to the interface, in its numeric representation\&. +.RE +.if n \{\ +.sp +.\} +.RS 4 +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBNote\fR +.ps -1 +.br +.sp +Interface names are not standardised in any way and should be assumed to be arbitrary and platform dependent\&. On Win32 platforms no short interface names exist, thus only the primary IPv4 address may be used to specify an \fIinterface\fR\&. The \fIinterface\fR part can be omitted, in that case the default one will be selected\&. +.sp .5v +.RE +.sp +A \fImulticast address\fR is specified by an IPv4 multicast address in its numeric representation\&. +.SH "WIRE FORMAT" +.sp +Consecutive PGM datagrams are interpreted by 0MQ as a single continuous stream of data where 0MQ messages are not necessarily aligned with PGM datagram boundaries and a single 0MQ message may span several PGM datagrams\&. This stream of data consists of 0MQ messages encapsulated in \fIframes\fR as described in \fBzmq_tcp\fR(7)\&. +.SS "PGM datagram payload" +.sp +The following ABNF grammar represents the payload of a single PGM datagram as used by 0MQ: +.sp +.if n \{\ +.RS 4 +.\} +.nf +datagram = (offset data) +offset = 2OCTET +data = *OCTET +.fi +.if n \{\ +.RE +.\} +.sp +In order for late joining consumers to be able to identify message boundaries, each PGM datagram payload starts with a 16\-bit unsigned integer in network byte order specifying either the offset of the first message \fIframe\fR in the datagram or containing the value 0xFFFF if the datagram contains solely an intermediate part of a larger message\&. +.sp +Note that offset specifies where the first message begins rather than the first message part\&. Thus, if there are trailing message parts at the beginning of the packet the offset ignores them and points to first initial message part in the packet\&. +.sp +The following diagram illustrates the layout of a single PGM datagram payload: +.sp +.if n \{\ +.RS 4 +.\} +.nf ++\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-+\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-+ +| offset (16 bits) | data | ++\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-+\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-+ +.fi +.if n \{\ +.RE +.\} +.sp +The following diagram further illustrates how three example 0MQ frames are laid out in consecutive PGM datagram payloads: +.sp +.if n \{\ +.RS 4 +.\} +.nf +First datagram payload ++\-\-\-\-\-\-\-\-\-\-\-\-\-\-+\-\-\-\-\-\-\-\-\-\-\-\-\-+\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-+ +| Frame offset | Frame 1 | Frame 2, part 1 | +| 0x0000 | (Message 1) | (Message 2, part 1) | ++\-\-\-\-\-\-\-\-\-\-\-\-\-\-+\-\-\-\-\-\-\-\-\-\-\-\-\-+\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-+ + +Second datagram payload ++\-\-\-\-\-\-\-\-\-\-\-\-\-\-+\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-+ +| Frame offset | Frame 2, part 2 | +| 0xFFFF | (Message 2, part 2) | ++\-\-\-\-\-\-\-\-\-\-\-\-\-\-+\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-+ + +Third datagram payload ++\-\-\-\-\-\-\-\-\-\-\-\-\-\-+\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-+\-\-\-\-\-\-\-\-\-\-\-\-\-+ +| Frame offset | Frame 2, final 8 bytes | Frame 3 | +| 0x0008 | (Message 2, final 8 bytes) | (Message 3) | ++\-\-\-\-\-\-\-\-\-\-\-\-\-\-+\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-\-+\-\-\-\-\-\-\-\-\-\-\-\-\-+ +.fi +.if n \{\ +.RE +.\} +.SH "EXAMPLE" +.PP +\fBConnecting a socket\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +// Connecting to the multicast address 239\&.192\&.1\&.1, port 5555, +// using the first Ethernet network interface on Linux +// and the Encapsulated PGM protocol +rc = zmq_connect(socket, "epgm://eth0;239\&.192\&.1\&.1:5555"); +assert (rc == 0); +// Connecting to the multicast address 239\&.192\&.1\&.1, port 5555, +// using the network interface with the address 192\&.168\&.1\&.1 +// and the standard PGM protocol +rc = zmq_connect(socket, "pgm://192\&.168\&.1\&.1;239\&.192\&.1\&.1:5555"); +assert (rc == 0); +.fi +.if n \{\ +.RE +.\} +.sp +.SH "SEE ALSO" +.sp +\fBzmq_connect\fR(3) \fBzmq_setsockopt\fR(3) \fBzmq_tcp\fR(7) \fBzmq_ipc\fR(7) \fBzmq_inproc\fR(7) \fBzmq_vmci\fR(7) \fBzmq\fR(7) +.SH "AUTHORS" +.sp +This page was written by the 0MQ community\&. To make a change please read the 0MQ Contribution Policy at \m[blue]\fBhttp://www\&.zeromq\&.org/docs:contributing\fR\m[]\&. diff --git a/phonelibs/zmq/aarch64-linux/share/man/man7/zmq_plain.7 b/phonelibs/zmq/aarch64-linux/share/man/man7/zmq_plain.7 new file mode 100644 index 00000000000000..912c92d5a98bae --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man7/zmq_plain.7 @@ -0,0 +1,43 @@ +'\" t +.\" Title: zmq_plain +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.78.1 +.\" Date: 02/18/2017 +.\" Manual: 0MQ Manual +.\" Source: 0MQ 4.2.2 +.\" Language: English +.\" +.TH "ZMQ_PLAIN" "7" "02/18/2017" "0MQ 4\&.2\&.2" "0MQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zmq_plain \- clear\-text authentication +.SH "SYNOPSIS" +.sp +The PLAIN mechanism defines a simple username/password mechanism that lets a server authenticate a client\&. PLAIN makes no attempt at security or confidentiality\&. It is intended for use on internal networks where security requirements are low\&. The PLAIN mechanism is defined by this document: \m[blue]\fBhttp://rfc\&.zeromq\&.org/spec:24\fR\m[]\&. +.SH "USAGE" +.sp +To use PLAIN, the server shall set the ZMQ_PLAIN_SERVER option, and the client shall set the ZMQ_PLAIN_USERNAME and ZMQ_PLAIN_PASSWORD socket options\&. Which peer binds, and which connects, is not relevant\&. +.SH "SEE ALSO" +.sp +\fBzmq_setsockopt\fR(3) \fBzmq_null\fR(7) \fBzmq_curve\fR(7) \fBzmq\fR(7) +.SH "AUTHORS" +.sp +This page was written by the 0MQ community\&. To make a change please read the 0MQ Contribution Policy at \m[blue]\fBhttp://www\&.zeromq\&.org/docs:contributing\fR\m[]\&. diff --git a/phonelibs/zmq/aarch64-linux/share/man/man7/zmq_tcp.7 b/phonelibs/zmq/aarch64-linux/share/man/man7/zmq_tcp.7 new file mode 100644 index 00000000000000..e0e0e006779a55 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man7/zmq_tcp.7 @@ -0,0 +1,188 @@ +'\" t +.\" Title: zmq_tcp +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.78.1 +.\" Date: 02/18/2017 +.\" Manual: 0MQ Manual +.\" Source: 0MQ 4.2.2 +.\" Language: English +.\" +.TH "ZMQ_TCP" "7" "02/18/2017" "0MQ 4\&.2\&.2" "0MQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zmq_tcp \- 0MQ unicast transport using TCP +.SH "SYNOPSIS" +.sp +TCP is an ubiquitous, reliable, unicast transport\&. When connecting distributed applications over a network with 0MQ, using the TCP transport will likely be your first choice\&. +.SH "ADDRESSING" +.sp +A 0MQ endpoint is a string consisting of a \fItransport\fR:// followed by an \fIaddress\fR\&. The \fItransport\fR specifies the underlying protocol to use\&. The \fIaddress\fR specifies the transport\-specific address to connect to\&. +.sp +For the TCP transport, the transport is tcp, and the meaning of the \fIaddress\fR part is defined below\&. +.SS "Assigning a local address to a socket" +.sp +When assigning a local address to a socket using \fIzmq_bind()\fR with the \fItcp\fR transport, the \fIendpoint\fR shall be interpreted as an \fIinterface\fR followed by a colon and the TCP port number to use\&. +.sp +An \fIinterface\fR may be specified by either of the following: +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +The wild\-card +*, meaning all available interfaces\&. +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +The primary IPv4 or IPv6 address assigned to the interface, in its numeric representation\&. +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +The non\-portable interface name as defined by the operating system\&. +.RE +.sp +The TCP port number may be specified by: +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +A numeric value, usually above 1024 on POSIX systems\&. +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +The wild\-card +*, meaning a system\-assigned ephemeral port\&. +.RE +.sp +When using ephemeral ports, the caller should retrieve the actual assigned port using the ZMQ_LAST_ENDPOINT socket option\&. See \fBzmq_getsockopt\fR(3) for details\&. +.SS "Unbinding wild\-card address from a socket" +.sp +When wild\-card * \fIendpoint\fR was used in \fIzmq_bind()\fR, the caller should use real \fIendpoint\fR obtained from the ZMQ_LAST_ENDPOINT socket option to unbind this \fIendpoint\fR from a socket using \fIzmq_unbind()\fR\&. +.SS "Connecting a socket" +.sp +When connecting a socket to a peer address using \fIzmq_connect()\fR with the \fItcp\fR transport, the \fIendpoint\fR shall be interpreted as a \fIpeer address\fR followed by a colon and the TCP port number to use\&. You can optionally specify a \fIsource_endpoint\fR which will be used as the source address for your connection; tcp://\fIsource_endpoint\fR;\*(Aqendpoint\*(Aq, see the \fIinterface\fR description above for details\&. +.sp +A \fIpeer address\fR may be specified by either of the following: +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +The DNS name of the peer\&. +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +The IPv4 or IPv6 address of the peer, in its numeric representation\&. +.RE +.sp +Note: A description of the ZeroMQ Message Transport Protocol (ZMTP) which is used by the TCP transport can be found at \m[blue]\fBhttp://rfc\&.zeromq\&.org/spec:15\fR\m[] +.SH "EXAMPLES" +.PP +\fBAssigning a local address to a socket\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +// TCP port 5555 on all available interfaces +rc = zmq_bind(socket, "tcp://*:5555"); +assert (rc == 0); +// TCP port 5555 on the local loop\-back interface on all platforms +rc = zmq_bind(socket, "tcp://127\&.0\&.0\&.1:5555"); +assert (rc == 0); +// TCP port 5555 on the first Ethernet network interface on Linux +rc = zmq_bind(socket, "tcp://eth0:5555"); +assert (rc == 0); +.fi +.if n \{\ +.RE +.\} +.PP +\fBConnecting a socket\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +// Connecting using an IP address +rc = zmq_connect(socket, "tcp://192\&.168\&.1\&.1:5555"); +assert (rc == 0); +// Connecting using a DNS name +rc = zmq_connect(socket, "tcp://server1:5555"); +assert (rc == 0); +// Connecting using a DNS name and bind to eth1 +rc = zmq_connect(socket, "tcp://eth1:0;server1:5555"); +assert (rc == 0); +// Connecting using a IP address and bind to an IP address +rc = zmq_connect(socket, "tcp://192\&.168\&.1\&.17:5555;192\&.168\&.1\&.1:5555"); +assert (rc == 0); +.fi +.if n \{\ +.RE +.\} +.sp +.SH "SEE ALSO" +.sp +\fBzmq_bind\fR(3) \fBzmq_connect\fR(3) \fBzmq_pgm\fR(7) \fBzmq_ipc\fR(7) \fBzmq_inproc\fR(7) \fBzmq_vmci\fR(7) \fBzmq\fR(7) +.SH "AUTHORS" +.sp +This page was written by the 0MQ community\&. To make a change please read the 0MQ Contribution Policy at \m[blue]\fBhttp://www\&.zeromq\&.org/docs:contributing\fR\m[]\&. diff --git a/phonelibs/zmq/aarch64-linux/share/man/man7/zmq_tipc.7 b/phonelibs/zmq/aarch64-linux/share/man/man7/zmq_tipc.7 new file mode 100644 index 00000000000000..cef14547579f7f --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man7/zmq_tipc.7 @@ -0,0 +1,110 @@ +'\" t +.\" Title: zmq_tipc +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.78.1 +.\" Date: 02/18/2017 +.\" Manual: 0MQ Manual +.\" Source: 0MQ 4.2.2 +.\" Language: English +.\" +.TH "ZMQ_TIPC" "7" "02/18/2017" "0MQ 4\&.2\&.2" "0MQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zmq_tipc \- 0MQ unicast transport using TIPC +.SH "SYNOPSIS" +.sp +TIPC is a cluster IPC protocol with a location transparent addressing scheme\&. +.SH "ADDRESSING" +.sp +A 0MQ endpoint is a string consisting of a \fItransport\fR:// followed by an \fIaddress\fR\&. The \fItransport\fR specifies the underlying protocol to use\&. The \fIaddress\fR specifies the transport\-specific address to connect to\&. +.sp +For the TIPC transport, the transport is tipc, and the meaning of the \fIaddress\fR part is defined below\&. +.SS "Assigning a port name to a socket" +.sp +When assigning a port name to a socket using \fIzmq_bind()\fR with the \fItipc\fR transport, the \fIendpoint\fR is defined in the form: {type, lower, upper} +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +Type is the numerical (u32) ID of your service\&. +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +Lower and Upper specify a range for your service\&. +.RE +.sp +Publishing the same service with overlapping lower/upper ID\(cqs will cause connection requests to be distributed over these in a round\-robin manner\&. +.SS "Connecting a socket" +.sp +When connecting a socket to a peer address using \fIzmq_connect()\fR with the \fItipc\fR transport, the \fIendpoint\fR shall be interpreted as a service ID, followed by a comma and the instance ID\&. +.sp +The instance ID must be within the lower/upper range of a published port name for the endpoint to be valid\&. +.SH "EXAMPLES" +.PP +\fBAssigning a local address to a socket\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +// Publish TIPC service ID 5555 +rc = zmq_bind(socket, "tipc://{5555,0,0}"); +assert (rc == 0); +// Publish TIPC service ID 5555 with a service range of 0\-100 +rc = zmq_bind(socket, "tipc://{5555,0,100}"); +assert (rc == 0); +.fi +.if n \{\ +.RE +.\} +.PP +\fBConnecting a socket\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +// Connect to service 5555 instance id 50 +rc = zmq_connect(socket, "tipc://{5555,50}"); +assert (rc == 0); +.fi +.if n \{\ +.RE +.\} +.sp +.SH "SEE ALSO" +.sp +\fBzmq_bind\fR(3) \fBzmq_connect\fR(3) \fBzmq_tcp\fR(7) \fBzmq_pgm\fR(7) \fBzmq_ipc\fR(7) \fBzmq_inproc\fR(7) \fBzmq_vmci\fR(7) \fBzmq\fR(7) +.SH "AUTHORS" +.sp +This page was written by the 0MQ community\&. To make a change please read the 0MQ Contribution Policy at \m[blue]\fBhttp://www\&.zeromq\&.org/docs:contributing\fR\m[]\&. diff --git a/phonelibs/zmq/aarch64-linux/share/man/man7/zmq_udp.7 b/phonelibs/zmq/aarch64-linux/share/man/man7/zmq_udp.7 new file mode 100644 index 00000000000000..cda022097f1ded --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man7/zmq_udp.7 @@ -0,0 +1,139 @@ +'\" t +.\" Title: zmq_udp +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.78.1 +.\" Date: 02/18/2017 +.\" Manual: 0MQ Manual +.\" Source: 0MQ 4.2.2 +.\" Language: English +.\" +.TH "ZMQ_UDP" "7" "02/18/2017" "0MQ 4\&.2\&.2" "0MQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zmq_udp \- 0MQ UDP multicast and unicast transport +.SH "SYNOPSIS" +.sp +UDP is unreliable protocol transport of data over IP networks\&. UDP support both unicast and multicast communication\&. +.SH "DESCRIPTION" +.sp +UDP transport can only be used with the \fIZMQ_RADIO\fR and \fIZMQ_DISH\fR socket types\&. +.SH "ADDRESSING" +.sp +A 0MQ endpoint is a string consisting of a \fItransport\fR:// followed by an \fIaddress\fR\&. The \fItransport\fR specifies the underlying protocol to use\&. The \fIaddress\fR specifies the transport\-specific address to connect to\&. +.sp +For the UDP transport, the transport is udp\&. The meaning of the \fIaddress\fR part is defined below\&. +.sp +Binding a socket +.sp +.if n \{\ +.RS 4 +.\} +.nf +With \*(Aqudp\*(Aq we can only bind the \*(AqZMQ_DISH\*(Aq socket type\&. +When binding a socket using _zmq_bind()_ with the \*(Aqudp\*(Aq +transport the \*(Aqendpoint\*(Aq shall be interpreted as an \*(Aqinterface\*(Aq followed by a +colon and the UDP port number to use\&. + +An \*(Aqinterface\*(Aq may be specified by either of the following: + +* The wild\-card `*`, meaning all available interfaces\&. +* The primary IPv4 address assigned to the interface, in its numeric + representation\&. +* Multicast address in its numeric representation the socket should join\&. + +The UDP port number may be specified a numeric value, usually above 1024 on POSIX systems\&. + +Connecting a socket +.fi +.if n \{\ +.RE +.\} +.sp +With \fIudp\fR we can only connect the \fIZMQ_RADIO\fR socket type\&. When connecting a socket to a peer address using \fIzmq_connect()\fR with the \fIudp\fR transport, the \fIendpoint\fR shall be interpreted as a \fIpeer address\fR followed by a colon and the UDP port number to use\&. +.sp +A \fIpeer address\fR may be specified by either of the following: +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +The IPv4 or IPv6 address of the peer, in its numeric representation\&. +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +Multicast address in its numeric representation\&. +.RE +.SH "EXAMPLES" +.PP +\fBBinding a socket\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +// Unicast \- UDP port 5555 on all available interfaces +rc = zmq_bind(dish, "udp://*:5555"); +assert (rc == 0); +// Unicast \- UDP port 5555 on the local loop\-back interface +rc = zmq_bind(dish, "udp://127\&.0\&.0\&.1:5555"); +assert (rc == 0); +// Multicast \- UDP port 5555 on a Multicast address +rc = zmq_bind(dish, "udp://239\&.0\&.0\&.1:5555"); +assert (rc == 0); +.fi +.if n \{\ +.RE +.\} +.PP +\fBConnecting a socket\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +// Connecting using an Unicast IP address +rc = zmq_connect(radio, "udp://192\&.168\&.1\&.1:5555"); +assert (rc == 0); +// Connecting using a Multicast address" +rc = zmq_connect(socket, "udp://239\&.0\&.0\&.1:5555); +assert (rc == 0); +.fi +.if n \{\ +.RE +.\} +.sp +.SH "SEE ALSO" +.sp +\fBzmq_connect\fR(3) \fBzmq_setsockopt\fR(3) \fBzmq_tcp\fR(7) \fBzmq_ipc\fR(7) \fBzmq_inproc\fR(7) \fBzmq_vmci\fR(7) \fBzmq\fR(7) +.SH "AUTHORS" +.sp +This page was written by the 0MQ community\&. To make a change please read the 0MQ Contribution Policy at \m[blue]\fBhttp://www\&.zeromq\&.org/docs:contributing\fR\m[]\&. diff --git a/phonelibs/zmq/aarch64-linux/share/man/man7/zmq_vmci.7 b/phonelibs/zmq/aarch64-linux/share/man/man7/zmq_vmci.7 new file mode 100644 index 00000000000000..5383060905483e --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/man/man7/zmq_vmci.7 @@ -0,0 +1,162 @@ +'\" t +.\" Title: zmq_vmci +.\" Author: [see the "AUTHORS" section] +.\" Generator: DocBook XSL Stylesheets v1.78.1 +.\" Date: 02/18/2017 +.\" Manual: 0MQ Manual +.\" Source: 0MQ 4.2.2 +.\" Language: English +.\" +.TH "ZMQ_VMCI" "7" "02/18/2017" "0MQ 4\&.2\&.2" "0MQ Manual" +.\" ----------------------------------------------------------------- +.\" * Define some portability stuff +.\" ----------------------------------------------------------------- +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.\" http://bugs.debian.org/507673 +.\" http://lists.gnu.org/archive/html/groff/2009-02/msg00013.html +.\" ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.ie \n(.g .ds Aq \(aq +.el .ds Aq ' +.\" ----------------------------------------------------------------- +.\" * set default formatting +.\" ----------------------------------------------------------------- +.\" disable hyphenation +.nh +.\" disable justification (adjust text to left margin only) +.ad l +.\" ----------------------------------------------------------------- +.\" * MAIN CONTENT STARTS HERE * +.\" ----------------------------------------------------------------- +.SH "NAME" +zmq_vmci \- 0MQ transport over virtual machine communicatios interface (VMCI) sockets +.SH "SYNOPSIS" +.sp +The VMCI transport passes messages between VMware virtual machines running on the same host, between virtual machine and the host and within virtual machines (inter\-process transport like ipc)\&. +.if n \{\ +.sp +.\} +.RS 4 +.it 1 an-trap +.nr an-no-space-flag 1 +.nr an-break-flag 1 +.br +.ps +1 +\fBNote\fR +.ps -1 +.br +.sp +Communication between a virtual machine and the host is not supported on Mac OS X 10\&.9 and above\&. +.sp .5v +.RE +.SH "ADDRESSING" +.sp +A 0MQ endpoint is a string consisting of a \fItransport\fR:// followed by an \fIaddress\fR\&. The \fItransport\fR specifies the underlying protocol to use\&. The \fIaddress\fR specifies the transport\-specific address to connect to\&. +.sp +For the VMCI transport, the transport is vmci, and the meaning of the \fIaddress\fR part is defined below\&. +.SS "Binding a socket" +.sp +When binding a \fIsocket\fR to a local address using \fIzmq_bind()\fR with the \fIvmci\fR transport, the \fIendpoint\fR shall be interpreted as an \fIinterface\fR followed by a colon and the TCP port number to use\&. +.sp +An \fIinterface\fR may be specified by either of the following: +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +The wild\-card +*, meaning all available interfaces\&. +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +An integer returned by +VMCISock_GetLocalCID +or +@ +(ZeroMQ will call VMCISock_GetLocalCID internally)\&. +.RE +.sp +The port may be specified by: +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +A numeric value, usually above 1024 on POSIX systems\&. +.RE +.sp +.RS 4 +.ie n \{\ +\h'-04'\(bu\h'+03'\c +.\} +.el \{\ +.sp -1 +.IP \(bu 2.3 +.\} +The wild\-card +*, meaning a system\-assigned ephemeral port\&. +.RE +.SS "Unbinding wild\-card address from a socket" +.sp +When wild\-card * \fIendpoint\fR was used in \fIzmq_bind()\fR, the caller should use real \fIendpoint\fR obtained from the ZMQ_LAST_ENDPOINT socket option to unbind this \fIendpoint\fR from a socket using \fIzmq_unbind()\fR\&. +.SS "Connecting a socket" +.sp +When connecting a socket to a peer address using \fIzmq_connect()\fR with the \fIvmci\fR transport, the \fIendpoint\fR shall be interpreted as a \fIpeer address\fR followed by a colon and the port number to use\&. +.sp +A \fIpeer address\fR must be a CID of the peer\&. +.SH "EXAMPLES" +.PP +\fBAssigning a local address to a socket\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +// VMCI port 5555 on all available interfaces +rc = zmq_bind(socket, "vmci://*:5555"); +assert (rc == 0); +// VMCI port 5555 on the local loop\-back interface on all platforms +cid = VMCISock_GetLocalCID(); +sprintf(endpoint, "vmci://%d:5555", cid); +rc = zmq_bind(socket, endpoint); +assert (rc == 0); +.fi +.if n \{\ +.RE +.\} +.PP +\fBConnecting a socket\fR. +.sp +.if n \{\ +.RS 4 +.\} +.nf +// Connecting using a CID +sprintf(endpoint, "vmci://%d:5555", cid); +rc = zmq_connect(socket, endpoint); +assert (rc == 0); +.fi +.if n \{\ +.RE +.\} +.sp +.SH "SEE ALSO" +.sp +\fBzmq_bind\fR(3) \fBzmq_connect\fR(3) \fBzmq_inproc\fR(7) \fBzmq_tcp\fR(7) \fBzmq_pgm\fR(7) \fBzmq_vmci\fR(7) \fBzmq_getsockopt\fR(3) \fBzmq\fR(7) +.SH "AUTHORS" +.sp +This page was written by the 0MQ community\&. To make a change please read the 0MQ Contribution Policy at \m[blue]\fBhttp://www\&.zeromq\&.org/docs:contributing\fR\m[]\&. diff --git a/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zactor.api b/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zactor.api new file mode 100644 index 00000000000000..2ff128b36e61f0 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zactor.api @@ -0,0 +1,62 @@ + + + provides a simple actor framework + + + Actors get a pipe and arguments from caller + + + + + + Create a new actor passing arbitrary arguments reference. + + + + + + Destroy an actor. + + + + Send a zmsg message to the actor, take ownership of the message + and destroy when it has been sent. + + + + + + Receive a zmsg message from the actor. Returns NULL if the actor + was interrupted before the message could be received, or if there + was a timeout on the actor. + + + + + Probe the supplied object, and report if it looks like a zactor_t. + + + + + + Probe the supplied reference. If it looks like a zactor_t instance, + return the underlying libzmq actor handle; else if it looks like + a libzmq actor handle, return the supplied value. + + + + + + Return the actor's zsock handle. Use this when you absolutely need + to work with the zsock instance rather than the actor. + + + diff --git a/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zarmour.api b/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zarmour.api new file mode 100644 index 00000000000000..887ca9ffdbc765 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zarmour.api @@ -0,0 +1,103 @@ + + + armoured text encoding and decoding + + Standard base 64 + URL and filename friendly base 64 + Standard base 32 + Extended hex base 32 + Standard base 16 + Z85 from ZeroMQ RFC 32 + + + Create a new zarmour + + + + Destroy the zarmour + + + + Encode a stream of bytes into an armoured string. Returns the armoured + string, or NULL if there was insufficient memory available to allocate + a new string. + + + + + + + Decode an armoured string into a chunk. The decoded output is + null-terminated, so it may be treated as a string, if that's what + it was prior to encoding. + + + + + + Get the mode property. + + + + + Get printable string for mode. + + + + + Set the mode property. + + + + + Return true if padding is turned on. + + + + + Turn padding on or off. Default is on. + + + + + Get the padding character. + + + + + Set the padding character. + + + + + Return if splitting output into lines is turned on. Default is off. + + + + + Turn splitting output into lines on or off. + + + + + Get the line length used for splitting lines. + + + + + Set the line length used for splitting lines. + + + + + Print properties of object + + diff --git a/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zcert.api b/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zcert.api new file mode 100644 index 00000000000000..d361ba216525e2 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zcert.api @@ -0,0 +1,122 @@ + + + work with CURVE security certificates + + + Create and initialize a new certificate in memory + + + + Accepts public/secret key pair from caller + + + + + + Load certificate from file + + + + + Destroy a certificate in memory + + + + Return public part of key pair as 32-byte binary string + + + + + Return secret part of key pair as 32-byte binary string + + + + + Return public part of key pair as Z85 armored string + + + + + Return secret part of key pair as Z85 armored string + + + + + Set certificate metadata from formatted string. + + + + + + Unset certificate metadata. + + + + + Get metadata value from certificate; if the metadata value doesn't + exist, returns NULL. + + + + + + Get list of metadata fields from certificate. Caller is responsible for + destroying list. Caller should not modify the values of list items. + + + + + Save full certificate (public + secret) to file for persistent storage + This creates one public file and one secret file (filename + "_secret"). + + + + + + Save public certificate only to file for persistent storage + + + + + + Save secret certificate only to file for persistent storage + + + + + + Apply certificate to socket, i.e. use for CURVE security on socket. + If certificate was loaded from public file, the secret key will be + undefined, and this certificate will not work successfully. + + + + + Return copy of certificate; if certificate is NULL or we exhausted + heap memory, returns NULL. + + + + + Return true if two certificates have the same keys + + + + + + Print certificate contents to stdout + + + + Self test of this class + + + diff --git a/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zcertstore.api b/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zcertstore.api new file mode 100644 index 00000000000000..b566fefa533f24 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zcertstore.api @@ -0,0 +1,72 @@ + + + work with CURVE security certificate stores + + + Create a new certificate store from a disk directory, loading and + indexing all certificates in that location. The directory itself may be + absent, and created later, or modified at any time. The certificate store + is automatically refreshed on any zcertstore_lookup() call. If the + location is specified as NULL, creates a pure-memory store, which you + can work with by inserting certificates at runtime. + + + + + Destroy a certificate store object in memory. Does not affect anything + stored on disk. + + + + Loaders retrieve certificates from an arbitrary source. + + + + + Destructor for loader state. + + + + + Override the default disk loader with a custom loader fn. + + + + + + + Look up certificate by public key, returns zcert_t object if found, + else returns NULL. The public key is provided in Z85 text format. + + + + + + Insert certificate into certificate store in memory. Note that this + does not save the certificate to disk. To do that, use zcert_save() + directly on the certificate. Takes ownership of zcert_t object. + + + + + Empty certificate hashtable. This wrapper exists to be friendly to bindings, + which don't usually have access to struct internals. + + + + Print list of certificates in store to logging facility + + + + Self test of this class + + + diff --git a/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zchunk.api b/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zchunk.api new file mode 100644 index 00000000000000..25b50e95815c00 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zchunk.api @@ -0,0 +1,171 @@ + + + work with memory chunks + + + Create a new chunk of the specified size. If you specify the data, it + is copied into the chunk. If you do not specify the data, the chunk is + allocated and left empty, and you can then add data using zchunk_append. + + + + + + Destroy a chunk + + + + Resizes chunk max_size as requested; chunk_cur size is set to zero + + + + + Return chunk cur size + + + + + Return chunk max size + + + + + Return chunk data + + + + + Set chunk data from user-supplied data; truncate if too large. Data may + be null. Returns actual size of chunk + + + + + + + Fill chunk data from user-supplied octet + + + + + + + Append user-supplied data to chunk, return resulting chunk size. If the + data would exceeded the available space, it is truncated. If you want to + grow the chunk to accommodate new data, use the zchunk_extend method. + + + + + + + Append user-supplied data to chunk, return resulting chunk size. If the + data would exceeded the available space, the chunk grows in size. + + + + + + + Copy as much data from 'source' into the chunk as possible; returns the + new size of chunk. If all data from 'source' is used, returns exhausted + on the source chunk. Source can be consumed as many times as needed until + it is exhausted. If source was already exhausted, does not change chunk. + + + + + + Returns true if the chunk was exhausted by consume methods, or if the + chunk has a size of zero. + + + + + Read chunk from an open file descriptor + + + + + + + Write chunk to an open file descriptor + + + + + + Try to slurp an entire file into a chunk. Will read up to maxsize of + the file. If maxsize is 0, will attempt to read the entire file and + fail with an assertion if that cannot fit into memory. Returns a new + chunk containing the file data, or NULL if the file could not be read. + + + + + + + Create copy of chunk, as new chunk object. Returns a fresh zchunk_t + object, or null if there was not enough heap memory. If chunk is null, + returns null. + + + + + Return chunk data encoded as printable hex string. Caller must free + string when finished with it. + + + + + Return chunk data copied into freshly allocated string + Caller must free string when finished with it. + + + + + Return TRUE if chunk body is equal to string, excluding terminator + + + + + + Transform zchunk into a zframe that can be sent in a message. + + + + + Transform a zframe into a zchunk. + + + + + + Calculate SHA1 digest for chunk, using zdigest class. + + + + + Dump chunk to FILE stream, for debugging and tracing. + + + + + Dump message to stderr, for debugging and tracing. + See zchunk_fprint for details + + + + Probe the supplied object, and report if it looks like a zchunk_t. + + + + diff --git a/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zclock.api b/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zclock.api new file mode 100644 index 00000000000000..a613180f1529cb --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zclock.api @@ -0,0 +1,43 @@ + + + millisecond clocks and delays + + + Sleep for a number of milliseconds + + + + + Return current system clock as milliseconds. Note that this clock can + jump backwards (if the system clock is changed) so is unsafe to use for + timers and time offsets. Use zclock_mono for that instead. + + + + + Return current monotonic clock in milliseconds. Use this when you compute + time offsets. The monotonic clock is not affected by system changes and + so will never be reset backwards, unlike a system clock. + + + + + Return current monotonic clock in microseconds. Use this when you compute + time offsets. The monotonic clock is not affected by system changes and + so will never be reset backwards, unlike a system clock. + + + + + Return formatted date/time as fresh string. Free using zstr_free(). + + + diff --git a/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zconfig.api b/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zconfig.api new file mode 100644 index 00000000000000..db46751fa8d7d9 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zconfig.api @@ -0,0 +1,196 @@ + + + work with config files written in rfc.zeromq.org/spec:4/ZPL. + + + + + + + + + + Create new config item + + + + + + Destroy a config item and all its children + + + + Return name of config item + + + + + Return value of config item + + + + + Insert or update configuration key with value + + + + + + Equivalent to zconfig_put, accepting a format specifier and variable + argument list, instead of a single string value. + + + + + + Get value for config item into a string value; leading slash is optional + and ignored. + + + + + + Set config item name, name may be NULL + + + + + Set new value for config item. The new value may be a string, a printf + format, or NULL. Note that if string may possibly contain '%', or if it + comes from an insecure source, you must use '%s' as the format, followed + by the string. + + + + + Find our first child, if any + + + + + Find our first sibling, if any + + + + + Find a config item along a path; leading slash is optional and ignored. + + + + + + Locate the last config item at a specified depth + + + + + + Execute a callback for each config item in the tree; returns zero if + successful, else -1. + + + + + + + Add comment to config item before saving to disk. You can add as many + comment lines as you like. If you use a null format, all comments are + deleted. + + + + + Return comments of config item, as zlist. + + + + + Load a config tree from a specified ZPL text file; returns a zconfig_t + reference for the root, if the file exists and is readable. Returns NULL + if the file does not exist. + + + + + Save a config tree to a specified ZPL text file, where a filename + "-" means dump to standard output. + + + + + + Equivalent to zconfig_load, taking a format string instead of a fixed + filename. + + + + + Equivalent to zconfig_save, taking a format string instead of a fixed + filename. + + + + + + Report filename used during zconfig_load, or NULL if none + + + + + Reload config tree from same file that it was previously loaded from. + Returns 0 if OK, -1 if there was an error (and then does not change + existing data). + + + + + + Load a config tree from a memory chunk + + + + + + Save a config tree to a new memory chunk + + + + + Load a config tree from a null-terminated string + + + + + + Save a config tree to a new null terminated string + + + + + Return true if a configuration tree was loaded from a file and that + file has changed in since the tree was loaded. + + + + + Print the config file to open stream + + + + + Print properties of object + + + + Self test of this class + + + diff --git a/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zdigest.api b/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zdigest.api new file mode 100644 index 00000000000000..83abb9b121d6d8 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zdigest.api @@ -0,0 +1,45 @@ + + + provides hashing functions (SHA-1 at present) + + + Constructor - creates new digest object, which you use to build up a + digest by repeatedly calling zdigest_update() on chunks of data. + + + + Destroy a digest object + + + + Add buffer into digest calculation + + + + + + Return final digest hash data. If built without crypto support, + returns NULL. + + + + + Return final digest hash size + + + + + Return digest as printable hex string; caller should not modify nor + free this string. After calling this, you may not use zdigest_update() + on the same digest. If built without crypto support, returns NULL. + + + diff --git a/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zdir.api b/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zdir.api new file mode 100644 index 00000000000000..cb8283a7027e56 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zdir.api @@ -0,0 +1,124 @@ + + + work with file-system directories + + + Create a new directory item that loads in the full tree of the specified + path, optionally located under some parent path. If parent is "-", then + loads only the top-level directory, and does not use parent as a path. + + + + + + Destroy a directory tree and all children it contains. + + + + Return directory path + + + + + Return last modification time for directory. + + + + + Return total hierarchy size, in bytes of data contained in all files + in the directory tree. + + + + + Return directory count + + + + + Returns a sorted list of zfile objects; Each entry in the list is a pointer + to a zfile_t item already allocated in the zdir tree. Do not destroy the + original zdir tree until you are done with this list. + + + + + Remove directory, optionally including all files that it contains, at + all levels. If force is false, will only remove the directory if empty. + If force is true, will remove all files and all subdirectories. + + + + + Calculate differences between two versions of a directory tree. + Returns a list of zdir_patch_t patches. Either older or newer may + be null, indicating the directory is empty/absent. If alias is set, + generates virtual filename (minus path, plus alias). + + + + + + + + Return full contents of directory as a zdir_patch list. + + + + + + Load directory cache; returns a hash table containing the SHA-1 digests + of every file in the tree. The cache is saved between runs in .cache. + + + + + Print contents of directory to open stream + + + + + + Print contents of directory to stdout + + + + + Create a new zdir_watch actor instance: + + zactor_t *watch = zactor_new (zdir_watch, NULL); + + Destroy zdir_watch instance: + + zactor_destroy (&watch); + + Enable verbose logging of commands and activity: + + zstr_send (watch, "VERBOSE"); + + Subscribe to changes to a directory path: + + zsock_send (watch, "ss", "SUBSCRIBE", "directory_path"); + + Unsubscribe from changes to a directory path: + + zsock_send (watch, "ss", "UNSUBSCRIBE", "directory_path"); + + Receive directory changes: + zsock_recv (watch, "sp", &path, &patches); + + // Delete the received data. + free (path); + zlist_destroy (&patches); + + + + diff --git a/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zdir_patch.api b/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zdir_patch.api new file mode 100644 index 00000000000000..8d102b887ae839 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zdir_patch.api @@ -0,0 +1,62 @@ + + + work with directory patches + + Creates a new file + Delete a file + + + Create new patch + + + + + + + + Destroy a patch + + + + Create copy of a patch. If the patch is null, or memory was exhausted, + returns null. + + + + + Return patch file directory path + + + + + Return patch file item + + + + + Return operation + + + + + Return patch virtual file path + + + + + Calculate hash digest for file (create only) + + + + Return hash digest for patch file + + + diff --git a/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zfile.api b/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zfile.api new file mode 100644 index 00000000000000..f60391bfeea16f --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zfile.api @@ -0,0 +1,152 @@ + + + helper functions for working with files. + + + If file exists, populates properties. CZMQ supports portable symbolic + links, which are files with the extension ".ln". A symbolic link is a + text file containing one line, the filename of a target file. Reading + data from the symbolic link actually reads from the target file. Path + may be NULL, in which case it is not used. + + + + + + Destroy a file item + + + + Duplicate a file item, returns a newly constructed item. If the file + is null, or memory was exhausted, returns null. + + + + + Return file name, remove path if provided + + + + + + Refresh file properties from disk; this is not done automatically + on access methods, otherwise it is not possible to compare directory + snapshots. + + + + Return when the file was last modified. If you want this to reflect the + current situation, call zfile_restat before checking this property. + + + + + Return the last-known size of the file. If you want this to reflect the + current situation, call zfile_restat before checking this property. + + + + + Return true if the file is a directory. If you want this to reflect + any external changes, call zfile_restat before checking this property. + + + + + Return true if the file is a regular file. If you want this to reflect + any external changes, call zfile_restat before checking this property. + + + + + Return true if the file is readable by this process. If you want this to + reflect any external changes, call zfile_restat before checking this + property. + + + + + Return true if the file is writeable by this process. If you want this + to reflect any external changes, call zfile_restat before checking this + property. + + + + + Check if file has stopped changing and can be safely processed. + Updates the file statistics from disk at every call. + + + + + Return true if the file was changed on disk since the zfile_t object + was created, or the last zfile_restat() call made on it. + + + + + Remove the file from disk + + + + Open file for reading + Returns 0 if OK, -1 if not found or not accessible + + + + + Open file for writing, creating directory if needed + File is created if necessary; chunks can be written to file at any + location. Returns 0 if OK, -1 if error. + + + + + Read chunk from file at specified position. If this was the last chunk, + sets the eof property. Returns a null chunk in case of error. + + + + + + + Returns true if zfile_read() just read the last chunk in the file. + + + + + Write chunk to file at specified position + Return 0 if OK, else -1 + + + + + + + Read next line of text from file. Returns a pointer to the text line, + or NULL if there was nothing more to read from the file. + + + + + Close file, if open + + + + Return file handle, if opened + + + + + Calculate SHA1 digest for file, using zdigest class. + + + diff --git a/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zframe.api b/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zframe.api new file mode 100644 index 00000000000000..cf3c3219f6f6c6 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zframe.api @@ -0,0 +1,156 @@ + + + working with single message frames + + + + + + + Create a new frame. If size is not null, allocates the frame data + to the specified size. If additionally, data is not null, copies + size octets from the specified data into the frame body. + + + + + + Destroy a frame + + + + Create an empty (zero-sized) frame + + + + Create a frame with a specified string content. + + + + + Receive frame from socket, returns zframe_t object or NULL if the recv + was interrupted. Does a blocking recv, if you want to not block then use + zpoller or zloop. + + + + + Send a frame to a socket, destroy frame after sending. + Return -1 on error, 0 on success. + + + + + + + + Return number of bytes in frame data + + + + + Return address of frame data + + + + + Return meta data property for frame + Caller must free string when finished with it. + + + + + + Create a new frame that duplicates an existing frame. If frame is null, + or memory was exhausted, returns null. + + + + + Return frame data encoded as printable hex string, useful for 0MQ UUIDs. + Caller must free string when finished with it. + + + + + Return frame data copied into freshly allocated string + Caller must free string when finished with it. + + + + + Return TRUE if frame body is equal to string, excluding terminator + + + + + + Return frame MORE indicator (1 or 0), set when reading frame from socket + or by the zframe_set_more() method + + + + + Set frame MORE indicator (1 or 0). Note this is NOT used when sending + frame to socket, you have to specify flag explicitly. + + + + + Return frame routing ID, if the frame came from a ZMQ_SERVER socket. + Else returns zero. + + + + + Set routing ID on frame. This is used if/when the frame is sent to a + ZMQ_SERVER socket. + + + + + Return frame group of radio-dish pattern. + + + + + Set group on frame. This is used if/when the frame is sent to a + ZMQ_RADIO socket. + Return -1 on error, 0 on success. + + + + + + Return TRUE if two frames have identical size and data + If either frame is NULL, equality is always false. + + + + + + Set new contents for frame + + + + + + Send message to zsys log sink (may be stdout, or system facility as + configured by zsys_set_logstream). Prefix shows before frame, if not null. + + + + + Probe the supplied object, and report if it looks like a zframe_t. + + + + diff --git a/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zgossip_msg.api b/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zgossip_msg.api new file mode 100644 index 00000000000000..0f314fab7c5bf8 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zgossip_msg.api @@ -0,0 +1,104 @@ + + + + + + + + + + Create a new empty zgossip_msg + + + + Destroy a zgossip_msg instance + + + + Receive a zgossip_msg from the socket. Returns 0 if OK, -1 if + there was an error. Blocks if there is no message waiting. + + + + + + Send the zgossip_msg to the output socket, does not destroy it + + + + + + Print contents of message to stdout + + + + Get the message routing id, as a frame + + + + + Set the message routing id from a frame + + + + + Get the zgossip_msg message id + + + + + Set the zgossip_msg message id + + + + + Get the zgossip_msg message id as printable text + + + + + Get the key field + + + + Set the key field + + + + Get the value field + + + + Set the value field + + + + Get the ttl field + + + + Set the ttl field + + + diff --git a/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zhash.api b/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zhash.api new file mode 100644 index 00000000000000..36d58847af46e4 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zhash.api @@ -0,0 +1,183 @@ + + + generic type-free hash container (simple) + + + Callback function for zhash_freefn method + + + + + Create a new, empty hash container + + + + Destroy a hash container and all items in it + + + + Insert item into hash table with specified key and item. + If key is already present returns -1 and leaves existing item unchanged + Returns 0 on success. + + + + + + + Update item into hash table with specified key and item. + If key is already present, destroys old item and inserts new one. + Use free_fn method to ensure deallocator is properly called on item. + + + + + + Remove an item specified by key from the hash table. If there was no such + item, this function does nothing. + + + + + Return the item at the specified key, or null + + + + + + Reindexes an item from an old key to a new key. If there was no such + item, does nothing. Returns 0 if successful, else -1. + + + + + + + Set a free function for the specified hash table item. When the item is + destroyed, the free function, if any, is called on that item. + Use this when hash items are dynamically allocated, to ensure that + you don't have memory leaks. You can pass 'free' or NULL as a free_fn. + Returns the item, or NULL if there is no such item. + + + + + + + Return the number of keys/items in the hash table + + + + + Make copy of hash table; if supplied table is null, returns null. + Does not copy items themselves. Rebuilds new table so may be slow on + very large tables. NOTE: only works with item values that are strings + since there's no other way to know how to duplicate the item value. + + + + + Return keys for items in table + + + + + Simple iterator; returns first item in hash table, in no given order, + or NULL if the table is empty. This method is simpler to use than the + foreach() method, which is deprecated. To access the key for this item + use zhash_cursor(). NOTE: do NOT modify the table while iterating. + + + + + Simple iterator; returns next item in hash table, in no given order, + or NULL if the last item was already returned. Use this together with + zhash_first() to process all items in a hash table. If you need the + items in sorted order, use zhash_keys() and then zlist_sort(). To + access the key for this item use zhash_cursor(). NOTE: do NOT modify + the table while iterating. + + + + + After a successful first/next method, returns the key for the item that + was returned. This is a constant string that you may not modify or + deallocate, and which lasts as long as the item in the hash. After an + unsuccessful first/next, returns NULL. + + + + + Add a comment to hash table before saving to disk. You can add as many + comment lines as you like. These comment lines are discarded when loading + the file. If you use a null format, all comments are deleted. + + + + + Serialize hash table to a binary frame that can be sent in a message. + The packed format is compatible with the 'dictionary' type defined in + http://rfc.zeromq.org/spec:35/FILEMQ, and implemented by zproto: + + ; A list of name/value pairs + dictionary = dict-count *( dict-name dict-value ) + dict-count = number-4 + dict-value = longstr + dict-name = string + + ; Strings are always length + text contents + longstr = number-4 *VCHAR + string = number-1 *VCHAR + + ; Numbers are unsigned integers in network byte order + number-1 = 1OCTET + number-4 = 4OCTET + + Comments are not included in the packed data. Item values MUST be + strings. + + + + + Unpack binary frame into a new hash table. Packed data must follow format + defined by zhash_pack. Hash table is set to autofree. An empty frame + unpacks to an empty hash table. + + + + + Save hash table to a text file in name=value format. Hash values must be + printable strings; keys may not contain '=' character. Returns 0 if OK, + else -1 if a file error occurred. + + + + + + Load hash table from a text file in name=value format; hash table must + already exist. Hash values must printable strings; keys may not contain + '=' character. Returns 0 if OK, else -1 if a file was not readable. + + + + + + When a hash table was loaded from a file by zhash_load, this method will + reload the file if it has been modified since, and is "stable", i.e. not + still changing. Returns 0 if OK, -1 if there was an error reloading the + file. + + + + + Set hash for automatic value destruction + + diff --git a/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zhashx.api b/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zhashx.api new file mode 100644 index 00000000000000..22087e0fe9fcd2 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zhashx.api @@ -0,0 +1,293 @@ + + + extended generic type-free hash container + + + Destroy an item + + + + + Duplicate an item + + + + + + Compare two items, for sorting + + + + + + + compare two items, for sorting + + + + + compare two items, for sorting + + + + + + Serializes an item to a longstr. + The caller takes ownership of the newly created object. + + + + + + Deserializes a longstr into an item. + The caller takes ownership of the newly created object. + + + + + + Create a new, empty hash container + + + + Destroy a hash container and all items in it + + + + Insert item into hash table with specified key and item. + If key is already present returns -1 and leaves existing item unchanged + Returns 0 on success. + + + + + + + Update or insert item into hash table with specified key and item. If the + key is already present, destroys old item and inserts new one. If you set + a container item destructor, this is called on the old value. If the key + was not already present, inserts a new item. Sets the hash cursor to the + new item. + + + + + + Remove an item specified by key from the hash table. If there was no such + item, this function does nothing. + + + + + Delete all items from the hash table. If the key destructor is + set, calls it on every key. If the item destructor is set, calls + it on every item. + + + + Return the item at the specified key, or null + + + + + + Reindexes an item from an old key to a new key. If there was no such + item, does nothing. Returns 0 if successful, else -1. + + + + + + + Set a free function for the specified hash table item. When the item is + destroyed, the free function, if any, is called on that item. + Use this when hash items are dynamically allocated, to ensure that + you don't have memory leaks. You can pass 'free' or NULL as a free_fn. + Returns the item, or NULL if there is no such item. + + + + + + + Return the number of keys/items in the hash table + + + + + Return a zlistx_t containing the keys for the items in the + table. Uses the key_duplicator to duplicate all keys and sets the + key_destructor as destructor for the list. + + + + + Return a zlistx_t containing the values for the items in the + table. Uses the duplicator to duplicate all items and sets the + destructor as destructor for the list. + + + + + Simple iterator; returns first item in hash table, in no given order, + or NULL if the table is empty. This method is simpler to use than the + foreach() method, which is deprecated. To access the key for this item + use zhashx_cursor(). NOTE: do NOT modify the table while iterating. + + + + + Simple iterator; returns next item in hash table, in no given order, + or NULL if the last item was already returned. Use this together with + zhashx_first() to process all items in a hash table. If you need the + items in sorted order, use zhashx_keys() and then zlistx_sort(). To + access the key for this item use zhashx_cursor(). NOTE: do NOT modify + the table while iterating. + + + + + After a successful first/next method, returns the key for the item that + was returned. This is a constant string that you may not modify or + deallocate, and which lasts as long as the item in the hash. After an + unsuccessful first/next, returns NULL. + + + + + Add a comment to hash table before saving to disk. You can add as many + comment lines as you like. These comment lines are discarded when loading + the file. If you use a null format, all comments are deleted. + + + + + Save hash table to a text file in name=value format. Hash values must be + printable strings; keys may not contain '=' character. Returns 0 if OK, + else -1 if a file error occurred. + + + + + + Load hash table from a text file in name=value format; hash table must + already exist. Hash values must printable strings; keys may not contain + '=' character. Returns 0 if OK, else -1 if a file was not readable. + + + + + + When a hash table was loaded from a file by zhashx_load, this method will + reload the file if it has been modified since, and is "stable", i.e. not + still changing. Returns 0 if OK, -1 if there was an error reloading the + file. + + + + + Serialize hash table to a binary frame that can be sent in a message. + The packed format is compatible with the 'dictionary' type defined in + http://rfc.zeromq.org/spec:35/FILEMQ, and implemented by zproto: + + ; A list of name/value pairs + dictionary = dict-count *( dict-name dict-value ) + dict-count = number-4 + dict-value = longstr + dict-name = string + + ; Strings are always length + text contents + longstr = number-4 *VCHAR + string = number-1 *VCHAR + + ; Numbers are unsigned integers in network byte order + number-1 = 1OCTET + number-4 = 4OCTET + + Comments are not included in the packed data. Item values MUST be + strings. + + + + + Same as pack but uses a user-defined serializer function to convert items + into longstr. + + + + + + Unpack binary frame into a new hash table. Packed data must follow format + defined by zhashx_pack. Hash table is set to autofree. An empty frame + unpacks to an empty hash table. + + + + + Same as unpack but uses a user-defined deserializer function to convert + a longstr back into item format. + + + + + + Make a copy of the list; items are duplicated if you set a duplicator + for the list, otherwise not. Copying a null reference returns a null + reference. Note that this method's behavior changed slightly for CZMQ + v3.x, as it does not set nor respect autofree. It does however let you + duplicate any hash table safely. The old behavior is in zhashx_dup_v2. + + + + + Set a user-defined deallocator for hash items; by default items are not + freed when the hash is destroyed. + + + + + Set a user-defined duplicator for hash items; by default items are not + copied when the hash is duplicated. + + + + + Set a user-defined deallocator for keys; by default keys are freed + when the hash is destroyed using free(). + + + + + Set a user-defined duplicator for keys; by default keys are duplicated + using strdup. + + + + + Set a user-defined comparator for keys; by default keys are + compared using strcmp. + + + + + Set a user-defined comparator for keys; by default keys are + compared using strcmp. + + + + + Make copy of hash table; if supplied table is null, returns null. + Does not copy items themselves. Rebuilds new table so may be slow on + very large tables. NOTE: only works with item values that are strings + since there's no other way to know how to duplicate the item value. + + + diff --git a/phonelibs/zmq/aarch64-linux/share/zproject/czmq/ziflist.api b/phonelibs/zmq/aarch64-linux/share/zproject/czmq/ziflist.api new file mode 100644 index 00000000000000..5dc362463c0dee --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/zproject/czmq/ziflist.api @@ -0,0 +1,58 @@ + + + List of network interfaces available on system + + + Get a list of network interfaces currently defined on the system + + + + Destroy a ziflist instance + + + + Reload network interfaces from system + + + + Return the number of network interfaces on system + + + + + Get first network interface, return NULL if there are none + + + + + Get next network interface, return NULL if we hit the last one + + + + + Return the current interface IP address as a printable string + + + + + Return the current interface broadcast address as a printable string + + + + + Return the current interface network mask as a printable string + + + + + Return the list of interfaces. + + diff --git a/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zlist.api b/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zlist.api new file mode 100644 index 00000000000000..67b4f01c577b5f --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zlist.api @@ -0,0 +1,158 @@ + + + simple generic list container + + + Comparison function e.g. for sorting and removing. + + + + + + + Callback function for zlist_freefn method + + + + + Create a new list container + + + + Destroy a list container + + + + Return the item at the head of list. If the list is empty, returns NULL. + Leaves cursor pointing at the head item, or NULL if the list is empty. + + + + + Return the next item. If the list is empty, returns NULL. To move to + the start of the list call zlist_first (). Advances the cursor. + + + + + Return the item at the tail of list. If the list is empty, returns NULL. + Leaves cursor pointing at the tail item, or NULL if the list is empty. + + + + + Return first item in the list, or null, leaves the cursor + + + + + Return last item in the list, or null, leaves the cursor + + + + + Return the current item of list. If the list is empty, returns NULL. + Leaves cursor pointing at the current item, or NULL if the list is empty. + + + + + Append an item to the end of the list, return 0 if OK or -1 if this + failed for some reason (out of memory). Note that if a duplicator has + been set, this method will also duplicate the item. + + + + + + Push an item to the start of the list, return 0 if OK or -1 if this + failed for some reason (out of memory). Note that if a duplicator has + been set, this method will also duplicate the item. + + + + + + Pop the item off the start of the list, if any + + + + + Checks if an item already is present. Uses compare method to determine if + items are equal. If the compare method is NULL the check will only compare + pointers. Returns true if item is present else false. + + + + + + Remove the specified item from the list if present + + + + + Make a copy of list. If the list has autofree set, the copied list will + duplicate all items, which must be strings. Otherwise, the list will hold + pointers back to the items in the original list. If list is null, returns + NULL. + + + + + Purge all items from list + + + + Return number of items in the list + + + + + Sort the list. If the compare function is null, sorts the list by + ascending key value using a straight ASCII comparison. If you specify + a compare function, this decides how items are sorted. The sort is not + stable, so may reorder items with the same keys. The algorithm used is + combsort, a compromise between performance and simplicity. + + + + + Set list for automatic item destruction; item values MUST be strings. + By default a list item refers to a value held elsewhere. When you set + this, each time you append or push a list item, zlist will take a copy + of the string value. Then, when you destroy the list, it will free all + item values automatically. If you use any other technique to allocate + list values, you must free them explicitly before destroying the list. + The usual technique is to pop list items and destroy them, until the + list is empty. + + + + Sets a compare function for this list. The function compares two items. + It returns an integer less than, equal to, or greater than zero if the + first item is found, respectively, to be less than, to match, or be + greater than the second item. + This function is used for sorting, removal and exists checking. + + + + + Set a free function for the specified list item. When the item is + destroyed, the free function, if any, is called on that item. + Use this when list items are dynamically allocated, to ensure that + you don't have memory leaks. You can pass 'free' or NULL as a free_fn. + Returns the item, or NULL if there is no such item. + + + + + + diff --git a/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zlistx.api b/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zlistx.api new file mode 100644 index 00000000000000..1dc95ea6374f9c --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zlistx.api @@ -0,0 +1,220 @@ + + + extended generic list container + + + Destroy an item + + + + + Duplicate an item + + + + + + Compare two items, for sorting + + + + + + + Create a new, empty list. + + + + Destroy a list. If an item destructor was specified, all items in the + list are automatically destroyed as well. + + + + Add an item to the head of the list. Calls the item duplicator, if any, + on the item. Resets cursor to list head. Returns an item handle on + success, NULL if memory was exhausted. + + + + + + Add an item to the tail of the list. Calls the item duplicator, if any, + on the item. Resets cursor to list head. Returns an item handle on + success, NULL if memory was exhausted. + + + + + + Return the number of items in the list + + + + + Return first item in the list, or null, leaves the cursor + + + + + Return last item in the list, or null, leaves the cursor + + + + + Return the item at the head of list. If the list is empty, returns NULL. + Leaves cursor pointing at the head item, or NULL if the list is empty. + + + + + Return the next item. At the end of the list (or in an empty list), + returns NULL. Use repeated zlistx_next () calls to work through the list + from zlistx_first (). First time, acts as zlistx_first(). + + + + + Return the previous item. At the start of the list (or in an empty list), + returns NULL. Use repeated zlistx_prev () calls to work through the list + backwards from zlistx_last (). First time, acts as zlistx_last(). + + + + + Return the item at the tail of list. If the list is empty, returns NULL. + Leaves cursor pointing at the tail item, or NULL if the list is empty. + + + + + Returns the value of the item at the cursor, or NULL if the cursor is + not pointing to an item. + + + + + Returns the handle of the item at the cursor, or NULL if the cursor is + not pointing to an item. + + + + + Returns the item associated with the given list handle, or NULL if passed + in handle is NULL. Asserts that the passed in handle points to a list element. + + + + + + Find an item in the list, searching from the start. Uses the item + comparator, if any, else compares item values directly. Returns the + item handle found, or NULL. Sets the cursor to the found item, if any. + + + + + + Detach an item from the list, using its handle. The item is not modified, + and the caller is responsible for destroying it if necessary. If handle is + null, detaches the first item on the list. Returns item that was detached, + or null if none was. If cursor was at item, moves cursor to previous item, + so you can detach items while iterating forwards through a list. + + + + + + Detach item at the cursor, if any, from the list. The item is not modified, + and the caller is responsible for destroying it as necessary. Returns item + that was detached, or null if none was. Moves cursor to previous item, so + you can detach items while iterating forwards through a list. + + + + + Delete an item, using its handle. Calls the item destructor is any is + set. If handle is null, deletes the first item on the list. Returns 0 + if an item was deleted, -1 if not. If cursor was at item, moves cursor + to previous item, so you can delete items while iterating forwards + through a list. + + + + + + Move an item to the start of the list, via its handle. + + + + + Move an item to the end of the list, via its handle. + + + + + Remove all items from the list, and destroy them if the item destructor + is set. + + + + Sort the list. If an item comparator was set, calls that to compare + items, otherwise compares on item value. The sort is not stable, so may + reorder equal items. + + + + Create a new node and insert it into a sorted list. Calls the item + duplicator, if any, on the item. If low_value is true, starts searching + from the start of the list, otherwise searches from the end. Use the item + comparator, if any, to find where to place the new node. Returns a handle + to the new node, or NULL if memory was exhausted. Resets the cursor to the + list head. + + + + + + + Move an item, specified by handle, into position in a sorted list. Uses + the item comparator, if any, to determine the new location. If low_value + is true, starts searching from the start of the list, otherwise searches + from the end. + + + + + + Make a copy of the list; items are duplicated if you set a duplicator + for the list, otherwise not. Copying a null reference returns a null + reference. + + + + + Set a user-defined deallocator for list items; by default items are not + freed when the list is destroyed. + + + + + Set a user-defined duplicator for list items; by default items are not + copied when the list is duplicated. + + + + + Set a user-defined comparator for zlistx_find and zlistx_sort; the method + must return -1, 0, or 1 depending on whether item1 is less than, equal to, + or greater than, item2. + + + + diff --git a/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zloop.api b/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zloop.api new file mode 100644 index 00000000000000..429e3b517a89fc --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zloop.api @@ -0,0 +1,176 @@ + + + event-driven reactor + + + Callback function for reactor socket activity + + + + + + + + Callback function for reactor events (low-level) + + + + + + + + Callback for reactor timer events + + + + + + + + Create a new zloop reactor + + + + Destroy a reactor + + + + Register socket reader with the reactor. When the reader has messages, + the reactor will call the handler, passing the arg. Returns 0 if OK, -1 + if there was an error. If you register the same socket more than once, + each instance will invoke its corresponding handler. + + + + + + + + Cancel a socket reader from the reactor. If multiple readers exist for + same socket, cancels ALL of them. + + + + + Configure a registered reader to ignore errors. If you do not set this, + then readers that have errors are removed from the reactor silently. + + + + + Register low-level libzmq pollitem with the reactor. When the pollitem + is ready, will call the handler, passing the arg. Returns 0 if OK, -1 + if there was an error. If you register the pollitem more than once, each + instance will invoke its corresponding handler. A pollitem with + socket=NULL and fd=0 means 'poll on FD zero'. + + + + + + + + Cancel a pollitem from the reactor, specified by socket or FD. If both + are specified, uses only socket. If multiple poll items exist for same + socket/FD, cancels ALL of them. + + + + + Configure a registered poller to ignore errors. If you do not set this, + then poller that have errors are removed from the reactor silently. + + + + + Register a timer that expires after some delay and repeats some number of + times. At each expiry, will call the handler, passing the arg. To run a + timer forever, use 0 times. Returns a timer_id that is used to cancel the + timer in the future. Returns -1 if there was an error. + + + + + + + + + Cancel a specific timer identified by a specific timer_id (as returned by + zloop_timer). + + + + + + Register a ticket timer. Ticket timers are very fast in the case where + you use a lot of timers (thousands), and frequently remove and add them. + The main use case is expiry timers for servers that handle many clients, + and which reset the expiry timer for each message received from a client. + Whereas normal timers perform poorly as the number of clients grows, the + cost of ticket timers is constant, no matter the number of clients. You + must set the ticket delay using zloop_set_ticket_delay before creating a + ticket. Returns a handle to the timer that you should use in + zloop_ticket_reset and zloop_ticket_delete. + + + + + + + Reset a ticket timer, which moves it to the end of the ticket list and + resets its execution time. This is a very fast operation. + + + + + Delete a ticket timer. We do not actually delete the ticket here, as + other code may still refer to the ticket. We mark as deleted, and remove + later and safely. + + + + + Set the ticket delay, which applies to all tickets. If you lower the + delay and there are already tickets created, the results are undefined. + + + + + Set hard limit on number of timers allowed. Setting more than a small + number of timers (10-100) can have a dramatic impact on the performance + of the reactor. For high-volume cases, use ticket timers. If the hard + limit is reached, the reactor stops creating new timers and logs an + error. + + + + + Set verbose tracing of reactor on/off. The default verbose setting is + off (false). + + + + + By default the reactor stops if the process receives a SIGINT or SIGTERM + signal. This makes it impossible to shut-down message based architectures + like zactors. This method lets you switch off break handling. The default + nonstop setting is off (false). + + + + + Start the reactor. Takes control of the thread and returns when the 0MQ + context is terminated or the process is interrupted, or any event handler + returns -1. Event handlers may register new sockets and timers, and + cancel sockets. Returns 0 if interrupted, -1 if canceled by a handler. + + + diff --git a/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zmsg.api b/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zmsg.api new file mode 100644 index 00000000000000..6205fd02e3d50b --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zmsg.api @@ -0,0 +1,250 @@ + + + working with multipart messages + + + Create a new empty message object + + + + Destroy a message object and all frames it contains + + + + Receive message from socket, returns zmsg_t object or NULL if the recv + was interrupted. Does a blocking recv. If you want to not block then use + the zloop class or zmsg_recv_nowait or zmq_poll to check for socket input + before receiving. + + + + + Send message to destination socket, and destroy the message after sending + it successfully. If the message has no frames, sends nothing but destroys + the message anyhow. Nullifies the caller's reference to the message (as + it is a destructor). + + + + + + + Send message to destination socket as part of a multipart sequence, and + destroy the message after sending it successfully. Note that after a + zmsg_sendm, you must call zmsg_send or another method that sends a final + message part. If the message has no frames, sends nothing but destroys + the message anyhow. Nullifies the caller's reference to the message (as + it is a destructor). + + + + + + + Return size of message, i.e. number of frames (0 or more). + + + + + Return total size of all frames in message. + + + + + Return message routing ID, if the message came from a ZMQ_SERVER socket. + Else returns zero. + + + + + Set routing ID on message. This is used if/when the message is sent to a + ZMQ_SERVER socket. + + + + + Push frame to the front of the message, i.e. before all other frames. + Message takes ownership of frame, will destroy it when message is sent. + Returns 0 on success, -1 on error. Deprecates zmsg_push, which did not + nullify the caller's frame reference. + + + + + + Add frame to the end of the message, i.e. after all other frames. + Message takes ownership of frame, will destroy it when message is sent. + Returns 0 on success. Deprecates zmsg_add, which did not nullify the + caller's frame reference. + + + + + + Remove first frame from message, if any. Returns frame, or NULL. + + + + + Push block of memory to front of message, as a new frame. + Returns 0 on success, -1 on error. + + + + + + + Add block of memory to the end of the message, as a new frame. + Returns 0 on success, -1 on error. + + + + + + + Push string as new frame to front of message. + Returns 0 on success, -1 on error. + + + + + + Push string as new frame to end of message. + Returns 0 on success, -1 on error. + + + + + + Push formatted string as new frame to front of message. + Returns 0 on success, -1 on error. + + + + + + Push formatted string as new frame to end of message. + Returns 0 on success, -1 on error. + + + + + + Pop frame off front of message, return as fresh string. If there were + no more frames in the message, returns NULL. + + + + + Push encoded message as a new frame. Message takes ownership of + submessage, so the original is destroyed in this call. Returns 0 on + success, -1 on error. + + + + + + Remove first submessage from message, if any. Returns zmsg_t, or NULL if + decoding was not successful. + + + + + Remove specified frame from list, if present. Does not destroy frame. + + + + + Set cursor to first frame in message. Returns frame, or NULL, if the + message is empty. Use this to navigate the frames as a list. + + + + + Return the next frame. If there are no more frames, returns NULL. To move + to the first frame call zmsg_first(). Advances the cursor. + + + + + Return the last frame. If there are no frames, returns NULL. + + + + + Save message to an open file, return 0 if OK, else -1. The message is + saved as a series of frames, each with length and data. Note that the + file is NOT guaranteed to be portable between operating systems, not + versions of CZMQ. The file format is at present undocumented and liable + to arbitrary change. + + + + + + Load/append an open file into new message, return the message. + Returns NULL if the message could not be loaded. + + + + + Serialize multipart message to a single message frame. Use this method + to send structured messages across transports that do not support + multipart data. Allocates and returns a new frame containing the + serialized message. To decode a serialized message frame, use + zmsg_decode (). + + + + + Decodes a serialized message frame created by zmsg_encode () and returns + a new zmsg_t object. Returns NULL if the frame was badly formatted or + there was insufficient memory to work. + + + + + Create copy of message, as new message object. Returns a fresh zmsg_t + object. If message is null, or memory was exhausted, returns null. + + + + + Send message to zsys log sink (may be stdout, or system facility as + configured by zsys_set_logstream). + + + + Return true if the two messages have the same number of frames and each + frame in the first message is identical to the corresponding frame in the + other message. As with zframe_eq, return false if either message is NULL. + + + + + + Generate a signal message encoding the given status. A signal is a short + message carrying a 1-byte success/failure code (by convention, 0 means + OK). Signals are encoded to be distinguishable from "normal" messages. + + + + + Return signal value, 0 or greater, if message is a signal, -1 if not. + + + + + Probe the supplied object, and report if it looks like a zmsg_t. + + + + diff --git a/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zpoller.api b/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zpoller.api new file mode 100644 index 00000000000000..fc00f6a0751a94 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zpoller.api @@ -0,0 +1,71 @@ + + + event-driven reactor + + + Create new poller, specifying zero or more readers. The list of + readers ends in a NULL. Each reader can be a zsock_t instance, a + zactor_t instance, a libzmq socket (void *), or a file handle. + + + + + Destroy a poller + + + + Add a reader to be polled. Returns 0 if OK, -1 on failure. The reader may + be a libzmq void * socket, a zsock_t instance, or a zactor_t instance. + + + + + + Remove a reader from the poller; returns 0 if OK, -1 on failure. The reader + must have been passed during construction, or in an zpoller_add () call. + + + + + + By default the poller stops if the process receives a SIGINT or SIGTERM + signal. This makes it impossible to shut-down message based architectures + like zactors. This method lets you switch off break handling. The default + nonstop setting is off (false). + + + + + Poll the registered readers for I/O, return first reader that has input. + The reader will be a libzmq void * socket, or a zsock_t or zactor_t + instance as specified in zpoller_new/zpoller_add. The timeout should be + zero or greater, or -1 to wait indefinitely. Socket priority is defined + by their order in the poll list. If you need a balanced poll, use the low + level zmq_poll method directly. If the poll call was interrupted (SIGINT), + or the ZMQ context was destroyed, or the timeout expired, returns NULL. + You can test the actual exit condition by calling zpoller_expired () and + zpoller_terminated (). The timeout is in msec. + + + + + + Return true if the last zpoller_wait () call ended because the timeout + expired, without any error. + + + + + Return true if the last zpoller_wait () call ended because the process + was interrupted, or the parent context was destroyed. + + + diff --git a/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zproc.api b/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zproc.api new file mode 100644 index 00000000000000..52c1c9123ba3ee --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zproc.api @@ -0,0 +1,139 @@ + + + process configuration and status + + + Returns CZMQ version as a single 6-digit integer encoding the major + version (x 10000), the minor version (x 100) and the patch. + + + + + Returns true if the process received a SIGINT or SIGTERM signal. + It is good practice to use this method to exit any infinite loop + processing messages. + + + + + Returns true if the underlying libzmq supports CURVE security. + + + + + Return current host name, for use in public tcp:// endpoints. + If the host name is not resolvable, returns NULL. + + + + + Move the current process into the background. The precise effect + depends on the operating system. On POSIX boxes, moves to a specified + working directory (if specified), closes all file handles, reopens + stdin, stdout, and stderr to the null device, and sets the process to + ignore SIGHUP. On Windows, does nothing. Returns 0 if OK, -1 if there + was an error. + + + + + Drop the process ID into the lockfile, with exclusive lock, and + switch the process to the specified group and/or user. Any of the + arguments may be null, indicating a no-op. Returns 0 on success, + -1 on failure. Note if you combine this with zsys_daemonize, run + after, not before that method, or the lockfile will hold the wrong + process ID. + + + + + + + Configure the number of I/O threads that ZeroMQ will use. A good + rule of thumb is one thread per gigabit of traffic in or out. The + default is 1, sufficient for most applications. If the environment + variable ZSYS_IO_THREADS is defined, that provides the default. + Note that this method is valid only before any socket is created. + + + + + Configure the number of sockets that ZeroMQ will allow. The default + is 1024. The actual limit depends on the system, and you can query it + by using zsys_socket_limit (). A value of zero means "maximum". + Note that this method is valid only before any socket is created. + + + + + Set network interface name to use for broadcasts, particularly zbeacon. + This lets the interface be configured for test environments where required. + For example, on Mac OS X, zbeacon cannot bind to 255.255.255.255 which is + the default when there is no specified interface. If the environment + variable ZSYS_INTERFACE is set, use that as the default interface name. + Setting the interface to "*" means "use all available interfaces". + + + + + Return network interface to use for broadcasts, or "" if none was set. + + + + + Set log identity, which is a string that prefixes all log messages sent + by this process. The log identity defaults to the environment variable + ZSYS_LOGIDENT, if that is set. + + + + + Sends log output to a PUB socket bound to the specified endpoint. To + collect such log output, create a SUB socket, subscribe to the traffic + you care about, and connect to the endpoint. Log traffic is sent as a + single string frame, in the same format as when sent to stdout. The + log system supports a single sender; multiple calls to this method will + bind the same sender to multiple endpoints. To disable the sender, call + this method with a null argument. + + + + + Enable or disable logging to the system facility (syslog on POSIX boxes, + event log on Windows). By default this is disabled. + + + + + Log error condition - highest priority + + + + + Log warning condition - high priority + + + + + Log normal, but significant, condition - normal priority + + + + + Log informational message - low priority + + + + + Log debug-level message - lowest priority + + + diff --git a/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zsock.api b/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zsock.api new file mode 100644 index 00000000000000..26b15cf509624d --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zsock.api @@ -0,0 +1,406 @@ + + + high-level socket API that hides libzmq contexts and sockets + + + Create a new socket. Returns the new socket, or NULL if the new socket + could not be created. Note that the symbol zsock_new (and other + constructors/destructors for zsock) are redirected to the *_checked + variant, enabling intelligent socket leak detection. This can have + performance implications if you use a LOT of sockets. To turn off this + redirection behaviour, define ZSOCK_NOCHECK. + + + + + + + + + + + + + + + + + + + + + + + + + + Destroy the socket. You must use this for any socket created via the + zsock_new method. + + + + Create a PUB socket. Default action is bind. + + + + + Create a SUB socket, and optionally subscribe to some prefix string. Default + action is connect. + + + + + + Create a REQ socket. Default action is connect. + + + + + Create a REP socket. Default action is bind. + + + + + Create a DEALER socket. Default action is connect. + + + + + Create a ROUTER socket. Default action is bind. + + + + + Create a PUSH socket. Default action is connect. + + + + + Create a PULL socket. Default action is bind. + + + + + Create an XPUB socket. Default action is bind. + + + + + Create an XSUB socket. Default action is connect. + + + + + Create a PAIR socket. Default action is connect. + + + + + Create a STREAM socket. Default action is connect. + + + + + Create a SERVER socket. Default action is bind. + + + + + Create a CLIENT socket. Default action is connect. + + + + + Create a RADIO socket. Default action is bind. + + + + + Create a DISH socket. Default action is connect. + + + + + Create a GATHER socket. Default action is bind. + + + + + Create a SCATTER socket. Default action is connect. + + + + + Bind a socket to a formatted endpoint. For tcp:// endpoints, supports + ephemeral ports, if you specify the port number as "*". By default + zsock uses the IANA designated range from C000 (49152) to FFFF (65535). + To override this range, follow the "*" with "[first-last]". Either or + both first and last may be empty. To bind to a random port within the + range, use "!" in place of "*". + + Examples: + tcp://127.0.0.1:* bind to first free port from C000 up + tcp://127.0.0.1:! bind to random port from C000 to FFFF + tcp://127.0.0.1:*[60000-] bind to first free port from 60000 up + tcp://127.0.0.1:![-60000] bind to random port from C000 to 60000 + tcp://127.0.0.1:![55000-55999] + bind to random port from 55000 to 55999 + + On success, returns the actual port number used, for tcp:// endpoints, + and 0 for other transports. On failure, returns -1. Note that when using + ephemeral ports, a port may be reused by different services without + clients being aware. Protocols that run on ephemeral ports should take + this into account. + + + + + + Returns last bound endpoint, if any. + + + + + Unbind a socket from a formatted endpoint. + Returns 0 if OK, -1 if the endpoint was invalid or the function + isn't supported. + + + + + + Connect a socket to a formatted endpoint + Returns 0 if OK, -1 if the endpoint was invalid. + + + + + + Disconnect a socket from a formatted endpoint + Returns 0 if OK, -1 if the endpoint was invalid or the function + isn't supported. + + + + + + Attach a socket to zero or more endpoints. If endpoints is not null, + parses as list of ZeroMQ endpoints, separated by commas, and prefixed by + '@' (to bind the socket) or '>' (to connect the socket). Returns 0 if all + endpoints were valid, or -1 if there was a syntax error. If the endpoint + does not start with '@' or '>', the serverish argument defines whether + it is used to bind (serverish = true) or connect (serverish = false). + + + + + + + Returns socket type as printable constant string. + + + + + Send a 'picture' message to the socket (or actor). The picture is a + string that defines the type of each frame. This makes it easy to send + a complex multiframe message in one call. The picture can contain any + of these characters, each corresponding to one or two arguments: + + i = int (signed) + 1 = uint8_t + 2 = uint16_t + 4 = uint32_t + 8 = uint64_t + s = char * + b = byte *, size_t (2 arguments) + c = zchunk_t * + f = zframe_t * + h = zhashx_t * + U = zuuid_t * + p = void * (sends the pointer value, only meaningful over inproc) + m = zmsg_t * (sends all frames in the zmsg) + z = sends zero-sized frame (0 arguments) + u = uint (deprecated) + + Note that s, b, c, and f are encoded the same way and the choice is + offered as a convenience to the sender, which may or may not already + have data in a zchunk or zframe. Does not change or take ownership of + any arguments. Returns 0 if successful, -1 if sending failed for any + reason. + + + + + + Send a 'picture' message to the socket (or actor). This is a va_list + version of zsock_send (), so please consult its documentation for the + details. + + + + + + + Receive a 'picture' message to the socket (or actor). See zsock_send for + the format and meaning of the picture. Returns the picture elements into + a series of pointers as provided by the caller: + + i = int * (stores signed integer) + 4 = uint32_t * (stores 32-bit unsigned integer) + 8 = uint64_t * (stores 64-bit unsigned integer) + s = char ** (allocates new string) + b = byte **, size_t * (2 arguments) (allocates memory) + c = zchunk_t ** (creates zchunk) + f = zframe_t ** (creates zframe) + U = zuuid_t * (creates a zuuid with the data) + h = zhashx_t ** (creates zhashx) + p = void ** (stores pointer) + m = zmsg_t ** (creates a zmsg with the remaing frames) + z = null, asserts empty frame (0 arguments) + u = uint * (stores unsigned integer, deprecated) + + Note that zsock_recv creates the returned objects, and the caller must + destroy them when finished with them. The supplied pointers do not need + to be initialized. Returns 0 if successful, or -1 if it failed to recv + a message, in which case the pointers are not modified. When message + frames are truncated (a short message), sets return values to zero/null. + If an argument pointer is NULL, does not store any value (skips it). + An 'n' picture matches an empty frame; if the message does not match, + the method will return -1. + + + + + + Receive a 'picture' message from the socket (or actor). This is a + va_list version of zsock_recv (), so please consult its documentation + for the details. + + + + + + + Send a binary encoded 'picture' message to the socket (or actor). This + method is similar to zsock_send, except the arguments are encoded in a + binary format that is compatible with zproto, and is designed to reduce + memory allocations. The pattern argument is a string that defines the + type of each argument. Supports these argument types: + + pattern C type zproto type: + 1 uint8_t type = "number" size = "1" + 2 uint16_t type = "number" size = "2" + 4 uint32_t type = "number" size = "3" + 8 uint64_t type = "number" size = "4" + s char *, 0-255 chars type = "string" + S char *, 0-2^32-1 chars type = "longstr" + c zchunk_t * type = "chunk" + f zframe_t * type = "frame" + u zuuid_t * type = "uuid" + m zmsg_t * type = "msg" + p void *, sends pointer value, only over inproc + + Does not change or take ownership of any arguments. Returns 0 if + successful, -1 if sending failed for any reason. + + + + + + Receive a binary encoded 'picture' message from the socket (or actor). + This method is similar to zsock_recv, except the arguments are encoded + in a binary format that is compatible with zproto, and is designed to + reduce memory allocations. The pattern argument is a string that defines + the type of each argument. See zsock_bsend for the supported argument + types. All arguments must be pointers; this call sets them to point to + values held on a per-socket basis. + Note that zsock_brecv creates the returned objects, and the caller must + destroy them when finished with them. The supplied pointers do not need + to be initialized. Returns 0 if successful, or -1 if it failed to read + a message. + + + + + + Return socket routing ID if any. This returns 0 if the socket is not + of type ZMQ_SERVER or if no request was already received on it. + + + + + Set routing ID on socket. The socket MUST be of type ZMQ_SERVER. + This will be used when sending messages on the socket via the zsock API. + + + + + Set socket to use unbounded pipes (HWM=0); use this in cases when you are + totally certain the message volume can fit in memory. This method works + across all versions of ZeroMQ. Takes a polymorphic socket reference. + + + + Send a signal over a socket. A signal is a short message carrying a + success/failure code (by convention, 0 means OK). Signals are encoded + to be distinguishable from "normal" messages. Accepts a zsock_t or a + zactor_t argument, and returns 0 if successful, -1 if the signal could + not be sent. Takes a polymorphic socket reference. + + + + + + Wait on a signal. Use this to coordinate between threads, over pipe + pairs. Blocks until the signal is received. Returns -1 on error, 0 or + greater on success. Accepts a zsock_t or a zactor_t as argument. + Takes a polymorphic socket reference. + + + + + If there is a partial message still waiting on the socket, remove and + discard it. This is useful when reading partial messages, to get specific + message types. + + + + Join a group for the RADIO-DISH pattern. Call only on ZMQ_DISH. + Returns 0 if OK, -1 if failed. + + + + + + Leave a group for the RADIO-DISH pattern. Call only on ZMQ_DISH. + Returns 0 if OK, -1 if failed. + + + + + + Probe the supplied object, and report if it looks like a zsock_t. + Takes a polymorphic socket reference. + + + + + + Probe the supplied reference. If it looks like a zsock_t instance, return + the underlying libzmq socket handle; else if it looks like a file + descriptor, return NULL; else if it looks like a libzmq socket handle, + return the supplied value. Takes a polymorphic socket reference. + + + + + + diff --git a/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zsock_option.api b/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zsock_option.api new file mode 100644 index 00000000000000..c5799b027e5bab --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zsock_option.api @@ -0,0 +1,797 @@ + + + + + + Get socket option `heartbeat_ivl`. + Available from libzmq 4.2.0. + + + + + Set socket option `heartbeat_ivl`. + Available from libzmq 4.2.0. + + + + + Get socket option `heartbeat_ttl`. + Available from libzmq 4.2.0. + + + + + Set socket option `heartbeat_ttl`. + Available from libzmq 4.2.0. + + + + + Get socket option `heartbeat_timeout`. + Available from libzmq 4.2.0. + + + + + Set socket option `heartbeat_timeout`. + Available from libzmq 4.2.0. + + + + + Get socket option `use_fd`. + Available from libzmq 4.2.0. + + + + + Set socket option `use_fd`. + Available from libzmq 4.2.0. + + + + + Set socket option `xpub_manual`. + Available from libzmq 4.2.0. + + + + + Set socket option `xpub_welcome_msg`. + Available from libzmq 4.2.0. + + + + + Set socket option `stream_notify`. + Available from libzmq 4.2.0. + + + + + Get socket option `invert_matching`. + Available from libzmq 4.2.0. + + + + + Set socket option `invert_matching`. + Available from libzmq 4.2.0. + + + + + Set socket option `xpub_verboser`. + Available from libzmq 4.2.0. + + + + + Get socket option `connect_timeout`. + Available from libzmq 4.2.0. + + + + + Set socket option `connect_timeout`. + Available from libzmq 4.2.0. + + + + + Get socket option `tcp_maxrt`. + Available from libzmq 4.2.0. + + + + + Set socket option `tcp_maxrt`. + Available from libzmq 4.2.0. + + + + + Get socket option `thread_safe`. + Available from libzmq 4.2.0. + + + + + Get socket option `multicast_maxtpdu`. + Available from libzmq 4.2.0. + + + + + Set socket option `multicast_maxtpdu`. + Available from libzmq 4.2.0. + + + + + Get socket option `vmci_buffer_size`. + Available from libzmq 4.2.0. + + + + + Set socket option `vmci_buffer_size`. + Available from libzmq 4.2.0. + + + + + Get socket option `vmci_buffer_min_size`. + Available from libzmq 4.2.0. + + + + + Set socket option `vmci_buffer_min_size`. + Available from libzmq 4.2.0. + + + + + Get socket option `vmci_buffer_max_size`. + Available from libzmq 4.2.0. + + + + + Set socket option `vmci_buffer_max_size`. + Available from libzmq 4.2.0. + + + + + Get socket option `vmci_connect_timeout`. + Available from libzmq 4.2.0. + + + + + Set socket option `vmci_connect_timeout`. + Available from libzmq 4.2.0. + + + + + + + Get socket option `tos`. + Available from libzmq 4.1.0. + + + + + Set socket option `tos`. + Available from libzmq 4.1.0. + + + + + Set socket option `router_handover`. + Available from libzmq 4.1.0. + + + + + Set socket option `connect_rid`. + Available from libzmq 4.1.0. + + + + + Set socket option `connect_rid` from 32-octet binary + Available from libzmq 4.1.0. + + + + + Get socket option `handshake_ivl`. + Available from libzmq 4.1.0. + + + + + Set socket option `handshake_ivl`. + Available from libzmq 4.1.0. + + + + + Get socket option `socks_proxy`. + Available from libzmq 4.1.0. + + + + + Set socket option `socks_proxy`. + Available from libzmq 4.1.0. + + + + + Set socket option `xpub_nodrop`. + Available from libzmq 4.1.0. + + + + + + + Set socket option `router_mandatory`. + Available from libzmq 4.0.0. + + + + + Set socket option `probe_router`. + Available from libzmq 4.0.0. + + + + + Set socket option `req_relaxed`. + Available from libzmq 4.0.0. + + + + + Set socket option `req_correlate`. + Available from libzmq 4.0.0. + + + + + Set socket option `conflate`. + Available from libzmq 4.0.0. + + + + + Get socket option `zap_domain`. + Available from libzmq 4.0.0. + + + + + Set socket option `zap_domain`. + Available from libzmq 4.0.0. + + + + + Get socket option `mechanism`. + Available from libzmq 4.0.0. + + + + + Get socket option `plain_server`. + Available from libzmq 4.0.0. + + + + + Set socket option `plain_server`. + Available from libzmq 4.0.0. + + + + + Get socket option `plain_username`. + Available from libzmq 4.0.0. + + + + + Set socket option `plain_username`. + Available from libzmq 4.0.0. + + + + + Get socket option `plain_password`. + Available from libzmq 4.0.0. + + + + + Set socket option `plain_password`. + Available from libzmq 4.0.0. + + + + + Get socket option `curve_server`. + Available from libzmq 4.0.0. + + + + + Set socket option `curve_server`. + Available from libzmq 4.0.0. + + + + + Get socket option `curve_publickey`. + Available from libzmq 4.0.0. + + + + + Set socket option `curve_publickey`. + Available from libzmq 4.0.0. + + + + + Set socket option `curve_publickey` from 32-octet binary + Available from libzmq 4.0.0. + + + + + Get socket option `curve_secretkey`. + Available from libzmq 4.0.0. + + + + + Set socket option `curve_secretkey`. + Available from libzmq 4.0.0. + + + + + Set socket option `curve_secretkey` from 32-octet binary + Available from libzmq 4.0.0. + + + + + Get socket option `curve_serverkey`. + Available from libzmq 4.0.0. + + + + + Set socket option `curve_serverkey`. + Available from libzmq 4.0.0. + + + + + Set socket option `curve_serverkey` from 32-octet binary + Available from libzmq 4.0.0. + + + + + Get socket option `gssapi_server`. + Available from libzmq 4.0.0. + + + + + Set socket option `gssapi_server`. + Available from libzmq 4.0.0. + + + + + Get socket option `gssapi_plaintext`. + Available from libzmq 4.0.0. + + + + + Set socket option `gssapi_plaintext`. + Available from libzmq 4.0.0. + + + + + Get socket option `gssapi_principal`. + Available from libzmq 4.0.0. + + + + + Set socket option `gssapi_principal`. + Available from libzmq 4.0.0. + + + + + Get socket option `gssapi_service_principal`. + Available from libzmq 4.0.0. + + + + + Set socket option `gssapi_service_principal`. + Available from libzmq 4.0.0. + + + + + Get socket option `ipv6`. + Available from libzmq 4.0.0. + + + + + Set socket option `ipv6`. + Available from libzmq 4.0.0. + + + + + Get socket option `immediate`. + Available from libzmq 4.0.0. + + + + + Set socket option `immediate`. + Available from libzmq 4.0.0. + + + + + + + Get socket option `type`. + Available from libzmq 3.0.0. + + + + + Get socket option `sndhwm`. + Available from libzmq 3.0.0. + + + + + Set socket option `sndhwm`. + Available from libzmq 3.0.0. + + + + + Get socket option `rcvhwm`. + Available from libzmq 3.0.0. + + + + + Set socket option `rcvhwm`. + Available from libzmq 3.0.0. + + + + + Get socket option `affinity`. + Available from libzmq 3.0.0. + + + + + Set socket option `affinity`. + Available from libzmq 3.0.0. + + + + + Set socket option `subscribe`. + Available from libzmq 3.0.0. + + + + + Set socket option `unsubscribe`. + Available from libzmq 3.0.0. + + + + + Get socket option `identity`. + Available from libzmq 3.0.0. + + + + + Set socket option `identity`. + Available from libzmq 3.0.0. + + + + + Get socket option `rate`. + Available from libzmq 3.0.0. + + + + + Set socket option `rate`. + Available from libzmq 3.0.0. + + + + + Get socket option `recovery_ivl`. + Available from libzmq 3.0.0. + + + + + Set socket option `recovery_ivl`. + Available from libzmq 3.0.0. + + + + + Get socket option `sndbuf`. + Available from libzmq 3.0.0. + + + + + Set socket option `sndbuf`. + Available from libzmq 3.0.0. + + + + + Get socket option `rcvbuf`. + Available from libzmq 3.0.0. + + + + + Set socket option `rcvbuf`. + Available from libzmq 3.0.0. + + + + + Get socket option `linger`. + Available from libzmq 3.0.0. + + + + + Set socket option `linger`. + Available from libzmq 3.0.0. + + + + + Get socket option `reconnect_ivl`. + Available from libzmq 3.0.0. + + + + + Set socket option `reconnect_ivl`. + Available from libzmq 3.0.0. + + + + + Get socket option `reconnect_ivl_max`. + Available from libzmq 3.0.0. + + + + + Set socket option `reconnect_ivl_max`. + Available from libzmq 3.0.0. + + + + + Get socket option `backlog`. + Available from libzmq 3.0.0. + + + + + Set socket option `backlog`. + Available from libzmq 3.0.0. + + + + + Get socket option `maxmsgsize`. + Available from libzmq 3.0.0. + + + + + Set socket option `maxmsgsize`. + Available from libzmq 3.0.0. + + + + + Get socket option `multicast_hops`. + Available from libzmq 3.0.0. + + + + + Set socket option `multicast_hops`. + Available from libzmq 3.0.0. + + + + + Get socket option `rcvtimeo`. + Available from libzmq 3.0.0. + + + + + Set socket option `rcvtimeo`. + Available from libzmq 3.0.0. + + + + + Get socket option `sndtimeo`. + Available from libzmq 3.0.0. + + + + + Set socket option `sndtimeo`. + Available from libzmq 3.0.0. + + + + + Set socket option `xpub_verbose`. + Available from libzmq 3.0.0. + + + + + Get socket option `tcp_keepalive`. + Available from libzmq 3.0.0. + + + + + Set socket option `tcp_keepalive`. + Available from libzmq 3.0.0. + + + + + Get socket option `tcp_keepalive_idle`. + Available from libzmq 3.0.0. + + + + + Set socket option `tcp_keepalive_idle`. + Available from libzmq 3.0.0. + + + + + Get socket option `tcp_keepalive_cnt`. + Available from libzmq 3.0.0. + + + + + Set socket option `tcp_keepalive_cnt`. + Available from libzmq 3.0.0. + + + + + Get socket option `tcp_keepalive_intvl`. + Available from libzmq 3.0.0. + + + + + Set socket option `tcp_keepalive_intvl`. + Available from libzmq 3.0.0. + + + + + Get socket option `tcp_accept_filter`. + Available from libzmq 3.0.0. + + + + + Set socket option `tcp_accept_filter`. + Available from libzmq 3.0.0. + + + + + Get socket option `rcvmore`. + Available from libzmq 3.0.0. + + + + + Get socket option `fd`. + Available from libzmq 3.0.0. + + + + + Get socket option `events`. + Available from libzmq 3.0.0. + + + + + Get socket option `last_endpoint`. + Available from libzmq 3.0.0. + + + + + Set socket option `router_raw`. + Available from libzmq 3.0.0. + + + + + Get socket option `ipv4only`. + Available from libzmq 3.0.0. + + + + + Set socket option `ipv4only`. + Available from libzmq 3.0.0. + + + + + Set socket option `delay_attach_on_connect`. + Available from libzmq 3.0.0. + + diff --git a/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zstr.api b/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zstr.api new file mode 100644 index 00000000000000..b4c951e7207ab5 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zstr.api @@ -0,0 +1,90 @@ + + + sending and receiving strings + + + Receive C string from socket. Caller must free returned string using + zstr_free(). Returns NULL if the context is being terminated or the + process was interrupted. + + + + + + Receive a series of strings (until NULL) from multipart data. + Each string is allocated and filled with string data; if there + are not enough frames, unallocated strings are set to NULL. + Returns -1 if the message could not be read, else returns the + number of strings filled, zero or more. Free each returned string + using zstr_free(). If not enough strings are provided, remaining + multipart frames in the message are dropped. + + + + + + + Send a C string to a socket, as a frame. The string is sent without + trailing null byte; to read this you can use zstr_recv, or a similar + method that adds a null terminator on the received string. String + may be NULL, which is sent as "". + + + + + + + Send a C string to a socket, as zstr_send(), with a MORE flag, so that + you can send further strings in the same multi-part message. + + + + + + + Send a formatted string to a socket. Note that you should NOT use + user-supplied strings in the format (they may contain '%' which + will create security holes). + + + + + + + Send a formatted string to a socket, as for zstr_sendf(), with a + MORE flag, so that you can send further strings in the same multi-part + message. + + + + + + + Send a series of strings (until NULL) as multipart data + Returns 0 if the strings could be sent OK, or -1 on error. + + + + + + + Accepts a void pointer and returns a fresh character string. If source + is null, returns an empty string. + + + + + + Free a provided string, and nullify the parent pointer. Safe to call on + a null pointer. + + + diff --git a/phonelibs/zmq/aarch64-linux/share/zproject/czmq/ztimerset.api b/phonelibs/zmq/aarch64-linux/share/zproject/czmq/ztimerset.api new file mode 100644 index 00000000000000..20d3ca71ad9065 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/zproject/czmq/ztimerset.api @@ -0,0 +1,69 @@ + + + timer set + + + Create new timer set. + + + + Destroy a timer set + + + + Callback function for timer event. + + + + + + Add a timer to the set. Returns timer id if OK, -1 on failure. + + + + + + + + Cancel a timer. Returns 0 if OK, -1 on failure. + + + + + + Set timer interval. Returns 0 if OK, -1 on failure. + This method is slow, canceling the timer and adding a new one yield better performance. + + + + + + + Reset timer to start interval counting from current time. Returns 0 if OK, -1 on failure. + This method is slow, canceling the timer and adding a new one yield better performance. + + + + + + Return the time until the next interval. + Should be used as timeout parameter for the zpoller wait method. + The timeout is in msec. + + + + + Invoke callback function of all timers which their interval has elapsed. + Should be call after zpoller wait method. + Returns 0 if OK, -1 on failure. + + + diff --git a/phonelibs/zmq/aarch64-linux/share/zproject/czmq/ztrie.api b/phonelibs/zmq/aarch64-linux/share/zproject/czmq/ztrie.api new file mode 100644 index 00000000000000..01fc3a4131e6a8 --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/zproject/czmq/ztrie.api @@ -0,0 +1,80 @@ + + + simple trie for tokenizable strings + + + Callback function for ztrie_node to destroy node data. + + + + + Creates a new ztrie. + + + + + Destroy the ztrie. + + + + Inserts a new route into the tree and attaches the data. Returns -1 + if the route already exists, otherwise 0. This method takes ownership of + the provided data if a destroy_data_fn is provided. + + + + + + + + Removes a route from the trie and destroys its data. Returns -1 if the + route does not exists, otherwise 0. + the start of the list call zlist_first (). Advances the cursor. + + + + + + Returns true if the path matches a route in the tree, otherwise false. + + + + + + Returns the data of a matched route from last ztrie_matches. If the path + did not match, returns NULL. Do not delete the data as it's owned by + ztrie. + + + + + Returns the count of parameters that a matched route has. + + + + + Returns the parameters of a matched route with named regexes from last + ztrie_matches. If the path did not match or the route did not contain any + named regexes, returns NULL. + + + + + Returns the asterisk matched part of a route, if there has been no match + or no asterisk match, returns NULL. + + + + + Print the trie + + + diff --git a/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zuuid.api b/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zuuid.api new file mode 100644 index 00000000000000..1fdb9c4e060f9e --- /dev/null +++ b/phonelibs/zmq/aarch64-linux/share/zproject/czmq/zuuid.api @@ -0,0 +1,82 @@ + + + UUID support class + + + Create a new UUID object. + + + + Destroy a specified UUID object. + + + + Create UUID object from supplied ZUUID_LEN-octet value. + + + + + Set UUID to new supplied ZUUID_LEN-octet value. + + + + + Set UUID to new supplied string value skipping '-' and '{' '}' + optional delimiters. Return 0 if OK, else returns -1. + + + + + + Return UUID binary data. + + + + + Return UUID binary size + + + + + Returns UUID as string + + + + + Return UUID in the canonical string format: 8-4-4-4-12, in lower + case. Caller does not modify or free returned value. See + http://en.wikipedia.org/wiki/Universally_unique_identifier + + + + + Store UUID blob in target array + + + + + Check if UUID is same as supplied value + + + + + + Check if UUID is different from supplied value + + + + + + Make copy of UUID object; if uuid is null, or memory was exhausted, + returns null. + + + diff --git a/phonelibs/zmq/aarch64/include/czmq.h b/phonelibs/zmq/aarch64/include/czmq.h new file mode 100644 index 00000000000000..ba21aa3bd1efdd --- /dev/null +++ b/phonelibs/zmq/aarch64/include/czmq.h @@ -0,0 +1,31 @@ +/* ========================================================================= + CZMQ - a high-level binding in C for ZeroMQ + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __CZMQ_H_INCLUDED__ +#define __CZMQ_H_INCLUDED__ + +// These are signatures for handler functions that customize the +// behavior of CZMQ containers. These are shared between all CZMQ +// container types. + +// -- destroy an item +typedef void (czmq_destructor) (void **item); +// -- duplicate an item +typedef void *(czmq_duplicator) (const void *item); +// - compare two items, for sorting +typedef int (czmq_comparator) (const void *item1, const void *item2); + +// Include the project library file +#include "czmq_library.h" + +#endif diff --git a/phonelibs/zmq/aarch64/include/czmq_library.h b/phonelibs/zmq/aarch64/include/czmq_library.h new file mode 100644 index 00000000000000..be348db3e9a414 --- /dev/null +++ b/phonelibs/zmq/aarch64/include/czmq_library.h @@ -0,0 +1,199 @@ +/* ========================================================================= + czmq - generated layer of public API + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + +################################################################################ +# THIS FILE IS 100% GENERATED BY ZPROJECT; DO NOT EDIT EXCEPT EXPERIMENTALLY # +# Read the zproject/README.md for information about making permanent changes. # +################################################################################ + ========================================================================= +*/ + +#ifndef CZMQ_LIBRARY_H_INCLUDED +#define CZMQ_LIBRARY_H_INCLUDED + +// Set up environment for the application +#include "czmq_prelude.h" + +// External dependencies +#include + +// CZMQ version macros for compile-time API detection +#define CZMQ_VERSION_MAJOR 3 +#define CZMQ_VERSION_MINOR 0 +#define CZMQ_VERSION_PATCH 3 + +#define CZMQ_MAKE_VERSION(major, minor, patch) \ + ((major) * 10000 + (minor) * 100 + (patch)) +#define CZMQ_VERSION \ + CZMQ_MAKE_VERSION(CZMQ_VERSION_MAJOR, CZMQ_VERSION_MINOR, CZMQ_VERSION_PATCH) + +#if defined (__WINDOWS__) +# if defined CZMQ_STATIC +# define CZMQ_EXPORT +# elif defined CZMQ_INTERNAL_BUILD +# if defined DLL_EXPORT +# define CZMQ_EXPORT __declspec(dllexport) +# else +# define CZMQ_EXPORT +# endif +# elif defined CZMQ_EXPORTS +# define CZMQ_EXPORT __declspec(dllexport) +# else +# define CZMQ_EXPORT __declspec(dllimport) +# endif +#else +# define CZMQ_EXPORT +#endif + +// Opaque class structures to allow forward references +// These classes are stable or legacy and built in all releases +typedef struct _zactor_t zactor_t; +#define ZACTOR_T_DEFINED +typedef struct _zarmour_t zarmour_t; +#define ZARMOUR_T_DEFINED +typedef struct _zcert_t zcert_t; +#define ZCERT_T_DEFINED +typedef struct _zcertstore_t zcertstore_t; +#define ZCERTSTORE_T_DEFINED +typedef struct _zchunk_t zchunk_t; +#define ZCHUNK_T_DEFINED +typedef struct _zclock_t zclock_t; +#define ZCLOCK_T_DEFINED +typedef struct _zconfig_t zconfig_t; +#define ZCONFIG_T_DEFINED +typedef struct _zdigest_t zdigest_t; +#define ZDIGEST_T_DEFINED +typedef struct _zdir_t zdir_t; +#define ZDIR_T_DEFINED +typedef struct _zdir_patch_t zdir_patch_t; +#define ZDIR_PATCH_T_DEFINED +typedef struct _zfile_t zfile_t; +#define ZFILE_T_DEFINED +typedef struct _zframe_t zframe_t; +#define ZFRAME_T_DEFINED +typedef struct _zhash_t zhash_t; +#define ZHASH_T_DEFINED +typedef struct _zhashx_t zhashx_t; +#define ZHASHX_T_DEFINED +typedef struct _ziflist_t ziflist_t; +#define ZIFLIST_T_DEFINED +typedef struct _zlist_t zlist_t; +#define ZLIST_T_DEFINED +typedef struct _zlistx_t zlistx_t; +#define ZLISTX_T_DEFINED +typedef struct _zloop_t zloop_t; +#define ZLOOP_T_DEFINED +typedef struct _zmsg_t zmsg_t; +#define ZMSG_T_DEFINED +typedef struct _zpoller_t zpoller_t; +#define ZPOLLER_T_DEFINED +typedef struct _zsock_t zsock_t; +#define ZSOCK_T_DEFINED +typedef struct _zstr_t zstr_t; +#define ZSTR_T_DEFINED +typedef struct _zuuid_t zuuid_t; +#define ZUUID_T_DEFINED +typedef struct _zauth_t zauth_t; +#define ZAUTH_T_DEFINED +typedef struct _zbeacon_t zbeacon_t; +#define ZBEACON_T_DEFINED +typedef struct _zgossip_t zgossip_t; +#define ZGOSSIP_T_DEFINED +typedef struct _zmonitor_t zmonitor_t; +#define ZMONITOR_T_DEFINED +typedef struct _zproxy_t zproxy_t; +#define ZPROXY_T_DEFINED +typedef struct _zrex_t zrex_t; +#define ZREX_T_DEFINED +typedef struct _zsys_t zsys_t; +#define ZSYS_T_DEFINED +typedef struct _zauth_v2_t zauth_v2_t; +#define ZAUTH_V2_T_DEFINED +typedef struct _zbeacon_v2_t zbeacon_v2_t; +#define ZBEACON_V2_T_DEFINED +typedef struct _zctx_t zctx_t; +#define ZCTX_T_DEFINED +typedef struct _zmonitor_v2_t zmonitor_v2_t; +#define ZMONITOR_V2_T_DEFINED +typedef struct _zmutex_t zmutex_t; +#define ZMUTEX_T_DEFINED +typedef struct _zproxy_v2_t zproxy_v2_t; +#define ZPROXY_V2_T_DEFINED +typedef struct _zsocket_t zsocket_t; +#define ZSOCKET_T_DEFINED +typedef struct _zsockopt_t zsockopt_t; +#define ZSOCKOPT_T_DEFINED +typedef struct _zthread_t zthread_t; +#define ZTHREAD_T_DEFINED +// Draft classes are by default not built in stable releases +#ifdef CZMQ_BUILD_DRAFT_API +typedef struct _zproc_t zproc_t; +#define ZPROC_T_DEFINED +typedef struct _ztimerset_t ztimerset_t; +#define ZTIMERSET_T_DEFINED +typedef struct _ztrie_t ztrie_t; +#define ZTRIE_T_DEFINED +#endif // CZMQ_BUILD_DRAFT_API + + +// Public classes, each with its own header file +#include "zactor.h" +#include "zarmour.h" +#include "zcert.h" +#include "zcertstore.h" +#include "zchunk.h" +#include "zclock.h" +#include "zconfig.h" +#include "zdigest.h" +#include "zdir.h" +#include "zdir_patch.h" +#include "zfile.h" +#include "zframe.h" +#include "zhash.h" +#include "zhashx.h" +#include "ziflist.h" +#include "zlist.h" +#include "zlistx.h" +#include "zloop.h" +#include "zmsg.h" +#include "zpoller.h" +#include "zsock.h" +#include "zstr.h" +#include "zuuid.h" +#include "zauth.h" +#include "zbeacon.h" +#include "zgossip.h" +#include "zmonitor.h" +#include "zproxy.h" +#include "zrex.h" +#include "zsys.h" +#include "zauth_v2.h" +#include "zbeacon_v2.h" +#include "zctx.h" +#include "zmonitor_v2.h" +#include "zmutex.h" +#include "zproxy_v2.h" +#include "zsocket.h" +#include "zsockopt.h" +#include "zthread.h" +#ifdef CZMQ_BUILD_DRAFT_API +#include "zproc.h" +#include "ztimerset.h" +#include "ztrie.h" +#endif // CZMQ_BUILD_DRAFT_API + +#endif +/* +################################################################################ +# THIS FILE IS 100% GENERATED BY ZPROJECT; DO NOT EDIT EXCEPT EXPERIMENTALLY # +# Read the zproject/README.md for information about making permanent changes. # +################################################################################ +*/ diff --git a/phonelibs/zmq/aarch64/include/czmq_prelude.h b/phonelibs/zmq/aarch64/include/czmq_prelude.h new file mode 100644 index 00000000000000..e9ceb691e839ef --- /dev/null +++ b/phonelibs/zmq/aarch64/include/czmq_prelude.h @@ -0,0 +1,641 @@ +/* ========================================================================= + czmq_prelude.h - CZMQ environment + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __CZMQ_PRELUDE_H_INCLUDED__ +#define __CZMQ_PRELUDE_H_INCLUDED__ + +//- Establish the compiler and computer system ------------------------------ +/* + * Defines zero or more of these symbols, for use in any non-portable + * code: + * + * __WINDOWS__ Microsoft C/C++ with Windows calls + * __MSDOS__ System is MS-DOS (set if __WINDOWS__ set) + * __VMS__ System is VAX/VMS or Alpha/OpenVMS + * __UNIX__ System is UNIX + * __OS2__ System is OS/2 + * + * __IS_32BIT__ OS/compiler is 32 bits + * __IS_64BIT__ OS/compiler is 64 bits + * + * When __UNIX__ is defined, we also define exactly one of these: + * + * __UTYPE_AUX Apple AUX + * __UTYPE_BEOS BeOS + * __UTYPE_BSDOS BSD/OS + * __UTYPE_DECALPHA Digital UNIX (Alpha) + * __UTYPE_IBMAIX IBM RS/6000 AIX + * __UTYPE_FREEBSD FreeBSD + * __UTYPE_HPUX HP/UX + * __UTYPE_ANDROID Android + * __UTYPE_LINUX Linux + * __UTYPE_GNU GNU/Hurd + * __UTYPE_MIPS MIPS (BSD 4.3/System V mixture) + * __UTYPE_NETBSD NetBSD + * __UTYPE_NEXT NeXT + * __UTYPE_OPENBSD OpenBSD + * __UTYPE_OSX Apple Macintosh OS X + * __UTYPE_IOS Apple iOS + * __UTYPE_QNX QNX + * __UTYPE_IRIX Silicon Graphics IRIX + * __UTYPE_SINIX SINIX-N (Siemens-Nixdorf Unix) + * __UTYPE_SUNOS SunOS + * __UTYPE_SUNSOLARIS Sun Solaris + * __UTYPE_UNIXWARE SCO UnixWare + * ... these are the ones I know about so far. + * __UTYPE_GENERIC Any other UNIX + * + * When __VMS__ is defined, we may define one or more of these: + * + * __VMS_XOPEN Supports XOPEN functions + */ + +#if (defined (__64BIT__) || defined (__x86_64__)) +# define __IS_64BIT__ // May have 64-bit OS/compiler +#else +# define __IS_32BIT__ // Else assume 32-bit OS/compiler +#endif + +#if (defined WIN32 || defined _WIN32) +# undef __WINDOWS__ +# define __WINDOWS__ +# undef __MSDOS__ +# define __MSDOS__ +#endif + +#if (defined WINDOWS || defined _WINDOWS || defined __WINDOWS__) +# undef __WINDOWS__ +# define __WINDOWS__ +# undef __MSDOS__ +# define __MSDOS__ +// Stop cheeky warnings about "deprecated" functions like fopen +# if _MSC_VER >= 1500 +# undef _CRT_SECURE_NO_DEPRECATE +# define _CRT_SECURE_NO_DEPRECATE +# pragma warning(disable: 4996) +# endif +#endif + +// MSDOS Microsoft C +// _MSC_VER Microsoft C +#if (defined (MSDOS) || defined (_MSC_VER)) +# undef __MSDOS__ +# define __MSDOS__ +# if (defined (_DEBUG) && !defined (DEBUG)) +# define DEBUG +# endif +#endif + +#if (defined (__EMX__) && defined (__i386__)) +# undef __OS2__ +# define __OS2__ +#endif + +// VMS VAX C (VAX/VMS) +// __VMS Dec C (Alpha/OpenVMS) +// __vax__ gcc +#if (defined (VMS) || defined (__VMS) || defined (__vax__)) +# undef __VMS__ +# define __VMS__ +# if (__VMS_VER >= 70000000) +# define __VMS_XOPEN +# endif +#endif + +// Try to define a __UTYPE_xxx symbol... +// unix SunOS at least +// __unix__ gcc +// _POSIX_SOURCE is various UNIX systems, maybe also VAX/VMS +#if (defined (unix) || defined (__unix__) || defined (_POSIX_SOURCE)) +# if (!defined (__VMS__)) +# undef __UNIX__ +# define __UNIX__ +# if (defined (__alpha)) // Digital UNIX is 64-bit +# undef __IS_32BIT__ +# define __IS_64BIT__ +# define __UTYPE_DECALPHA +# endif +# endif +#endif + +#if (defined (_AUX)) +# define __UTYPE_AUX +# define __UNIX__ +#elif (defined (__BEOS__)) +# define __UTYPE_BEOS +# define __UNIX__ +#elif (defined (__hpux)) +# define __UTYPE_HPUX +# define __UNIX__ +# define _INCLUDE_HPUX_SOURCE +# define _INCLUDE_XOPEN_SOURCE +# define _INCLUDE_POSIX_SOURCE +#elif (defined (_AIX) || defined (AIX)) +# define __UTYPE_IBMAIX +# define __UNIX__ +#elif (defined (BSD) || defined (bsd)) +# define __UTYPE_BSDOS +# define __UNIX__ +#elif (defined (__ANDROID__)) +# define __UTYPE_ANDROID +# define __UNIX__ +#elif (defined (LINUX) || defined (linux) || defined (__linux__)) +# define __UTYPE_LINUX +# define __UNIX__ +# ifndef __NO_CTYPE +# define __NO_CTYPE // Suppress warnings on tolower() +# endif +# ifndef _DEFAULT_SOURCE +# define _DEFAULT_SOURCE // Include stuff from 4.3 BSD Unix +# endif +#elif (defined (__GNU__)) +# define __UTYPE_GNU +# define __UNIX__ +#elif (defined (Mips)) +# define __UTYPE_MIPS +# define __UNIX__ +#elif (defined (FreeBSD) || defined (__FreeBSD__)) +# define __UTYPE_FREEBSD +# define __UNIX__ +#elif (defined (NetBSD) || defined (__NetBSD__)) +# define __UTYPE_NETBSD +# define __UNIX__ +#elif (defined (OpenBSD) || defined (__OpenBSD__)) +# define __UTYPE_OPENBSD +# define __UNIX__ +#elif (defined (APPLE) || defined (__APPLE__)) +# include +# define __UNIX__ +# if TARGET_OS_IPHONE || TARGET_IPHONE_SIMULATOR +# define __UTYPE_IOS +# else +# define __UTYPE_OSX +# endif +#elif (defined (NeXT)) +# define __UTYPE_NEXT +# define __UNIX__ +#elif (defined (__QNX__)) +# define __UTYPE_QNX +# define __UNIX__ +#elif (defined (sgi)) +# define __UTYPE_IRIX +# define __UNIX__ +#elif (defined (sinix)) +# define __UTYPE_SINIX +# define __UNIX__ +#elif (defined (SOLARIS) || defined (__SRV4)) +# define __UTYPE_SUNSOLARIS +# define __UNIX__ +#elif (defined (SUNOS) || defined (SUN) || defined (sun)) +# define __UTYPE_SUNOS +# define __UNIX__ +#elif (defined (__USLC__) || defined (UnixWare)) +# define __UTYPE_UNIXWARE +# define __UNIX__ +#elif (defined (__CYGWIN__)) +# define __UTYPE_CYGWIN +# define __UNIX__ +#elif (defined (__UNIX__)) +# define __UTYPE_GENERIC +#endif + +//- Always include ZeroMQ headers ------------------------------------------- + +#include "zmq.h" +#if (ZMQ_VERSION < ZMQ_MAKE_VERSION (4, 2, 0)) +# include "zmq_utils.h" +#endif + +//- Standard ANSI include files --------------------------------------------- + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +//- System-specific include files ------------------------------------------- + +#if (defined (__MSDOS__)) +# if (defined (__WINDOWS__)) +# if (_WIN32_WINNT < 0x0501) +# undef _WIN32_WINNT +# define _WIN32_WINNT 0x0501 +# endif +# if (!defined (FD_SETSIZE)) +# define FD_SETSIZE 1024 // Max. filehandles/sockets +# endif +# include +# include +# include +# include +# include // For getnameinfo () +# include // For GetAdaptersAddresses () +# endif +# include +# include +# include +# include +# include +# include +# include +# include +#endif + +#if (defined (__UNIX__)) +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include // Let CZMQ build with libzmq/3.x +# include // Must come before arpa/inet.h +# if (!defined (__UTYPE_ANDROID)) && (!defined (__UTYPE_IBMAIX)) \ + && (!defined (__UTYPE_HPUX)) +# include +# endif +# if defined (__UTYPE_SUNSOLARIS) || defined (__UTYPE_SUNOS) +# include +# endif +# if (!defined (__UTYPE_BEOS)) +# include +# if (!defined (TCP_NODELAY)) +# include +# endif +# endif +# if (defined (__UTYPE_IBMAIX) || defined(__UTYPE_QNX)) +# include +# endif +# if (defined (__UTYPE_BEOS)) +# include +# endif +# if ((defined (_XOPEN_REALTIME) && (_XOPEN_REALTIME >= 1)) \ + || (defined (_POSIX_VERSION) && (_POSIX_VERSION >= 199309L))) +# include +# endif +# if (defined (__UTYPE_OSX) || defined (__UTYPE_IOS)) +# include +# include // For monotonic clocks +# endif +# if (defined (__UTYPE_OSX)) +# include // For _NSGetEnviron() +# endif +# if (defined (__UTYPE_ANDROID)) +# include +# endif +# if (defined (__UTYPE_LINUX) && defined (HAVE_LIBSYSTEMD)) +# include +# endif +#endif + +#if (defined (__VMS__)) +# if (!defined (vaxc)) +# include // Not provided by Vax C +# endif +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +#endif + +#if (defined (__OS2__)) +# include // Required near top +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include // Must come before arpa/inet.h +# include +# include +# if (!defined (TCP_NODELAY)) +# include +# endif +#endif + +// Add missing defines for non-POSIX systems +#ifndef S_IRUSR +# define S_IRUSR S_IREAD +#endif +#ifndef S_IWUSR +# define S_IWUSR S_IWRITE +#endif +#ifndef S_ISDIR +# define S_ISDIR(m) (((m) & S_IFDIR) != 0) +#endif +#ifndef S_ISREG +# define S_ISREG(m) (((m) & S_IFREG) != 0) +#endif + + +//- Check compiler data type sizes ------------------------------------------ + +#if (UCHAR_MAX != 0xFF) +# error "Cannot compile: must change definition of 'byte'." +#endif +#if (USHRT_MAX != 0xFFFFU) +# error "Cannot compile: must change definition of 'dbyte'." +#endif +#if (UINT_MAX != 0xFFFFFFFFU) +# error "Cannot compile: must change definition of 'qbyte'." +#endif + +//- Data types -------------------------------------------------------------- + +typedef unsigned char byte; // Single unsigned byte = 8 bits +typedef unsigned short dbyte; // Double byte = 16 bits +typedef unsigned int qbyte; // Quad byte = 32 bits +typedef struct sockaddr_in inaddr_t; // Internet socket address structure +typedef struct sockaddr_in6 in6addr_t; // Internet 6 socket address structure + +// Common structure to hold inaddr_t and in6addr_t with length +typedef struct { + union { + inaddr_t __addr; // IPv4 address + in6addr_t __addr6; // IPv6 address + } __inaddr_u; +#define ipv4addr __inaddr_u.__addr +#define ipv6addr __inaddr_u.__addr6 + int inaddrlen; +} inaddr_storage_t; + +//- Inevitable macros ------------------------------------------------------- + +#define streq(s1,s2) (!strcmp ((s1), (s2))) +#define strneq(s1,s2) (strcmp ((s1), (s2))) + +// Provide random number from 0..(num-1) +#if (defined (__WINDOWS__)) || (defined (__UTYPE_IBMAIX)) \ + || (defined (__UTYPE_HPUX)) || (defined (__UTYPE_SUNOS)) +# define randof(num) (int) ((float) (num) * rand () / (RAND_MAX + 1.0)) +#else +# define randof(num) (int) ((float) (num) * random () / (RAND_MAX + 1.0)) +#endif + +// Windows MSVS doesn't have stdbool +#if (defined (_MSC_VER)) +# if (!defined (__cplusplus) && (!defined (true))) +# define true 1 +# define false 0 + typedef char bool; +# endif +#else +# include +#endif + +//- A number of POSIX and C99 keywords and data types ----------------------- +// CZMQ uses uint for array indices; equivalent to unsigned int, but more +// convenient in code. We define it in czmq_prelude.h on systems that do +// not define it by default. + +#if (defined (__WINDOWS__)) +# if (!defined (__cplusplus) && (!defined (inline))) +# define inline __inline +# endif +# define strtoull _strtoui64 +# define atoll _atoi64 +# define srandom srand +# define TIMEZONE _timezone +# if (!defined (__MINGW32__)) +# define snprintf _snprintf +# define vsnprintf _vsnprintf +# endif + typedef unsigned long ulong; + typedef unsigned int uint; +# if (!defined (__MINGW32__)) + typedef int mode_t; +# if !defined (_SSIZE_T_DEFINED) +typedef intptr_t ssize_t; +# define _SSIZE_T_DEFINED +# endif +# endif +# if ((!defined (__MINGW32__) \ + || (defined (__MINGW32__) && defined (__IS_64BIT__))) \ + && !defined (ZMQ_DEFINED_STDINT)) + typedef __int8 int8_t; + typedef __int16 int16_t; + typedef __int32 int32_t; + typedef __int64 int64_t; + typedef unsigned __int8 uint8_t; + typedef unsigned __int16 uint16_t; + typedef unsigned __int32 uint32_t; + typedef unsigned __int64 uint64_t; +# endif + typedef uint32_t in_addr_t; +# if (!defined (PRId8)) +# define PRId8 "d" +# endif +# if (!defined (PRId16)) +# define PRId16 "d" +# endif +# if (!defined (PRId32)) +# define PRId32 "d" +# endif +# if (!defined (PRId64)) +# define PRId64 "I64d" +# endif +# if (!defined (PRIu8)) +# define PRIu8 "u" +# endif +# if (!defined (PRIu16)) +# define PRIu16 "u" +# endif +# if (!defined (PRIu32)) +# define PRIu32 "u" +# endif +# if (!defined (PRIu64)) +# define PRIu64 "I64u" +# endif +# if (!defined (va_copy)) + // MSVC does not support C99's va_copy so we use a regular assignment +# define va_copy(dest,src) (dest) = (src) +# endif +#elif (defined (__UTYPE_OSX)) + typedef unsigned long ulong; + typedef unsigned int uint; + // This fixes header-order dependence problem with some Linux versions +#elif (defined (__UTYPE_LINUX)) +# if (__STDC_VERSION__ >= 199901L && !defined (__USE_MISC)) + typedef unsigned int uint; +# endif +#endif + +//- Non-portable declaration specifiers ------------------------------------- + +// For thread-local storage +#if defined (__WINDOWS__) +# define CZMQ_THREADLS __declspec(thread) +#else +# define CZMQ_THREADLS __thread +#endif + +// Replacement for malloc() which asserts if we run out of heap, and +// which zeroes the allocated block. +static inline void * +safe_malloc (size_t size, const char *file, unsigned line) +{ +// printf ("%s:%u %08d\n", file, line, (int) size); + void *mem = calloc (1, size); + if (mem == NULL) { + fprintf (stderr, "FATAL ERROR at %s:%u\n", file, line); + fprintf (stderr, "OUT OF MEMORY (malloc returned NULL)\n"); + fflush (stderr); + abort (); + } + return mem; +} + +// Define _ZMALLOC_DEBUG if you need to trace memory leaks using e.g. mtrace, +// otherwise all allocations will claim to come from czmq_prelude.h. For best +// results, compile all classes so you see dangling object allocations. +// _ZMALLOC_PEDANTIC does the same thing, but its intention is to propagate +// out of memory condition back up the call stack. +#if defined _ZMALLOC_DEBUG || _ZMALLOC_PEDANTIC +# define zmalloc(size) calloc(1,(size)) +#else +# define zmalloc(size) safe_malloc((size), __FILE__, __LINE__) +#endif + +// GCC supports validating format strings for functions that act like printf +#if defined (__GNUC__) && (__GNUC__ >= 2) +# define CHECK_PRINTF(a) __attribute__((format (printf, a, a + 1))) +#else +# define CHECK_PRINTF(a) +#endif + +// Lets us write code that compiles both on Windows and normal platforms +#if !defined (__WINDOWS__) +typedef int SOCKET; +# define closesocket close +# define INVALID_SOCKET -1 +# define SOCKET_ERROR -1 +# define O_BINARY 0 +#endif + +//- Include non-portable header files based on platform.h ------------------- + +#if defined (HAVE_LINUX_WIRELESS_H) +# include +// This would normally come from net/if.h +unsigned int if_nametoindex (const char *ifname); +#else +# if defined (HAVE_NET_IF_H) +# include +# endif +# if defined (HAVE_NET_IF_MEDIA_H) +# include +# endif +#endif + +#if defined (__WINDOWS__) && !defined (HAVE_UUID) +# define HAVE_UUID 1 +#endif +#if defined (__UTYPE_OSX) && !defined (HAVE_UUID) +# define HAVE_UUID 1 +#endif +#if defined (HAVE_UUID) +# if defined (__UTYPE_FREEBSD) || defined (__UTYPE_NETBSD) +# include +# elif defined __UTYPE_HPUX +# include +# elif defined (__UNIX__) +# include +# endif +#endif + +// ZMQ compatibility macros + +#if ZMQ_VERSION_MAJOR == 4 +# define ZMQ_POLL_MSEC 1 // zmq_poll is msec + +#elif ZMQ_VERSION_MAJOR == 3 +# define ZMQ_POLL_MSEC 1 // zmq_poll is msec +# if ZMQ_VERSION_MINOR < 2 +# define zmq_ctx_new zmq_init +# endif +# define zmq_ctx_term zmq_term + +#elif ZMQ_VERSION_MAJOR == 2 +# define ZMQ_POLL_MSEC 1000 // zmq_poll is usec +# define zmq_sendmsg zmq_send // Smooth out 2.x changes +# define zmq_recvmsg zmq_recv +# define zmq_ctx_new zmq_init +# define zmq_ctx_term zmq_term +# define zmq_msg_send(m,s,f) zmq_sendmsg ((s),(m),(f)) +# define zmq_msg_recv(m,s,f) zmq_recvmsg ((s),(m),(f)) + // Older libzmq APIs may be missing some aspects of libzmq v3.0 +# ifndef ZMQ_ROUTER +# define ZMQ_ROUTER ZMQ_XREP +# endif +# ifndef ZMQ_DEALER +# define ZMQ_DEALER ZMQ_XREQ +# endif +# ifndef ZMQ_DONTWAIT +# define ZMQ_DONTWAIT ZMQ_NOBLOCK +# endif +# ifndef ZMQ_XSUB +# error "please upgrade your libzmq from http://zeromq.org" +# endif +# if ZMQ_VERSION_MINOR == 0 \ + || (ZMQ_VERSION_MINOR == 1 && ZMQ_VERSION_PATCH < 7) +# error "CZMQ requires at least libzmq/2.1.7 stable" +# endif +#endif + +#endif diff --git a/phonelibs/zmq/aarch64/include/zactor.h b/phonelibs/zmq/aarch64/include/zactor.h new file mode 100644 index 00000000000000..c865c65daf1efa --- /dev/null +++ b/phonelibs/zmq/aarch64/include/zactor.h @@ -0,0 +1,76 @@ +/* ========================================================================= + zactor - actor + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZACTOR_H_INCLUDED__ +#define __ZACTOR_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/zactor.api" to make changes. +// @interface +// This is a stable class, and may not change except for emergencies. It +// is provided in stable builds. +// Actors get a pipe and arguments from caller +typedef void (zactor_fn) ( + zsock_t *pipe, void *args); + +// Create a new actor passing arbitrary arguments reference. +CZMQ_EXPORT zactor_t * + zactor_new (zactor_fn task, void *args); + +// Destroy an actor. +CZMQ_EXPORT void + zactor_destroy (zactor_t **self_p); + +// Send a zmsg message to the actor, take ownership of the message +// and destroy when it has been sent. +CZMQ_EXPORT int + zactor_send (zactor_t *self, zmsg_t **msg_p); + +// Receive a zmsg message from the actor. Returns NULL if the actor +// was interrupted before the message could be received, or if there +// was a timeout on the actor. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zmsg_t * + zactor_recv (zactor_t *self); + +// Probe the supplied object, and report if it looks like a zactor_t. +CZMQ_EXPORT bool + zactor_is (void *self); + +// Probe the supplied reference. If it looks like a zactor_t instance, +// return the underlying libzmq actor handle; else if it looks like +// a libzmq actor handle, return the supplied value. +CZMQ_EXPORT void * + zactor_resolve (void *self); + +// Return the actor's zsock handle. Use this when you absolutely need +// to work with the zsock instance rather than the actor. +CZMQ_EXPORT zsock_t * + zactor_sock (zactor_t *self); + +// Self test of this class. +CZMQ_EXPORT void + zactor_test (bool verbose); + +// @end + + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/aarch64/include/zarmour.h b/phonelibs/zmq/aarch64/include/zarmour.h new file mode 100644 index 00000000000000..c7f299f7afe989 --- /dev/null +++ b/phonelibs/zmq/aarch64/include/zarmour.h @@ -0,0 +1,114 @@ +/* ========================================================================= + zarmour - armoured text encoding and decoding + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZARMOUR_H_INCLUDED__ +#define __ZARMOUR_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/zarmour.api" to make changes. +// @interface +// This is a stable class, and may not change except for emergencies. It +// is provided in stable builds. +#define ZARMOUR_MODE_BASE64_STD 0 // Standard base 64 +#define ZARMOUR_MODE_BASE64_URL 1 // URL and filename friendly base 64 +#define ZARMOUR_MODE_BASE32_STD 2 // Standard base 32 +#define ZARMOUR_MODE_BASE32_HEX 3 // Extended hex base 32 +#define ZARMOUR_MODE_BASE16 4 // Standard base 16 +#define ZARMOUR_MODE_Z85 5 // Z85 from ZeroMQ RFC 32 + +// Create a new zarmour +CZMQ_EXPORT zarmour_t * + zarmour_new (void); + +// Destroy the zarmour +CZMQ_EXPORT void + zarmour_destroy (zarmour_t **self_p); + +// Encode a stream of bytes into an armoured string. Returns the armoured +// string, or NULL if there was insufficient memory available to allocate +// a new string. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT char * + zarmour_encode (zarmour_t *self, const byte *data, size_t size); + +// Decode an armoured string into a chunk. The decoded output is +// null-terminated, so it may be treated as a string, if that's what +// it was prior to encoding. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zchunk_t * + zarmour_decode (zarmour_t *self, const char *data); + +// Get the mode property. +CZMQ_EXPORT int + zarmour_mode (zarmour_t *self); + +// Get printable string for mode. +CZMQ_EXPORT const char * + zarmour_mode_str (zarmour_t *self); + +// Set the mode property. +CZMQ_EXPORT void + zarmour_set_mode (zarmour_t *self, int mode); + +// Return true if padding is turned on. +CZMQ_EXPORT bool + zarmour_pad (zarmour_t *self); + +// Turn padding on or off. Default is on. +CZMQ_EXPORT void + zarmour_set_pad (zarmour_t *self, bool pad); + +// Get the padding character. +CZMQ_EXPORT char + zarmour_pad_char (zarmour_t *self); + +// Set the padding character. +CZMQ_EXPORT void + zarmour_set_pad_char (zarmour_t *self, char pad_char); + +// Return if splitting output into lines is turned on. Default is off. +CZMQ_EXPORT bool + zarmour_line_breaks (zarmour_t *self); + +// Turn splitting output into lines on or off. +CZMQ_EXPORT void + zarmour_set_line_breaks (zarmour_t *self, bool line_breaks); + +// Get the line length used for splitting lines. +CZMQ_EXPORT size_t + zarmour_line_length (zarmour_t *self); + +// Set the line length used for splitting lines. +CZMQ_EXPORT void + zarmour_set_line_length (zarmour_t *self, size_t line_length); + +// Print properties of object +CZMQ_EXPORT void + zarmour_print (zarmour_t *self); + +// Self test of this class. +CZMQ_EXPORT void + zarmour_test (bool verbose); + +// @end + + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/aarch64/include/zauth.h b/phonelibs/zmq/aarch64/include/zauth.h new file mode 100644 index 00000000000000..ca6bb913c8f5aa --- /dev/null +++ b/phonelibs/zmq/aarch64/include/zauth.h @@ -0,0 +1,100 @@ +/* ========================================================================= + zauth - authentication for ZeroMQ security mechanisms + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZAUTH_H_INCLUDED__ +#define __ZAUTH_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @interface +#define CURVE_ALLOW_ANY "*" + +// CZMQ v3 API (for use with zsock, not zsocket, which is deprecated). +// +// Create new zauth actor instance. This installs authentication on all +// zsock sockets. Until you add policies, all incoming NULL connections are +// allowed (classic ZeroMQ behaviour), and all PLAIN and CURVE connections +// are denied: +// +// zactor_t *auth = zactor_new (zauth, NULL); +// +// Destroy zauth instance. This removes authentication and allows all +// connections to pass, without authentication: +// +// zactor_destroy (&auth); +// +// Note that all zauth commands are synchronous, so your application always +// waits for a signal from the actor after each command. +// +// Enable verbose logging of commands and activity. Verbose logging can help +// debug non-trivial authentication policies: +// +// zstr_send (auth, "VERBOSE"); +// zsock_wait (auth); +// +// Allow (whitelist) a list of IP addresses. For NULL, all clients from +// these addresses will be accepted. For PLAIN and CURVE, they will be +// allowed to continue with authentication. You can call this method +// multiple times to whitelist more IP addresses. If you whitelist one +// or nmore addresses, any non-whitelisted addresses are treated as +// blacklisted: +// +// zstr_sendx (auth, "ALLOW", "127.0.0.1", "127.0.0.2", NULL); +// zsock_wait (auth); +// +// Deny (blacklist) a list of IP addresses. For all security mechanisms, +// this rejects the connection without any further authentication. Use +// either a whitelist, or a blacklist, not not both. If you define both +// a whitelist and a blacklist, only the whitelist takes effect: +// +// zstr_sendx (auth, "DENY", "192.168.0.1", "192.168.0.2", NULL); +// zsock_wait (auth); +// +// Configure PLAIN authentication using a plain-text password file. You can +// modify the password file at any time; zauth will reload it automatically +// if modified externally: +// +// zstr_sendx (auth, "PLAIN", filename, NULL); +// zsock_wait (auth); +// +// Configure CURVE authentication, using a directory that holds all public +// client certificates, i.e. their public keys. The certificates must be in +// zcert_save format. You can add and remove certificates in that directory +// at any time. To allow all client keys without checking, specify +// CURVE_ALLOW_ANY for the directory name: +// +// zstr_sendx (auth, "CURVE", directory, NULL); +// zsock_wait (auth); +// +// Configure GSSAPI authentication, using an underlying mechanism (usually +// Kerberos) to establish a secure context and perform mutual authentication: +// +// zstr_sendx (auth, "GSSAPI", NULL); +// zsock_wait (auth); +// +// This is the zauth constructor as a zactor_fn: +CZMQ_EXPORT void + zauth (zsock_t *pipe, void *certstore); + +// Selftest +CZMQ_EXPORT void + zauth_test (bool verbose); +// @end + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/aarch64/include/zauth_v2.h b/phonelibs/zmq/aarch64/include/zauth_v2.h new file mode 100644 index 00000000000000..bbbee86b03e62d --- /dev/null +++ b/phonelibs/zmq/aarch64/include/zauth_v2.h @@ -0,0 +1,88 @@ +/* ========================================================================= + zauth_v2 - authentication for ZeroMQ servers (deprecated) + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZAUTH_V2_H_INCLUDED__ +#define __ZAUTH_V2_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @interface +#ifndef CURVE_ALLOW_ANY +# define CURVE_ALLOW_ANY "*" +#endif + +// Constructor +// Install authentication for the specified context. Returns a new zauth +// object that you can use to configure authentication. Note that until you +// add policies, all incoming NULL connections are allowed (classic ZeroMQ +// behaviour), and all PLAIN and CURVE connections are denied. If there was +// an error during initialization, returns NULL. +CZMQ_EXPORT zauth_t * + zauth_new (zctx_t *ctx); + +// Destructor +CZMQ_EXPORT void + zauth_destroy (zauth_t **self_p); + +// Allow (whitelist) a single IP address. For NULL, all clients from this +// address will be accepted. For PLAIN and CURVE, they will be allowed to +// continue with authentication. You can call this method multiple times +// to whitelist multiple IP addresses. If you whitelist a single address, +// any non-whitelisted addresses are treated as blacklisted. +CZMQ_EXPORT void + zauth_allow (zauth_t *self, const char *address); + +// Deny (blacklist) a single IP address. For all security mechanisms, this +// rejects the connection without any further authentication. Use either a +// whitelist, or a blacklist, not not both. If you define both a whitelist +// and a blacklist, only the whitelist takes effect. +CZMQ_EXPORT void + zauth_deny (zauth_t *self, const char *address); + +// Configure PLAIN authentication for a given domain. PLAIN authentication +// uses a plain-text password file. To cover all domains, use "*". You can +// modify the password file at any time; it is reloaded automatically. +CZMQ_EXPORT void + zauth_configure_plain (zauth_t *self, const char *domain, const char *filename); + +// Configure CURVE authentication for a given domain. CURVE authentication +// uses a directory that holds all public client certificates, i.e. their +// public keys. The certificates must be in zcert_save () format. To cover +// all domains, use "*". You can add and remove certificates in that +// directory at any time. To allow all client keys without checking, specify +// CURVE_ALLOW_ANY for the location. +CZMQ_EXPORT void + zauth_configure_curve (zauth_t *self, const char *domain, const char *location); + +// Configure GSSAPI authentication for a given domain. GSSAPI authentication +// uses an underlying mechanism (usually Kerberos) to establish a secure +// context and perform mutual authentication. To cover all domains, use "*". +CZMQ_EXPORT void + zauth_configure_gssapi (zauth_t *self, char *domain); + +// Enable verbose tracing of commands and activity +CZMQ_EXPORT void + zauth_set_verbose (zauth_t *self, bool verbose); + +// Selftest +CZMQ_EXPORT void + zauth_v2_test (bool verbose); +// @end + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/aarch64/include/zbeacon.h b/phonelibs/zmq/aarch64/include/zbeacon.h new file mode 100644 index 00000000000000..78917e9577e40f --- /dev/null +++ b/phonelibs/zmq/aarch64/include/zbeacon.h @@ -0,0 +1,86 @@ +/* ========================================================================= + zbeacon - LAN discovery and presence + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZBEACON_H_INCLUDED__ +#define __ZBEACON_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @interface +// Create new zbeacon actor instance: +// +// zactor_t *beacon = zactor_new (zbeacon, NULL); +// +// Destroy zbeacon instance: +// +// zactor_destroy (&beacon); +// +// Enable verbose logging of commands and activity: +// +// zstr_send (beacon, "VERBOSE"); +// +// Configure beacon to run on specified UDP port, and return the name of +// the host, which can be used as endpoint for incoming connections. To +// force the beacon to operate on a given interface, set the environment +// variable ZSYS_INTERFACE, or call zsys_set_interface() before creating +// the beacon. If the system does not support UDP broadcasts (lacking a +// workable interface), returns an empty hostname: +// +// // Pictures: 's' = C string, 'i' = int +// zsock_send (beacon, "si", "CONFIGURE", port_number); +// char *hostname = zstr_recv (beacon); +// +// Start broadcasting a beacon at a specified interval in msec. The beacon +// data can be at most UDP_FRAME_MAX bytes; this constant is defined in +// zsys.h to be 255: +// +// // Pictures: 'b' = byte * data + size_t size +// zsock_send (beacon, "sbi", "PUBLISH", data, size, interval); +// +// Stop broadcasting the beacon: +// +// zstr_sendx (beacon, "SILENCE", NULL); +// +// Start listening to beacons from peers. The filter is used to do a prefix +// match on received beacons, to remove junk. Note that any received data +// that is identical to our broadcast beacon_data is discarded in any case. +// If the filter size is zero, we get all peer beacons: +// +// zsock_send (beacon, "sb", "SUBSCRIBE", filter_data, filter_size); +// +// Stop listening to other peers +// +// zstr_sendx (beacon, "UNSUBSCRIBE", NULL); +// +// Receive next beacon from a peer. Received beacons are always a 2-frame +// message containing the ipaddress of the sender, and then the binary +// beacon data as published by the sender: +// +// zmsg_t *msg = zmsg_recv (beacon); +// +// This is the zbeacon constructor as a zactor_fn: +CZMQ_EXPORT void + zbeacon (zsock_t *pipe, void *unused); + +// Self test of this class +CZMQ_EXPORT void + zbeacon_test (bool verbose); +// @end + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/aarch64/include/zbeacon_v2.h b/phonelibs/zmq/aarch64/include/zbeacon_v2.h new file mode 100644 index 00000000000000..8e8f3b4cde9967 --- /dev/null +++ b/phonelibs/zmq/aarch64/include/zbeacon_v2.h @@ -0,0 +1,75 @@ +/* ========================================================================= + zbeacon - LAN discovery and presence (deprecated) + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZBEACON_V2_H_INCLUDED__ +#define __ZBEACON_V2_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @interface +// Create a new beacon on a certain UDP port. If the system does not +// support UDP broadcasts (lacking a useful interface), returns NULL. +// To force the beacon to operate on a given port, set the environment +// variable ZSYS_INTERFACE, or call zsys_set_interface() beforehand. +// If you are using the new zsock API then pass NULL as the ctx here. +CZMQ_EXPORT zbeacon_t * + zbeacon_new (zctx_t *ctx, int port_nbr); + +// Destroy a beacon +CZMQ_EXPORT void + zbeacon_destroy (zbeacon_t **self_p); + +// Return our own IP address as printable string +CZMQ_EXPORT char * + zbeacon_hostname (zbeacon_t *self); + +// Set broadcast interval in milliseconds (default is 1000 msec) +CZMQ_EXPORT void + zbeacon_set_interval (zbeacon_t *self, int interval); + +// Filter out any beacon that looks exactly like ours +CZMQ_EXPORT void + zbeacon_noecho (zbeacon_t *self); + +// Start broadcasting beacon to peers at the specified interval +CZMQ_EXPORT void + zbeacon_publish (zbeacon_t *self, byte *transmit, size_t size); + +// Stop broadcasting beacons +CZMQ_EXPORT void + zbeacon_silence (zbeacon_t *self); + +// Start listening to other peers; zero-sized filter means get everything +CZMQ_EXPORT void + zbeacon_subscribe (zbeacon_t *self, byte *filter, size_t size); + +// Stop listening to other peers +CZMQ_EXPORT void + zbeacon_unsubscribe (zbeacon_t *self); + +// Get beacon ZeroMQ socket, for polling or receiving messages +CZMQ_EXPORT void * + zbeacon_socket (zbeacon_t *self); + +// Self test of this class +CZMQ_EXPORT void + zbeacon_v2_test (bool verbose); +// @end + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/aarch64/include/zcert.h b/phonelibs/zmq/aarch64/include/zcert.h new file mode 100644 index 00000000000000..495b579cda9317 --- /dev/null +++ b/phonelibs/zmq/aarch64/include/zcert.h @@ -0,0 +1,139 @@ +/* ========================================================================= + zcert - work with CURVE security certificates + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZCERT_H_INCLUDED__ +#define __ZCERT_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/zcert.api" to make changes. +// @interface +// This is a stable class, and may not change except for emergencies. It +// is provided in stable builds. +// This class has draft methods, which may change over time. They are not +// in stable releases, by default. Use --enable-drafts to enable. +// This class has legacy methods, which will be removed over time. You +// should not use them, and migrate any code that is still using them. +// Create and initialize a new certificate in memory +CZMQ_EXPORT zcert_t * + zcert_new (void); + +// Accepts public/secret key pair from caller +CZMQ_EXPORT zcert_t * + zcert_new_from (const byte *public_key, const byte *secret_key); + +// Load certificate from file +CZMQ_EXPORT zcert_t * + zcert_load (const char *filename); + +// Destroy a certificate in memory +CZMQ_EXPORT void + zcert_destroy (zcert_t **self_p); + +// Return public part of key pair as 32-byte binary string +CZMQ_EXPORT const byte * + zcert_public_key (zcert_t *self); + +// Return secret part of key pair as 32-byte binary string +CZMQ_EXPORT const byte * + zcert_secret_key (zcert_t *self); + +// Return public part of key pair as Z85 armored string +CZMQ_EXPORT const char * + zcert_public_txt (zcert_t *self); + +// Return secret part of key pair as Z85 armored string +CZMQ_EXPORT const char * + zcert_secret_txt (zcert_t *self); + +// Set certificate metadata from formatted string. +CZMQ_EXPORT void + zcert_set_meta (zcert_t *self, const char *name, const char *format, ...); + +// Get metadata value from certificate; if the metadata value doesn't +// exist, returns NULL. +CZMQ_EXPORT const char * + zcert_meta (zcert_t *self, const char *name); + +// Get list of metadata fields from certificate. Caller is responsible for +// destroying list. Caller should not modify the values of list items. +CZMQ_EXPORT zlist_t * + zcert_meta_keys (zcert_t *self); + +// Save full certificate (public + secret) to file for persistent storage +// This creates one public file and one secret file (filename + "_secret"). +CZMQ_EXPORT int + zcert_save (zcert_t *self, const char *filename); + +// Save public certificate only to file for persistent storage +CZMQ_EXPORT int + zcert_save_public (zcert_t *self, const char *filename); + +// Save secret certificate only to file for persistent storage +CZMQ_EXPORT int + zcert_save_secret (zcert_t *self, const char *filename); + +// Apply certificate to socket, i.e. use for CURVE security on socket. +// If certificate was loaded from public file, the secret key will be +// undefined, and this certificate will not work successfully. +CZMQ_EXPORT void + zcert_apply (zcert_t *self, void *socket); + +// Return copy of certificate; if certificate is NULL or we exhausted +// heap memory, returns NULL. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zcert_t * + zcert_dup (zcert_t *self); + +// Return true if two certificates have the same keys +CZMQ_EXPORT bool + zcert_eq (zcert_t *self, zcert_t *compare); + +// Print certificate contents to stdout +CZMQ_EXPORT void + zcert_print (zcert_t *self); + +// *** Deprecated method, slated for removal: avoid using it *** +// Print certificate contents to open stream. This method is deprecated +// and you should use the print method. +CZMQ_EXPORT void + zcert_fprint (zcert_t *self, FILE *file); + +// Self test of this class +CZMQ_EXPORT void + zcert_test (bool verbose); + +#ifdef CZMQ_BUILD_DRAFT_API +// *** Draft method, for development use, may change without warning *** +// Unset certificate metadata. +CZMQ_EXPORT void + zcert_unset_meta (zcert_t *self, const char *name); + +#endif // CZMQ_BUILD_DRAFT_API +// @ignore +CZMQ_EXPORT void + zcert_set_meta (zcert_t *self, const char *name, const char *format, ...) CHECK_PRINTF (3); +// @end + + +#ifdef __cplusplus +} +#endif + +// Deprecated method aliases +#define zcert_dump(s) zcert_print(s) + +#endif diff --git a/phonelibs/zmq/aarch64/include/zcertstore.h b/phonelibs/zmq/aarch64/include/zcertstore.h new file mode 100644 index 00000000000000..c7f93c5a7d4604 --- /dev/null +++ b/phonelibs/zmq/aarch64/include/zcertstore.h @@ -0,0 +1,100 @@ +/* ========================================================================= + zcertstore - work with CURVE security certificate stores + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZCERTSTORE_H_INCLUDED__ +#define __ZCERTSTORE_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/zcertstore.api" to make changes. +// @interface +// This is a stable class, and may not change except for emergencies. It +// is provided in stable builds. +// This class has draft methods, which may change over time. They are not +// in stable releases, by default. Use --enable-drafts to enable. +// This class has legacy methods, which will be removed over time. You +// should not use them, and migrate any code that is still using them. +// Create a new certificate store from a disk directory, loading and +// indexing all certificates in that location. The directory itself may be +// absent, and created later, or modified at any time. The certificate store +// is automatically refreshed on any zcertstore_lookup() call. If the +// location is specified as NULL, creates a pure-memory store, which you +// can work with by inserting certificates at runtime. +CZMQ_EXPORT zcertstore_t * + zcertstore_new (const char *location); + +// Destroy a certificate store object in memory. Does not affect anything +// stored on disk. +CZMQ_EXPORT void + zcertstore_destroy (zcertstore_t **self_p); + +// Look up certificate by public key, returns zcert_t object if found, +// else returns NULL. The public key is provided in Z85 text format. +CZMQ_EXPORT zcert_t * + zcertstore_lookup (zcertstore_t *self, const char *public_key); + +// Insert certificate into certificate store in memory. Note that this +// does not save the certificate to disk. To do that, use zcert_save() +// directly on the certificate. Takes ownership of zcert_t object. +CZMQ_EXPORT void + zcertstore_insert (zcertstore_t *self, zcert_t **cert_p); + +// Print list of certificates in store to logging facility +CZMQ_EXPORT void + zcertstore_print (zcertstore_t *self); + +// *** Deprecated method, slated for removal: avoid using it *** +// Print list of certificates in store to open stream. This method is +// deprecated, and you should use the print method. +CZMQ_EXPORT void + zcertstore_fprint (zcertstore_t *self, FILE *file); + +// Self test of this class +CZMQ_EXPORT void + zcertstore_test (bool verbose); + +#ifdef CZMQ_BUILD_DRAFT_API +// Loaders retrieve certificates from an arbitrary source. +typedef void (zcertstore_loader) ( + zcertstore_t *self); + +// Destructor for loader state. +typedef void (zcertstore_destructor) ( + void **self_p); + +// *** Draft method, for development use, may change without warning *** +// Override the default disk loader with a custom loader fn. +CZMQ_EXPORT void + zcertstore_set_loader (zcertstore_t *self, zcertstore_loader loader, zcertstore_destructor destructor, void *state); + +// *** Draft method, for development use, may change without warning *** +// Empty certificate hashtable. This wrapper exists to be friendly to bindings, +// which don't usually have access to struct internals. +CZMQ_EXPORT void + zcertstore_empty (zcertstore_t *self); + +#endif // CZMQ_BUILD_DRAFT_API +// @end + + +#ifdef __cplusplus +} +#endif + +// Deprecated method aliases +#define zcertstore_dump(s) zcertstore_print(s) + +#endif diff --git a/phonelibs/zmq/aarch64/include/zchunk.h b/phonelibs/zmq/aarch64/include/zchunk.h new file mode 100644 index 00000000000000..56f29b161a37e5 --- /dev/null +++ b/phonelibs/zmq/aarch64/include/zchunk.h @@ -0,0 +1,163 @@ +/* ========================================================================= + zchunk - work with memory chunks + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZCHUNK_H_INCLUDED__ +#define __ZCHUNK_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/zchunk.api" to make changes. +// @interface +// This is a stable class, and may not change except for emergencies. It +// is provided in stable builds. +// Create a new chunk of the specified size. If you specify the data, it +// is copied into the chunk. If you do not specify the data, the chunk is +// allocated and left empty, and you can then add data using zchunk_append. +CZMQ_EXPORT zchunk_t * + zchunk_new (const void *data, size_t size); + +// Destroy a chunk +CZMQ_EXPORT void + zchunk_destroy (zchunk_t **self_p); + +// Resizes chunk max_size as requested; chunk_cur size is set to zero +CZMQ_EXPORT void + zchunk_resize (zchunk_t *self, size_t size); + +// Return chunk cur size +CZMQ_EXPORT size_t + zchunk_size (zchunk_t *self); + +// Return chunk max size +CZMQ_EXPORT size_t + zchunk_max_size (zchunk_t *self); + +// Return chunk data +CZMQ_EXPORT byte * + zchunk_data (zchunk_t *self); + +// Set chunk data from user-supplied data; truncate if too large. Data may +// be null. Returns actual size of chunk +CZMQ_EXPORT size_t + zchunk_set (zchunk_t *self, const void *data, size_t size); + +// Fill chunk data from user-supplied octet +CZMQ_EXPORT size_t + zchunk_fill (zchunk_t *self, byte filler, size_t size); + +// Append user-supplied data to chunk, return resulting chunk size. If the +// data would exceeded the available space, it is truncated. If you want to +// grow the chunk to accommodate new data, use the zchunk_extend method. +CZMQ_EXPORT size_t + zchunk_append (zchunk_t *self, const void *data, size_t size); + +// Append user-supplied data to chunk, return resulting chunk size. If the +// data would exceeded the available space, the chunk grows in size. +CZMQ_EXPORT size_t + zchunk_extend (zchunk_t *self, const void *data, size_t size); + +// Copy as much data from 'source' into the chunk as possible; returns the +// new size of chunk. If all data from 'source' is used, returns exhausted +// on the source chunk. Source can be consumed as many times as needed until +// it is exhausted. If source was already exhausted, does not change chunk. +CZMQ_EXPORT size_t + zchunk_consume (zchunk_t *self, zchunk_t *source); + +// Returns true if the chunk was exhausted by consume methods, or if the +// chunk has a size of zero. +CZMQ_EXPORT bool + zchunk_exhausted (zchunk_t *self); + +// Read chunk from an open file descriptor +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zchunk_t * + zchunk_read (FILE *handle, size_t bytes); + +// Write chunk to an open file descriptor +CZMQ_EXPORT int + zchunk_write (zchunk_t *self, FILE *handle); + +// Try to slurp an entire file into a chunk. Will read up to maxsize of +// the file. If maxsize is 0, will attempt to read the entire file and +// fail with an assertion if that cannot fit into memory. Returns a new +// chunk containing the file data, or NULL if the file could not be read. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zchunk_t * + zchunk_slurp (const char *filename, size_t maxsize); + +// Create copy of chunk, as new chunk object. Returns a fresh zchunk_t +// object, or null if there was not enough heap memory. If chunk is null, +// returns null. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zchunk_t * + zchunk_dup (zchunk_t *self); + +// Return chunk data encoded as printable hex string. Caller must free +// string when finished with it. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT char * + zchunk_strhex (zchunk_t *self); + +// Return chunk data copied into freshly allocated string +// Caller must free string when finished with it. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT char * + zchunk_strdup (zchunk_t *self); + +// Return TRUE if chunk body is equal to string, excluding terminator +CZMQ_EXPORT bool + zchunk_streq (zchunk_t *self, const char *string); + +// Transform zchunk into a zframe that can be sent in a message. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zframe_t * + zchunk_pack (zchunk_t *self); + +// Transform a zframe into a zchunk. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zchunk_t * + zchunk_unpack (zframe_t *frame); + +// Calculate SHA1 digest for chunk, using zdigest class. +CZMQ_EXPORT const char * + zchunk_digest (zchunk_t *self); + +// Dump chunk to FILE stream, for debugging and tracing. +CZMQ_EXPORT void + zchunk_fprint (zchunk_t *self, FILE *file); + +// Dump message to stderr, for debugging and tracing. +// See zchunk_fprint for details +CZMQ_EXPORT void + zchunk_print (zchunk_t *self); + +// Probe the supplied object, and report if it looks like a zchunk_t. +CZMQ_EXPORT bool + zchunk_is (void *self); + +// Self test of this class. +CZMQ_EXPORT void + zchunk_test (bool verbose); + +// @end + + +#ifdef __cplusplus +} +#endif + +#endif + diff --git a/phonelibs/zmq/aarch64/include/zclock.h b/phonelibs/zmq/aarch64/include/zclock.h new file mode 100644 index 00000000000000..eb064162c4722a --- /dev/null +++ b/phonelibs/zmq/aarch64/include/zclock.h @@ -0,0 +1,73 @@ +/* ========================================================================= + zclock - millisecond clocks and delays + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZCLOCK_H_INCLUDED__ +#define __ZCLOCK_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/zclock.api" to make changes. +// @interface +// This is a stable class, and may not change except for emergencies. It +// is provided in stable builds. +// Sleep for a number of milliseconds +CZMQ_EXPORT void + zclock_sleep (int msecs); + +// Return current system clock as milliseconds. Note that this clock can +// jump backwards (if the system clock is changed) so is unsafe to use for +// timers and time offsets. Use zclock_mono for that instead. +CZMQ_EXPORT int64_t + zclock_time (void); + +// Return current monotonic clock in milliseconds. Use this when you compute +// time offsets. The monotonic clock is not affected by system changes and +// so will never be reset backwards, unlike a system clock. +CZMQ_EXPORT int64_t + zclock_mono (void); + +// Return current monotonic clock in microseconds. Use this when you compute +// time offsets. The monotonic clock is not affected by system changes and +// so will never be reset backwards, unlike a system clock. +CZMQ_EXPORT int64_t + zclock_usecs (void); + +// Return formatted date/time as fresh string. Free using zstr_free(). +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT char * + zclock_timestr (void); + +// Self test of this class. +CZMQ_EXPORT void + zclock_test (bool verbose); + +// @end + + +// DEPRECATED in favor of zsys logging, see issue #519 +// Print formatted string to stdout, prefixed by date/time and +// terminated with a newline. +CZMQ_EXPORT void + zclock_log (const char *format, ...); + +// Compiler hints +CZMQ_EXPORT void zclock_log (const char *format, ...) CHECK_PRINTF (1); + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/aarch64/include/zconfig.h b/phonelibs/zmq/aarch64/include/zconfig.h new file mode 100644 index 00000000000000..4ec4e1c81f03e1 --- /dev/null +++ b/phonelibs/zmq/aarch64/include/zconfig.h @@ -0,0 +1,194 @@ +/* ========================================================================= + zconfig - work with config files written in rfc.zeromq.org/spec:4/ZPL. + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZCONFIG_H_INCLUDED__ +#define __ZCONFIG_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/zconfig.api" to make changes. +// @interface +// This is a stable class, and may not change except for emergencies. It +// is provided in stable builds. +// +typedef int (zconfig_fct) ( + zconfig_t *self, void *arg, int level); + +// Create new config item +CZMQ_EXPORT zconfig_t * + zconfig_new (const char *name, zconfig_t *parent); + +// Load a config tree from a specified ZPL text file; returns a zconfig_t +// reference for the root, if the file exists and is readable. Returns NULL +// if the file does not exist. +CZMQ_EXPORT zconfig_t * + zconfig_load (const char *filename); + +// Equivalent to zconfig_load, taking a format string instead of a fixed +// filename. +CZMQ_EXPORT zconfig_t * + zconfig_loadf (const char *format, ...); + +// Destroy a config item and all its children +CZMQ_EXPORT void + zconfig_destroy (zconfig_t **self_p); + +// Return name of config item +CZMQ_EXPORT char * + zconfig_name (zconfig_t *self); + +// Return value of config item +CZMQ_EXPORT char * + zconfig_value (zconfig_t *self); + +// Insert or update configuration key with value +CZMQ_EXPORT void + zconfig_put (zconfig_t *self, const char *path, const char *value); + +// Equivalent to zconfig_put, accepting a format specifier and variable +// argument list, instead of a single string value. +CZMQ_EXPORT void + zconfig_putf (zconfig_t *self, const char *path, const char *format, ...); + +// Get value for config item into a string value; leading slash is optional +// and ignored. +CZMQ_EXPORT char * + zconfig_get (zconfig_t *self, const char *path, const char *default_value); + +// Set config item name, name may be NULL +CZMQ_EXPORT void + zconfig_set_name (zconfig_t *self, const char *name); + +// Set new value for config item. The new value may be a string, a printf +// format, or NULL. Note that if string may possibly contain '%', or if it +// comes from an insecure source, you must use '%s' as the format, followed +// by the string. +CZMQ_EXPORT void + zconfig_set_value (zconfig_t *self, const char *format, ...); + +// Find our first child, if any +CZMQ_EXPORT zconfig_t * + zconfig_child (zconfig_t *self); + +// Find our first sibling, if any +CZMQ_EXPORT zconfig_t * + zconfig_next (zconfig_t *self); + +// Find a config item along a path; leading slash is optional and ignored. +CZMQ_EXPORT zconfig_t * + zconfig_locate (zconfig_t *self, const char *path); + +// Locate the last config item at a specified depth +CZMQ_EXPORT zconfig_t * + zconfig_at_depth (zconfig_t *self, int level); + +// Execute a callback for each config item in the tree; returns zero if +// successful, else -1. +CZMQ_EXPORT int + zconfig_execute (zconfig_t *self, zconfig_fct handler, void *arg); + +// Add comment to config item before saving to disk. You can add as many +// comment lines as you like. If you use a null format, all comments are +// deleted. +CZMQ_EXPORT void + zconfig_set_comment (zconfig_t *self, const char *format, ...); + +// Return comments of config item, as zlist. +CZMQ_EXPORT zlist_t * + zconfig_comments (zconfig_t *self); + +// Save a config tree to a specified ZPL text file, where a filename +// "-" means dump to standard output. +CZMQ_EXPORT int + zconfig_save (zconfig_t *self, const char *filename); + +// Equivalent to zconfig_save, taking a format string instead of a fixed +// filename. +CZMQ_EXPORT int + zconfig_savef (zconfig_t *self, const char *format, ...); + +// Report filename used during zconfig_load, or NULL if none +CZMQ_EXPORT const char * + zconfig_filename (zconfig_t *self); + +// Reload config tree from same file that it was previously loaded from. +// Returns 0 if OK, -1 if there was an error (and then does not change +// existing data). +CZMQ_EXPORT int + zconfig_reload (zconfig_t **self_p); + +// Load a config tree from a memory chunk +CZMQ_EXPORT zconfig_t * + zconfig_chunk_load (zchunk_t *chunk); + +// Save a config tree to a new memory chunk +CZMQ_EXPORT zchunk_t * + zconfig_chunk_save (zconfig_t *self); + +// Load a config tree from a null-terminated string +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zconfig_t * + zconfig_str_load (const char *string); + +// Save a config tree to a new null terminated string +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT char * + zconfig_str_save (zconfig_t *self); + +// Return true if a configuration tree was loaded from a file and that +// file has changed in since the tree was loaded. +CZMQ_EXPORT bool + zconfig_has_changed (zconfig_t *self); + +// Print the config file to open stream +CZMQ_EXPORT void + zconfig_fprint (zconfig_t *self, FILE *file); + +// Print properties of object +CZMQ_EXPORT void + zconfig_print (zconfig_t *self); + +// Self test of this class +CZMQ_EXPORT void + zconfig_test (bool verbose); + +// @ignore +CZMQ_EXPORT void + zconfig_putf (zconfig_t *self, const char *path, const char *format, ...) CHECK_PRINTF (3); +CZMQ_EXPORT void + zconfig_set_value (zconfig_t *self, const char *format, ...) CHECK_PRINTF (2); +CZMQ_EXPORT void + zconfig_set_comment (zconfig_t *self, const char *format, ...) CHECK_PRINTF (2); +CZMQ_EXPORT int + zconfig_savef (zconfig_t *self, const char *format, ...) CHECK_PRINTF (2); +// @end + +// Self test of this class +CZMQ_EXPORT void + zconfig_test (bool verbose); + +// Compiler hints +CZMQ_EXPORT void zconfig_set_value (zconfig_t *self, const char *format, ...) CHECK_PRINTF (2); + +#ifdef __cplusplus +} +#endif + +// Deprecated method aliases +#define zconfig_dump(s) zconfig_print(s) +#define zconfig_resolve(s,p,d) zconfig_get((s),(p),(d)) + +#endif diff --git a/phonelibs/zmq/aarch64/include/zctx.h b/phonelibs/zmq/aarch64/include/zctx.h new file mode 100644 index 00000000000000..88898410dc8e99 --- /dev/null +++ b/phonelibs/zmq/aarch64/include/zctx.h @@ -0,0 +1,107 @@ +/* ========================================================================= + zctx - working with 0MQ contexts + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZCTX_H_INCLUDED__ +#define __ZCTX_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + + +// @interface +// Create new context, returns context object, replaces zmq_init +CZMQ_EXPORT zctx_t * + zctx_new (void); + +// Destroy context and all sockets in it, replaces zmq_term +CZMQ_EXPORT void + zctx_destroy (zctx_t **self_p); + +// Create new shadow context, returns context object +CZMQ_EXPORT zctx_t * + zctx_shadow (zctx_t *self); +// @end + +// Create a new context by shadowing a plain zmq context +CZMQ_EXPORT zctx_t * +zctx_shadow_zmq_ctx (void *zmqctx); + +// @interface +// Raise default I/O threads from 1, for crazy heavy applications +// The rule of thumb is one I/O thread per gigabyte of traffic in +// or out. Call this method before creating any sockets on the context, +// or calling zctx_shadow, or the setting will have no effect. +CZMQ_EXPORT void + zctx_set_iothreads (zctx_t *self, int iothreads); + +// Set msecs to flush sockets when closing them, see the ZMQ_LINGER +// man page section for more details. By default, set to zero, so +// any in-transit messages are discarded when you destroy a socket or +// a context. +CZMQ_EXPORT void + zctx_set_linger (zctx_t *self, int linger); + +// Set initial high-water mark for inter-thread pipe sockets. Note that +// this setting is separate from the default for normal sockets. You +// should change the default for pipe sockets *with care*. Too low values +// will cause blocked threads, and an infinite setting can cause memory +// exhaustion. The default, no matter the underlying ZeroMQ version, is +// 1,000. +CZMQ_EXPORT void + zctx_set_pipehwm (zctx_t *self, int pipehwm); + +// Set initial send HWM for all new normal sockets created in context. +// You can set this per-socket after the socket is created. +// The default, no matter the underlying ZeroMQ version, is 1,000. +CZMQ_EXPORT void + zctx_set_sndhwm (zctx_t *self, int sndhwm); + +// Set initial receive HWM for all new normal sockets created in context. +// You can set this per-socket after the socket is created. +// The default, no matter the underlying ZeroMQ version, is 1,000. +CZMQ_EXPORT void + zctx_set_rcvhwm (zctx_t *self, int rcvhwm); + +// Return low-level 0MQ context object, will be NULL before first socket +// is created. Use with care. +CZMQ_EXPORT void * + zctx_underlying (zctx_t *self); + +// Self test of this class +CZMQ_EXPORT void + zctx_test (bool verbose); +// @end + +// Create socket within this context, for CZMQ use only +void * + zctx__socket_new (zctx_t *self, int type); + +// Create pipe socket within this context, for CZMQ use only +void * + zctx__socket_pipe (zctx_t *self); + +// Destroy socket within this context, for CZMQ use only +void + zctx__socket_destroy (zctx_t *self, void *socket); + +// Initialize the low-level 0MQ context object, for CZMQ use only +void + zctx__initialize_underlying(zctx_t *self); +// @end + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/aarch64/include/zdigest.h b/phonelibs/zmq/aarch64/include/zdigest.h new file mode 100644 index 00000000000000..def9e860537094 --- /dev/null +++ b/phonelibs/zmq/aarch64/include/zdigest.h @@ -0,0 +1,65 @@ +/* ========================================================================= + zdigest - provides hashing functions (SHA-1 at present) + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZDIGEST_H_INCLUDED__ +#define __ZDIGEST_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/zdigest.api" to make changes. +// @interface +// This is a stable class, and may not change except for emergencies. It +// is provided in stable builds. +// Constructor - creates new digest object, which you use to build up a +// digest by repeatedly calling zdigest_update() on chunks of data. +CZMQ_EXPORT zdigest_t * + zdigest_new (void); + +// Destroy a digest object +CZMQ_EXPORT void + zdigest_destroy (zdigest_t **self_p); + +// Add buffer into digest calculation +CZMQ_EXPORT void + zdigest_update (zdigest_t *self, const byte *buffer, size_t length); + +// Return final digest hash data. If built without crypto support, +// returns NULL. +CZMQ_EXPORT const byte * + zdigest_data (zdigest_t *self); + +// Return final digest hash size +CZMQ_EXPORT size_t + zdigest_size (zdigest_t *self); + +// Return digest as printable hex string; caller should not modify nor +// free this string. After calling this, you may not use zdigest_update() +// on the same digest. If built without crypto support, returns NULL. +CZMQ_EXPORT char * + zdigest_string (zdigest_t *self); + +// Self test of this class. +CZMQ_EXPORT void + zdigest_test (bool verbose); + +// @end + + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/aarch64/include/zdir.h b/phonelibs/zmq/aarch64/include/zdir.h new file mode 100644 index 00000000000000..6c5551b57eead4 --- /dev/null +++ b/phonelibs/zmq/aarch64/include/zdir.h @@ -0,0 +1,149 @@ +/* ========================================================================= + zdir - work with file-system directories + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZDIR_H_INCLUDED__ +#define __ZDIR_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/zdir.api" to make changes. +// @interface +// This is a stable class, and may not change except for emergencies. It +// is provided in stable builds. +// Create a new directory item that loads in the full tree of the specified +// path, optionally located under some parent path. If parent is "-", then +// loads only the top-level directory, and does not use parent as a path. +CZMQ_EXPORT zdir_t * + zdir_new (const char *path, const char *parent); + +// Destroy a directory tree and all children it contains. +CZMQ_EXPORT void + zdir_destroy (zdir_t **self_p); + +// Return directory path +CZMQ_EXPORT const char * + zdir_path (zdir_t *self); + +// Return last modification time for directory. +CZMQ_EXPORT time_t + zdir_modified (zdir_t *self); + +// Return total hierarchy size, in bytes of data contained in all files +// in the directory tree. +CZMQ_EXPORT off_t + zdir_cursize (zdir_t *self); + +// Return directory count +CZMQ_EXPORT size_t + zdir_count (zdir_t *self); + +// Returns a sorted list of zfile objects; Each entry in the list is a pointer +// to a zfile_t item already allocated in the zdir tree. Do not destroy the +// original zdir tree until you are done with this list. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zlist_t * + zdir_list (zdir_t *self); + +// Remove directory, optionally including all files that it contains, at +// all levels. If force is false, will only remove the directory if empty. +// If force is true, will remove all files and all subdirectories. +CZMQ_EXPORT void + zdir_remove (zdir_t *self, bool force); + +// Calculate differences between two versions of a directory tree. +// Returns a list of zdir_patch_t patches. Either older or newer may +// be null, indicating the directory is empty/absent. If alias is set, +// generates virtual filename (minus path, plus alias). +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zlist_t * + zdir_diff (zdir_t *older, zdir_t *newer, const char *alias); + +// Return full contents of directory as a zdir_patch list. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zlist_t * + zdir_resync (zdir_t *self, const char *alias); + +// Load directory cache; returns a hash table containing the SHA-1 digests +// of every file in the tree. The cache is saved between runs in .cache. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zhash_t * + zdir_cache (zdir_t *self); + +// Print contents of directory to open stream +CZMQ_EXPORT void + zdir_fprint (zdir_t *self, FILE *file, int indent); + +// Print contents of directory to stdout +CZMQ_EXPORT void + zdir_print (zdir_t *self, int indent); + +// Create a new zdir_watch actor instance: +// +// zactor_t *watch = zactor_new (zdir_watch, NULL); +// +// Destroy zdir_watch instance: +// +// zactor_destroy (&watch); +// +// Enable verbose logging of commands and activity: +// +// zstr_send (watch, "VERBOSE"); +// +// Subscribe to changes to a directory path: +// +// zsock_send (watch, "ss", "SUBSCRIBE", "directory_path"); +// +// Unsubscribe from changes to a directory path: +// +// zsock_send (watch, "ss", "UNSUBSCRIBE", "directory_path"); +// +// Receive directory changes: +// zsock_recv (watch, "sp", &path, &patches); +// +// // Delete the received data. +// free (path); +// zlist_destroy (&patches); +CZMQ_EXPORT void + zdir_watch (zsock_t *pipe, void *unused); + +// Self test of this class. +CZMQ_EXPORT void + zdir_test (bool verbose); + +// @end + + +// Returns a sorted array of zfile objects; returns a single block of memory, +// that you destroy by calling zstr_free(). Each entry in the array is a pointer +// to a zfile_t item already allocated in the zdir tree. The array ends with +// a null pointer. Do not destroy the original zdir tree until you are done +// with this array. +CZMQ_EXPORT zfile_t ** + zdir_flatten (zdir_t *self); + +// Free a provided string, and nullify the parent pointer. Safe to call on +// a null pointer. +CZMQ_EXPORT void + zdir_flatten_free (zfile_t ***files_p); + +#ifdef __cplusplus +} +#endif + +// Deprecated method aliases +#define zdir_dump(s,i) zdir_print(s,i) + +#endif diff --git a/phonelibs/zmq/aarch64/include/zdir_patch.h b/phonelibs/zmq/aarch64/include/zdir_patch.h new file mode 100644 index 00000000000000..8d15b9aeb40c42 --- /dev/null +++ b/phonelibs/zmq/aarch64/include/zdir_patch.h @@ -0,0 +1,82 @@ +/* ========================================================================= + zdir_patch - work with directory patches + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZDIR_PATCH_H_INCLUDED__ +#define __ZDIR_PATCH_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// un-namespaced enumeration values +#define patch_create ZDIR_PATCH_CREATE +#define patch_delete ZDIR_PATCH_DELETE + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/zdir_patch.api" to make changes. +// @interface +// This is a stable class, and may not change except for emergencies. It +// is provided in stable builds. +#define ZDIR_PATCH_CREATE 1 // Creates a new file +#define ZDIR_PATCH_DELETE 2 // Delete a file + +// Create new patch +CZMQ_EXPORT zdir_patch_t * + zdir_patch_new (const char *path, zfile_t *file, int op, const char *alias); + +// Destroy a patch +CZMQ_EXPORT void + zdir_patch_destroy (zdir_patch_t **self_p); + +// Create copy of a patch. If the patch is null, or memory was exhausted, +// returns null. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zdir_patch_t * + zdir_patch_dup (zdir_patch_t *self); + +// Return patch file directory path +CZMQ_EXPORT const char * + zdir_patch_path (zdir_patch_t *self); + +// Return patch file item +CZMQ_EXPORT zfile_t * + zdir_patch_file (zdir_patch_t *self); + +// Return operation +CZMQ_EXPORT int + zdir_patch_op (zdir_patch_t *self); + +// Return patch virtual file path +CZMQ_EXPORT const char * + zdir_patch_vpath (zdir_patch_t *self); + +// Calculate hash digest for file (create only) +CZMQ_EXPORT void + zdir_patch_digest_set (zdir_patch_t *self); + +// Return hash digest for patch file +CZMQ_EXPORT const char * + zdir_patch_digest (zdir_patch_t *self); + +// Self test of this class. +CZMQ_EXPORT void + zdir_patch_test (bool verbose); + +// @end + + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/aarch64/include/zfile.h b/phonelibs/zmq/aarch64/include/zfile.h new file mode 100644 index 00000000000000..75c35774b97fd1 --- /dev/null +++ b/phonelibs/zmq/aarch64/include/zfile.h @@ -0,0 +1,177 @@ +/* ========================================================================= + zfile - helper functions for working with files. + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZFILE_H_INCLUDED__ +#define __ZFILE_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/zfile.api" to make changes. +// @interface +// This is a stable class, and may not change except for emergencies. It +// is provided in stable builds. +// If file exists, populates properties. CZMQ supports portable symbolic +// links, which are files with the extension ".ln". A symbolic link is a +// text file containing one line, the filename of a target file. Reading +// data from the symbolic link actually reads from the target file. Path +// may be NULL, in which case it is not used. +CZMQ_EXPORT zfile_t * + zfile_new (const char *path, const char *name); + +// Destroy a file item +CZMQ_EXPORT void + zfile_destroy (zfile_t **self_p); + +// Duplicate a file item, returns a newly constructed item. If the file +// is null, or memory was exhausted, returns null. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zfile_t * + zfile_dup (zfile_t *self); + +// Return file name, remove path if provided +CZMQ_EXPORT const char * + zfile_filename (zfile_t *self, const char *path); + +// Refresh file properties from disk; this is not done automatically +// on access methods, otherwise it is not possible to compare directory +// snapshots. +CZMQ_EXPORT void + zfile_restat (zfile_t *self); + +// Return when the file was last modified. If you want this to reflect the +// current situation, call zfile_restat before checking this property. +CZMQ_EXPORT time_t + zfile_modified (zfile_t *self); + +// Return the last-known size of the file. If you want this to reflect the +// current situation, call zfile_restat before checking this property. +CZMQ_EXPORT off_t + zfile_cursize (zfile_t *self); + +// Return true if the file is a directory. If you want this to reflect +// any external changes, call zfile_restat before checking this property. +CZMQ_EXPORT bool + zfile_is_directory (zfile_t *self); + +// Return true if the file is a regular file. If you want this to reflect +// any external changes, call zfile_restat before checking this property. +CZMQ_EXPORT bool + zfile_is_regular (zfile_t *self); + +// Return true if the file is readable by this process. If you want this to +// reflect any external changes, call zfile_restat before checking this +// property. +CZMQ_EXPORT bool + zfile_is_readable (zfile_t *self); + +// Return true if the file is writeable by this process. If you want this +// to reflect any external changes, call zfile_restat before checking this +// property. +CZMQ_EXPORT bool + zfile_is_writeable (zfile_t *self); + +// Check if file has stopped changing and can be safely processed. +// Updates the file statistics from disk at every call. +CZMQ_EXPORT bool + zfile_is_stable (zfile_t *self); + +// Return true if the file was changed on disk since the zfile_t object +// was created, or the last zfile_restat() call made on it. +CZMQ_EXPORT bool + zfile_has_changed (zfile_t *self); + +// Remove the file from disk +CZMQ_EXPORT void + zfile_remove (zfile_t *self); + +// Open file for reading +// Returns 0 if OK, -1 if not found or not accessible +CZMQ_EXPORT int + zfile_input (zfile_t *self); + +// Open file for writing, creating directory if needed +// File is created if necessary; chunks can be written to file at any +// location. Returns 0 if OK, -1 if error. +CZMQ_EXPORT int + zfile_output (zfile_t *self); + +// Read chunk from file at specified position. If this was the last chunk, +// sets the eof property. Returns a null chunk in case of error. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zchunk_t * + zfile_read (zfile_t *self, size_t bytes, off_t offset); + +// Returns true if zfile_read() just read the last chunk in the file. +CZMQ_EXPORT bool + zfile_eof (zfile_t *self); + +// Write chunk to file at specified position +// Return 0 if OK, else -1 +CZMQ_EXPORT int + zfile_write (zfile_t *self, zchunk_t *chunk, off_t offset); + +// Read next line of text from file. Returns a pointer to the text line, +// or NULL if there was nothing more to read from the file. +CZMQ_EXPORT const char * + zfile_readln (zfile_t *self); + +// Close file, if open +CZMQ_EXPORT void + zfile_close (zfile_t *self); + +// Return file handle, if opened +CZMQ_EXPORT FILE * + zfile_handle (zfile_t *self); + +// Calculate SHA1 digest for file, using zdigest class. +CZMQ_EXPORT const char * + zfile_digest (zfile_t *self); + +// Self test of this class. +CZMQ_EXPORT void + zfile_test (bool verbose); + +// @end + + +// @interface +// These methods are deprecated, and now moved to zsys class. +CZMQ_EXPORT bool + zfile_exists (const char *filename); +CZMQ_EXPORT ssize_t + zfile_size (const char *filename); +CZMQ_EXPORT mode_t + zfile_mode (const char *filename); +CZMQ_EXPORT int + zfile_delete (const char *filename); +CZMQ_EXPORT bool + zfile_stable (const char *filename); +CZMQ_EXPORT int + zfile_mkdir (const char *pathname); +CZMQ_EXPORT int + zfile_rmdir (const char *pathname); +CZMQ_EXPORT void + zfile_mode_private (void); +CZMQ_EXPORT void + zfile_mode_default (void); +// @end + +#ifdef __cplusplus +} +#endif + + +#endif // __ZFILE_H_INCLUDED__ diff --git a/phonelibs/zmq/aarch64/include/zframe.h b/phonelibs/zmq/aarch64/include/zframe.h new file mode 100644 index 00000000000000..728093c36ce117 --- /dev/null +++ b/phonelibs/zmq/aarch64/include/zframe.h @@ -0,0 +1,176 @@ +/* ========================================================================= + zframe - working with single message frames + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZFRAME_H_INCLUDED__ +#define __ZFRAME_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/zframe.api" to make changes. +// @interface +// This is a stable class, and may not change except for emergencies. It +// is provided in stable builds. +// This class has draft methods, which may change over time. They are not +// in stable releases, by default. Use --enable-drafts to enable. +#define ZFRAME_MORE 1 // +#define ZFRAME_REUSE 2 // +#define ZFRAME_DONTWAIT 4 // + +// Create a new frame. If size is not null, allocates the frame data +// to the specified size. If additionally, data is not null, copies +// size octets from the specified data into the frame body. +CZMQ_EXPORT zframe_t * + zframe_new (const void *data, size_t size); + +// Create an empty (zero-sized) frame +CZMQ_EXPORT zframe_t * + zframe_new_empty (void); + +// Create a frame with a specified string content. +CZMQ_EXPORT zframe_t * + zframe_from (const char *string); + +// Receive frame from socket, returns zframe_t object or NULL if the recv +// was interrupted. Does a blocking recv, if you want to not block then use +// zpoller or zloop. +CZMQ_EXPORT zframe_t * + zframe_recv (void *source); + +// Destroy a frame +CZMQ_EXPORT void + zframe_destroy (zframe_t **self_p); + +// Send a frame to a socket, destroy frame after sending. +// Return -1 on error, 0 on success. +CZMQ_EXPORT int + zframe_send (zframe_t **self_p, void *dest, int flags); + +// Return number of bytes in frame data +CZMQ_EXPORT size_t + zframe_size (zframe_t *self); + +// Return address of frame data +CZMQ_EXPORT byte * + zframe_data (zframe_t *self); + +// Return meta data property for frame +// Caller must free string when finished with it. +CZMQ_EXPORT const char * + zframe_meta (zframe_t *self, const char *property); + +// Create a new frame that duplicates an existing frame. If frame is null, +// or memory was exhausted, returns null. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zframe_t * + zframe_dup (zframe_t *self); + +// Return frame data encoded as printable hex string, useful for 0MQ UUIDs. +// Caller must free string when finished with it. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT char * + zframe_strhex (zframe_t *self); + +// Return frame data copied into freshly allocated string +// Caller must free string when finished with it. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT char * + zframe_strdup (zframe_t *self); + +// Return TRUE if frame body is equal to string, excluding terminator +CZMQ_EXPORT bool + zframe_streq (zframe_t *self, const char *string); + +// Return frame MORE indicator (1 or 0), set when reading frame from socket +// or by the zframe_set_more() method +CZMQ_EXPORT int + zframe_more (zframe_t *self); + +// Set frame MORE indicator (1 or 0). Note this is NOT used when sending +// frame to socket, you have to specify flag explicitly. +CZMQ_EXPORT void + zframe_set_more (zframe_t *self, int more); + +// Return TRUE if two frames have identical size and data +// If either frame is NULL, equality is always false. +CZMQ_EXPORT bool + zframe_eq (zframe_t *self, zframe_t *other); + +// Set new contents for frame +CZMQ_EXPORT void + zframe_reset (zframe_t *self, const void *data, size_t size); + +// Send message to zsys log sink (may be stdout, or system facility as +// configured by zsys_set_logstream). Prefix shows before frame, if not null. +CZMQ_EXPORT void + zframe_print (zframe_t *self, const char *prefix); + +// Probe the supplied object, and report if it looks like a zframe_t. +CZMQ_EXPORT bool + zframe_is (void *self); + +// Self test of this class. +CZMQ_EXPORT void + zframe_test (bool verbose); + +#ifdef CZMQ_BUILD_DRAFT_API +// *** Draft method, for development use, may change without warning *** +// Return frame routing ID, if the frame came from a ZMQ_SERVER socket. +// Else returns zero. +CZMQ_EXPORT uint32_t + zframe_routing_id (zframe_t *self); + +// *** Draft method, for development use, may change without warning *** +// Set routing ID on frame. This is used if/when the frame is sent to a +// ZMQ_SERVER socket. +CZMQ_EXPORT void + zframe_set_routing_id (zframe_t *self, uint32_t routing_id); + +// *** Draft method, for development use, may change without warning *** +// Return frame group of radio-dish pattern. +CZMQ_EXPORT const char * + zframe_group (zframe_t *self); + +// *** Draft method, for development use, may change without warning *** +// Set group on frame. This is used if/when the frame is sent to a +// ZMQ_RADIO socket. +// Return -1 on error, 0 on success. +CZMQ_EXPORT int + zframe_set_group (zframe_t *self, const char *group); + +#endif // CZMQ_BUILD_DRAFT_API +// @end + + +// DEPRECATED as poor style -- callers should use zloop or zpoller +// Receive a new frame off the socket. Returns newly allocated frame, or +// NULL if there was no input waiting, or if the read was interrupted. +CZMQ_EXPORT zframe_t * + zframe_recv_nowait (void *source); + +// DEPRECATED as inconsistent; breaks principle that logging should all go +// to a single destination. +// Print contents of the frame to FILE stream. +CZMQ_EXPORT void + zframe_fprint (zframe_t *self, const char *prefix, FILE *file); + +// Deprecated method aliases +#define zframe_print_to_stream(s,p,F) zframe_fprint(s,p,F) + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/aarch64/include/zgossip.h b/phonelibs/zmq/aarch64/include/zgossip.h new file mode 100644 index 00000000000000..647cb28c080731 --- /dev/null +++ b/phonelibs/zmq/aarch64/include/zgossip.h @@ -0,0 +1,95 @@ +/* ========================================================================= + zgossip - zgossip server + + ** WARNING ************************************************************* + THIS SOURCE FILE IS 100% GENERATED. If you edit this file, you will lose + your changes at the next build cycle. This is great for temporary printf + statements. DO NOT MAKE ANY CHANGES YOU WISH TO KEEP. The correct places + for commits are: + + * The XML model used for this code generation: zgossip.xml, or + * The code generation script that built this file: zproto_server_c + ************************************************************************ + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef ZGOSSIP_H_INCLUDED +#define ZGOSSIP_H_INCLUDED + +#include "czmq.h" + +#ifdef __cplusplus +extern "C" { +#endif + +// @interface +// To work with zgossip, use the CZMQ zactor API: +// +// Create new zgossip instance, passing logging prefix: +// +// zactor_t *zgossip = zactor_new (zgossip, "myname"); +// +// Destroy zgossip instance +// +// zactor_destroy (&zgossip); +// +// Enable verbose logging of commands and activity: +// +// zstr_send (zgossip, "VERBOSE"); +// +// Bind zgossip to specified endpoint. TCP endpoints may specify +// the port number as "*" to aquire an ephemeral port: +// +// zstr_sendx (zgossip, "BIND", endpoint, NULL); +// +// Return assigned port number, specifically when BIND was done using an +// an ephemeral port: +// +// zstr_sendx (zgossip, "PORT", NULL); +// char *command, *port_str; +// zstr_recvx (zgossip, &command, &port_str, NULL); +// assert (streq (command, "PORT")); +// +// Specify configuration file to load, overwriting any previous loaded +// configuration file or options: +// +// zstr_sendx (zgossip, "LOAD", filename, NULL); +// +// Set configuration path value: +// +// zstr_sendx (zgossip, "SET", path, value, NULL); +// +// Save configuration data to config file on disk: +// +// zstr_sendx (zgossip, "SAVE", filename, NULL); +// +// Send zmsg_t instance to zgossip: +// +// zactor_send (zgossip, &msg); +// +// Receive zmsg_t instance from zgossip: +// +// zmsg_t *msg = zactor_recv (zgossip); +// +// This is the zgossip constructor as a zactor_fn: +// +CZMQ_EXPORT void + zgossip (zsock_t *pipe, void *args); + +// Self test of this class +CZMQ_EXPORT void + zgossip_test (bool verbose); +// @end + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/aarch64/include/zhash.h b/phonelibs/zmq/aarch64/include/zhash.h new file mode 100644 index 00000000000000..929bc2683aec36 --- /dev/null +++ b/phonelibs/zmq/aarch64/include/zhash.h @@ -0,0 +1,198 @@ +/* ========================================================================= + zhash - generic type-free hash container (simple) + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZHASH_H_INCLUDED__ +#define __ZHASH_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/zhash.api" to make changes. +// @interface +// This is a stable class, and may not change except for emergencies. It +// is provided in stable builds. +// This class has legacy methods, which will be removed over time. You +// should not use them, and migrate any code that is still using them. +// Callback function for zhash_freefn method +typedef void (zhash_free_fn) ( + void *data); + +// Callback function for zhash_foreach method. Deprecated. +typedef int (zhash_foreach_fn) ( + const char *key, void *item, void *argument); + +// Create a new, empty hash container +CZMQ_EXPORT zhash_t * + zhash_new (void); + +// Unpack binary frame into a new hash table. Packed data must follow format +// defined by zhash_pack. Hash table is set to autofree. An empty frame +// unpacks to an empty hash table. +CZMQ_EXPORT zhash_t * + zhash_unpack (zframe_t *frame); + +// Destroy a hash container and all items in it +CZMQ_EXPORT void + zhash_destroy (zhash_t **self_p); + +// Insert item into hash table with specified key and item. +// If key is already present returns -1 and leaves existing item unchanged +// Returns 0 on success. +CZMQ_EXPORT int + zhash_insert (zhash_t *self, const char *key, void *item); + +// Update item into hash table with specified key and item. +// If key is already present, destroys old item and inserts new one. +// Use free_fn method to ensure deallocator is properly called on item. +CZMQ_EXPORT void + zhash_update (zhash_t *self, const char *key, void *item); + +// Remove an item specified by key from the hash table. If there was no such +// item, this function does nothing. +CZMQ_EXPORT void + zhash_delete (zhash_t *self, const char *key); + +// Return the item at the specified key, or null +CZMQ_EXPORT void * + zhash_lookup (zhash_t *self, const char *key); + +// Reindexes an item from an old key to a new key. If there was no such +// item, does nothing. Returns 0 if successful, else -1. +CZMQ_EXPORT int + zhash_rename (zhash_t *self, const char *old_key, const char *new_key); + +// Set a free function for the specified hash table item. When the item is +// destroyed, the free function, if any, is called on that item. +// Use this when hash items are dynamically allocated, to ensure that +// you don't have memory leaks. You can pass 'free' or NULL as a free_fn. +// Returns the item, or NULL if there is no such item. +CZMQ_EXPORT void * + zhash_freefn (zhash_t *self, const char *key, zhash_free_fn free_fn); + +// Return the number of keys/items in the hash table +CZMQ_EXPORT size_t + zhash_size (zhash_t *self); + +// Make copy of hash table; if supplied table is null, returns null. +// Does not copy items themselves. Rebuilds new table so may be slow on +// very large tables. NOTE: only works with item values that are strings +// since there's no other way to know how to duplicate the item value. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zhash_t * + zhash_dup (zhash_t *self); + +// Return keys for items in table +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zlist_t * + zhash_keys (zhash_t *self); + +// Simple iterator; returns first item in hash table, in no given order, +// or NULL if the table is empty. This method is simpler to use than the +// foreach() method, which is deprecated. To access the key for this item +// use zhash_cursor(). NOTE: do NOT modify the table while iterating. +CZMQ_EXPORT void * + zhash_first (zhash_t *self); + +// Simple iterator; returns next item in hash table, in no given order, +// or NULL if the last item was already returned. Use this together with +// zhash_first() to process all items in a hash table. If you need the +// items in sorted order, use zhash_keys() and then zlist_sort(). To +// access the key for this item use zhash_cursor(). NOTE: do NOT modify +// the table while iterating. +CZMQ_EXPORT void * + zhash_next (zhash_t *self); + +// After a successful first/next method, returns the key for the item that +// was returned. This is a constant string that you may not modify or +// deallocate, and which lasts as long as the item in the hash. After an +// unsuccessful first/next, returns NULL. +CZMQ_EXPORT const char * + zhash_cursor (zhash_t *self); + +// Add a comment to hash table before saving to disk. You can add as many +// comment lines as you like. These comment lines are discarded when loading +// the file. If you use a null format, all comments are deleted. +CZMQ_EXPORT void + zhash_comment (zhash_t *self, const char *format, ...); + +// Serialize hash table to a binary frame that can be sent in a message. +// The packed format is compatible with the 'dictionary' type defined in +// http://rfc.zeromq.org/spec:35/FILEMQ, and implemented by zproto: +// +// ; A list of name/value pairs +// dictionary = dict-count *( dict-name dict-value ) +// dict-count = number-4 +// dict-value = longstr +// dict-name = string +// +// ; Strings are always length + text contents +// longstr = number-4 *VCHAR +// string = number-1 *VCHAR +// +// ; Numbers are unsigned integers in network byte order +// number-1 = 1OCTET +// number-4 = 4OCTET +// +// Comments are not included in the packed data. Item values MUST be +// strings. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zframe_t * + zhash_pack (zhash_t *self); + +// Save hash table to a text file in name=value format. Hash values must be +// printable strings; keys may not contain '=' character. Returns 0 if OK, +// else -1 if a file error occurred. +CZMQ_EXPORT int + zhash_save (zhash_t *self, const char *filename); + +// Load hash table from a text file in name=value format; hash table must +// already exist. Hash values must printable strings; keys may not contain +// '=' character. Returns 0 if OK, else -1 if a file was not readable. +CZMQ_EXPORT int + zhash_load (zhash_t *self, const char *filename); + +// When a hash table was loaded from a file by zhash_load, this method will +// reload the file if it has been modified since, and is "stable", i.e. not +// still changing. Returns 0 if OK, -1 if there was an error reloading the +// file. +CZMQ_EXPORT int + zhash_refresh (zhash_t *self); + +// Set hash for automatic value destruction +CZMQ_EXPORT void + zhash_autofree (zhash_t *self); + +// *** Deprecated method, slated for removal: avoid using it *** +// Apply function to each item in the hash table. Items are iterated in no +// defined order. Stops if callback function returns non-zero and returns +// final return code from callback function (zero = success). Deprecated. +CZMQ_EXPORT int + zhash_foreach (zhash_t *self, zhash_foreach_fn callback, void *argument); + +// Self test of this class. +CZMQ_EXPORT void + zhash_test (bool verbose); + +// @ignore +CZMQ_EXPORT void + zhash_comment (zhash_t *self, const char *format, ...) CHECK_PRINTF (2); +// @end + + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/aarch64/include/zhashx.h b/phonelibs/zmq/aarch64/include/zhashx.h new file mode 100644 index 00000000000000..8776073156cf3c --- /dev/null +++ b/phonelibs/zmq/aarch64/include/zhashx.h @@ -0,0 +1,301 @@ +/* ========================================================================= + zhashx - extended generic type-free hash container + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZHASHX_H_INCLUDED__ +#define __ZHASHX_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/zhashx.api" to make changes. +// @interface +// This is a stable class, and may not change except for emergencies. It +// is provided in stable builds. +// This class has draft methods, which may change over time. They are not +// in stable releases, by default. Use --enable-drafts to enable. +// This class has legacy methods, which will be removed over time. You +// should not use them, and migrate any code that is still using them. +// Destroy an item +typedef void (zhashx_destructor_fn) ( + void **item); + +// Duplicate an item +typedef void * (zhashx_duplicator_fn) ( + const void *item); + +// Compare two items, for sorting +typedef int (zhashx_comparator_fn) ( + const void *item1, const void *item2); + +// compare two items, for sorting +typedef void (zhashx_free_fn) ( + void *data); + +// compare two items, for sorting +typedef size_t (zhashx_hash_fn) ( + const void *key); + +// Serializes an item to a longstr. +// The caller takes ownership of the newly created object. +typedef char * (zhashx_serializer_fn) ( + const void *item); + +// Deserializes a longstr into an item. +// The caller takes ownership of the newly created object. +typedef void * (zhashx_deserializer_fn) ( + const char *item_str); + +// Callback function for zhashx_foreach method. +// This callback is deprecated and you should use zhashx_first/_next instead. +typedef int (zhashx_foreach_fn) ( + const char *key, void *item, void *argument); + +// Create a new, empty hash container +CZMQ_EXPORT zhashx_t * + zhashx_new (void); + +// Unpack binary frame into a new hash table. Packed data must follow format +// defined by zhashx_pack. Hash table is set to autofree. An empty frame +// unpacks to an empty hash table. +CZMQ_EXPORT zhashx_t * + zhashx_unpack (zframe_t *frame); + +// Destroy a hash container and all items in it +CZMQ_EXPORT void + zhashx_destroy (zhashx_t **self_p); + +// Insert item into hash table with specified key and item. +// If key is already present returns -1 and leaves existing item unchanged +// Returns 0 on success. +CZMQ_EXPORT int + zhashx_insert (zhashx_t *self, const void *key, void *item); + +// Update or insert item into hash table with specified key and item. If the +// key is already present, destroys old item and inserts new one. If you set +// a container item destructor, this is called on the old value. If the key +// was not already present, inserts a new item. Sets the hash cursor to the +// new item. +CZMQ_EXPORT void + zhashx_update (zhashx_t *self, const void *key, void *item); + +// Remove an item specified by key from the hash table. If there was no such +// item, this function does nothing. +CZMQ_EXPORT void + zhashx_delete (zhashx_t *self, const void *key); + +// Delete all items from the hash table. If the key destructor is +// set, calls it on every key. If the item destructor is set, calls +// it on every item. +CZMQ_EXPORT void + zhashx_purge (zhashx_t *self); + +// Return the item at the specified key, or null +CZMQ_EXPORT void * + zhashx_lookup (zhashx_t *self, const void *key); + +// Reindexes an item from an old key to a new key. If there was no such +// item, does nothing. Returns 0 if successful, else -1. +CZMQ_EXPORT int + zhashx_rename (zhashx_t *self, const void *old_key, const void *new_key); + +// Set a free function for the specified hash table item. When the item is +// destroyed, the free function, if any, is called on that item. +// Use this when hash items are dynamically allocated, to ensure that +// you don't have memory leaks. You can pass 'free' or NULL as a free_fn. +// Returns the item, or NULL if there is no such item. +CZMQ_EXPORT void * + zhashx_freefn (zhashx_t *self, const void *key, zhashx_free_fn free_fn); + +// Return the number of keys/items in the hash table +CZMQ_EXPORT size_t + zhashx_size (zhashx_t *self); + +// Return a zlistx_t containing the keys for the items in the +// table. Uses the key_duplicator to duplicate all keys and sets the +// key_destructor as destructor for the list. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zlistx_t * + zhashx_keys (zhashx_t *self); + +// Return a zlistx_t containing the values for the items in the +// table. Uses the duplicator to duplicate all items and sets the +// destructor as destructor for the list. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zlistx_t * + zhashx_values (zhashx_t *self); + +// Simple iterator; returns first item in hash table, in no given order, +// or NULL if the table is empty. This method is simpler to use than the +// foreach() method, which is deprecated. To access the key for this item +// use zhashx_cursor(). NOTE: do NOT modify the table while iterating. +CZMQ_EXPORT void * + zhashx_first (zhashx_t *self); + +// Simple iterator; returns next item in hash table, in no given order, +// or NULL if the last item was already returned. Use this together with +// zhashx_first() to process all items in a hash table. If you need the +// items in sorted order, use zhashx_keys() and then zlistx_sort(). To +// access the key for this item use zhashx_cursor(). NOTE: do NOT modify +// the table while iterating. +CZMQ_EXPORT void * + zhashx_next (zhashx_t *self); + +// After a successful first/next method, returns the key for the item that +// was returned. This is a constant string that you may not modify or +// deallocate, and which lasts as long as the item in the hash. After an +// unsuccessful first/next, returns NULL. +CZMQ_EXPORT const void * + zhashx_cursor (zhashx_t *self); + +// Add a comment to hash table before saving to disk. You can add as many +// comment lines as you like. These comment lines are discarded when loading +// the file. If you use a null format, all comments are deleted. +CZMQ_EXPORT void + zhashx_comment (zhashx_t *self, const char *format, ...); + +// Save hash table to a text file in name=value format. Hash values must be +// printable strings; keys may not contain '=' character. Returns 0 if OK, +// else -1 if a file error occurred. +CZMQ_EXPORT int + zhashx_save (zhashx_t *self, const char *filename); + +// Load hash table from a text file in name=value format; hash table must +// already exist. Hash values must printable strings; keys may not contain +// '=' character. Returns 0 if OK, else -1 if a file was not readable. +CZMQ_EXPORT int + zhashx_load (zhashx_t *self, const char *filename); + +// When a hash table was loaded from a file by zhashx_load, this method will +// reload the file if it has been modified since, and is "stable", i.e. not +// still changing. Returns 0 if OK, -1 if there was an error reloading the +// file. +CZMQ_EXPORT int + zhashx_refresh (zhashx_t *self); + +// Serialize hash table to a binary frame that can be sent in a message. +// The packed format is compatible with the 'dictionary' type defined in +// http://rfc.zeromq.org/spec:35/FILEMQ, and implemented by zproto: +// +// ; A list of name/value pairs +// dictionary = dict-count *( dict-name dict-value ) +// dict-count = number-4 +// dict-value = longstr +// dict-name = string +// +// ; Strings are always length + text contents +// longstr = number-4 *VCHAR +// string = number-1 *VCHAR +// +// ; Numbers are unsigned integers in network byte order +// number-1 = 1OCTET +// number-4 = 4OCTET +// +// Comments are not included in the packed data. Item values MUST be +// strings. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zframe_t * + zhashx_pack (zhashx_t *self); + +// Make a copy of the list; items are duplicated if you set a duplicator +// for the list, otherwise not. Copying a null reference returns a null +// reference. Note that this method's behavior changed slightly for CZMQ +// v3.x, as it does not set nor respect autofree. It does however let you +// duplicate any hash table safely. The old behavior is in zhashx_dup_v2. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zhashx_t * + zhashx_dup (zhashx_t *self); + +// Set a user-defined deallocator for hash items; by default items are not +// freed when the hash is destroyed. +CZMQ_EXPORT void + zhashx_set_destructor (zhashx_t *self, zhashx_destructor_fn destructor); + +// Set a user-defined duplicator for hash items; by default items are not +// copied when the hash is duplicated. +CZMQ_EXPORT void + zhashx_set_duplicator (zhashx_t *self, zhashx_duplicator_fn duplicator); + +// Set a user-defined deallocator for keys; by default keys are freed +// when the hash is destroyed using free(). +CZMQ_EXPORT void + zhashx_set_key_destructor (zhashx_t *self, zhashx_destructor_fn destructor); + +// Set a user-defined duplicator for keys; by default keys are duplicated +// using strdup. +CZMQ_EXPORT void + zhashx_set_key_duplicator (zhashx_t *self, zhashx_duplicator_fn duplicator); + +// Set a user-defined comparator for keys; by default keys are +// compared using strcmp. +CZMQ_EXPORT void + zhashx_set_key_comparator (zhashx_t *self, zhashx_comparator_fn comparator); + +// Set a user-defined comparator for keys; by default keys are +// compared using strcmp. +CZMQ_EXPORT void + zhashx_set_key_hasher (zhashx_t *self, zhashx_hash_fn hasher); + +// Make copy of hash table; if supplied table is null, returns null. +// Does not copy items themselves. Rebuilds new table so may be slow on +// very large tables. NOTE: only works with item values that are strings +// since there's no other way to know how to duplicate the item value. +CZMQ_EXPORT zhashx_t * + zhashx_dup_v2 (zhashx_t *self); + +// *** Deprecated method, slated for removal: avoid using it *** +// Set hash for automatic value destruction. This method is deprecated +// and you should use set_destructor instead. +CZMQ_EXPORT void + zhashx_autofree (zhashx_t *self); + +// *** Deprecated method, slated for removal: avoid using it *** +// Apply function to each item in the hash table. Items are iterated in no +// defined order. Stops if callback function returns non-zero and returns +// final return code from callback function (zero = success). This method +// is deprecated and you should use zhashx_first/_next instead. +CZMQ_EXPORT int + zhashx_foreach (zhashx_t *self, zhashx_foreach_fn callback, void *argument); + +// Self test of this class. +CZMQ_EXPORT void + zhashx_test (bool verbose); + +#ifdef CZMQ_BUILD_DRAFT_API +// *** Draft method, for development use, may change without warning *** +// Same as unpack but uses a user-defined deserializer function to convert +// a longstr back into item format. +CZMQ_EXPORT zhashx_t * + zhashx_unpack_own (zframe_t *frame, zhashx_deserializer_fn deserializer); + +// *** Draft method, for development use, may change without warning *** +// Same as pack but uses a user-defined serializer function to convert items +// into longstr. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zframe_t * + zhashx_pack_own (zhashx_t *self, zhashx_serializer_fn serializer); + +#endif // CZMQ_BUILD_DRAFT_API +// @ignore +CZMQ_EXPORT void + zhashx_comment (zhashx_t *self, const char *format, ...) CHECK_PRINTF (2); +// @end + + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/aarch64/include/ziflist.h b/phonelibs/zmq/aarch64/include/ziflist.h new file mode 100644 index 00000000000000..cb2b1448025f89 --- /dev/null +++ b/phonelibs/zmq/aarch64/include/ziflist.h @@ -0,0 +1,77 @@ +/* ========================================================================= + ziflist - List of network interfaces available on system + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZIFLIST_H_INCLUDED__ +#define __ZIFLIST_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/ziflist.api" to make changes. +// @interface +// This is a stable class, and may not change except for emergencies. It +// is provided in stable builds. +// Get a list of network interfaces currently defined on the system +CZMQ_EXPORT ziflist_t * + ziflist_new (void); + +// Destroy a ziflist instance +CZMQ_EXPORT void + ziflist_destroy (ziflist_t **self_p); + +// Reload network interfaces from system +CZMQ_EXPORT void + ziflist_reload (ziflist_t *self); + +// Return the number of network interfaces on system +CZMQ_EXPORT size_t + ziflist_size (ziflist_t *self); + +// Get first network interface, return NULL if there are none +CZMQ_EXPORT const char * + ziflist_first (ziflist_t *self); + +// Get next network interface, return NULL if we hit the last one +CZMQ_EXPORT const char * + ziflist_next (ziflist_t *self); + +// Return the current interface IP address as a printable string +CZMQ_EXPORT const char * + ziflist_address (ziflist_t *self); + +// Return the current interface broadcast address as a printable string +CZMQ_EXPORT const char * + ziflist_broadcast (ziflist_t *self); + +// Return the current interface network mask as a printable string +CZMQ_EXPORT const char * + ziflist_netmask (ziflist_t *self); + +// Return the list of interfaces. +CZMQ_EXPORT void + ziflist_print (ziflist_t *self); + +// Self test of this class. +CZMQ_EXPORT void + ziflist_test (bool verbose); + +// @end + + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/aarch64/include/zlist.h b/phonelibs/zmq/aarch64/include/zlist.h new file mode 100644 index 00000000000000..1dcd39b9955c9e --- /dev/null +++ b/phonelibs/zmq/aarch64/include/zlist.h @@ -0,0 +1,158 @@ +/* ========================================================================= + zlist - simple generic list container + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZLIST_H_INCLUDED__ +#define __ZLIST_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/zlist.api" to make changes. +// @interface +// This is a stable class, and may not change except for emergencies. It +// is provided in stable builds. +// Comparison function e.g. for sorting and removing. +typedef int (zlist_compare_fn) ( + void *item1, void *item2); + +// Callback function for zlist_freefn method +typedef void (zlist_free_fn) ( + void *data); + +// Create a new list container +CZMQ_EXPORT zlist_t * + zlist_new (void); + +// Destroy a list container +CZMQ_EXPORT void + zlist_destroy (zlist_t **self_p); + +// Return the item at the head of list. If the list is empty, returns NULL. +// Leaves cursor pointing at the head item, or NULL if the list is empty. +CZMQ_EXPORT void * + zlist_first (zlist_t *self); + +// Return the next item. If the list is empty, returns NULL. To move to +// the start of the list call zlist_first (). Advances the cursor. +CZMQ_EXPORT void * + zlist_next (zlist_t *self); + +// Return the item at the tail of list. If the list is empty, returns NULL. +// Leaves cursor pointing at the tail item, or NULL if the list is empty. +CZMQ_EXPORT void * + zlist_last (zlist_t *self); + +// Return first item in the list, or null, leaves the cursor +CZMQ_EXPORT void * + zlist_head (zlist_t *self); + +// Return last item in the list, or null, leaves the cursor +CZMQ_EXPORT void * + zlist_tail (zlist_t *self); + +// Return the current item of list. If the list is empty, returns NULL. +// Leaves cursor pointing at the current item, or NULL if the list is empty. +CZMQ_EXPORT void * + zlist_item (zlist_t *self); + +// Append an item to the end of the list, return 0 if OK or -1 if this +// failed for some reason (out of memory). Note that if a duplicator has +// been set, this method will also duplicate the item. +CZMQ_EXPORT int + zlist_append (zlist_t *self, void *item); + +// Push an item to the start of the list, return 0 if OK or -1 if this +// failed for some reason (out of memory). Note that if a duplicator has +// been set, this method will also duplicate the item. +CZMQ_EXPORT int + zlist_push (zlist_t *self, void *item); + +// Pop the item off the start of the list, if any +CZMQ_EXPORT void * + zlist_pop (zlist_t *self); + +// Checks if an item already is present. Uses compare method to determine if +// items are equal. If the compare method is NULL the check will only compare +// pointers. Returns true if item is present else false. +CZMQ_EXPORT bool + zlist_exists (zlist_t *self, void *item); + +// Remove the specified item from the list if present +CZMQ_EXPORT void + zlist_remove (zlist_t *self, void *item); + +// Make a copy of list. If the list has autofree set, the copied list will +// duplicate all items, which must be strings. Otherwise, the list will hold +// pointers back to the items in the original list. If list is null, returns +// NULL. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zlist_t * + zlist_dup (zlist_t *self); + +// Purge all items from list +CZMQ_EXPORT void + zlist_purge (zlist_t *self); + +// Return number of items in the list +CZMQ_EXPORT size_t + zlist_size (zlist_t *self); + +// Sort the list. If the compare function is null, sorts the list by +// ascending key value using a straight ASCII comparison. If you specify +// a compare function, this decides how items are sorted. The sort is not +// stable, so may reorder items with the same keys. The algorithm used is +// combsort, a compromise between performance and simplicity. +CZMQ_EXPORT void + zlist_sort (zlist_t *self, zlist_compare_fn compare); + +// Set list for automatic item destruction; item values MUST be strings. +// By default a list item refers to a value held elsewhere. When you set +// this, each time you append or push a list item, zlist will take a copy +// of the string value. Then, when you destroy the list, it will free all +// item values automatically. If you use any other technique to allocate +// list values, you must free them explicitly before destroying the list. +// The usual technique is to pop list items and destroy them, until the +// list is empty. +CZMQ_EXPORT void + zlist_autofree (zlist_t *self); + +// Sets a compare function for this list. The function compares two items. +// It returns an integer less than, equal to, or greater than zero if the +// first item is found, respectively, to be less than, to match, or be +// greater than the second item. +// This function is used for sorting, removal and exists checking. +CZMQ_EXPORT void + zlist_comparefn (zlist_t *self, zlist_compare_fn fn); + +// Set a free function for the specified list item. When the item is +// destroyed, the free function, if any, is called on that item. +// Use this when list items are dynamically allocated, to ensure that +// you don't have memory leaks. You can pass 'free' or NULL as a free_fn. +// Returns the item, or NULL if there is no such item. +CZMQ_EXPORT void * + zlist_freefn (zlist_t *self, void *item, zlist_free_fn fn, bool at_tail); + +// Self test of this class. +CZMQ_EXPORT void + zlist_test (bool verbose); + +// @end + + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/aarch64/include/zlistx.h b/phonelibs/zmq/aarch64/include/zlistx.h new file mode 100644 index 00000000000000..512637cef3bff5 --- /dev/null +++ b/phonelibs/zmq/aarch64/include/zlistx.h @@ -0,0 +1,205 @@ +/* ========================================================================= + zlistx - extended generic list container + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZLISTX_H_INCLUDED__ +#define __ZLISTX_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/zlistx.api" to make changes. +// @interface +// This is a stable class, and may not change except for emergencies. It +// is provided in stable builds. +// Destroy an item +typedef void (zlistx_destructor_fn) ( + void **item); + +// Duplicate an item +typedef void * (zlistx_duplicator_fn) ( + const void *item); + +// Compare two items, for sorting +typedef int (zlistx_comparator_fn) ( + const void *item1, const void *item2); + +// Create a new, empty list. +CZMQ_EXPORT zlistx_t * + zlistx_new (void); + +// Destroy a list. If an item destructor was specified, all items in the +// list are automatically destroyed as well. +CZMQ_EXPORT void + zlistx_destroy (zlistx_t **self_p); + +// Add an item to the head of the list. Calls the item duplicator, if any, +// on the item. Resets cursor to list head. Returns an item handle on +// success, NULL if memory was exhausted. +CZMQ_EXPORT void * + zlistx_add_start (zlistx_t *self, void *item); + +// Add an item to the tail of the list. Calls the item duplicator, if any, +// on the item. Resets cursor to list head. Returns an item handle on +// success, NULL if memory was exhausted. +CZMQ_EXPORT void * + zlistx_add_end (zlistx_t *self, void *item); + +// Return the number of items in the list +CZMQ_EXPORT size_t + zlistx_size (zlistx_t *self); + +// Return first item in the list, or null, leaves the cursor +CZMQ_EXPORT void * + zlistx_head (zlistx_t *self); + +// Return last item in the list, or null, leaves the cursor +CZMQ_EXPORT void * + zlistx_tail (zlistx_t *self); + +// Return the item at the head of list. If the list is empty, returns NULL. +// Leaves cursor pointing at the head item, or NULL if the list is empty. +CZMQ_EXPORT void * + zlistx_first (zlistx_t *self); + +// Return the next item. At the end of the list (or in an empty list), +// returns NULL. Use repeated zlistx_next () calls to work through the list +// from zlistx_first (). First time, acts as zlistx_first(). +CZMQ_EXPORT void * + zlistx_next (zlistx_t *self); + +// Return the previous item. At the start of the list (or in an empty list), +// returns NULL. Use repeated zlistx_prev () calls to work through the list +// backwards from zlistx_last (). First time, acts as zlistx_last(). +CZMQ_EXPORT void * + zlistx_prev (zlistx_t *self); + +// Return the item at the tail of list. If the list is empty, returns NULL. +// Leaves cursor pointing at the tail item, or NULL if the list is empty. +CZMQ_EXPORT void * + zlistx_last (zlistx_t *self); + +// Returns the value of the item at the cursor, or NULL if the cursor is +// not pointing to an item. +CZMQ_EXPORT void * + zlistx_item (zlistx_t *self); + +// Returns the handle of the item at the cursor, or NULL if the cursor is +// not pointing to an item. +CZMQ_EXPORT void * + zlistx_cursor (zlistx_t *self); + +// Returns the item associated with the given list handle, or NULL if passed +// in handle is NULL. Asserts that the passed in handle points to a list element. +CZMQ_EXPORT void * + zlistx_handle_item (void *handle); + +// Find an item in the list, searching from the start. Uses the item +// comparator, if any, else compares item values directly. Returns the +// item handle found, or NULL. Sets the cursor to the found item, if any. +CZMQ_EXPORT void * + zlistx_find (zlistx_t *self, void *item); + +// Detach an item from the list, using its handle. The item is not modified, +// and the caller is responsible for destroying it if necessary. If handle is +// null, detaches the first item on the list. Returns item that was detached, +// or null if none was. If cursor was at item, moves cursor to previous item, +// so you can detach items while iterating forwards through a list. +CZMQ_EXPORT void * + zlistx_detach (zlistx_t *self, void *handle); + +// Detach item at the cursor, if any, from the list. The item is not modified, +// and the caller is responsible for destroying it as necessary. Returns item +// that was detached, or null if none was. Moves cursor to previous item, so +// you can detach items while iterating forwards through a list. +CZMQ_EXPORT void * + zlistx_detach_cur (zlistx_t *self); + +// Delete an item, using its handle. Calls the item destructor is any is +// set. If handle is null, deletes the first item on the list. Returns 0 +// if an item was deleted, -1 if not. If cursor was at item, moves cursor +// to previous item, so you can delete items while iterating forwards +// through a list. +CZMQ_EXPORT int + zlistx_delete (zlistx_t *self, void *handle); + +// Move an item to the start of the list, via its handle. +CZMQ_EXPORT void + zlistx_move_start (zlistx_t *self, void *handle); + +// Move an item to the end of the list, via its handle. +CZMQ_EXPORT void + zlistx_move_end (zlistx_t *self, void *handle); + +// Remove all items from the list, and destroy them if the item destructor +// is set. +CZMQ_EXPORT void + zlistx_purge (zlistx_t *self); + +// Sort the list. If an item comparator was set, calls that to compare +// items, otherwise compares on item value. The sort is not stable, so may +// reorder equal items. +CZMQ_EXPORT void + zlistx_sort (zlistx_t *self); + +// Create a new node and insert it into a sorted list. Calls the item +// duplicator, if any, on the item. If low_value is true, starts searching +// from the start of the list, otherwise searches from the end. Use the item +// comparator, if any, to find where to place the new node. Returns a handle +// to the new node, or NULL if memory was exhausted. Resets the cursor to the +// list head. +CZMQ_EXPORT void * + zlistx_insert (zlistx_t *self, void *item, bool low_value); + +// Move an item, specified by handle, into position in a sorted list. Uses +// the item comparator, if any, to determine the new location. If low_value +// is true, starts searching from the start of the list, otherwise searches +// from the end. +CZMQ_EXPORT void + zlistx_reorder (zlistx_t *self, void *handle, bool low_value); + +// Make a copy of the list; items are duplicated if you set a duplicator +// for the list, otherwise not. Copying a null reference returns a null +// reference. +CZMQ_EXPORT zlistx_t * + zlistx_dup (zlistx_t *self); + +// Set a user-defined deallocator for list items; by default items are not +// freed when the list is destroyed. +CZMQ_EXPORT void + zlistx_set_destructor (zlistx_t *self, zlistx_destructor_fn destructor); + +// Set a user-defined duplicator for list items; by default items are not +// copied when the list is duplicated. +CZMQ_EXPORT void + zlistx_set_duplicator (zlistx_t *self, zlistx_duplicator_fn duplicator); + +// Set a user-defined comparator for zlistx_find and zlistx_sort; the method +// must return -1, 0, or 1 depending on whether item1 is less than, equal to, +// or greater than, item2. +CZMQ_EXPORT void + zlistx_set_comparator (zlistx_t *self, zlistx_comparator_fn comparator); + +// Self test of this class. +CZMQ_EXPORT void + zlistx_test (bool verbose); + +// @end + + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/aarch64/include/zloop.h b/phonelibs/zmq/aarch64/include/zloop.h new file mode 100644 index 00000000000000..bc58ea0530e7b3 --- /dev/null +++ b/phonelibs/zmq/aarch64/include/zloop.h @@ -0,0 +1,168 @@ +/* ========================================================================= + zloop - event-driven reactor + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZLOOP_H_INCLUDED__ +#define __ZLOOP_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/zloop.api" to make changes. +// @interface +// This is a stable class, and may not change except for emergencies. It +// is provided in stable builds. +// This class has draft methods, which may change over time. They are not +// in stable releases, by default. Use --enable-drafts to enable. +// Callback function for reactor socket activity +typedef int (zloop_reader_fn) ( + zloop_t *loop, zsock_t *reader, void *arg); + +// Callback function for reactor events (low-level) +typedef int (zloop_fn) ( + zloop_t *loop, zmq_pollitem_t *item, void *arg); + +// Callback for reactor timer events +typedef int (zloop_timer_fn) ( + zloop_t *loop, int timer_id, void *arg); + +// Create a new zloop reactor +CZMQ_EXPORT zloop_t * + zloop_new (void); + +// Destroy a reactor +CZMQ_EXPORT void + zloop_destroy (zloop_t **self_p); + +// Register socket reader with the reactor. When the reader has messages, +// the reactor will call the handler, passing the arg. Returns 0 if OK, -1 +// if there was an error. If you register the same socket more than once, +// each instance will invoke its corresponding handler. +CZMQ_EXPORT int + zloop_reader (zloop_t *self, zsock_t *sock, zloop_reader_fn handler, void *arg); + +// Cancel a socket reader from the reactor. If multiple readers exist for +// same socket, cancels ALL of them. +CZMQ_EXPORT void + zloop_reader_end (zloop_t *self, zsock_t *sock); + +// Configure a registered reader to ignore errors. If you do not set this, +// then readers that have errors are removed from the reactor silently. +CZMQ_EXPORT void + zloop_reader_set_tolerant (zloop_t *self, zsock_t *sock); + +// Register low-level libzmq pollitem with the reactor. When the pollitem +// is ready, will call the handler, passing the arg. Returns 0 if OK, -1 +// if there was an error. If you register the pollitem more than once, each +// instance will invoke its corresponding handler. A pollitem with +// socket=NULL and fd=0 means 'poll on FD zero'. +CZMQ_EXPORT int + zloop_poller (zloop_t *self, zmq_pollitem_t *item, zloop_fn handler, void *arg); + +// Cancel a pollitem from the reactor, specified by socket or FD. If both +// are specified, uses only socket. If multiple poll items exist for same +// socket/FD, cancels ALL of them. +CZMQ_EXPORT void + zloop_poller_end (zloop_t *self, zmq_pollitem_t *item); + +// Configure a registered poller to ignore errors. If you do not set this, +// then poller that have errors are removed from the reactor silently. +CZMQ_EXPORT void + zloop_poller_set_tolerant (zloop_t *self, zmq_pollitem_t *item); + +// Register a timer that expires after some delay and repeats some number of +// times. At each expiry, will call the handler, passing the arg. To run a +// timer forever, use 0 times. Returns a timer_id that is used to cancel the +// timer in the future. Returns -1 if there was an error. +CZMQ_EXPORT int + zloop_timer (zloop_t *self, size_t delay, size_t times, zloop_timer_fn handler, void *arg); + +// Cancel a specific timer identified by a specific timer_id (as returned by +// zloop_timer). +CZMQ_EXPORT int + zloop_timer_end (zloop_t *self, int timer_id); + +// Register a ticket timer. Ticket timers are very fast in the case where +// you use a lot of timers (thousands), and frequently remove and add them. +// The main use case is expiry timers for servers that handle many clients, +// and which reset the expiry timer for each message received from a client. +// Whereas normal timers perform poorly as the number of clients grows, the +// cost of ticket timers is constant, no matter the number of clients. You +// must set the ticket delay using zloop_set_ticket_delay before creating a +// ticket. Returns a handle to the timer that you should use in +// zloop_ticket_reset and zloop_ticket_delete. +CZMQ_EXPORT void * + zloop_ticket (zloop_t *self, zloop_timer_fn handler, void *arg); + +// Reset a ticket timer, which moves it to the end of the ticket list and +// resets its execution time. This is a very fast operation. +CZMQ_EXPORT void + zloop_ticket_reset (zloop_t *self, void *handle); + +// Delete a ticket timer. We do not actually delete the ticket here, as +// other code may still refer to the ticket. We mark as deleted, and remove +// later and safely. +CZMQ_EXPORT void + zloop_ticket_delete (zloop_t *self, void *handle); + +// Set the ticket delay, which applies to all tickets. If you lower the +// delay and there are already tickets created, the results are undefined. +CZMQ_EXPORT void + zloop_set_ticket_delay (zloop_t *self, size_t ticket_delay); + +// Set hard limit on number of timers allowed. Setting more than a small +// number of timers (10-100) can have a dramatic impact on the performance +// of the reactor. For high-volume cases, use ticket timers. If the hard +// limit is reached, the reactor stops creating new timers and logs an +// error. +CZMQ_EXPORT void + zloop_set_max_timers (zloop_t *self, size_t max_timers); + +// Set verbose tracing of reactor on/off. The default verbose setting is +// off (false). +CZMQ_EXPORT void + zloop_set_verbose (zloop_t *self, bool verbose); + +// Start the reactor. Takes control of the thread and returns when the 0MQ +// context is terminated or the process is interrupted, or any event handler +// returns -1. Event handlers may register new sockets and timers, and +// cancel sockets. Returns 0 if interrupted, -1 if canceled by a handler. +CZMQ_EXPORT int + zloop_start (zloop_t *self); + +// Self test of this class. +CZMQ_EXPORT void + zloop_test (bool verbose); + +#ifdef CZMQ_BUILD_DRAFT_API +// *** Draft method, for development use, may change without warning *** +// By default the reactor stops if the process receives a SIGINT or SIGTERM +// signal. This makes it impossible to shut-down message based architectures +// like zactors. This method lets you switch off break handling. The default +// nonstop setting is off (false). +CZMQ_EXPORT void + zloop_set_nonstop (zloop_t *self, bool nonstop); + +#endif // CZMQ_BUILD_DRAFT_API +// @end + + +// Deprecated method aliases +#define zloop_set_tolerant(s,i) zloop_poller_set_tolerant(s,i) + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/aarch64/include/zmonitor.h b/phonelibs/zmq/aarch64/include/zmonitor.h new file mode 100644 index 00000000000000..b490bcb1a0dfbc --- /dev/null +++ b/phonelibs/zmq/aarch64/include/zmonitor.h @@ -0,0 +1,73 @@ +/* ========================================================================= + zmonitor - socket event monitor + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZMONITOR_H_INCLUDED__ +#define __ZMONITOR_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @interface +// Create new zmonitor actor instance to monitor a zsock_t socket: +// +// zactor_t *monitor = zactor_new (zmonitor, mysocket); +// +// Destroy zmonitor instance. +// +// zactor_destroy (&monitor); +// +// Enable verbose logging of commands and activity. +// +// zstr_send (monitor, "VERBOSE"); +// +// Listen to monitor event type (zero or types, ending in NULL): +// zstr_sendx (monitor, "LISTEN", type, ..., NULL); +// +// Events: +// CONNECTED +// CONNECT_DELAYED +// CONNECT_RETRIED +// LISTENING +// BIND_FAILED +// ACCEPTED +// ACCEPT_FAILED +// CLOSED +// CLOSE_FAILED +// DISCONNECTED +// MONITOR_STOPPED +// ALL +// +// Start monitor; after this, any further LISTEN commands are ignored. +// +// zstr_send (monitor, "START"); +// zsock_wait (monitor); +// +// Receive next monitor event: +// +// zmsg_t *msg = zmsg_recv (monitor); +// +// This is the zmonitor constructor as a zactor_fn; the argument can be +// a zactor_t, zsock_t, or libzmq void * socket: +CZMQ_EXPORT void + zmonitor (zsock_t *pipe, void *sock); + +// Selftest +CZMQ_EXPORT void + zmonitor_test (bool verbose); +// @end +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/aarch64/include/zmonitor_v2.h b/phonelibs/zmq/aarch64/include/zmonitor_v2.h new file mode 100644 index 00000000000000..5780e0bcb785ae --- /dev/null +++ b/phonelibs/zmq/aarch64/include/zmonitor_v2.h @@ -0,0 +1,56 @@ +/* ========================================================================= + zmonitor_v2 - socket event monitor (deprecated) + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZMONITOR_V2_H_INCLUDED__ +#define __ZMONITOR_V2_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @interface +// This code needs backporting to work with ZMQ v3.2 +#if (ZMQ_VERSION_MAJOR == 4) + +// Create a new socket monitor +CZMQ_EXPORT zmonitor_t * + zmonitor_new (zctx_t *ctx, void *socket, int events); + +// Destroy a socket monitor +CZMQ_EXPORT void + zmonitor_destroy (zmonitor_t **self_p); + +// Receive a status message from the monitor; if no message arrives within +// 500 msec, or the call was interrupted, returns NULL. +CZMQ_EXPORT zmsg_t * + zmonitor_recv (zmonitor_t *self); + +// Get the ZeroMQ socket, for polling +CZMQ_EXPORT void * + zmonitor_socket (zmonitor_t *self); + +// Enable verbose tracing of commands and activity +CZMQ_EXPORT void + zmonitor_set_verbose (zmonitor_t *self, bool verbose); +#endif // ZeroMQ 4.0 or later + +// Self test of this class +CZMQ_EXPORT void + zmonitor_v2_test (bool verbose); +// @end + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/aarch64/include/zmq.h b/phonelibs/zmq/aarch64/include/zmq.h new file mode 100644 index 00000000000000..5f35d1915fcd92 --- /dev/null +++ b/phonelibs/zmq/aarch64/include/zmq.h @@ -0,0 +1,617 @@ +/* + Copyright (c) 2007-2016 Contributors as noted in the AUTHORS file + + This file is part of libzmq, the ZeroMQ core engine in C++. + + libzmq is free software; you can redistribute it and/or modify it under + the terms of the GNU Lesser General Public License (LGPL) as published + by the Free Software Foundation; either version 3 of the License, or + (at your option) any later version. + + As a special exception, the Contributors give you permission to link + this library with independent modules to produce an executable, + regardless of the license terms of these independent modules, and to + copy and distribute the resulting executable under terms of your choice, + provided that you also meet, for each linked independent module, the + terms and conditions of the license of that module. An independent + module is a module which is not derived from or based on this library. + If you modify this library, you must extend this exception to your + version of the library. + + libzmq 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 this program. If not, see . + + ************************************************************************* + NOTE to contributors. This file comprises the principal public contract + for ZeroMQ API users. Any change to this file supplied in a stable + release SHOULD not break existing applications. + In practice this means that the value of constants must not change, and + that old values may not be reused for new constants. + ************************************************************************* +*/ + +#ifndef __ZMQ_H_INCLUDED__ +#define __ZMQ_H_INCLUDED__ + +/* Version macros for compile-time API version detection */ +#define ZMQ_VERSION_MAJOR 4 +#define ZMQ_VERSION_MINOR 2 +#define ZMQ_VERSION_PATCH 0 + +#define ZMQ_MAKE_VERSION(major, minor, patch) \ + ((major) * 10000 + (minor) * 100 + (patch)) +#define ZMQ_VERSION \ + ZMQ_MAKE_VERSION(ZMQ_VERSION_MAJOR, ZMQ_VERSION_MINOR, ZMQ_VERSION_PATCH) + +#ifdef __cplusplus +extern "C" { +#endif + +#if !defined _WIN32_WCE +#include +#endif +#include +#include +#if defined _WIN32 +// Set target version to Windows Server 2008, Windows Vista or higher. +// Windows XP (0x0501) is supported but without client & server socket types. +#ifndef _WIN32_WINNT +#define _WIN32_WINNT 0x0600 +#endif + +#ifdef __MINGW32__ +// Require Windows XP or higher with MinGW for getaddrinfo(). +#if(_WIN32_WINNT >= 0x0600) +#else +#undef _WIN32_WINNT +#define _WIN32_WINNT 0x0600 +#endif +#endif +#include +#endif + +/* Handle DSO symbol visibility */ +#if defined _WIN32 +# if defined ZMQ_STATIC +# define ZMQ_EXPORT +# elif defined DLL_EXPORT +# define ZMQ_EXPORT __declspec(dllexport) +# else +# define ZMQ_EXPORT __declspec(dllimport) +# endif +#else +# if defined __SUNPRO_C || defined __SUNPRO_CC +# define ZMQ_EXPORT __global +# elif (defined __GNUC__ && __GNUC__ >= 4) || defined __INTEL_COMPILER +# define ZMQ_EXPORT __attribute__ ((visibility("default"))) +# else +# define ZMQ_EXPORT +# endif +#endif + +/* Define integer types needed for event interface */ +#define ZMQ_DEFINED_STDINT 1 +#if defined ZMQ_HAVE_SOLARIS || defined ZMQ_HAVE_OPENVMS +# include +#elif defined _MSC_VER && _MSC_VER < 1600 +# ifndef int32_t + typedef __int32 int32_t; +# endif +# ifndef uint16_t + typedef unsigned __int16 uint16_t; +# endif +# ifndef uint8_t + typedef unsigned __int8 uint8_t; +# endif +#else +# include +#endif + + +/******************************************************************************/ +/* 0MQ errors. */ +/******************************************************************************/ + +/* A number random enough not to collide with different errno ranges on */ +/* different OSes. The assumption is that error_t is at least 32-bit type. */ +#define ZMQ_HAUSNUMERO 156384712 + +/* On Windows platform some of the standard POSIX errnos are not defined. */ +#ifndef ENOTSUP +#define ENOTSUP (ZMQ_HAUSNUMERO + 1) +#endif +#ifndef EPROTONOSUPPORT +#define EPROTONOSUPPORT (ZMQ_HAUSNUMERO + 2) +#endif +#ifndef ENOBUFS +#define ENOBUFS (ZMQ_HAUSNUMERO + 3) +#endif +#ifndef ENETDOWN +#define ENETDOWN (ZMQ_HAUSNUMERO + 4) +#endif +#ifndef EADDRINUSE +#define EADDRINUSE (ZMQ_HAUSNUMERO + 5) +#endif +#ifndef EADDRNOTAVAIL +#define EADDRNOTAVAIL (ZMQ_HAUSNUMERO + 6) +#endif +#ifndef ECONNREFUSED +#define ECONNREFUSED (ZMQ_HAUSNUMERO + 7) +#endif +#ifndef EINPROGRESS +#define EINPROGRESS (ZMQ_HAUSNUMERO + 8) +#endif +#ifndef ENOTSOCK +#define ENOTSOCK (ZMQ_HAUSNUMERO + 9) +#endif +#ifndef EMSGSIZE +#define EMSGSIZE (ZMQ_HAUSNUMERO + 10) +#endif +#ifndef EAFNOSUPPORT +#define EAFNOSUPPORT (ZMQ_HAUSNUMERO + 11) +#endif +#ifndef ENETUNREACH +#define ENETUNREACH (ZMQ_HAUSNUMERO + 12) +#endif +#ifndef ECONNABORTED +#define ECONNABORTED (ZMQ_HAUSNUMERO + 13) +#endif +#ifndef ECONNRESET +#define ECONNRESET (ZMQ_HAUSNUMERO + 14) +#endif +#ifndef ENOTCONN +#define ENOTCONN (ZMQ_HAUSNUMERO + 15) +#endif +#ifndef ETIMEDOUT +#define ETIMEDOUT (ZMQ_HAUSNUMERO + 16) +#endif +#ifndef EHOSTUNREACH +#define EHOSTUNREACH (ZMQ_HAUSNUMERO + 17) +#endif +#ifndef ENETRESET +#define ENETRESET (ZMQ_HAUSNUMERO + 18) +#endif + +/* Native 0MQ error codes. */ +#define EFSM (ZMQ_HAUSNUMERO + 51) +#define ENOCOMPATPROTO (ZMQ_HAUSNUMERO + 52) +#define ETERM (ZMQ_HAUSNUMERO + 53) +#define EMTHREAD (ZMQ_HAUSNUMERO + 54) + +/* This function retrieves the errno as it is known to 0MQ library. The goal */ +/* of this function is to make the code 100% portable, including where 0MQ */ +/* compiled with certain CRT library (on Windows) is linked to an */ +/* application that uses different CRT library. */ +ZMQ_EXPORT int zmq_errno (void); + +/* Resolves system errors and 0MQ errors to human-readable string. */ +ZMQ_EXPORT const char *zmq_strerror (int errnum); + +/* Run-time API version detection */ +ZMQ_EXPORT void zmq_version (int *major, int *minor, int *patch); + +/******************************************************************************/ +/* 0MQ infrastructure (a.k.a. context) initialisation & termination. */ +/******************************************************************************/ + +/* Context options */ +#define ZMQ_IO_THREADS 1 +#define ZMQ_MAX_SOCKETS 2 +#define ZMQ_SOCKET_LIMIT 3 +#define ZMQ_THREAD_PRIORITY 3 +#define ZMQ_THREAD_SCHED_POLICY 4 +#define ZMQ_MAX_MSGSZ 5 + +/* Default for new contexts */ +#define ZMQ_IO_THREADS_DFLT 1 +#define ZMQ_MAX_SOCKETS_DFLT 1023 +#define ZMQ_THREAD_PRIORITY_DFLT -1 +#define ZMQ_THREAD_SCHED_POLICY_DFLT -1 + +ZMQ_EXPORT void *zmq_ctx_new (void); +ZMQ_EXPORT int zmq_ctx_term (void *context); +ZMQ_EXPORT int zmq_ctx_shutdown (void *context); +ZMQ_EXPORT int zmq_ctx_set (void *context, int option, int optval); +ZMQ_EXPORT int zmq_ctx_get (void *context, int option); + +/* Old (legacy) API */ +ZMQ_EXPORT void *zmq_init (int io_threads); +ZMQ_EXPORT int zmq_term (void *context); +ZMQ_EXPORT int zmq_ctx_destroy (void *context); + + +/******************************************************************************/ +/* 0MQ message definition. */ +/******************************************************************************/ + +/* union here ensures correct alignment on architectures that require it, e.g. + * SPARC + */ +typedef union zmq_msg_t {unsigned char _ [64]; void *p; } zmq_msg_t; + +typedef void (zmq_free_fn) (void *data, void *hint); + +ZMQ_EXPORT int zmq_msg_init (zmq_msg_t *msg); +ZMQ_EXPORT int zmq_msg_init_size (zmq_msg_t *msg, size_t size); +ZMQ_EXPORT int zmq_msg_init_data (zmq_msg_t *msg, void *data, + size_t size, zmq_free_fn *ffn, void *hint); +ZMQ_EXPORT int zmq_msg_send (zmq_msg_t *msg, void *s, int flags); +ZMQ_EXPORT int zmq_msg_recv (zmq_msg_t *msg, void *s, int flags); +ZMQ_EXPORT int zmq_msg_close (zmq_msg_t *msg); +ZMQ_EXPORT int zmq_msg_move (zmq_msg_t *dest, zmq_msg_t *src); +ZMQ_EXPORT int zmq_msg_copy (zmq_msg_t *dest, zmq_msg_t *src); +ZMQ_EXPORT void *zmq_msg_data (zmq_msg_t *msg); +ZMQ_EXPORT size_t zmq_msg_size (zmq_msg_t *msg); +ZMQ_EXPORT int zmq_msg_more (zmq_msg_t *msg); +ZMQ_EXPORT int zmq_msg_get (zmq_msg_t *msg, int property); +ZMQ_EXPORT int zmq_msg_set (zmq_msg_t *msg, int property, int optval); +ZMQ_EXPORT const char *zmq_msg_gets (zmq_msg_t *msg, const char *property); + +/******************************************************************************/ +/* 0MQ socket definition. */ +/******************************************************************************/ + +/* Socket types. */ +#define ZMQ_PAIR 0 +#define ZMQ_PUB 1 +#define ZMQ_SUB 2 +#define ZMQ_REQ 3 +#define ZMQ_REP 4 +#define ZMQ_DEALER 5 +#define ZMQ_ROUTER 6 +#define ZMQ_PULL 7 +#define ZMQ_PUSH 8 +#define ZMQ_XPUB 9 +#define ZMQ_XSUB 10 +#define ZMQ_STREAM 11 + +/* Deprecated aliases */ +#define ZMQ_XREQ ZMQ_DEALER +#define ZMQ_XREP ZMQ_ROUTER + +/* Socket options. */ +#define ZMQ_AFFINITY 4 +#define ZMQ_IDENTITY 5 +#define ZMQ_SUBSCRIBE 6 +#define ZMQ_UNSUBSCRIBE 7 +#define ZMQ_RATE 8 +#define ZMQ_RECOVERY_IVL 9 +#define ZMQ_SNDBUF 11 +#define ZMQ_RCVBUF 12 +#define ZMQ_RCVMORE 13 +#define ZMQ_FD 14 +#define ZMQ_EVENTS 15 +#define ZMQ_TYPE 16 +#define ZMQ_LINGER 17 +#define ZMQ_RECONNECT_IVL 18 +#define ZMQ_BACKLOG 19 +#define ZMQ_RECONNECT_IVL_MAX 21 +#define ZMQ_MAXMSGSIZE 22 +#define ZMQ_SNDHWM 23 +#define ZMQ_RCVHWM 24 +#define ZMQ_MULTICAST_HOPS 25 +#define ZMQ_RCVTIMEO 27 +#define ZMQ_SNDTIMEO 28 +#define ZMQ_LAST_ENDPOINT 32 +#define ZMQ_ROUTER_MANDATORY 33 +#define ZMQ_TCP_KEEPALIVE 34 +#define ZMQ_TCP_KEEPALIVE_CNT 35 +#define ZMQ_TCP_KEEPALIVE_IDLE 36 +#define ZMQ_TCP_KEEPALIVE_INTVL 37 +#define ZMQ_IMMEDIATE 39 +#define ZMQ_XPUB_VERBOSE 40 +#define ZMQ_ROUTER_RAW 41 +#define ZMQ_IPV6 42 +#define ZMQ_MECHANISM 43 +#define ZMQ_PLAIN_SERVER 44 +#define ZMQ_PLAIN_USERNAME 45 +#define ZMQ_PLAIN_PASSWORD 46 +#define ZMQ_CURVE_SERVER 47 +#define ZMQ_CURVE_PUBLICKEY 48 +#define ZMQ_CURVE_SECRETKEY 49 +#define ZMQ_CURVE_SERVERKEY 50 +#define ZMQ_PROBE_ROUTER 51 +#define ZMQ_REQ_CORRELATE 52 +#define ZMQ_REQ_RELAXED 53 +#define ZMQ_CONFLATE 54 +#define ZMQ_ZAP_DOMAIN 55 +#define ZMQ_ROUTER_HANDOVER 56 +#define ZMQ_TOS 57 +#define ZMQ_CONNECT_RID 61 +#define ZMQ_GSSAPI_SERVER 62 +#define ZMQ_GSSAPI_PRINCIPAL 63 +#define ZMQ_GSSAPI_SERVICE_PRINCIPAL 64 +#define ZMQ_GSSAPI_PLAINTEXT 65 +#define ZMQ_HANDSHAKE_IVL 66 +#define ZMQ_SOCKS_PROXY 68 +#define ZMQ_XPUB_NODROP 69 +// All options after this is for version 4.2 and still *draft* +// Subject to arbitrary change without notice +#define ZMQ_BLOCKY 70 +#define ZMQ_XPUB_MANUAL 71 +#define ZMQ_XPUB_WELCOME_MSG 72 +#define ZMQ_STREAM_NOTIFY 73 +#define ZMQ_INVERT_MATCHING 74 +#define ZMQ_HEARTBEAT_IVL 75 +#define ZMQ_HEARTBEAT_TTL 76 +#define ZMQ_HEARTBEAT_TIMEOUT 77 +#define ZMQ_XPUB_VERBOSER 78 +#define ZMQ_CONNECT_TIMEOUT 79 +#define ZMQ_TCP_MAXRT 80 +#define ZMQ_THREAD_SAFE 81 +#define ZMQ_MULTICAST_MAXTPDU 84 +#define ZMQ_VMCI_BUFFER_SIZE 85 +#define ZMQ_VMCI_BUFFER_MIN_SIZE 86 +#define ZMQ_VMCI_BUFFER_MAX_SIZE 87 +#define ZMQ_VMCI_CONNECT_TIMEOUT 88 +#define ZMQ_USE_FD 89 + +/* Message options */ +#define ZMQ_MORE 1 +#define ZMQ_SHARED 3 + +/* Send/recv options. */ +#define ZMQ_DONTWAIT 1 +#define ZMQ_SNDMORE 2 + +/* Security mechanisms */ +#define ZMQ_NULL 0 +#define ZMQ_PLAIN 1 +#define ZMQ_CURVE 2 +#define ZMQ_GSSAPI 3 + +/* RADIO-DISH protocol */ +#define ZMQ_GROUP_MAX_LENGTH 15 + +/* Deprecated options and aliases */ +#define ZMQ_TCP_ACCEPT_FILTER 38 +#define ZMQ_IPC_FILTER_PID 58 +#define ZMQ_IPC_FILTER_UID 59 +#define ZMQ_IPC_FILTER_GID 60 +#define ZMQ_IPV4ONLY 31 +#define ZMQ_DELAY_ATTACH_ON_CONNECT ZMQ_IMMEDIATE +#define ZMQ_NOBLOCK ZMQ_DONTWAIT +#define ZMQ_FAIL_UNROUTABLE ZMQ_ROUTER_MANDATORY +#define ZMQ_ROUTER_BEHAVIOR ZMQ_ROUTER_MANDATORY + +/* Deprecated Message options */ +#define ZMQ_SRCFD 2 + +/******************************************************************************/ +/* 0MQ socket events and monitoring */ +/******************************************************************************/ + +/* Socket transport events (TCP, IPC and TIPC only) */ + +#define ZMQ_EVENT_CONNECTED 0x0001 +#define ZMQ_EVENT_CONNECT_DELAYED 0x0002 +#define ZMQ_EVENT_CONNECT_RETRIED 0x0004 +#define ZMQ_EVENT_LISTENING 0x0008 +#define ZMQ_EVENT_BIND_FAILED 0x0010 +#define ZMQ_EVENT_ACCEPTED 0x0020 +#define ZMQ_EVENT_ACCEPT_FAILED 0x0040 +#define ZMQ_EVENT_CLOSED 0x0080 +#define ZMQ_EVENT_CLOSE_FAILED 0x0100 +#define ZMQ_EVENT_DISCONNECTED 0x0200 +#define ZMQ_EVENT_MONITOR_STOPPED 0x0400 +#define ZMQ_EVENT_ALL 0xFFFF + +ZMQ_EXPORT void *zmq_socket (void *, int type); +ZMQ_EXPORT int zmq_close (void *s); +ZMQ_EXPORT int zmq_setsockopt (void *s, int option, const void *optval, + size_t optvallen); +ZMQ_EXPORT int zmq_getsockopt (void *s, int option, void *optval, + size_t *optvallen); +ZMQ_EXPORT int zmq_bind (void *s, const char *addr); +ZMQ_EXPORT int zmq_connect (void *s, const char *addr); +ZMQ_EXPORT int zmq_unbind (void *s, const char *addr); +ZMQ_EXPORT int zmq_disconnect (void *s, const char *addr); +ZMQ_EXPORT int zmq_send (void *s, const void *buf, size_t len, int flags); +ZMQ_EXPORT int zmq_send_const (void *s, const void *buf, size_t len, int flags); +ZMQ_EXPORT int zmq_recv (void *s, void *buf, size_t len, int flags); +ZMQ_EXPORT int zmq_socket_monitor (void *s, const char *addr, int events); + + +/******************************************************************************/ +/* I/O multiplexing. */ +/******************************************************************************/ + +#define ZMQ_POLLIN 1 +#define ZMQ_POLLOUT 2 +#define ZMQ_POLLERR 4 +#define ZMQ_POLLPRI 8 + +typedef struct zmq_pollitem_t +{ + void *socket; +#if defined _WIN32 + SOCKET fd; +#else + int fd; +#endif + short events; + short revents; +} zmq_pollitem_t; + +#define ZMQ_POLLITEMS_DFLT 16 + +ZMQ_EXPORT int zmq_poll (zmq_pollitem_t *items, int nitems, long timeout); + +/******************************************************************************/ +/* Message proxying */ +/******************************************************************************/ + +ZMQ_EXPORT int zmq_proxy (void *frontend, void *backend, void *capture); +ZMQ_EXPORT int zmq_proxy_steerable (void *frontend, void *backend, void *capture, void *control); + +/******************************************************************************/ +/* Probe library capabilities */ +/******************************************************************************/ + +#define ZMQ_HAS_CAPABILITIES 1 +ZMQ_EXPORT int zmq_has (const char *capability); + +/* Deprecated aliases */ +#define ZMQ_STREAMER 1 +#define ZMQ_FORWARDER 2 +#define ZMQ_QUEUE 3 + +/* Deprecated methods */ +ZMQ_EXPORT int zmq_device (int type, void *frontend, void *backend); +ZMQ_EXPORT int zmq_sendmsg (void *s, zmq_msg_t *msg, int flags); +ZMQ_EXPORT int zmq_recvmsg (void *s, zmq_msg_t *msg, int flags); +struct iovec; +ZMQ_EXPORT int zmq_sendiov (void *s, struct iovec *iov, size_t count, int flags); +ZMQ_EXPORT int zmq_recviov (void *s, struct iovec *iov, size_t *count, int flags); + +/******************************************************************************/ +/* Encryption functions */ +/******************************************************************************/ + +/* Encode data with Z85 encoding. Returns encoded data */ +ZMQ_EXPORT char *zmq_z85_encode (char *dest, const uint8_t *data, size_t size); + +/* Decode data with Z85 encoding. Returns decoded data */ +ZMQ_EXPORT uint8_t *zmq_z85_decode (uint8_t *dest, const char *string); + +/* Generate z85-encoded public and private keypair with tweetnacl/libsodium. */ +/* Returns 0 on success. */ +ZMQ_EXPORT int zmq_curve_keypair (char *z85_public_key, char *z85_secret_key); + +/* Derive the z85-encoded public key from the z85-encoded secret key. */ +/* Returns 0 on success. */ +ZMQ_EXPORT int zmq_curve_public (char *z85_public_key, const char *z85_secret_key); + +/******************************************************************************/ +/* Atomic utility methods */ +/******************************************************************************/ + +ZMQ_EXPORT void *zmq_atomic_counter_new (void); +ZMQ_EXPORT void zmq_atomic_counter_set (void *counter, int value); +ZMQ_EXPORT int zmq_atomic_counter_inc (void *counter); +ZMQ_EXPORT int zmq_atomic_counter_dec (void *counter); +ZMQ_EXPORT int zmq_atomic_counter_value (void *counter); +ZMQ_EXPORT void zmq_atomic_counter_destroy (void **counter_p); + + +/******************************************************************************/ +/* These functions are not documented by man pages -- use at your own risk. */ +/* If you need these to be part of the formal ZMQ API, then (a) write a man */ +/* page, and (b) write a test case in tests. */ +/******************************************************************************/ + +/* Helper functions are used by perf tests so that they don't have to care */ +/* about minutiae of time-related functions on different OS platforms. */ + +/* Starts the stopwatch. Returns the handle to the watch. */ +ZMQ_EXPORT void *zmq_stopwatch_start (void); + +/* Stops the stopwatch. Returns the number of microseconds elapsed since */ +/* the stopwatch was started. */ +ZMQ_EXPORT unsigned long zmq_stopwatch_stop (void *watch_); + +/* Sleeps for specified number of seconds. */ +ZMQ_EXPORT void zmq_sleep (int seconds_); + +typedef void (zmq_thread_fn) (void*); + +/* Start a thread. Returns a handle to the thread. */ +ZMQ_EXPORT void *zmq_threadstart (zmq_thread_fn* func, void* arg); + +/* Wait for thread to complete then free up resources. */ +ZMQ_EXPORT void zmq_threadclose (void* thread); + + +/******************************************************************************/ +/* These functions are DRAFT and disabled in stable releases, and subject to */ +/* change at ANY time until declared stable. */ +/******************************************************************************/ + +#ifdef ZMQ_BUILD_DRAFT_API + +/* DRAFT Socket types. */ +#define ZMQ_SERVER 12 +#define ZMQ_CLIENT 13 +#define ZMQ_RADIO 14 +#define ZMQ_DISH 15 +#define ZMQ_GATHER 16 +#define ZMQ_SCATTER 17 +#define ZMQ_DGRAM 18 + +/* DRAFT Socket methods. */ +ZMQ_EXPORT int zmq_join (void *s, const char *group); +ZMQ_EXPORT int zmq_leave (void *s, const char *group); + +/* DRAFT Msg methods. */ +ZMQ_EXPORT int zmq_msg_set_routing_id(zmq_msg_t *msg, uint32_t routing_id); +ZMQ_EXPORT uint32_t zmq_msg_routing_id(zmq_msg_t *msg); +ZMQ_EXPORT int zmq_msg_set_group(zmq_msg_t *msg, const char *group); +ZMQ_EXPORT const char *zmq_msg_group(zmq_msg_t *msg); + +/******************************************************************************/ +/* Poller polling on sockets,fd and thread-safe sockets */ +/******************************************************************************/ + +#define ZMQ_HAVE_POLLER + +typedef struct zmq_poller_event_t +{ + void *socket; +#if defined _WIN32 + SOCKET fd; +#else + int fd; +#endif + void *user_data; + short events; +} zmq_poller_event_t; + +ZMQ_EXPORT void *zmq_poller_new (void); +ZMQ_EXPORT int zmq_poller_destroy (void **poller_p); +ZMQ_EXPORT int zmq_poller_add (void *poller, void *socket, void *user_data, short events); +ZMQ_EXPORT int zmq_poller_modify (void *poller, void *socket, short events); +ZMQ_EXPORT int zmq_poller_remove (void *poller, void *socket); +ZMQ_EXPORT int zmq_poller_wait (void *poller, zmq_poller_event_t *event, long timeout); + +#if defined _WIN32 +ZMQ_EXPORT int zmq_poller_add_fd (void *poller, SOCKET fd, void *user_data, short events); +ZMQ_EXPORT int zmq_poller_modify_fd (void *poller, SOCKET fd, short events); +ZMQ_EXPORT int zmq_poller_remove_fd (void *poller, SOCKET fd); +#else +ZMQ_EXPORT int zmq_poller_add_fd (void *poller, int fd, void *user_data, short events); +ZMQ_EXPORT int zmq_poller_modify_fd (void *poller, int fd, short events); +ZMQ_EXPORT int zmq_poller_remove_fd (void *poller, int fd); +#endif + +/******************************************************************************/ +/* Scheduling timers */ +/******************************************************************************/ + +#define ZMQ_HAVE_TIMERS + +typedef void (zmq_timer_fn)(int timer_id, void *arg); + +ZMQ_EXPORT void *zmq_timers_new (void); +ZMQ_EXPORT int zmq_timers_destroy (void **timers_p); +ZMQ_EXPORT int zmq_timers_add (void *timers, size_t interval, zmq_timer_fn handler, void *arg); +ZMQ_EXPORT int zmq_timers_cancel (void *timers, int timer_id); +ZMQ_EXPORT int zmq_timers_set_interval (void *timers, int timer_id, size_t interval); +ZMQ_EXPORT int zmq_timers_reset (void *timers, int timer_id); +ZMQ_EXPORT long zmq_timers_timeout (void *timers); +ZMQ_EXPORT int zmq_timers_execute (void *timers); + +#endif // ZMQ_BUILD_DRAFT_API + + +#undef ZMQ_EXPORT + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/aarch64/include/zmq_utils.h b/phonelibs/zmq/aarch64/include/zmq_utils.h new file mode 100644 index 00000000000000..f29638d5539414 --- /dev/null +++ b/phonelibs/zmq/aarch64/include/zmq_utils.h @@ -0,0 +1,48 @@ +/* + Copyright (c) 2007-2016 Contributors as noted in the AUTHORS file + + This file is part of libzmq, the ZeroMQ core engine in C++. + + libzmq is free software; you can redistribute it and/or modify it under + the terms of the GNU Lesser General Public License (LGPL) as published + by the Free Software Foundation; either version 3 of the License, or + (at your option) any later version. + + As a special exception, the Contributors give you permission to link + this library with independent modules to produce an executable, + regardless of the license terms of these independent modules, and to + copy and distribute the resulting executable under terms of your choice, + provided that you also meet, for each linked independent module, the + terms and conditions of the license of that module. An independent + module is a module which is not derived from or based on this library. + If you modify this library, you must extend this exception to your + version of the library. + + libzmq 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 this program. If not, see . +*/ + +/* This file is deprecated, and all its functionality provided by zmq.h */ +/* Note that -Wpedantic compilation requires GCC to avoid using its custom + extensions such as #warning, hence the trick below. Also, pragmas for + warnings or other messages are not standard, not portable, and not all + compilers even have an equivalent concept. + So in the worst case, this include file is treated as silently empty. */ + +#if defined(__clang__) || defined(__GNUC__) || defined(__GNUG__) || defined(_MSC_VER) +#if defined(__GNUC__) || defined(__GNUG__) +#pragma GCC diagnostic push +#pragma GCC diagnostic warning "-Wcpp" +#pragma GCC diagnostic ignored "-Werror" +#pragma GCC diagnostic ignored "-Wall" +#endif +#pragma message("Warning: zmq_utils.h is deprecated. All its functionality is provided by zmq.h.") +#if defined(__GNUC__) || defined(__GNUG__) +#pragma GCC diagnostic pop +#endif +#endif diff --git a/phonelibs/zmq/aarch64/include/zmsg.h b/phonelibs/zmq/aarch64/include/zmsg.h new file mode 100644 index 00000000000000..c6ab16c66e953c --- /dev/null +++ b/phonelibs/zmq/aarch64/include/zmsg.h @@ -0,0 +1,285 @@ +/* ========================================================================= + zmsg - working with multipart messages + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZMSG_H_INCLUDED__ +#define __ZMSG_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/zmsg.api" to make changes. +// @interface +// This is a stable class, and may not change except for emergencies. It +// is provided in stable builds. +// This class has draft methods, which may change over time. They are not +// in stable releases, by default. Use --enable-drafts to enable. +// Create a new empty message object +CZMQ_EXPORT zmsg_t * + zmsg_new (void); + +// Receive message from socket, returns zmsg_t object or NULL if the recv +// was interrupted. Does a blocking recv. If you want to not block then use +// the zloop class or zmsg_recv_nowait or zmq_poll to check for socket input +// before receiving. +CZMQ_EXPORT zmsg_t * + zmsg_recv (void *source); + +// Load/append an open file into new message, return the message. +// Returns NULL if the message could not be loaded. +CZMQ_EXPORT zmsg_t * + zmsg_load (FILE *file); + +// Decodes a serialized message frame created by zmsg_encode () and returns +// a new zmsg_t object. Returns NULL if the frame was badly formatted or +// there was insufficient memory to work. +CZMQ_EXPORT zmsg_t * + zmsg_decode (zframe_t *frame); + +// Generate a signal message encoding the given status. A signal is a short +// message carrying a 1-byte success/failure code (by convention, 0 means +// OK). Signals are encoded to be distinguishable from "normal" messages. +CZMQ_EXPORT zmsg_t * + zmsg_new_signal (byte status); + +// Destroy a message object and all frames it contains +CZMQ_EXPORT void + zmsg_destroy (zmsg_t **self_p); + +// Send message to destination socket, and destroy the message after sending +// it successfully. If the message has no frames, sends nothing but destroys +// the message anyhow. Nullifies the caller's reference to the message (as +// it is a destructor). +CZMQ_EXPORT int + zmsg_send (zmsg_t **self_p, void *dest); + +// Send message to destination socket as part of a multipart sequence, and +// destroy the message after sending it successfully. Note that after a +// zmsg_sendm, you must call zmsg_send or another method that sends a final +// message part. If the message has no frames, sends nothing but destroys +// the message anyhow. Nullifies the caller's reference to the message (as +// it is a destructor). +CZMQ_EXPORT int + zmsg_sendm (zmsg_t **self_p, void *dest); + +// Return size of message, i.e. number of frames (0 or more). +CZMQ_EXPORT size_t + zmsg_size (zmsg_t *self); + +// Return total size of all frames in message. +CZMQ_EXPORT size_t + zmsg_content_size (zmsg_t *self); + +// Push frame to the front of the message, i.e. before all other frames. +// Message takes ownership of frame, will destroy it when message is sent. +// Returns 0 on success, -1 on error. Deprecates zmsg_push, which did not +// nullify the caller's frame reference. +CZMQ_EXPORT int + zmsg_prepend (zmsg_t *self, zframe_t **frame_p); + +// Add frame to the end of the message, i.e. after all other frames. +// Message takes ownership of frame, will destroy it when message is sent. +// Returns 0 on success. Deprecates zmsg_add, which did not nullify the +// caller's frame reference. +CZMQ_EXPORT int + zmsg_append (zmsg_t *self, zframe_t **frame_p); + +// Remove first frame from message, if any. Returns frame, or NULL. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zframe_t * + zmsg_pop (zmsg_t *self); + +// Push block of memory to front of message, as a new frame. +// Returns 0 on success, -1 on error. +CZMQ_EXPORT int + zmsg_pushmem (zmsg_t *self, const void *data, size_t size); + +// Add block of memory to the end of the message, as a new frame. +// Returns 0 on success, -1 on error. +CZMQ_EXPORT int + zmsg_addmem (zmsg_t *self, const void *data, size_t size); + +// Push string as new frame to front of message. +// Returns 0 on success, -1 on error. +CZMQ_EXPORT int + zmsg_pushstr (zmsg_t *self, const char *string); + +// Push string as new frame to end of message. +// Returns 0 on success, -1 on error. +CZMQ_EXPORT int + zmsg_addstr (zmsg_t *self, const char *string); + +// Push formatted string as new frame to front of message. +// Returns 0 on success, -1 on error. +CZMQ_EXPORT int + zmsg_pushstrf (zmsg_t *self, const char *format, ...); + +// Push formatted string as new frame to end of message. +// Returns 0 on success, -1 on error. +CZMQ_EXPORT int + zmsg_addstrf (zmsg_t *self, const char *format, ...); + +// Pop frame off front of message, return as fresh string. If there were +// no more frames in the message, returns NULL. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT char * + zmsg_popstr (zmsg_t *self); + +// Push encoded message as a new frame. Message takes ownership of +// submessage, so the original is destroyed in this call. Returns 0 on +// success, -1 on error. +CZMQ_EXPORT int + zmsg_addmsg (zmsg_t *self, zmsg_t **msg_p); + +// Remove first submessage from message, if any. Returns zmsg_t, or NULL if +// decoding was not successful. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zmsg_t * + zmsg_popmsg (zmsg_t *self); + +// Remove specified frame from list, if present. Does not destroy frame. +CZMQ_EXPORT void + zmsg_remove (zmsg_t *self, zframe_t *frame); + +// Set cursor to first frame in message. Returns frame, or NULL, if the +// message is empty. Use this to navigate the frames as a list. +CZMQ_EXPORT zframe_t * + zmsg_first (zmsg_t *self); + +// Return the next frame. If there are no more frames, returns NULL. To move +// to the first frame call zmsg_first(). Advances the cursor. +CZMQ_EXPORT zframe_t * + zmsg_next (zmsg_t *self); + +// Return the last frame. If there are no frames, returns NULL. +CZMQ_EXPORT zframe_t * + zmsg_last (zmsg_t *self); + +// Save message to an open file, return 0 if OK, else -1. The message is +// saved as a series of frames, each with length and data. Note that the +// file is NOT guaranteed to be portable between operating systems, not +// versions of CZMQ. The file format is at present undocumented and liable +// to arbitrary change. +CZMQ_EXPORT int + zmsg_save (zmsg_t *self, FILE *file); + +// Serialize multipart message to a single message frame. Use this method +// to send structured messages across transports that do not support +// multipart data. Allocates and returns a new frame containing the +// serialized message. To decode a serialized message frame, use +// zmsg_decode (). +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zframe_t * + zmsg_encode (zmsg_t *self); + +// Create copy of message, as new message object. Returns a fresh zmsg_t +// object. If message is null, or memory was exhausted, returns null. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zmsg_t * + zmsg_dup (zmsg_t *self); + +// Send message to zsys log sink (may be stdout, or system facility as +// configured by zsys_set_logstream). +CZMQ_EXPORT void + zmsg_print (zmsg_t *self); + +// Return true if the two messages have the same number of frames and each +// frame in the first message is identical to the corresponding frame in the +// other message. As with zframe_eq, return false if either message is NULL. +CZMQ_EXPORT bool + zmsg_eq (zmsg_t *self, zmsg_t *other); + +// Return signal value, 0 or greater, if message is a signal, -1 if not. +CZMQ_EXPORT int + zmsg_signal (zmsg_t *self); + +// Probe the supplied object, and report if it looks like a zmsg_t. +CZMQ_EXPORT bool + zmsg_is (void *self); + +// Self test of this class. +CZMQ_EXPORT void + zmsg_test (bool verbose); + +#ifdef CZMQ_BUILD_DRAFT_API +// *** Draft method, for development use, may change without warning *** +// Return message routing ID, if the message came from a ZMQ_SERVER socket. +// Else returns zero. +CZMQ_EXPORT uint32_t + zmsg_routing_id (zmsg_t *self); + +// *** Draft method, for development use, may change without warning *** +// Set routing ID on message. This is used if/when the message is sent to a +// ZMQ_SERVER socket. +CZMQ_EXPORT void + zmsg_set_routing_id (zmsg_t *self, uint32_t routing_id); + +#endif // CZMQ_BUILD_DRAFT_API +// @ignore +CZMQ_EXPORT int + zmsg_pushstrf (zmsg_t *self, const char *format, ...) CHECK_PRINTF (2); +CZMQ_EXPORT int + zmsg_addstrf (zmsg_t *self, const char *format, ...) CHECK_PRINTF (2); +// @end + + +// DEPRECATED as over-engineered, poor style +// Pop frame off front of message, caller now owns frame +// If next frame is empty, pops and destroys that empty frame. +CZMQ_EXPORT zframe_t * + zmsg_unwrap (zmsg_t *self); + +// DEPRECATED as poor style -- callers should use zloop or zpoller +// Receive message from socket, returns zmsg_t object, or NULL either if +// there was no input waiting, or the recv was interrupted. +CZMQ_EXPORT zmsg_t * + zmsg_recv_nowait (void *source); + +// DEPRECATED as unsafe -- does not nullify frame reference. +// Push frame plus empty frame to front of message, before first frame. +// Message takes ownership of frame, will destroy it when message is sent. +CZMQ_EXPORT void + zmsg_wrap (zmsg_t *self, zframe_t *frame); + +// DEPRECATED - will be removed for next + 1 stable release +// Add frame to the front of the message, i.e. before all other frames. +// Message takes ownership of frame, will destroy it when message is sent. +// Returns 0 on success, -1 on error. +CZMQ_EXPORT int + zmsg_push (zmsg_t *self, zframe_t *frame); + +// DEPRECATED - will be removed for next stable release +CZMQ_EXPORT int + zmsg_add (zmsg_t *self, zframe_t *frame); + +// DEPRECATED as inconsistent; breaks principle that logging should all go +// to a single destination. +// Print message to open stream +// Truncates to first 10 frames, for readability. +CZMQ_EXPORT void + zmsg_fprint (zmsg_t *self, FILE *file); + +// Compiler hints +CZMQ_EXPORT int zmsg_addstrf (zmsg_t *self, const char *format, ...) CHECK_PRINTF (2); +CZMQ_EXPORT int zmsg_pushstrf (zmsg_t *self, const char *format, ...) CHECK_PRINTF (2); + +#ifdef __cplusplus +} +#endif + +// Deprecated method aliases +#define zmsg_dump(s) zmsg_print(s) +#define zmsg_dump_to_stream(s,F) zmsg_fprint(s,F) + +#endif diff --git a/phonelibs/zmq/aarch64/include/zmutex.h b/phonelibs/zmq/aarch64/include/zmutex.h new file mode 100644 index 00000000000000..cba315999b7598 --- /dev/null +++ b/phonelibs/zmq/aarch64/include/zmutex.h @@ -0,0 +1,55 @@ +/* ========================================================================= + zmutex - working with mutexes + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZMUTEX_H_INCLUDED__ +#define __ZMUTEX_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @interface +// This is a deprecated class, and will be removed over time. It is +// provided in stable builds to support old applications. You should +// stop using this class, and migrate any code that is still using it. + +// Create a new mutex container +CZMQ_EXPORT zmutex_t * + zmutex_new (void); + +// Destroy a mutex container +CZMQ_EXPORT void + zmutex_destroy (zmutex_t **self_p); + +// Lock mutex +CZMQ_EXPORT void + zmutex_lock (zmutex_t *self); + +// Unlock mutex +CZMQ_EXPORT void + zmutex_unlock (zmutex_t *self); + +// Try to lock mutex +CZMQ_EXPORT int + zmutex_try_lock (zmutex_t *self); + +// Self test of this class. +CZMQ_EXPORT void + zmutex_test (bool verbose); +// @end + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/aarch64/include/zpoller.h b/phonelibs/zmq/aarch64/include/zpoller.h new file mode 100644 index 00000000000000..3756a935a64008 --- /dev/null +++ b/phonelibs/zmq/aarch64/include/zpoller.h @@ -0,0 +1,92 @@ +/* ========================================================================= + zpoller - trivial socket poller class + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __zpoller_H_INCLUDED__ +#define __zpoller_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/zpoller.api" to make changes. +// @interface +// This is a stable class, and may not change except for emergencies. It +// is provided in stable builds. +// This class has draft methods, which may change over time. They are not +// in stable releases, by default. Use --enable-drafts to enable. +// Create new poller, specifying zero or more readers. The list of +// readers ends in a NULL. Each reader can be a zsock_t instance, a +// zactor_t instance, a libzmq socket (void *), or a file handle. +CZMQ_EXPORT zpoller_t * + zpoller_new (void *reader, ...); + +// Destroy a poller +CZMQ_EXPORT void + zpoller_destroy (zpoller_t **self_p); + +// Add a reader to be polled. Returns 0 if OK, -1 on failure. The reader may +// be a libzmq void * socket, a zsock_t instance, or a zactor_t instance. +CZMQ_EXPORT int + zpoller_add (zpoller_t *self, void *reader); + +// Remove a reader from the poller; returns 0 if OK, -1 on failure. The reader +// must have been passed during construction, or in an zpoller_add () call. +CZMQ_EXPORT int + zpoller_remove (zpoller_t *self, void *reader); + +// Poll the registered readers for I/O, return first reader that has input. +// The reader will be a libzmq void * socket, or a zsock_t or zactor_t +// instance as specified in zpoller_new/zpoller_add. The timeout should be +// zero or greater, or -1 to wait indefinitely. Socket priority is defined +// by their order in the poll list. If you need a balanced poll, use the low +// level zmq_poll method directly. If the poll call was interrupted (SIGINT), +// or the ZMQ context was destroyed, or the timeout expired, returns NULL. +// You can test the actual exit condition by calling zpoller_expired () and +// zpoller_terminated (). The timeout is in msec. +CZMQ_EXPORT void * + zpoller_wait (zpoller_t *self, int timeout); + +// Return true if the last zpoller_wait () call ended because the timeout +// expired, without any error. +CZMQ_EXPORT bool + zpoller_expired (zpoller_t *self); + +// Return true if the last zpoller_wait () call ended because the process +// was interrupted, or the parent context was destroyed. +CZMQ_EXPORT bool + zpoller_terminated (zpoller_t *self); + +// Self test of this class. +CZMQ_EXPORT void + zpoller_test (bool verbose); + +#ifdef CZMQ_BUILD_DRAFT_API +// *** Draft method, for development use, may change without warning *** +// By default the poller stops if the process receives a SIGINT or SIGTERM +// signal. This makes it impossible to shut-down message based architectures +// like zactors. This method lets you switch off break handling. The default +// nonstop setting is off (false). +CZMQ_EXPORT void + zpoller_set_nonstop (zpoller_t *self, bool nonstop); + +#endif // CZMQ_BUILD_DRAFT_API +// @end + + +#ifdef __cplusplus +} +#endif + +#endif + diff --git a/phonelibs/zmq/aarch64/include/zproc.h b/phonelibs/zmq/aarch64/include/zproc.h new file mode 100644 index 00000000000000..a2e1b3dd9913c6 --- /dev/null +++ b/phonelibs/zmq/aarch64/include/zproc.h @@ -0,0 +1,179 @@ +/* ========================================================================= + zproc - process configuration and status + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef ZPROC_H_INCLUDED +#define ZPROC_H_INCLUDED + +#ifdef __cplusplus +extern "C" { +#endif + + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/zproc.api" to make changes. +// @interface +// This is a draft class, and may change without notice. It is disabled in +// stable builds by default. If you use this in applications, please ask +// for it to be pushed to stable state. Use --enable-drafts to enable. +#ifdef CZMQ_BUILD_DRAFT_API +// *** Draft method, for development use, may change without warning *** +// Returns CZMQ version as a single 6-digit integer encoding the major +// version (x 10000), the minor version (x 100) and the patch. +CZMQ_EXPORT int + zproc_czmq_version (void); + +// *** Draft method, for development use, may change without warning *** +// Returns true if the process received a SIGINT or SIGTERM signal. +// It is good practice to use this method to exit any infinite loop +// processing messages. +CZMQ_EXPORT bool + zproc_interrupted (void); + +// *** Draft method, for development use, may change without warning *** +// Returns true if the underlying libzmq supports CURVE security. +CZMQ_EXPORT bool + zproc_has_curve (void); + +// *** Draft method, for development use, may change without warning *** +// Return current host name, for use in public tcp:// endpoints. +// If the host name is not resolvable, returns NULL. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT char * + zproc_hostname (void); + +// *** Draft method, for development use, may change without warning *** +// Move the current process into the background. The precise effect +// depends on the operating system. On POSIX boxes, moves to a specified +// working directory (if specified), closes all file handles, reopens +// stdin, stdout, and stderr to the null device, and sets the process to +// ignore SIGHUP. On Windows, does nothing. Returns 0 if OK, -1 if there +// was an error. +CZMQ_EXPORT void + zproc_daemonize (const char *workdir); + +// *** Draft method, for development use, may change without warning *** +// Drop the process ID into the lockfile, with exclusive lock, and +// switch the process to the specified group and/or user. Any of the +// arguments may be null, indicating a no-op. Returns 0 on success, +// -1 on failure. Note if you combine this with zsys_daemonize, run +// after, not before that method, or the lockfile will hold the wrong +// process ID. +CZMQ_EXPORT void + zproc_run_as (const char *lockfile, const char *group, const char *user); + +// *** Draft method, for development use, may change without warning *** +// Configure the number of I/O threads that ZeroMQ will use. A good +// rule of thumb is one thread per gigabit of traffic in or out. The +// default is 1, sufficient for most applications. If the environment +// variable ZSYS_IO_THREADS is defined, that provides the default. +// Note that this method is valid only before any socket is created. +CZMQ_EXPORT void + zproc_set_io_threads (size_t io_threads); + +// *** Draft method, for development use, may change without warning *** +// Configure the number of sockets that ZeroMQ will allow. The default +// is 1024. The actual limit depends on the system, and you can query it +// by using zsys_socket_limit (). A value of zero means "maximum". +// Note that this method is valid only before any socket is created. +CZMQ_EXPORT void + zproc_set_max_sockets (size_t max_sockets); + +// *** Draft method, for development use, may change without warning *** +// Set network interface name to use for broadcasts, particularly zbeacon. +// This lets the interface be configured for test environments where required. +// For example, on Mac OS X, zbeacon cannot bind to 255.255.255.255 which is +// the default when there is no specified interface. If the environment +// variable ZSYS_INTERFACE is set, use that as the default interface name. +// Setting the interface to "*" means "use all available interfaces". +CZMQ_EXPORT void + zproc_set_biface (const char *value); + +// *** Draft method, for development use, may change without warning *** +// Return network interface to use for broadcasts, or "" if none was set. +CZMQ_EXPORT const char * + zproc_biface (void); + +// *** Draft method, for development use, may change without warning *** +// Set log identity, which is a string that prefixes all log messages sent +// by this process. The log identity defaults to the environment variable +// ZSYS_LOGIDENT, if that is set. +CZMQ_EXPORT void + zproc_set_log_ident (const char *value); + +// *** Draft method, for development use, may change without warning *** +// Sends log output to a PUB socket bound to the specified endpoint. To +// collect such log output, create a SUB socket, subscribe to the traffic +// you care about, and connect to the endpoint. Log traffic is sent as a +// single string frame, in the same format as when sent to stdout. The +// log system supports a single sender; multiple calls to this method will +// bind the same sender to multiple endpoints. To disable the sender, call +// this method with a null argument. +CZMQ_EXPORT void + zproc_set_log_sender (const char *endpoint); + +// *** Draft method, for development use, may change without warning *** +// Enable or disable logging to the system facility (syslog on POSIX boxes, +// event log on Windows). By default this is disabled. +CZMQ_EXPORT void + zproc_set_log_system (bool logsystem); + +// *** Draft method, for development use, may change without warning *** +// Log error condition - highest priority +CZMQ_EXPORT void + zproc_log_error (const char *format, ...); + +// *** Draft method, for development use, may change without warning *** +// Log warning condition - high priority +CZMQ_EXPORT void + zproc_log_warning (const char *format, ...); + +// *** Draft method, for development use, may change without warning *** +// Log normal, but significant, condition - normal priority +CZMQ_EXPORT void + zproc_log_notice (const char *format, ...); + +// *** Draft method, for development use, may change without warning *** +// Log informational message - low priority +CZMQ_EXPORT void + zproc_log_info (const char *format, ...); + +// *** Draft method, for development use, may change without warning *** +// Log debug-level message - lowest priority +CZMQ_EXPORT void + zproc_log_debug (const char *format, ...); + +// *** Draft method, for development use, may change without warning *** +// Self test of this class. +CZMQ_EXPORT void + zproc_test (bool verbose); + +#endif // CZMQ_BUILD_DRAFT_API +// @ignore +CZMQ_EXPORT void + zproc_log_error (const char *format, ...) CHECK_PRINTF (1); +CZMQ_EXPORT void + zproc_log_warning (const char *format, ...) CHECK_PRINTF (1); +CZMQ_EXPORT void + zproc_log_notice (const char *format, ...) CHECK_PRINTF (1); +CZMQ_EXPORT void + zproc_log_info (const char *format, ...) CHECK_PRINTF (1); +CZMQ_EXPORT void + zproc_log_debug (const char *format, ...) CHECK_PRINTF (1); +// @end + + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/aarch64/include/zproxy.h b/phonelibs/zmq/aarch64/include/zproxy.h new file mode 100644 index 00000000000000..f672c5e72417a5 --- /dev/null +++ b/phonelibs/zmq/aarch64/include/zproxy.h @@ -0,0 +1,111 @@ +/* ========================================================================= + zproxy - run a steerable proxy in the background + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZPROXY_H_INCLUDED__ +#define __ZPROXY_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @interface +// Create new zproxy actor instance. The proxy switches messages between +// a frontend socket and a backend socket; use the FRONTEND and BACKEND +// commands to configure these: +// +// zactor_t *proxy = zactor_new (zproxy, NULL); +// +// Destroy zproxy instance. This destroys the two sockets and stops any +// message flow between them: +// +// zactor_destroy (&proxy); +// +// Note that all zproxy commands are synchronous, so your application always +// waits for a signal from the actor after each command. +// +// Enable verbose logging of commands and activity: +// +// zstr_send (proxy, "VERBOSE"); +// zsock_wait (proxy); +// +// Specify frontend socket type -- see zsock_type_str () -- and attach to +// endpoints, see zsock_attach (). Note that a proxy socket is always +// serverish: +// +// zstr_sendx (proxy, "FRONTEND", "XSUB", endpoints, NULL); +// zsock_wait (proxy); +// +// Specify backend socket type -- see zsock_type_str () -- and attach to +// endpoints, see zsock_attach (). Note that a proxy socket is always +// serverish: +// +// zstr_sendx (proxy, "BACKEND", "XPUB", endpoints, NULL); +// zsock_wait (proxy); +// +// Capture all proxied messages; these are delivered to the application +// via an inproc PULL socket that you have already bound to the specified +// endpoint: +// +// zstr_sendx (proxy, "CAPTURE", endpoint, NULL); +// zsock_wait (proxy); +// +// Pause the proxy. A paused proxy will cease processing messages, causing +// them to be queued up and potentially hit the high-water mark on the +// frontend or backend socket, causing messages to be dropped, or writing +// applications to block: +// +// zstr_sendx (proxy, "PAUSE", NULL); +// zsock_wait (proxy); +// +// Resume the proxy. Note that the proxy starts automatically as soon as it +// has a properly attached frontend and backend socket: +// +// zstr_sendx (proxy, "RESUME", NULL); +// zsock_wait (proxy); +// +// Configure an authentication domain for the "FRONTEND" or "BACKEND" proxy +// socket -- see zsock_set_zap_domain (). Call before binding socket: +// +// zstr_sendx (proxy, "DOMAIN", "FRONTEND", "global", NULL); +// zsock_wait (proxy); +// +// Configure PLAIN authentication for the "FRONTEND" or "BACKEND" proxy +// socket -- see zsock_set_plain_server (). Call before binding socket: +// +// zstr_sendx (proxy, "PLAIN", "BACKEND", NULL); +// zsock_wait (proxy); +// +// Configure CURVE authentication for the "FRONTEND" or "BACKEND" proxy +// socket -- see zsock_set_curve_server () -- specifying both the public and +// secret keys of a certificate as Z85 armored strings -- see +// zcert_public_txt () and zcert_secret_txt (). Call before binding socket: +// +// zstr_sendx (proxy, "CURVE", "FRONTEND", public_txt, secret_txt, NULL); +// zsock_wait (proxy); +// +// This is the zproxy constructor as a zactor_fn; the argument is a +// character string specifying frontend and backend socket types as two +// uppercase strings separated by a hyphen: +CZMQ_EXPORT void + zproxy (zsock_t *pipe, void *unused); + +// Selftest +CZMQ_EXPORT void + zproxy_test (bool verbose); +// @end + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/aarch64/include/zproxy_v2.h b/phonelibs/zmq/aarch64/include/zproxy_v2.h new file mode 100644 index 00000000000000..4bde9515916935 --- /dev/null +++ b/phonelibs/zmq/aarch64/include/zproxy_v2.h @@ -0,0 +1,62 @@ +/* ========================================================================= + zproxy_v2 - run a steerable proxy in the background (deprecated) + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZPROXY_V2_H_INCLUDED__ +#define __ZPROXY_V2_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @interface + +// Constructor +// Create a new zproxy object. You must create the frontend and backend +// sockets, configure them, and connect or bind them, before you pass them +// to the constructor. Do NOT use the sockets again, after passing them to +// this method. +CZMQ_EXPORT zproxy_t * + zproxy_new (zctx_t *ctx, void *frontend, void *backend); + +// Destructor +// Destroy a zproxy object; note this first stops the proxy. +CZMQ_EXPORT void + zproxy_destroy (zproxy_t **self_p); + +// Copy all proxied messages to specified endpoint; if this is NULL, any +// in-progress capturing will be stopped. You must already have bound the +// endpoint to a PULL socket. +CZMQ_EXPORT void + zproxy_capture (zproxy_t *self, const char *endpoint); + +// Pauses a zproxy object; a paused proxy will cease processing messages, +// causing them to be queued up and potentially hit the high-water mark on +// the frontend socket, causing messages to be dropped, or writing +// applications to block. +CZMQ_EXPORT void + zproxy_pause (zproxy_t *self); + +// Resume a zproxy object +CZMQ_EXPORT void + zproxy_resume (zproxy_t *self); + +// Self test of this class +CZMQ_EXPORT void + zproxy_v2_test (bool verbose); +// @end + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/aarch64/include/zrex.h b/phonelibs/zmq/aarch64/include/zrex.h new file mode 100644 index 00000000000000..8b50618a34837c --- /dev/null +++ b/phonelibs/zmq/aarch64/include/zrex.h @@ -0,0 +1,82 @@ +/* ========================================================================= + zrex - work with regular expressions + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZREX_H_INCLUDED__ +#define __ZREX_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @interface +// Constructor. Optionally, sets an expression against which we can match +// text and capture hits. If there is an error in the expression, reports +// zrex_valid() as false and provides the error in zrex_strerror(). If you +// set a pattern, you can call zrex_matches() to test it against text. +CZMQ_EXPORT zrex_t * + zrex_new (const char *expression); + +// Destructor +CZMQ_EXPORT void + zrex_destroy (zrex_t **self_p); + +// Return true if the expression was valid and compiled without errors. +CZMQ_EXPORT bool + zrex_valid (zrex_t *self); + +// Return the error message generated during compilation of the expression. +CZMQ_EXPORT const char * + zrex_strerror (zrex_t *self); + +// Returns true if the text matches the previously compiled expression. +// Use this method to compare one expression against many strings. +CZMQ_EXPORT bool + zrex_matches (zrex_t *self, const char *text); + +// Returns true if the text matches the supplied expression. Use this +// method to compare one string against several expressions. +CZMQ_EXPORT bool + zrex_eq (zrex_t *self, const char *text, const char *expression); + +// Returns number of hits from last zrex_matches or zrex_eq. If the text +// matched, returns 1 plus the number of capture groups. If the text did +// not match, returns zero. To retrieve individual capture groups, call +// zrex_hit (). +CZMQ_EXPORT int + zrex_hits (zrex_t *self); + +// Returns the Nth capture group from the last expression match, where +// N is 0 to the value returned by zrex_hits(). Capture group 0 is the +// whole matching string. Sequence 1 is the first capture group, if any, +// and so on. +CZMQ_EXPORT const char * + zrex_hit (zrex_t *self, uint index); + +// Fetches hits into string variables provided by caller; this makes for +// nicer code than accessing hits by index. Caller should not modify nor +// free the returned values. Returns number of strings returned. This +// method starts at hit 1, i.e. first capture group, as hit 0 is always +// the original matched string. +CZMQ_EXPORT int + zrex_fetch (zrex_t *self, const char **string_p, ...); + +// Self test of this class +CZMQ_EXPORT void + zrex_test (bool verbose); +// @end + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/aarch64/include/zsock.h b/phonelibs/zmq/aarch64/include/zsock.h new file mode 100644 index 00000000000000..fc5c46e45e9810 --- /dev/null +++ b/phonelibs/zmq/aarch64/include/zsock.h @@ -0,0 +1,921 @@ +/* ========================================================================= + zsock - high-level socket API that hides libzmq contexts and sockets + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZSOCK_H_INCLUDED__ +#define __ZSOCK_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// This interface includes some smart constructors, which create sockets with +// additional set-up. In all of these, the endpoint is NULL, or starts with +// '@' (bind) or '>' (connect). Multiple endpoints are allowed, separated by +// commas. If endpoint does not start with '@' or '>', default action depends +// on socket type. + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/zsock.api" to make changes. +// @interface +// This is a stable class, and may not change except for emergencies. It +// is provided in stable builds. +// This class has draft methods, which may change over time. They are not +// in stable releases, by default. Use --enable-drafts to enable. +// Create a new socket. Returns the new socket, or NULL if the new socket +// could not be created. Note that the symbol zsock_new (and other +// constructors/destructors for zsock) are redirected to the *_checked +// variant, enabling intelligent socket leak detection. This can have +// performance implications if you use a LOT of sockets. To turn off this +// redirection behaviour, define ZSOCK_NOCHECK. +CZMQ_EXPORT zsock_t * + zsock_new (int type); + +// Create a PUB socket. Default action is bind. +CZMQ_EXPORT zsock_t * + zsock_new_pub (const char *endpoint); + +// Create a SUB socket, and optionally subscribe to some prefix string. Default +// action is connect. +CZMQ_EXPORT zsock_t * + zsock_new_sub (const char *endpoint, const char *subscribe); + +// Create a REQ socket. Default action is connect. +CZMQ_EXPORT zsock_t * + zsock_new_req (const char *endpoint); + +// Create a REP socket. Default action is bind. +CZMQ_EXPORT zsock_t * + zsock_new_rep (const char *endpoint); + +// Create a DEALER socket. Default action is connect. +CZMQ_EXPORT zsock_t * + zsock_new_dealer (const char *endpoint); + +// Create a ROUTER socket. Default action is bind. +CZMQ_EXPORT zsock_t * + zsock_new_router (const char *endpoint); + +// Create a PUSH socket. Default action is connect. +CZMQ_EXPORT zsock_t * + zsock_new_push (const char *endpoint); + +// Create a PULL socket. Default action is bind. +CZMQ_EXPORT zsock_t * + zsock_new_pull (const char *endpoint); + +// Create an XPUB socket. Default action is bind. +CZMQ_EXPORT zsock_t * + zsock_new_xpub (const char *endpoint); + +// Create an XSUB socket. Default action is connect. +CZMQ_EXPORT zsock_t * + zsock_new_xsub (const char *endpoint); + +// Create a PAIR socket. Default action is connect. +CZMQ_EXPORT zsock_t * + zsock_new_pair (const char *endpoint); + +// Create a STREAM socket. Default action is connect. +CZMQ_EXPORT zsock_t * + zsock_new_stream (const char *endpoint); + +// Destroy the socket. You must use this for any socket created via the +// zsock_new method. +CZMQ_EXPORT void + zsock_destroy (zsock_t **self_p); + +// Bind a socket to a formatted endpoint. For tcp:// endpoints, supports +// ephemeral ports, if you specify the port number as "*". By default +// zsock uses the IANA designated range from C000 (49152) to FFFF (65535). +// To override this range, follow the "*" with "[first-last]". Either or +// both first and last may be empty. To bind to a random port within the +// range, use "!" in place of "*". +// +// Examples: +// tcp://127.0.0.1:* bind to first free port from C000 up +// tcp://127.0.0.1:! bind to random port from C000 to FFFF +// tcp://127.0.0.1:*[60000-] bind to first free port from 60000 up +// tcp://127.0.0.1:![-60000] bind to random port from C000 to 60000 +// tcp://127.0.0.1:![55000-55999] +// bind to random port from 55000 to 55999 +// +// On success, returns the actual port number used, for tcp:// endpoints, +// and 0 for other transports. On failure, returns -1. Note that when using +// ephemeral ports, a port may be reused by different services without +// clients being aware. Protocols that run on ephemeral ports should take +// this into account. +CZMQ_EXPORT int + zsock_bind (zsock_t *self, const char *format, ...); + +// Returns last bound endpoint, if any. +CZMQ_EXPORT const char * + zsock_endpoint (zsock_t *self); + +// Unbind a socket from a formatted endpoint. +// Returns 0 if OK, -1 if the endpoint was invalid or the function +// isn't supported. +CZMQ_EXPORT int + zsock_unbind (zsock_t *self, const char *format, ...); + +// Connect a socket to a formatted endpoint +// Returns 0 if OK, -1 if the endpoint was invalid. +CZMQ_EXPORT int + zsock_connect (zsock_t *self, const char *format, ...); + +// Disconnect a socket from a formatted endpoint +// Returns 0 if OK, -1 if the endpoint was invalid or the function +// isn't supported. +CZMQ_EXPORT int + zsock_disconnect (zsock_t *self, const char *format, ...); + +// Attach a socket to zero or more endpoints. If endpoints is not null, +// parses as list of ZeroMQ endpoints, separated by commas, and prefixed by +// '@' (to bind the socket) or '>' (to connect the socket). Returns 0 if all +// endpoints were valid, or -1 if there was a syntax error. If the endpoint +// does not start with '@' or '>', the serverish argument defines whether +// it is used to bind (serverish = true) or connect (serverish = false). +CZMQ_EXPORT int + zsock_attach (zsock_t *self, const char *endpoints, bool serverish); + +// Returns socket type as printable constant string. +CZMQ_EXPORT const char * + zsock_type_str (zsock_t *self); + +// Send a 'picture' message to the socket (or actor). The picture is a +// string that defines the type of each frame. This makes it easy to send +// a complex multiframe message in one call. The picture can contain any +// of these characters, each corresponding to one or two arguments: +// +// i = int (signed) +// 1 = uint8_t +// 2 = uint16_t +// 4 = uint32_t +// 8 = uint64_t +// s = char * +// b = byte *, size_t (2 arguments) +// c = zchunk_t * +// f = zframe_t * +// h = zhashx_t * +// U = zuuid_t * +// p = void * (sends the pointer value, only meaningful over inproc) +// m = zmsg_t * (sends all frames in the zmsg) +// z = sends zero-sized frame (0 arguments) +// u = uint (deprecated) +// +// Note that s, b, c, and f are encoded the same way and the choice is +// offered as a convenience to the sender, which may or may not already +// have data in a zchunk or zframe. Does not change or take ownership of +// any arguments. Returns 0 if successful, -1 if sending failed for any +// reason. +CZMQ_EXPORT int + zsock_send (void *self, const char *picture, ...); + +// Send a 'picture' message to the socket (or actor). This is a va_list +// version of zsock_send (), so please consult its documentation for the +// details. +CZMQ_EXPORT int + zsock_vsend (void *self, const char *picture, va_list argptr); + +// Receive a 'picture' message to the socket (or actor). See zsock_send for +// the format and meaning of the picture. Returns the picture elements into +// a series of pointers as provided by the caller: +// +// i = int * (stores signed integer) +// 4 = uint32_t * (stores 32-bit unsigned integer) +// 8 = uint64_t * (stores 64-bit unsigned integer) +// s = char ** (allocates new string) +// b = byte **, size_t * (2 arguments) (allocates memory) +// c = zchunk_t ** (creates zchunk) +// f = zframe_t ** (creates zframe) +// U = zuuid_t * (creates a zuuid with the data) +// h = zhashx_t ** (creates zhashx) +// p = void ** (stores pointer) +// m = zmsg_t ** (creates a zmsg with the remaing frames) +// z = null, asserts empty frame (0 arguments) +// u = uint * (stores unsigned integer, deprecated) +// +// Note that zsock_recv creates the returned objects, and the caller must +// destroy them when finished with them. The supplied pointers do not need +// to be initialized. Returns 0 if successful, or -1 if it failed to recv +// a message, in which case the pointers are not modified. When message +// frames are truncated (a short message), sets return values to zero/null. +// If an argument pointer is NULL, does not store any value (skips it). +// An 'n' picture matches an empty frame; if the message does not match, +// the method will return -1. +CZMQ_EXPORT int + zsock_recv (void *self, const char *picture, ...); + +// Receive a 'picture' message from the socket (or actor). This is a +// va_list version of zsock_recv (), so please consult its documentation +// for the details. +CZMQ_EXPORT int + zsock_vrecv (void *self, const char *picture, va_list argptr); + +// Send a binary encoded 'picture' message to the socket (or actor). This +// method is similar to zsock_send, except the arguments are encoded in a +// binary format that is compatible with zproto, and is designed to reduce +// memory allocations. The pattern argument is a string that defines the +// type of each argument. Supports these argument types: +// +// pattern C type zproto type: +// 1 uint8_t type = "number" size = "1" +// 2 uint16_t type = "number" size = "2" +// 4 uint32_t type = "number" size = "3" +// 8 uint64_t type = "number" size = "4" +// s char *, 0-255 chars type = "string" +// S char *, 0-2^32-1 chars type = "longstr" +// c zchunk_t * type = "chunk" +// f zframe_t * type = "frame" +// u zuuid_t * type = "uuid" +// m zmsg_t * type = "msg" +// p void *, sends pointer value, only over inproc +// +// Does not change or take ownership of any arguments. Returns 0 if +// successful, -1 if sending failed for any reason. +CZMQ_EXPORT int + zsock_bsend (void *self, const char *picture, ...); + +// Receive a binary encoded 'picture' message from the socket (or actor). +// This method is similar to zsock_recv, except the arguments are encoded +// in a binary format that is compatible with zproto, and is designed to +// reduce memory allocations. The pattern argument is a string that defines +// the type of each argument. See zsock_bsend for the supported argument +// types. All arguments must be pointers; this call sets them to point to +// values held on a per-socket basis. +// Note that zsock_brecv creates the returned objects, and the caller must +// destroy them when finished with them. The supplied pointers do not need +// to be initialized. Returns 0 if successful, or -1 if it failed to read +// a message. +CZMQ_EXPORT int + zsock_brecv (void *self, const char *picture, ...); + +// Set socket to use unbounded pipes (HWM=0); use this in cases when you are +// totally certain the message volume can fit in memory. This method works +// across all versions of ZeroMQ. Takes a polymorphic socket reference. +CZMQ_EXPORT void + zsock_set_unbounded (void *self); + +// Send a signal over a socket. A signal is a short message carrying a +// success/failure code (by convention, 0 means OK). Signals are encoded +// to be distinguishable from "normal" messages. Accepts a zsock_t or a +// zactor_t argument, and returns 0 if successful, -1 if the signal could +// not be sent. Takes a polymorphic socket reference. +CZMQ_EXPORT int + zsock_signal (void *self, byte status); + +// Wait on a signal. Use this to coordinate between threads, over pipe +// pairs. Blocks until the signal is received. Returns -1 on error, 0 or +// greater on success. Accepts a zsock_t or a zactor_t as argument. +// Takes a polymorphic socket reference. +CZMQ_EXPORT int + zsock_wait (void *self); + +// If there is a partial message still waiting on the socket, remove and +// discard it. This is useful when reading partial messages, to get specific +// message types. +CZMQ_EXPORT void + zsock_flush (void *self); + +// Probe the supplied object, and report if it looks like a zsock_t. +// Takes a polymorphic socket reference. +CZMQ_EXPORT bool + zsock_is (void *self); + +// Probe the supplied reference. If it looks like a zsock_t instance, return +// the underlying libzmq socket handle; else if it looks like a file +// descriptor, return NULL; else if it looks like a libzmq socket handle, +// return the supplied value. Takes a polymorphic socket reference. +CZMQ_EXPORT void * + zsock_resolve (void *self); + +// Get socket option `tos`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_tos (void *self); + +// Set socket option `tos`. +CZMQ_EXPORT void + zsock_set_tos (void *self, int tos); + +// Set socket option `router_handover`. +CZMQ_EXPORT void + zsock_set_router_handover (void *self, int router_handover); + +// Set socket option `router_mandatory`. +CZMQ_EXPORT void + zsock_set_router_mandatory (void *self, int router_mandatory); + +// Set socket option `probe_router`. +CZMQ_EXPORT void + zsock_set_probe_router (void *self, int probe_router); + +// Set socket option `req_relaxed`. +CZMQ_EXPORT void + zsock_set_req_relaxed (void *self, int req_relaxed); + +// Set socket option `req_correlate`. +CZMQ_EXPORT void + zsock_set_req_correlate (void *self, int req_correlate); + +// Set socket option `conflate`. +CZMQ_EXPORT void + zsock_set_conflate (void *self, int conflate); + +// Get socket option `zap_domain`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT char * + zsock_zap_domain (void *self); + +// Set socket option `zap_domain`. +CZMQ_EXPORT void + zsock_set_zap_domain (void *self, const char *zap_domain); + +// Get socket option `mechanism`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_mechanism (void *self); + +// Get socket option `plain_server`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_plain_server (void *self); + +// Set socket option `plain_server`. +CZMQ_EXPORT void + zsock_set_plain_server (void *self, int plain_server); + +// Get socket option `plain_username`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT char * + zsock_plain_username (void *self); + +// Set socket option `plain_username`. +CZMQ_EXPORT void + zsock_set_plain_username (void *self, const char *plain_username); + +// Get socket option `plain_password`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT char * + zsock_plain_password (void *self); + +// Set socket option `plain_password`. +CZMQ_EXPORT void + zsock_set_plain_password (void *self, const char *plain_password); + +// Get socket option `curve_server`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_curve_server (void *self); + +// Set socket option `curve_server`. +CZMQ_EXPORT void + zsock_set_curve_server (void *self, int curve_server); + +// Get socket option `curve_publickey`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT char * + zsock_curve_publickey (void *self); + +// Set socket option `curve_publickey`. +CZMQ_EXPORT void + zsock_set_curve_publickey (void *self, const char *curve_publickey); + +// Set socket option `curve_publickey` from 32-octet binary +CZMQ_EXPORT void + zsock_set_curve_publickey_bin (void *self, const byte *curve_publickey); + +// Get socket option `curve_secretkey`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT char * + zsock_curve_secretkey (void *self); + +// Set socket option `curve_secretkey`. +CZMQ_EXPORT void + zsock_set_curve_secretkey (void *self, const char *curve_secretkey); + +// Set socket option `curve_secretkey` from 32-octet binary +CZMQ_EXPORT void + zsock_set_curve_secretkey_bin (void *self, const byte *curve_secretkey); + +// Get socket option `curve_serverkey`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT char * + zsock_curve_serverkey (void *self); + +// Set socket option `curve_serverkey`. +CZMQ_EXPORT void + zsock_set_curve_serverkey (void *self, const char *curve_serverkey); + +// Set socket option `curve_serverkey` from 32-octet binary +CZMQ_EXPORT void + zsock_set_curve_serverkey_bin (void *self, const byte *curve_serverkey); + +// Get socket option `gssapi_server`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_gssapi_server (void *self); + +// Set socket option `gssapi_server`. +CZMQ_EXPORT void + zsock_set_gssapi_server (void *self, int gssapi_server); + +// Get socket option `gssapi_plaintext`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_gssapi_plaintext (void *self); + +// Set socket option `gssapi_plaintext`. +CZMQ_EXPORT void + zsock_set_gssapi_plaintext (void *self, int gssapi_plaintext); + +// Get socket option `gssapi_principal`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT char * + zsock_gssapi_principal (void *self); + +// Set socket option `gssapi_principal`. +CZMQ_EXPORT void + zsock_set_gssapi_principal (void *self, const char *gssapi_principal); + +// Get socket option `gssapi_service_principal`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT char * + zsock_gssapi_service_principal (void *self); + +// Set socket option `gssapi_service_principal`. +CZMQ_EXPORT void + zsock_set_gssapi_service_principal (void *self, const char *gssapi_service_principal); + +// Get socket option `ipv6`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_ipv6 (void *self); + +// Set socket option `ipv6`. +CZMQ_EXPORT void + zsock_set_ipv6 (void *self, int ipv6); + +// Get socket option `immediate`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_immediate (void *self); + +// Set socket option `immediate`. +CZMQ_EXPORT void + zsock_set_immediate (void *self, int immediate); + +// Set socket option `router_raw`. +CZMQ_EXPORT void + zsock_set_router_raw (void *self, int router_raw); + +// Get socket option `ipv4only`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_ipv4only (void *self); + +// Set socket option `ipv4only`. +CZMQ_EXPORT void + zsock_set_ipv4only (void *self, int ipv4only); + +// Set socket option `delay_attach_on_connect`. +CZMQ_EXPORT void + zsock_set_delay_attach_on_connect (void *self, int delay_attach_on_connect); + +// Get socket option `type`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_type (void *self); + +// Get socket option `sndhwm`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_sndhwm (void *self); + +// Set socket option `sndhwm`. +CZMQ_EXPORT void + zsock_set_sndhwm (void *self, int sndhwm); + +// Get socket option `rcvhwm`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_rcvhwm (void *self); + +// Set socket option `rcvhwm`. +CZMQ_EXPORT void + zsock_set_rcvhwm (void *self, int rcvhwm); + +// Get socket option `affinity`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_affinity (void *self); + +// Set socket option `affinity`. +CZMQ_EXPORT void + zsock_set_affinity (void *self, int affinity); + +// Set socket option `subscribe`. +CZMQ_EXPORT void + zsock_set_subscribe (void *self, const char *subscribe); + +// Set socket option `unsubscribe`. +CZMQ_EXPORT void + zsock_set_unsubscribe (void *self, const char *unsubscribe); + +// Get socket option `identity`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT char * + zsock_identity (void *self); + +// Set socket option `identity`. +CZMQ_EXPORT void + zsock_set_identity (void *self, const char *identity); + +// Get socket option `rate`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_rate (void *self); + +// Set socket option `rate`. +CZMQ_EXPORT void + zsock_set_rate (void *self, int rate); + +// Get socket option `recovery_ivl`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_recovery_ivl (void *self); + +// Set socket option `recovery_ivl`. +CZMQ_EXPORT void + zsock_set_recovery_ivl (void *self, int recovery_ivl); + +// Get socket option `sndbuf`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_sndbuf (void *self); + +// Set socket option `sndbuf`. +CZMQ_EXPORT void + zsock_set_sndbuf (void *self, int sndbuf); + +// Get socket option `rcvbuf`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_rcvbuf (void *self); + +// Set socket option `rcvbuf`. +CZMQ_EXPORT void + zsock_set_rcvbuf (void *self, int rcvbuf); + +// Get socket option `linger`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_linger (void *self); + +// Set socket option `linger`. +CZMQ_EXPORT void + zsock_set_linger (void *self, int linger); + +// Get socket option `reconnect_ivl`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_reconnect_ivl (void *self); + +// Set socket option `reconnect_ivl`. +CZMQ_EXPORT void + zsock_set_reconnect_ivl (void *self, int reconnect_ivl); + +// Get socket option `reconnect_ivl_max`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_reconnect_ivl_max (void *self); + +// Set socket option `reconnect_ivl_max`. +CZMQ_EXPORT void + zsock_set_reconnect_ivl_max (void *self, int reconnect_ivl_max); + +// Get socket option `backlog`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_backlog (void *self); + +// Set socket option `backlog`. +CZMQ_EXPORT void + zsock_set_backlog (void *self, int backlog); + +// Get socket option `maxmsgsize`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_maxmsgsize (void *self); + +// Set socket option `maxmsgsize`. +CZMQ_EXPORT void + zsock_set_maxmsgsize (void *self, int maxmsgsize); + +// Get socket option `multicast_hops`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_multicast_hops (void *self); + +// Set socket option `multicast_hops`. +CZMQ_EXPORT void + zsock_set_multicast_hops (void *self, int multicast_hops); + +// Get socket option `rcvtimeo`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_rcvtimeo (void *self); + +// Set socket option `rcvtimeo`. +CZMQ_EXPORT void + zsock_set_rcvtimeo (void *self, int rcvtimeo); + +// Get socket option `sndtimeo`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_sndtimeo (void *self); + +// Set socket option `sndtimeo`. +CZMQ_EXPORT void + zsock_set_sndtimeo (void *self, int sndtimeo); + +// Set socket option `xpub_verbose`. +CZMQ_EXPORT void + zsock_set_xpub_verbose (void *self, int xpub_verbose); + +// Get socket option `tcp_keepalive`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_tcp_keepalive (void *self); + +// Set socket option `tcp_keepalive`. +CZMQ_EXPORT void + zsock_set_tcp_keepalive (void *self, int tcp_keepalive); + +// Get socket option `tcp_keepalive_idle`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_tcp_keepalive_idle (void *self); + +// Set socket option `tcp_keepalive_idle`. +CZMQ_EXPORT void + zsock_set_tcp_keepalive_idle (void *self, int tcp_keepalive_idle); + +// Get socket option `tcp_keepalive_cnt`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_tcp_keepalive_cnt (void *self); + +// Set socket option `tcp_keepalive_cnt`. +CZMQ_EXPORT void + zsock_set_tcp_keepalive_cnt (void *self, int tcp_keepalive_cnt); + +// Get socket option `tcp_keepalive_intvl`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_tcp_keepalive_intvl (void *self); + +// Set socket option `tcp_keepalive_intvl`. +CZMQ_EXPORT void + zsock_set_tcp_keepalive_intvl (void *self, int tcp_keepalive_intvl); + +// Get socket option `tcp_accept_filter`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT char * + zsock_tcp_accept_filter (void *self); + +// Set socket option `tcp_accept_filter`. +CZMQ_EXPORT void + zsock_set_tcp_accept_filter (void *self, const char *tcp_accept_filter); + +// Get socket option `rcvmore`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_rcvmore (void *self); + +// Get socket option `fd`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT SOCKET + zsock_fd (void *self); + +// Get socket option `events`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_events (void *self); + +// Get socket option `last_endpoint`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT char * + zsock_last_endpoint (void *self); + +// Self test of this class. +CZMQ_EXPORT void + zsock_test (bool verbose); + +#ifdef CZMQ_BUILD_DRAFT_API +// *** Draft method, for development use, may change without warning *** +// Create a SERVER socket. Default action is bind. +CZMQ_EXPORT zsock_t * + zsock_new_server (const char *endpoint); + +// *** Draft method, for development use, may change without warning *** +// Create a CLIENT socket. Default action is connect. +CZMQ_EXPORT zsock_t * + zsock_new_client (const char *endpoint); + +// *** Draft method, for development use, may change without warning *** +// Create a RADIO socket. Default action is bind. +CZMQ_EXPORT zsock_t * + zsock_new_radio (const char *endpoint); + +// *** Draft method, for development use, may change without warning *** +// Create a DISH socket. Default action is connect. +CZMQ_EXPORT zsock_t * + zsock_new_dish (const char *endpoint); + +// *** Draft method, for development use, may change without warning *** +// Create a GATHER socket. Default action is bind. +CZMQ_EXPORT zsock_t * + zsock_new_gather (const char *endpoint); + +// *** Draft method, for development use, may change without warning *** +// Create a SCATTER socket. Default action is connect. +CZMQ_EXPORT zsock_t * + zsock_new_scatter (const char *endpoint); + +// *** Draft method, for development use, may change without warning *** +// Return socket routing ID if any. This returns 0 if the socket is not +// of type ZMQ_SERVER or if no request was already received on it. +CZMQ_EXPORT uint32_t + zsock_routing_id (zsock_t *self); + +// *** Draft method, for development use, may change without warning *** +// Set routing ID on socket. The socket MUST be of type ZMQ_SERVER. +// This will be used when sending messages on the socket via the zsock API. +CZMQ_EXPORT void + zsock_set_routing_id (zsock_t *self, uint32_t routing_id); + +// *** Draft method, for development use, may change without warning *** +// Join a group for the RADIO-DISH pattern. Call only on ZMQ_DISH. +// Returns 0 if OK, -1 if failed. +CZMQ_EXPORT int + zsock_join (void *self, const char *group); + +// *** Draft method, for development use, may change without warning *** +// Leave a group for the RADIO-DISH pattern. Call only on ZMQ_DISH. +// Returns 0 if OK, -1 if failed. +CZMQ_EXPORT int + zsock_leave (void *self, const char *group); + +// *** Draft method, for development use, may change without warning *** +// Get socket option `heartbeat_ivl`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_heartbeat_ivl (void *self); + +// *** Draft method, for development use, may change without warning *** +// Set socket option `heartbeat_ivl`. +CZMQ_EXPORT void + zsock_set_heartbeat_ivl (void *self, int heartbeat_ivl); + +// *** Draft method, for development use, may change without warning *** +// Get socket option `heartbeat_ttl`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_heartbeat_ttl (void *self); + +// *** Draft method, for development use, may change without warning *** +// Set socket option `heartbeat_ttl`. +CZMQ_EXPORT void + zsock_set_heartbeat_ttl (void *self, int heartbeat_ttl); + +// *** Draft method, for development use, may change without warning *** +// Get socket option `heartbeat_timeout`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_heartbeat_timeout (void *self); + +// *** Draft method, for development use, may change without warning *** +// Set socket option `heartbeat_timeout`. +CZMQ_EXPORT void + zsock_set_heartbeat_timeout (void *self, int heartbeat_timeout); + +// *** Draft method, for development use, may change without warning *** +// Get socket option `use_fd`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_use_fd (void *self); + +// *** Draft method, for development use, may change without warning *** +// Set socket option `use_fd`. +CZMQ_EXPORT void + zsock_set_use_fd (void *self, int use_fd); + +#endif // CZMQ_BUILD_DRAFT_API +// @ignore +CZMQ_EXPORT int + zsock_bind (zsock_t *self, const char *format, ...) CHECK_PRINTF (2); +CZMQ_EXPORT int + zsock_unbind (zsock_t *self, const char *format, ...) CHECK_PRINTF (2); +CZMQ_EXPORT int + zsock_connect (zsock_t *self, const char *format, ...) CHECK_PRINTF (2); +CZMQ_EXPORT int + zsock_disconnect (zsock_t *self, const char *format, ...) CHECK_PRINTF (2); +// @end + + +// zsock leak detection - not a part of the official interface to zsock. This +// enables CZMQ to report socket leaks intelligently. +#if defined ZSOCK_NOCHECK + // no checking active - use the above interface methods directly. +#else +# define zsock_new(t) zsock_new_checked((t), __FILE__, __LINE__) +# define zsock_new_pub(e) zsock_new_pub_checked((e), __FILE__, __LINE__) +# define zsock_new_sub(e,s) zsock_new_sub_checked((e), (s), __FILE__, __LINE__) +# define zsock_new_req(e) zsock_new_req_checked((e), __FILE__, __LINE__) +# define zsock_new_rep(e) zsock_new_rep_checked((e), __FILE__, __LINE__) +# define zsock_new_dealer(e) zsock_new_dealer_checked((e), __FILE__, __LINE__) +# define zsock_new_router(e) zsock_new_router_checked((e), __FILE__, __LINE__) +# define zsock_new_pull(e) zsock_new_pull_checked((e), __FILE__, __LINE__) +# define zsock_new_push(e) zsock_new_push_checked((e), __FILE__, __LINE__) +# define zsock_new_xpub(e) zsock_new_xpub_checked((e), __FILE__, __LINE__) +# define zsock_new_xsub(e) zsock_new_xsub_checked((e), __FILE__, __LINE__) +# define zsock_new_pair(e) zsock_new_pair_checked((e), __FILE__, __LINE__) +# define zsock_new_stream(e) zsock_new_stream_checked((e), __FILE__, __LINE__) +# define zsock_destroy(t) zsock_destroy_checked((t), __FILE__, __LINE__) +#endif + +CZMQ_EXPORT zsock_t * + zsock_new_checked (int type, const char *filename, size_t line_nbr); + +CZMQ_EXPORT void + zsock_destroy_checked (zsock_t **self_p, const char *filename, size_t line_nbr); + +CZMQ_EXPORT zsock_t * + zsock_new_pub_checked (const char *endpoint, const char *filename, size_t line_nbr); + +CZMQ_EXPORT zsock_t * + zsock_new_sub_checked (const char *endpoint, const char *subscribe, const char *filename, size_t line_nbr); + +CZMQ_EXPORT zsock_t * + zsock_new_req_checked (const char *endpoint, const char *filename, size_t line_nbr); + +CZMQ_EXPORT zsock_t * + zsock_new_rep_checked (const char *endpoint, const char *filename, size_t line_nbr); + +CZMQ_EXPORT zsock_t * + zsock_new_dealer_checked (const char *endpoint, const char *filename, size_t line_nbr); + +CZMQ_EXPORT zsock_t * + zsock_new_router_checked (const char *endpoint, const char *filename, size_t line_nbr); + +CZMQ_EXPORT zsock_t * + zsock_new_push_checked (const char *endpoint, const char *filename, size_t line_nbr); + +CZMQ_EXPORT zsock_t * + zsock_new_pull_checked (const char *endpoint, const char *filename, size_t line_nbr); + +CZMQ_EXPORT zsock_t * + zsock_new_xpub_checked (const char *endpoint, const char *filename, size_t line_nbr); + +CZMQ_EXPORT zsock_t * + zsock_new_xsub_checked (const char *endpoint, const char *filename, size_t line_nbr); + +CZMQ_EXPORT zsock_t * + zsock_new_pair_checked (const char *endpoint, const char *filename, size_t line_nbr); + +CZMQ_EXPORT zsock_t * + zsock_new_stream_checked (const char *endpoint, const char *filename, size_t line_nbr); + +CZMQ_EXPORT zsock_t * + zsock_new_server_checked (const char *endpoint, const char *filename, size_t line_nbr); + +CZMQ_EXPORT zsock_t * + zsock_new_client_checked (const char *endpoint, const char *filename, size_t line_nbr); + +CZMQ_EXPORT zsock_t * + zsock_new_radio_checked (const char *endpoint, const char *filename, size_t line_nbr); + +CZMQ_EXPORT zsock_t * + zsock_new_dish_checked (const char *endpoint, const char *filename, size_t line_nbr); + +CZMQ_EXPORT zsock_t * + zsock_new_gather_checked (const char *endpoint, const char *filename, size_t line_nbr); + +CZMQ_EXPORT zsock_t * + zsock_new_scatter_checked (const char *endpoint, const char *filename, size_t line_nbr); + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/aarch64/include/zsocket.h b/phonelibs/zmq/aarch64/include/zsocket.h new file mode 100644 index 00000000000000..a60a0d9db3e7da --- /dev/null +++ b/phonelibs/zmq/aarch64/include/zsocket.h @@ -0,0 +1,110 @@ +/* ========================================================================= + zsocket - working with 0MQ sockets + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZSOCKET_H_INCLUDED__ +#define __ZSOCKET_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @interface +// This port range is defined by IANA for dynamic or private ports +// We use this when choosing a port for dynamic binding. +#define ZSOCKET_DYNFROM 0xc000 +#define ZSOCKET_DYNTO 0xffff + +// Callback function for zero-copy methods +typedef void (zsocket_free_fn) (void *data, void *arg); + +// Create a new socket within our CZMQ context, replaces zmq_socket. +// Use this to get automatic management of the socket at shutdown. +// Note: SUB sockets do not automatically subscribe to everything; you +// must set filters explicitly. +CZMQ_EXPORT void * + zsocket_new (zctx_t *self, int type); + +// Destroy a socket within our CZMQ context, replaces zmq_close. +CZMQ_EXPORT void + zsocket_destroy (zctx_t *ctx, void *self); + +// Bind a socket to a formatted endpoint. If the port is specified as +// '*', binds to any free port from ZSOCKET_DYNFROM to ZSOCKET_DYNTO +// and returns the actual port number used. Otherwise asserts that the +// bind succeeded with the specified port number. Always returns the +// port number if successful. +CZMQ_EXPORT int + zsocket_bind (void *self, const char *format, ...); + +// Unbind a socket from a formatted endpoint. +// Returns 0 if OK, -1 if the endpoint was invalid or the function +// isn't supported. +CZMQ_EXPORT int + zsocket_unbind (void *self, const char *format, ...); + +// Connect a socket to a formatted endpoint +// Returns 0 if OK, -1 if the endpoint was invalid. +CZMQ_EXPORT int + zsocket_connect (void *self, const char *format, ...); + +// Disconnect a socket from a formatted endpoint +// Returns 0 if OK, -1 if the endpoint was invalid or the function +// isn't supported. +CZMQ_EXPORT int + zsocket_disconnect (void *self, const char *format, ...); + +// Poll for input events on the socket. Returns TRUE if there is input +// ready on the socket, else FALSE. +CZMQ_EXPORT bool + zsocket_poll (void *self, int msecs); + +// Returns socket type as printable constant string +CZMQ_EXPORT const char * + zsocket_type_str (void *self); + +// Send data over a socket as a single message frame. +// Accepts these flags: ZFRAME_MORE and ZFRAME_DONTWAIT. +// Returns -1 on error, 0 on success +CZMQ_EXPORT int + zsocket_sendmem (void *self, const void *data, size_t size, int flags); + +// Send a signal over a socket. A signal is a zero-byte message. +// Signals are used primarily between threads, over pipe sockets. +// Returns -1 if there was an error sending the signal. +CZMQ_EXPORT int + zsocket_signal (void *self); + +// Wait on a signal. Use this to coordinate between threads, over +// pipe pairs. Returns -1 on error, 0 on success. +CZMQ_EXPORT int + zsocket_wait (void *self); + +// Self test of this class +CZMQ_EXPORT void + zsocket_test (bool verbose); +// @end + +// Compiler hints +CZMQ_EXPORT int zsocket_bind (void *self, const char *format, ...) CHECK_PRINTF (2); +CZMQ_EXPORT int zsocket_unbind (void *self, const char *format, ...) CHECK_PRINTF (2); +CZMQ_EXPORT int zsocket_connect (void *self, const char *format, ...) CHECK_PRINTF (2); +CZMQ_EXPORT int zsocket_disconnect (void *self, const char *format, ...) CHECK_PRINTF (2); + +// Emulation of widely-used 2.x socket options +CZMQ_EXPORT void zsocket_set_hwm (void *self, int hwm); + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/aarch64/include/zsockopt.h b/phonelibs/zmq/aarch64/include/zsockopt.h new file mode 100644 index 00000000000000..5246986dd0b367 --- /dev/null +++ b/phonelibs/zmq/aarch64/include/zsockopt.h @@ -0,0 +1,256 @@ +/* ========================================================================= + zsockopt - get/set 0MQ socket options (deprecated) + + **************************************************** + * GENERATED SOURCE CODE, DO NOT EDIT!! * + * TO CHANGE THIS, EDIT src/zsockopt.gsl * + * AND RUN `gsl sockopts` in src/. * + **************************************************** + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZSOCKOPT_H_INCLUDED__ +#define __ZSOCKOPT_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @interface +#if (ZMQ_VERSION_MAJOR == 4) +// Get socket options +CZMQ_EXPORT int zsocket_heartbeat_ivl (void *zocket); +CZMQ_EXPORT int zsocket_heartbeat_ttl (void *zocket); +CZMQ_EXPORT int zsocket_heartbeat_timeout (void *zocket); +CZMQ_EXPORT int zsocket_use_fd (void *zocket); +CZMQ_EXPORT int zsocket_tos (void *zocket); +CZMQ_EXPORT char * zsocket_zap_domain (void *zocket); +CZMQ_EXPORT int zsocket_mechanism (void *zocket); +CZMQ_EXPORT int zsocket_plain_server (void *zocket); +CZMQ_EXPORT char * zsocket_plain_username (void *zocket); +CZMQ_EXPORT char * zsocket_plain_password (void *zocket); +CZMQ_EXPORT int zsocket_curve_server (void *zocket); +CZMQ_EXPORT char * zsocket_curve_publickey (void *zocket); +CZMQ_EXPORT char * zsocket_curve_secretkey (void *zocket); +CZMQ_EXPORT char * zsocket_curve_serverkey (void *zocket); +CZMQ_EXPORT int zsocket_gssapi_server (void *zocket); +CZMQ_EXPORT int zsocket_gssapi_plaintext (void *zocket); +CZMQ_EXPORT char * zsocket_gssapi_principal (void *zocket); +CZMQ_EXPORT char * zsocket_gssapi_service_principal (void *zocket); +CZMQ_EXPORT int zsocket_ipv6 (void *zocket); +CZMQ_EXPORT int zsocket_immediate (void *zocket); +CZMQ_EXPORT int zsocket_ipv4only (void *zocket); +CZMQ_EXPORT int zsocket_type (void *zocket); +CZMQ_EXPORT int zsocket_sndhwm (void *zocket); +CZMQ_EXPORT int zsocket_rcvhwm (void *zocket); +CZMQ_EXPORT int zsocket_affinity (void *zocket); +CZMQ_EXPORT char * zsocket_identity (void *zocket); +CZMQ_EXPORT int zsocket_rate (void *zocket); +CZMQ_EXPORT int zsocket_recovery_ivl (void *zocket); +CZMQ_EXPORT int zsocket_sndbuf (void *zocket); +CZMQ_EXPORT int zsocket_rcvbuf (void *zocket); +CZMQ_EXPORT int zsocket_linger (void *zocket); +CZMQ_EXPORT int zsocket_reconnect_ivl (void *zocket); +CZMQ_EXPORT int zsocket_reconnect_ivl_max (void *zocket); +CZMQ_EXPORT int zsocket_backlog (void *zocket); +CZMQ_EXPORT int zsocket_maxmsgsize (void *zocket); +CZMQ_EXPORT int zsocket_multicast_hops (void *zocket); +CZMQ_EXPORT int zsocket_rcvtimeo (void *zocket); +CZMQ_EXPORT int zsocket_sndtimeo (void *zocket); +CZMQ_EXPORT int zsocket_tcp_keepalive (void *zocket); +CZMQ_EXPORT int zsocket_tcp_keepalive_idle (void *zocket); +CZMQ_EXPORT int zsocket_tcp_keepalive_cnt (void *zocket); +CZMQ_EXPORT int zsocket_tcp_keepalive_intvl (void *zocket); +CZMQ_EXPORT char * zsocket_tcp_accept_filter (void *zocket); +CZMQ_EXPORT int zsocket_rcvmore (void *zocket); +CZMQ_EXPORT SOCKET zsocket_fd (void *zocket); +CZMQ_EXPORT int zsocket_events (void *zocket); +CZMQ_EXPORT char * zsocket_last_endpoint (void *zocket); + +// Set socket options +CZMQ_EXPORT void zsocket_set_heartbeat_ivl (void *zocket, int heartbeat_ivl); +CZMQ_EXPORT void zsocket_set_heartbeat_ttl (void *zocket, int heartbeat_ttl); +CZMQ_EXPORT void zsocket_set_heartbeat_timeout (void *zocket, int heartbeat_timeout); +CZMQ_EXPORT void zsocket_set_use_fd (void *zocket, int use_fd); +CZMQ_EXPORT void zsocket_set_tos (void *zocket, int tos); +CZMQ_EXPORT void zsocket_set_router_handover (void *zocket, int router_handover); +CZMQ_EXPORT void zsocket_set_router_mandatory (void *zocket, int router_mandatory); +CZMQ_EXPORT void zsocket_set_probe_router (void *zocket, int probe_router); +CZMQ_EXPORT void zsocket_set_req_relaxed (void *zocket, int req_relaxed); +CZMQ_EXPORT void zsocket_set_req_correlate (void *zocket, int req_correlate); +CZMQ_EXPORT void zsocket_set_conflate (void *zocket, int conflate); +CZMQ_EXPORT void zsocket_set_zap_domain (void *zocket, const char * zap_domain); +CZMQ_EXPORT void zsocket_set_plain_server (void *zocket, int plain_server); +CZMQ_EXPORT void zsocket_set_plain_username (void *zocket, const char * plain_username); +CZMQ_EXPORT void zsocket_set_plain_password (void *zocket, const char * plain_password); +CZMQ_EXPORT void zsocket_set_curve_server (void *zocket, int curve_server); +CZMQ_EXPORT void zsocket_set_curve_publickey (void *zocket, const char * curve_publickey); +CZMQ_EXPORT void zsocket_set_curve_publickey_bin (void *zocket, const byte *curve_publickey); +CZMQ_EXPORT void zsocket_set_curve_secretkey (void *zocket, const char * curve_secretkey); +CZMQ_EXPORT void zsocket_set_curve_secretkey_bin (void *zocket, const byte *curve_secretkey); +CZMQ_EXPORT void zsocket_set_curve_serverkey (void *zocket, const char * curve_serverkey); +CZMQ_EXPORT void zsocket_set_curve_serverkey_bin (void *zocket, const byte *curve_serverkey); +CZMQ_EXPORT void zsocket_set_gssapi_server (void *zocket, int gssapi_server); +CZMQ_EXPORT void zsocket_set_gssapi_plaintext (void *zocket, int gssapi_plaintext); +CZMQ_EXPORT void zsocket_set_gssapi_principal (void *zocket, const char * gssapi_principal); +CZMQ_EXPORT void zsocket_set_gssapi_service_principal (void *zocket, const char * gssapi_service_principal); +CZMQ_EXPORT void zsocket_set_ipv6 (void *zocket, int ipv6); +CZMQ_EXPORT void zsocket_set_immediate (void *zocket, int immediate); +CZMQ_EXPORT void zsocket_set_router_raw (void *zocket, int router_raw); +CZMQ_EXPORT void zsocket_set_ipv4only (void *zocket, int ipv4only); +CZMQ_EXPORT void zsocket_set_delay_attach_on_connect (void *zocket, int delay_attach_on_connect); +CZMQ_EXPORT void zsocket_set_sndhwm (void *zocket, int sndhwm); +CZMQ_EXPORT void zsocket_set_rcvhwm (void *zocket, int rcvhwm); +CZMQ_EXPORT void zsocket_set_affinity (void *zocket, int affinity); +CZMQ_EXPORT void zsocket_set_subscribe (void *zocket, const char * subscribe); +CZMQ_EXPORT void zsocket_set_unsubscribe (void *zocket, const char * unsubscribe); +CZMQ_EXPORT void zsocket_set_identity (void *zocket, const char * identity); +CZMQ_EXPORT void zsocket_set_rate (void *zocket, int rate); +CZMQ_EXPORT void zsocket_set_recovery_ivl (void *zocket, int recovery_ivl); +CZMQ_EXPORT void zsocket_set_sndbuf (void *zocket, int sndbuf); +CZMQ_EXPORT void zsocket_set_rcvbuf (void *zocket, int rcvbuf); +CZMQ_EXPORT void zsocket_set_linger (void *zocket, int linger); +CZMQ_EXPORT void zsocket_set_reconnect_ivl (void *zocket, int reconnect_ivl); +CZMQ_EXPORT void zsocket_set_reconnect_ivl_max (void *zocket, int reconnect_ivl_max); +CZMQ_EXPORT void zsocket_set_backlog (void *zocket, int backlog); +CZMQ_EXPORT void zsocket_set_maxmsgsize (void *zocket, int maxmsgsize); +CZMQ_EXPORT void zsocket_set_multicast_hops (void *zocket, int multicast_hops); +CZMQ_EXPORT void zsocket_set_rcvtimeo (void *zocket, int rcvtimeo); +CZMQ_EXPORT void zsocket_set_sndtimeo (void *zocket, int sndtimeo); +CZMQ_EXPORT void zsocket_set_xpub_verbose (void *zocket, int xpub_verbose); +CZMQ_EXPORT void zsocket_set_tcp_keepalive (void *zocket, int tcp_keepalive); +CZMQ_EXPORT void zsocket_set_tcp_keepalive_idle (void *zocket, int tcp_keepalive_idle); +CZMQ_EXPORT void zsocket_set_tcp_keepalive_cnt (void *zocket, int tcp_keepalive_cnt); +CZMQ_EXPORT void zsocket_set_tcp_keepalive_intvl (void *zocket, int tcp_keepalive_intvl); +CZMQ_EXPORT void zsocket_set_tcp_accept_filter (void *zocket, const char * tcp_accept_filter); +#endif + +#if (ZMQ_VERSION_MAJOR == 3) +// Get socket options +CZMQ_EXPORT int zsocket_ipv4only (void *zocket); +CZMQ_EXPORT int zsocket_type (void *zocket); +CZMQ_EXPORT int zsocket_sndhwm (void *zocket); +CZMQ_EXPORT int zsocket_rcvhwm (void *zocket); +CZMQ_EXPORT int zsocket_affinity (void *zocket); +CZMQ_EXPORT char * zsocket_identity (void *zocket); +CZMQ_EXPORT int zsocket_rate (void *zocket); +CZMQ_EXPORT int zsocket_recovery_ivl (void *zocket); +CZMQ_EXPORT int zsocket_sndbuf (void *zocket); +CZMQ_EXPORT int zsocket_rcvbuf (void *zocket); +CZMQ_EXPORT int zsocket_linger (void *zocket); +CZMQ_EXPORT int zsocket_reconnect_ivl (void *zocket); +CZMQ_EXPORT int zsocket_reconnect_ivl_max (void *zocket); +CZMQ_EXPORT int zsocket_backlog (void *zocket); +CZMQ_EXPORT int zsocket_maxmsgsize (void *zocket); +CZMQ_EXPORT int zsocket_multicast_hops (void *zocket); +CZMQ_EXPORT int zsocket_rcvtimeo (void *zocket); +CZMQ_EXPORT int zsocket_sndtimeo (void *zocket); +CZMQ_EXPORT int zsocket_tcp_keepalive (void *zocket); +CZMQ_EXPORT int zsocket_tcp_keepalive_idle (void *zocket); +CZMQ_EXPORT int zsocket_tcp_keepalive_cnt (void *zocket); +CZMQ_EXPORT int zsocket_tcp_keepalive_intvl (void *zocket); +CZMQ_EXPORT char * zsocket_tcp_accept_filter (void *zocket); +CZMQ_EXPORT int zsocket_rcvmore (void *zocket); +CZMQ_EXPORT SOCKET zsocket_fd (void *zocket); +CZMQ_EXPORT int zsocket_events (void *zocket); +CZMQ_EXPORT char * zsocket_last_endpoint (void *zocket); + +// Set socket options +CZMQ_EXPORT void zsocket_set_router_raw (void *zocket, int router_raw); +CZMQ_EXPORT void zsocket_set_ipv4only (void *zocket, int ipv4only); +CZMQ_EXPORT void zsocket_set_delay_attach_on_connect (void *zocket, int delay_attach_on_connect); +CZMQ_EXPORT void zsocket_set_sndhwm (void *zocket, int sndhwm); +CZMQ_EXPORT void zsocket_set_rcvhwm (void *zocket, int rcvhwm); +CZMQ_EXPORT void zsocket_set_affinity (void *zocket, int affinity); +CZMQ_EXPORT void zsocket_set_subscribe (void *zocket, const char * subscribe); +CZMQ_EXPORT void zsocket_set_unsubscribe (void *zocket, const char * unsubscribe); +CZMQ_EXPORT void zsocket_set_identity (void *zocket, const char * identity); +CZMQ_EXPORT void zsocket_set_rate (void *zocket, int rate); +CZMQ_EXPORT void zsocket_set_recovery_ivl (void *zocket, int recovery_ivl); +CZMQ_EXPORT void zsocket_set_sndbuf (void *zocket, int sndbuf); +CZMQ_EXPORT void zsocket_set_rcvbuf (void *zocket, int rcvbuf); +CZMQ_EXPORT void zsocket_set_linger (void *zocket, int linger); +CZMQ_EXPORT void zsocket_set_reconnect_ivl (void *zocket, int reconnect_ivl); +CZMQ_EXPORT void zsocket_set_reconnect_ivl_max (void *zocket, int reconnect_ivl_max); +CZMQ_EXPORT void zsocket_set_backlog (void *zocket, int backlog); +CZMQ_EXPORT void zsocket_set_maxmsgsize (void *zocket, int maxmsgsize); +CZMQ_EXPORT void zsocket_set_multicast_hops (void *zocket, int multicast_hops); +CZMQ_EXPORT void zsocket_set_rcvtimeo (void *zocket, int rcvtimeo); +CZMQ_EXPORT void zsocket_set_sndtimeo (void *zocket, int sndtimeo); +CZMQ_EXPORT void zsocket_set_xpub_verbose (void *zocket, int xpub_verbose); +CZMQ_EXPORT void zsocket_set_tcp_keepalive (void *zocket, int tcp_keepalive); +CZMQ_EXPORT void zsocket_set_tcp_keepalive_idle (void *zocket, int tcp_keepalive_idle); +CZMQ_EXPORT void zsocket_set_tcp_keepalive_cnt (void *zocket, int tcp_keepalive_cnt); +CZMQ_EXPORT void zsocket_set_tcp_keepalive_intvl (void *zocket, int tcp_keepalive_intvl); +CZMQ_EXPORT void zsocket_set_tcp_accept_filter (void *zocket, const char * tcp_accept_filter); +#endif + +#if (ZMQ_VERSION_MAJOR == 2) +// Get socket options +CZMQ_EXPORT int zsocket_hwm (void *zocket); +CZMQ_EXPORT int zsocket_swap (void *zocket); +CZMQ_EXPORT int zsocket_affinity (void *zocket); +CZMQ_EXPORT char * zsocket_identity (void *zocket); +CZMQ_EXPORT int zsocket_rate (void *zocket); +CZMQ_EXPORT int zsocket_recovery_ivl (void *zocket); +CZMQ_EXPORT int zsocket_recovery_ivl_msec (void *zocket); +CZMQ_EXPORT int zsocket_mcast_loop (void *zocket); +# if (ZMQ_VERSION_MINOR == 2) +CZMQ_EXPORT int zsocket_rcvtimeo (void *zocket); +# endif +# if (ZMQ_VERSION_MINOR == 2) +CZMQ_EXPORT int zsocket_sndtimeo (void *zocket); +# endif +CZMQ_EXPORT int zsocket_sndbuf (void *zocket); +CZMQ_EXPORT int zsocket_rcvbuf (void *zocket); +CZMQ_EXPORT int zsocket_linger (void *zocket); +CZMQ_EXPORT int zsocket_reconnect_ivl (void *zocket); +CZMQ_EXPORT int zsocket_reconnect_ivl_max (void *zocket); +CZMQ_EXPORT int zsocket_backlog (void *zocket); +CZMQ_EXPORT int zsocket_type (void *zocket); +CZMQ_EXPORT int zsocket_rcvmore (void *zocket); +CZMQ_EXPORT SOCKET zsocket_fd (void *zocket); +CZMQ_EXPORT int zsocket_events (void *zocket); + +// Set socket options +CZMQ_EXPORT void zsocket_set_hwm (void *zocket, int hwm); +CZMQ_EXPORT void zsocket_set_swap (void *zocket, int swap); +CZMQ_EXPORT void zsocket_set_affinity (void *zocket, int affinity); +CZMQ_EXPORT void zsocket_set_identity (void *zocket, const char * identity); +CZMQ_EXPORT void zsocket_set_rate (void *zocket, int rate); +CZMQ_EXPORT void zsocket_set_recovery_ivl (void *zocket, int recovery_ivl); +CZMQ_EXPORT void zsocket_set_recovery_ivl_msec (void *zocket, int recovery_ivl_msec); +CZMQ_EXPORT void zsocket_set_mcast_loop (void *zocket, int mcast_loop); +# if (ZMQ_VERSION_MINOR == 2) +CZMQ_EXPORT void zsocket_set_rcvtimeo (void *zocket, int rcvtimeo); +# endif +# if (ZMQ_VERSION_MINOR == 2) +CZMQ_EXPORT void zsocket_set_sndtimeo (void *zocket, int sndtimeo); +# endif +CZMQ_EXPORT void zsocket_set_sndbuf (void *zocket, int sndbuf); +CZMQ_EXPORT void zsocket_set_rcvbuf (void *zocket, int rcvbuf); +CZMQ_EXPORT void zsocket_set_linger (void *zocket, int linger); +CZMQ_EXPORT void zsocket_set_reconnect_ivl (void *zocket, int reconnect_ivl); +CZMQ_EXPORT void zsocket_set_reconnect_ivl_max (void *zocket, int reconnect_ivl_max); +CZMQ_EXPORT void zsocket_set_backlog (void *zocket, int backlog); +CZMQ_EXPORT void zsocket_set_subscribe (void *zocket, const char * subscribe); +CZMQ_EXPORT void zsocket_set_unsubscribe (void *zocket, const char * unsubscribe); +#endif + +// Self test of this class +CZMQ_EXPORT void zsockopt_test (bool verbose); +// @end + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/aarch64/include/zstr.h b/phonelibs/zmq/aarch64/include/zstr.h new file mode 100644 index 00000000000000..3d3f1a862ad7e5 --- /dev/null +++ b/phonelibs/zmq/aarch64/include/zstr.h @@ -0,0 +1,115 @@ +/* ========================================================================= + zstr - sending and receiving strings + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZSTR_H_INCLUDED__ +#define __ZSTR_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/zstr.api" to make changes. +// @interface +// This is a stable class, and may not change except for emergencies. It +// is provided in stable builds. +// This class has draft methods, which may change over time. They are not +// in stable releases, by default. Use --enable-drafts to enable. +// Receive C string from socket. Caller must free returned string using +// zstr_free(). Returns NULL if the context is being terminated or the +// process was interrupted. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT char * + zstr_recv (void *source); + +// Receive a series of strings (until NULL) from multipart data. +// Each string is allocated and filled with string data; if there +// are not enough frames, unallocated strings are set to NULL. +// Returns -1 if the message could not be read, else returns the +// number of strings filled, zero or more. Free each returned string +// using zstr_free(). If not enough strings are provided, remaining +// multipart frames in the message are dropped. +CZMQ_EXPORT int + zstr_recvx (void *source, char **string_p, ...); + +// Send a C string to a socket, as a frame. The string is sent without +// trailing null byte; to read this you can use zstr_recv, or a similar +// method that adds a null terminator on the received string. String +// may be NULL, which is sent as "". +CZMQ_EXPORT int + zstr_send (void *dest, const char *string); + +// Send a C string to a socket, as zstr_send(), with a MORE flag, so that +// you can send further strings in the same multi-part message. +CZMQ_EXPORT int + zstr_sendm (void *dest, const char *string); + +// Send a formatted string to a socket. Note that you should NOT use +// user-supplied strings in the format (they may contain '%' which +// will create security holes). +CZMQ_EXPORT int + zstr_sendf (void *dest, const char *format, ...); + +// Send a formatted string to a socket, as for zstr_sendf(), with a +// MORE flag, so that you can send further strings in the same multi-part +// message. +CZMQ_EXPORT int + zstr_sendfm (void *dest, const char *format, ...); + +// Send a series of strings (until NULL) as multipart data +// Returns 0 if the strings could be sent OK, or -1 on error. +CZMQ_EXPORT int + zstr_sendx (void *dest, const char *string, ...); + +// Free a provided string, and nullify the parent pointer. Safe to call on +// a null pointer. +CZMQ_EXPORT void + zstr_free (char **string_p); + +// Self test of this class. +CZMQ_EXPORT void + zstr_test (bool verbose); + +#ifdef CZMQ_BUILD_DRAFT_API +// *** Draft method, for development use, may change without warning *** +// Accepts a void pointer and returns a fresh character string. If source +// is null, returns an empty string. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT char * + zstr_str (void *source); + +#endif // CZMQ_BUILD_DRAFT_API +// @ignore +CZMQ_EXPORT int + zstr_sendf (void *dest, const char *format, ...) CHECK_PRINTF (2); +CZMQ_EXPORT int + zstr_sendfm (void *dest, const char *format, ...) CHECK_PRINTF (2); +// @end + + +// DEPRECATED as poor style -- callers should use zloop or zpoller +// Receive C string from socket, if socket had input ready. Caller must +// free returned string using zstr_free. Returns NULL if there was no input +// waiting, or if the context was terminated. Use zctx_interrupted to exit +// any loop that relies on this method. +CZMQ_EXPORT char * + zstr_recv_nowait (void *source); + +// Compiler hints +CZMQ_EXPORT int zstr_sendf (void *dest, const char *format, ...) CHECK_PRINTF (2); + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/aarch64/include/zsys.h b/phonelibs/zmq/aarch64/include/zsys.h new file mode 100644 index 00000000000000..97f88a9555b8e0 --- /dev/null +++ b/phonelibs/zmq/aarch64/include/zsys.h @@ -0,0 +1,386 @@ +/* ========================================================================= + zsys - system-level methods + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZSYS_H_INCLUDED__ +#define __ZSYS_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @interface +#define UDP_FRAME_MAX 255 // Max size of UDP frame + +// Callback for interrupt signal handler +typedef void (zsys_handler_fn) (int signal_value); + +// Initialize CZMQ zsys layer; this happens automatically when you create +// a socket or an actor; however this call lets you force initialization +// earlier, so e.g. logging is properly set-up before you start working. +// Not threadsafe, so call only from main thread. Safe to call multiple +// times. Returns global CZMQ context. +CZMQ_EXPORT void * + zsys_init (void); + +// Optionally shut down the CZMQ zsys layer; this normally happens automatically +// when the process exits; however this call lets you force a shutdown +// earlier, avoiding any potential problems with atexit() ordering, especially +// with Windows dlls. +CZMQ_EXPORT void + zsys_shutdown (void); + +// Get a new ZMQ socket, automagically creating a ZMQ context if this is +// the first time. Caller is responsible for destroying the ZMQ socket +// before process exits, to avoid a ZMQ deadlock. Note: you should not use +// this method in CZMQ apps, use zsock_new() instead. +// *** This is for CZMQ internal use only and may change arbitrarily *** +CZMQ_EXPORT void * + zsys_socket (int type, const char *filename, size_t line_nbr); + +// Destroy/close a ZMQ socket. You should call this for every socket you +// create using zsys_socket(). +// *** This is for CZMQ internal use only and may change arbitrarily *** +CZMQ_EXPORT int + zsys_close (void *handle, const char *filename, size_t line_nbr); + +// Return ZMQ socket name for socket type +// *** This is for CZMQ internal use only and may change arbitrarily *** +CZMQ_EXPORT char * + zsys_sockname (int socktype); + +// Create a pipe, which consists of two PAIR sockets connected over inproc. +// The pipe is configured to use the zsys_pipehwm setting. Returns the +// frontend socket successful, NULL if failed. +CZMQ_EXPORT zsock_t * + zsys_create_pipe (zsock_t **backend_p); + +// Set interrupt handler; this saves the default handlers so that a +// zsys_handler_reset () can restore them. If you call this multiple times +// then the last handler will take affect. If handler_fn is NULL, disables +// default SIGINT/SIGTERM handling in CZMQ. +CZMQ_EXPORT void + zsys_handler_set (zsys_handler_fn *handler_fn); + +// Reset interrupt handler, call this at exit if needed +CZMQ_EXPORT void + zsys_handler_reset (void); + +// Set default interrupt handler, so Ctrl-C or SIGTERM will set +// zsys_interrupted. Idempotent; safe to call multiple times. +// *** This is for CZMQ internal use only and may change arbitrarily *** +CZMQ_EXPORT void + zsys_catch_interrupts (void); + +// Return 1 if file exists, else zero +CZMQ_EXPORT bool + zsys_file_exists (const char *filename); + +// Return size of file, or -1 if not found +CZMQ_EXPORT ssize_t + zsys_file_size (const char *filename); + +// Return file modification time. Returns 0 if the file does not exist. +CZMQ_EXPORT time_t + zsys_file_modified (const char *filename); + +// Return file mode; provides at least support for the POSIX S_ISREG(m) +// and S_ISDIR(m) macros and the S_IRUSR and S_IWUSR bits, on all boxes. +// Returns a mode_t cast to int, or -1 in case of error. +CZMQ_EXPORT int + zsys_file_mode (const char *filename); + +// Delete file. Does not complain if the file is absent +CZMQ_EXPORT int + zsys_file_delete (const char *filename); + +// Check if file is 'stable' +CZMQ_EXPORT bool + zsys_file_stable (const char *filename); + +// Create a file path if it doesn't exist. The file path is treated as a +// printf format. +CZMQ_EXPORT int + zsys_dir_create (const char *pathname, ...); + +// Remove a file path if empty; the pathname is treated as printf format. +CZMQ_EXPORT int + zsys_dir_delete (const char *pathname, ...); + +// Move to a specified working directory. Returns 0 if OK, -1 if this failed. +CZMQ_EXPORT int + zsys_dir_change (const char *pathname); + +// Set private file creation mode; all files created from here will be +// readable/writable by the owner only. +CZMQ_EXPORT void + zsys_file_mode_private (void); + +// Reset default file creation mode; all files created from here will use +// process file mode defaults. +CZMQ_EXPORT void + zsys_file_mode_default (void); + +// Return the CZMQ version for run-time API detection; returns version +// number into provided fields, providing reference isn't null in each case. +CZMQ_EXPORT void + zsys_version (int *major, int *minor, int *patch); + +// Format a string using printf formatting, returning a freshly allocated +// buffer. If there was insufficient memory, returns NULL. Free the returned +// string using zstr_free(). +CZMQ_EXPORT char * + zsys_sprintf (const char *format, ...); + +// Format a string with a va_list argument, returning a freshly allocated +// buffer. If there was insufficient memory, returns NULL. Free the returned +// string using zstr_free(). +CZMQ_EXPORT char * + zsys_vprintf (const char *format, va_list argptr); + +// Create UDP beacon socket; if the routable option is true, uses +// multicast (not yet implemented), else uses broadcast. This method +// and related ones might _eventually_ be moved to a zudp class. +// *** This is for CZMQ internal use only and may change arbitrarily *** +CZMQ_EXPORT SOCKET + zsys_udp_new (bool routable); + +// Close a UDP socket +// *** This is for CZMQ internal use only and may change arbitrarily *** +CZMQ_EXPORT int + zsys_udp_close (SOCKET handle); + +// Send zframe to UDP socket, return -1 if sending failed due to +// interface having disappeared (happens easily with WiFi) +// *** This is for CZMQ internal use only and may change arbitrarily *** +CZMQ_EXPORT int + zsys_udp_send (SOCKET udpsock, zframe_t *frame, inaddr_t *address, int addrlen); + +// Receive zframe from UDP socket, and set address of peer that sent it +// The peername must be a char [INET_ADDRSTRLEN] array. +// *** This is for CZMQ internal use only and may change arbitrarily *** +CZMQ_EXPORT zframe_t * + zsys_udp_recv (SOCKET udpsock, char *peername, int peerlen); + +// Handle an I/O error on some socket operation; will report and die on +// fatal errors, and continue silently on "try again" errors. +// *** This is for CZMQ internal use only and may change arbitrarily *** +CZMQ_EXPORT void + zsys_socket_error (const char *reason); + +// Return current host name, for use in public tcp:// endpoints. Caller gets +// a freshly allocated string, should free it using zstr_free(). If the host +// name is not resolvable, returns NULL. +CZMQ_EXPORT char * + zsys_hostname (void); + +// Move the current process into the background. The precise effect depends +// on the operating system. On POSIX boxes, moves to a specified working +// directory (if specified), closes all file handles, reopens stdin, stdout, +// and stderr to the null device, and sets the process to ignore SIGHUP. On +// Windows, does nothing. Returns 0 if OK, -1 if there was an error. +CZMQ_EXPORT int + zsys_daemonize (const char *workdir); + +// Drop the process ID into the lockfile, with exclusive lock, and switch +// the process to the specified group and/or user. Any of the arguments +// may be null, indicating a no-op. Returns 0 on success, -1 on failure. +// Note if you combine this with zsys_daemonize, run after, not before +// that method, or the lockfile will hold the wrong process ID. +CZMQ_EXPORT int + zsys_run_as (const char *lockfile, const char *group, const char *user); + +// Returns true if the underlying libzmq supports CURVE security. +// Uses a heuristic probe according to the version of libzmq being used. +CZMQ_EXPORT bool + zsys_has_curve (void); + +// Configure the number of I/O threads that ZeroMQ will use. A good +// rule of thumb is one thread per gigabit of traffic in or out. The +// default is 1, sufficient for most applications. If the environment +// variable ZSYS_IO_THREADS is defined, that provides the default. +// Note that this method is valid only before any socket is created. +CZMQ_EXPORT void + zsys_set_io_threads (size_t io_threads); + +// Configure the number of sockets that ZeroMQ will allow. The default +// is 1024. The actual limit depends on the system, and you can query it +// by using zsys_socket_limit (). A value of zero means "maximum". +// Note that this method is valid only before any socket is created. +CZMQ_EXPORT void + zsys_set_max_sockets (size_t max_sockets); + +// Return maximum number of ZeroMQ sockets that the system will support. +CZMQ_EXPORT size_t + zsys_socket_limit (void); + +// Configure the default linger timeout in msecs for new zsock instances. +// You can also set this separately on each zsock_t instance. The default +// linger time is zero, i.e. any pending messages will be dropped. If the +// environment variable ZSYS_LINGER is defined, that provides the default. +// Note that process exit will typically be delayed by the linger time. +CZMQ_EXPORT void + zsys_set_linger (size_t linger); + +// Configure the default outgoing pipe limit (HWM) for new zsock instances. +// You can also set this separately on each zsock_t instance. The default +// HWM is 1,000, on all versions of ZeroMQ. If the environment variable +// ZSYS_SNDHWM is defined, that provides the default. Note that a value of +// zero means no limit, i.e. infinite memory consumption. +CZMQ_EXPORT void + zsys_set_sndhwm (size_t sndhwm); + +// Configure the default incoming pipe limit (HWM) for new zsock instances. +// You can also set this separately on each zsock_t instance. The default +// HWM is 1,000, on all versions of ZeroMQ. If the environment variable +// ZSYS_RCVHWM is defined, that provides the default. Note that a value of +// zero means no limit, i.e. infinite memory consumption. +CZMQ_EXPORT void + zsys_set_rcvhwm (size_t rcvhwm); + +// Configure the default HWM for zactor internal pipes; this is set on both +// ends of the pipe, for outgoing messages only (sndhwm). The default HWM is +// 1,000, on all versions of ZeroMQ. If the environment var ZSYS_ACTORHWM is +// defined, that provides the default. Note that a value of zero means no +// limit, i.e. infinite memory consumption. +CZMQ_EXPORT void + zsys_set_pipehwm (size_t pipehwm); + +// Return the HWM for zactor internal pipes. +CZMQ_EXPORT size_t + zsys_pipehwm (void); + +// Configure use of IPv6 for new zsock instances. By default sockets accept +// and make only IPv4 connections. When you enable IPv6, sockets will accept +// and connect to both IPv4 and IPv6 peers. You can override the setting on +// each zsock_t instance. The default is IPv4 only (ipv6 set to 0). If the +// environment variable ZSYS_IPV6 is defined (as 1 or 0), this provides the +// default. Note: has no effect on ZMQ v2. +CZMQ_EXPORT void + zsys_set_ipv6 (int ipv6); + +// Return use of IPv6 for zsock instances. +CZMQ_EXPORT int + zsys_ipv6 (void); + +// Set network interface name to use for broadcasts, particularly zbeacon. +// This lets the interface be configured for test environments where required. +// For example, on Mac OS X, zbeacon cannot bind to 255.255.255.255 which is +// the default when there is no specified interface. If the environment +// variable ZSYS_INTERFACE is set, use that as the default interface name. +// Setting the interface to "*" means "use all available interfaces". +CZMQ_EXPORT void + zsys_set_interface (const char *value); + +// Return network interface to use for broadcasts, or "" if none was set. +CZMQ_EXPORT const char * + zsys_interface (void); + +// Set IPv6 address to use zbeacon socket, particularly for receiving zbeacon. +// This needs to be set IPv6 is enabled as IPv6 can have multiple addresses +// on a given interface. If the environment variable ZSYS_IPV6_ADDRESS is set, +// use that as the default IPv6 address. +CZMQ_EXPORT void + zsys_set_ipv6_address (const char *value); + +// Return IPv6 address to use for zbeacon reception, or "" if none was set. +CZMQ_EXPORT const char * + zsys_ipv6_address (void); + +// Set IPv6 milticast address to use for sending zbeacon messages. This needs +// to be set if IPv6 is enabled. If the environment variable +// ZSYS_IPV6_MCAST_ADDRESS is set, use that as the default IPv6 multicast +// address. +CZMQ_EXPORT void + zsys_set_ipv6_mcast_address (const char *value); + +// Return IPv6 multicast address to use for sending zbeacon, or "" if none was +// set. +CZMQ_EXPORT const char * + zsys_ipv6_mcast_address (void); + +// Configure the automatic use of pre-allocated FDs when creating new sockets. +// If 0 (default), nothing will happen. Else, when a new socket is bound, the +// system API will be used to check if an existing pre-allocated FD with a +// matching port (if TCP) or path (if IPC) exists, and if it does it will be +// set via the ZMQ_USE_FD socket option so that the library will use it +// instead of creating a new socket. +CZMQ_EXPORT void + zsys_set_auto_use_fd (int auto_use_fd); + +// Return use of automatic pre-allocated FDs for zsock instances. +CZMQ_EXPORT int + zsys_auto_use_fd (void); + +// Set log identity, which is a string that prefixes all log messages sent +// by this process. The log identity defaults to the environment variable +// ZSYS_LOGIDENT, if that is set. +CZMQ_EXPORT void + zsys_set_logident (const char *value); + +// Set stream to receive log traffic. By default, log traffic is sent to +// stdout. If you set the stream to NULL, no stream will receive the log +// traffic (it may still be sent to the system facility). +CZMQ_EXPORT void + zsys_set_logstream (FILE *stream); + +// Sends log output to a PUB socket bound to the specified endpoint. To +// collect such log output, create a SUB socket, subscribe to the traffic +// you care about, and connect to the endpoint. Log traffic is sent as a +// single string frame, in the same format as when sent to stdout. The +// log system supports a single sender; multiple calls to this method will +// bind the same sender to multiple endpoints. To disable the sender, call +// this method with a null argument. +CZMQ_EXPORT void + zsys_set_logsender (const char *endpoint); + +// Enable or disable logging to the system facility (syslog on POSIX boxes, +// event log on Windows). By default this is disabled. +CZMQ_EXPORT void + zsys_set_logsystem (bool logsystem); + +// Log error condition - highest priority +CZMQ_EXPORT void + zsys_error (const char *format, ...); + +// Log warning condition - high priority +CZMQ_EXPORT void + zsys_warning (const char *format, ...); + +// Log normal, but significant, condition - normal priority +CZMQ_EXPORT void + zsys_notice (const char *format, ...); + +// Log informational message - low priority +CZMQ_EXPORT void + zsys_info (const char *format, ...); + +// Log debug-level message - lowest priority +CZMQ_EXPORT void + zsys_debug (const char *format, ...); + +// Self test of this class +CZMQ_EXPORT void + zsys_test (bool verbose); + +// Global signal indicator, TRUE when user presses Ctrl-C or the process +// gets a SIGTERM signal. +CZMQ_EXPORT extern volatile int zsys_interrupted; +// Deprecated name for this variable +CZMQ_EXPORT extern volatile int zctx_interrupted; +// @end + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/aarch64/include/zthread.h b/phonelibs/zmq/aarch64/include/zthread.h new file mode 100644 index 00000000000000..fc0602dd9ff483 --- /dev/null +++ b/phonelibs/zmq/aarch64/include/zthread.h @@ -0,0 +1,50 @@ +/* ========================================================================= + zthread - working with system threads (deprecated) + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZTHREAD_H_INCLUDED__ +#define __ZTHREAD_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @interface +// Detached threads follow POSIX pthreads API +typedef void *(zthread_detached_fn) (void *args); + +// Attached threads get context and pipe from parent +typedef void (zthread_attached_fn) (void *args, zctx_t *ctx, void *pipe); + +// Create a detached thread. A detached thread operates autonomously +// and is used to simulate a separate process. It gets no ctx, and no +// pipe. +CZMQ_EXPORT int + zthread_new (zthread_detached_fn *thread_fn, void *args); + +// Create an attached thread. An attached thread gets a ctx and a PAIR +// pipe back to its parent. It must monitor its pipe, and exit if the +// pipe becomes unreadable. Do not destroy the ctx, the thread does this +// automatically when it ends. +CZMQ_EXPORT void * + zthread_fork (zctx_t *ctx, zthread_attached_fn *thread_fn, void *args); + +// Self test of this class +CZMQ_EXPORT void + zthread_test (bool verbose); +// @end + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/aarch64/include/ztimerset.h b/phonelibs/zmq/aarch64/include/ztimerset.h new file mode 100644 index 00000000000000..29633fafdbdd30 --- /dev/null +++ b/phonelibs/zmq/aarch64/include/ztimerset.h @@ -0,0 +1,90 @@ +/* ========================================================================= + ztimerset - timer set + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef ZTIMERSET_H_INCLUDED +#define ZTIMERSET_H_INCLUDED + +#ifdef __cplusplus +extern "C" { +#endif + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/ztimerset.api" to make changes. +// @interface +// This is a draft class, and may change without notice. It is disabled in +// stable builds by default. If you use this in applications, please ask +// for it to be pushed to stable state. Use --enable-drafts to enable. +#ifdef CZMQ_BUILD_DRAFT_API +// Callback function for timer event. +typedef void (ztimerset_fn) ( + int timer_id, void *arg); + +// *** Draft method, for development use, may change without warning *** +// Create new timer set. +CZMQ_EXPORT ztimerset_t * + ztimerset_new (void); + +// *** Draft method, for development use, may change without warning *** +// Destroy a timer set +CZMQ_EXPORT void + ztimerset_destroy (ztimerset_t **self_p); + +// *** Draft method, for development use, may change without warning *** +// Add a timer to the set. Returns timer id if OK, -1 on failure. +CZMQ_EXPORT int + ztimerset_add (ztimerset_t *self, size_t interval, ztimerset_fn handler, void *arg); + +// *** Draft method, for development use, may change without warning *** +// Cancel a timer. Returns 0 if OK, -1 on failure. +CZMQ_EXPORT int + ztimerset_cancel (ztimerset_t *self, int timer_id); + +// *** Draft method, for development use, may change without warning *** +// Set timer interval. Returns 0 if OK, -1 on failure. +// This method is slow, canceling the timer and adding a new one yield better performance. +CZMQ_EXPORT int + ztimerset_set_interval (ztimerset_t *self, int timer_id, size_t interval); + +// *** Draft method, for development use, may change without warning *** +// Reset timer to start interval counting from current time. Returns 0 if OK, -1 on failure. +// This method is slow, canceling the timer and adding a new one yield better performance. +CZMQ_EXPORT int + ztimerset_reset (ztimerset_t *self, int timer_id); + +// *** Draft method, for development use, may change without warning *** +// Return the time until the next interval. +// Should be used as timeout parameter for the zpoller wait method. +// The timeout is in msec. +CZMQ_EXPORT int + ztimerset_timeout (ztimerset_t *self); + +// *** Draft method, for development use, may change without warning *** +// Invoke callback function of all timers which their interval has elapsed. +// Should be call after zpoller wait method. +// Returns 0 if OK, -1 on failure. +CZMQ_EXPORT int + ztimerset_execute (ztimerset_t *self); + +// *** Draft method, for development use, may change without warning *** +// Self test of this class. +CZMQ_EXPORT void + ztimerset_test (bool verbose); + +#endif // CZMQ_BUILD_DRAFT_API +// @end + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/aarch64/include/ztrie.h b/phonelibs/zmq/aarch64/include/ztrie.h new file mode 100644 index 00000000000000..6fd53234b1274c --- /dev/null +++ b/phonelibs/zmq/aarch64/include/ztrie.h @@ -0,0 +1,106 @@ +/* ========================================================================= + ztrie - simple trie for tokenizable strings + + Copyright (c) 1991-2012 iMatix Corporation -- http://www.imatix.com + Copyright other contributors as noted in the AUTHORS file. + + This file is part of CZMQ, the high-level C binding for 0MQ: http://czmq.zeromq.org + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef ZTRIE_H_INCLUDED +#define ZTRIE_H_INCLUDED + +#ifdef __cplusplus +extern "C" { +#endif + + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/ztrie.api" to make changes. +// @interface +// This is a draft class, and may change without notice. It is disabled in +// stable builds by default. If you use this in applications, please ask +// for it to be pushed to stable state. Use --enable-drafts to enable. +#ifdef CZMQ_BUILD_DRAFT_API +// Callback function for ztrie_node to destroy node data. +typedef void (ztrie_destroy_data_fn) ( + void **data); + +// *** Draft method, for development use, may change without warning *** +// Creates a new ztrie. +CZMQ_EXPORT ztrie_t * + ztrie_new (char delimiter); + +// *** Draft method, for development use, may change without warning *** +// Destroy the ztrie. +CZMQ_EXPORT void + ztrie_destroy (ztrie_t **self_p); + +// *** Draft method, for development use, may change without warning *** +// Inserts a new route into the tree and attaches the data. Returns -1 +// if the route already exists, otherwise 0. This method takes ownership of +// the provided data if a destroy_data_fn is provided. +CZMQ_EXPORT int + ztrie_insert_route (ztrie_t *self, const char *path, void *data, ztrie_destroy_data_fn destroy_data_fn); + +// *** Draft method, for development use, may change without warning *** +// Removes a route from the trie and destroys its data. Returns -1 if the +// route does not exists, otherwise 0. +// the start of the list call zlist_first (). Advances the cursor. +CZMQ_EXPORT int + ztrie_remove_route (ztrie_t *self, const char *path); + +// *** Draft method, for development use, may change without warning *** +// Returns true if the path matches a route in the tree, otherwise false. +CZMQ_EXPORT bool + ztrie_matches (ztrie_t *self, const char *path); + +// *** Draft method, for development use, may change without warning *** +// Returns the data of a matched route from last ztrie_matches. If the path +// did not match, returns NULL. Do not delete the data as it's owned by +// ztrie. +CZMQ_EXPORT void * + ztrie_hit_data (ztrie_t *self); + +// *** Draft method, for development use, may change without warning *** +// Returns the count of parameters that a matched route has. +CZMQ_EXPORT size_t + ztrie_hit_parameter_count (ztrie_t *self); + +// *** Draft method, for development use, may change without warning *** +// Returns the parameters of a matched route with named regexes from last +// ztrie_matches. If the path did not match or the route did not contain any +// named regexes, returns NULL. +CZMQ_EXPORT zhashx_t * + ztrie_hit_parameters (ztrie_t *self); + +// *** Draft method, for development use, may change without warning *** +// Returns the asterisk matched part of a route, if there has been no match +// or no asterisk match, returns NULL. +CZMQ_EXPORT const char * + ztrie_hit_asterisk_match (ztrie_t *self); + +// *** Draft method, for development use, may change without warning *** +// Print the trie +CZMQ_EXPORT void + ztrie_print (ztrie_t *self); + +// *** Draft method, for development use, may change without warning *** +// Self test of this class. +CZMQ_EXPORT void + ztrie_test (bool verbose); + +#endif // CZMQ_BUILD_DRAFT_API +// @end + + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/aarch64/include/zuuid.h b/phonelibs/zmq/aarch64/include/zuuid.h new file mode 100644 index 00000000000000..afc1104fea952b --- /dev/null +++ b/phonelibs/zmq/aarch64/include/zuuid.h @@ -0,0 +1,96 @@ +/* ========================================================================= + zuuid - UUID support class + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZUUID_H_INCLUDED__ +#define __ZUUID_H_INCLUDED__ + +#define ZUUID_LEN 16 +#define ZUUID_STR_LEN (ZUUID_LEN * 2) + +#ifdef __cplusplus +extern "C" { +#endif + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/zuuid.api" to make changes. +// @interface +// This is a stable class, and may not change except for emergencies. It +// is provided in stable builds. +// Create a new UUID object. +CZMQ_EXPORT zuuid_t * + zuuid_new (void); + +// Create UUID object from supplied ZUUID_LEN-octet value. +CZMQ_EXPORT zuuid_t * + zuuid_new_from (const byte *source); + +// Destroy a specified UUID object. +CZMQ_EXPORT void + zuuid_destroy (zuuid_t **self_p); + +// Set UUID to new supplied ZUUID_LEN-octet value. +CZMQ_EXPORT void + zuuid_set (zuuid_t *self, const byte *source); + +// Set UUID to new supplied string value skipping '-' and '{' '}' +// optional delimiters. Return 0 if OK, else returns -1. +CZMQ_EXPORT int + zuuid_set_str (zuuid_t *self, const char *source); + +// Return UUID binary data. +CZMQ_EXPORT const byte * + zuuid_data (zuuid_t *self); + +// Return UUID binary size +CZMQ_EXPORT size_t + zuuid_size (zuuid_t *self); + +// Returns UUID as string +CZMQ_EXPORT const char * + zuuid_str (zuuid_t *self); + +// Return UUID in the canonical string format: 8-4-4-4-12, in lower +// case. Caller does not modify or free returned value. See +// http://en.wikipedia.org/wiki/Universally_unique_identifier +CZMQ_EXPORT const char * + zuuid_str_canonical (zuuid_t *self); + +// Store UUID blob in target array +CZMQ_EXPORT void + zuuid_export (zuuid_t *self, byte *target); + +// Check if UUID is same as supplied value +CZMQ_EXPORT bool + zuuid_eq (zuuid_t *self, const byte *compare); + +// Check if UUID is different from supplied value +CZMQ_EXPORT bool + zuuid_neq (zuuid_t *self, const byte *compare); + +// Make copy of UUID object; if uuid is null, or memory was exhausted, +// returns null. +CZMQ_EXPORT zuuid_t * + zuuid_dup (zuuid_t *self); + +// Self test of this class. +CZMQ_EXPORT void + zuuid_test (bool verbose); + +// @end + + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/aarch64/lib/libczmq.a b/phonelibs/zmq/aarch64/lib/libczmq.a new file mode 100644 index 00000000000000..2d2a251c2f453e Binary files /dev/null and b/phonelibs/zmq/aarch64/lib/libczmq.a differ diff --git a/phonelibs/zmq/aarch64/lib/libczmq.la b/phonelibs/zmq/aarch64/lib/libczmq.la new file mode 100755 index 00000000000000..7eb675e692d303 --- /dev/null +++ b/phonelibs/zmq/aarch64/lib/libczmq.la @@ -0,0 +1,41 @@ +# libczmq.la - a libtool library file +# Generated by libtool (GNU libtool) 2.4.6 +# +# Please DO NOT delete this file! +# It is necessary for linking the library. + +# The name that we can dlopen(3). +dlname='libczmq.so' + +# Names of this library. +library_names='libczmq.so' + +# The name of the static archive. +old_library='libczmq.a' + +# Linker flags that cannot go in dependency_libs. +inherited_linker_flags='' + +# Libraries that this one depends upon. +dependency_libs=' -L/Users/batman/src/czmq/builds/android/prefix/aarch64-linux-android-4.9/lib -L/opt/android-ndk/platforms/android-21/arch-arm64/usr/lib -L/opt/android-ndk/sources/cxx-stl/gnu-libstdc++/4.9/libs/arm64-v8a -L/Users/batman/src/libzmq/builds/android/prefix/aarch64-linux-android-4.9/lib /Users/batman/src/libzmq/builds/android/prefix/aarch64-linux-android-4.9/lib/libzmq.la -llog -lc -lgcc -ldl -lm -lgnustl_shared' + +# Names of additional weak libraries provided by this library +weak_library_names='' + +# Version information for libczmq. +current=3 +age=0 +revision=0 + +# Is this an already installed library? +installed=yes + +# Should we warn about portability when linking against -modules? +shouldnotlink=no + +# Files to dlopen/dlpreopen +dlopen='' +dlpreopen='' + +# Directory that this library needs to be installed in: +libdir='/Users/batman/src/czmq/builds/android/prefix/aarch64-linux-android-4.9/lib' diff --git a/phonelibs/zmq/aarch64/lib/libczmq.so b/phonelibs/zmq/aarch64/lib/libczmq.so new file mode 100755 index 00000000000000..6b662a197f2c93 Binary files /dev/null and b/phonelibs/zmq/aarch64/lib/libczmq.so differ diff --git a/phonelibs/zmq/aarch64/lib/libzmq.a b/phonelibs/zmq/aarch64/lib/libzmq.a new file mode 100644 index 00000000000000..b764af7b6136e6 Binary files /dev/null and b/phonelibs/zmq/aarch64/lib/libzmq.a differ diff --git a/phonelibs/zmq/aarch64/lib/libzmq.la b/phonelibs/zmq/aarch64/lib/libzmq.la new file mode 100755 index 00000000000000..d7d420a4bd98f2 --- /dev/null +++ b/phonelibs/zmq/aarch64/lib/libzmq.la @@ -0,0 +1,41 @@ +# libzmq.la - a libtool library file +# Generated by libtool (GNU libtool) 2.4.6 +# +# Please DO NOT delete this file! +# It is necessary for linking the library. + +# The name that we can dlopen(3). +dlname='libzmq.so' + +# Names of this library. +library_names='libzmq.so' + +# The name of the static archive. +old_library='libzmq.a' + +# Linker flags that cannot go in dependency_libs. +inherited_linker_flags='' + +# Libraries that this one depends upon. +dependency_libs=' -L/Users/batman/src/libzmq/builds/android/prefix/aarch64-linux-android-4.9/lib -L/opt/android-ndk/sources/cxx-stl/gnu-libstdc++/4.9/libs/arm64-v8a -lgnustl_shared' + +# Names of additional weak libraries provided by this library +weak_library_names='' + +# Version information for libzmq. +current=5 +age=0 +revision=0 + +# Is this an already installed library? +installed=yes + +# Should we warn about portability when linking against -modules? +shouldnotlink=no + +# Files to dlopen/dlpreopen +dlopen='' +dlpreopen='' + +# Directory that this library needs to be installed in: +libdir='/Users/batman/src/libzmq/builds/android/prefix/aarch64-linux-android-4.9/lib' diff --git a/phonelibs/zmq/aarch64/lib/libzmq.so b/phonelibs/zmq/aarch64/lib/libzmq.so new file mode 100755 index 00000000000000..909c7f43a6a5f3 Binary files /dev/null and b/phonelibs/zmq/aarch64/lib/libzmq.so differ diff --git a/phonelibs/zmq/arm/include/czmq.h b/phonelibs/zmq/arm/include/czmq.h new file mode 100644 index 00000000000000..ba21aa3bd1efdd --- /dev/null +++ b/phonelibs/zmq/arm/include/czmq.h @@ -0,0 +1,31 @@ +/* ========================================================================= + CZMQ - a high-level binding in C for ZeroMQ + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __CZMQ_H_INCLUDED__ +#define __CZMQ_H_INCLUDED__ + +// These are signatures for handler functions that customize the +// behavior of CZMQ containers. These are shared between all CZMQ +// container types. + +// -- destroy an item +typedef void (czmq_destructor) (void **item); +// -- duplicate an item +typedef void *(czmq_duplicator) (const void *item); +// - compare two items, for sorting +typedef int (czmq_comparator) (const void *item1, const void *item2); + +// Include the project library file +#include "czmq_library.h" + +#endif diff --git a/phonelibs/zmq/arm/include/czmq_library.h b/phonelibs/zmq/arm/include/czmq_library.h new file mode 100644 index 00000000000000..be348db3e9a414 --- /dev/null +++ b/phonelibs/zmq/arm/include/czmq_library.h @@ -0,0 +1,199 @@ +/* ========================================================================= + czmq - generated layer of public API + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + +################################################################################ +# THIS FILE IS 100% GENERATED BY ZPROJECT; DO NOT EDIT EXCEPT EXPERIMENTALLY # +# Read the zproject/README.md for information about making permanent changes. # +################################################################################ + ========================================================================= +*/ + +#ifndef CZMQ_LIBRARY_H_INCLUDED +#define CZMQ_LIBRARY_H_INCLUDED + +// Set up environment for the application +#include "czmq_prelude.h" + +// External dependencies +#include + +// CZMQ version macros for compile-time API detection +#define CZMQ_VERSION_MAJOR 3 +#define CZMQ_VERSION_MINOR 0 +#define CZMQ_VERSION_PATCH 3 + +#define CZMQ_MAKE_VERSION(major, minor, patch) \ + ((major) * 10000 + (minor) * 100 + (patch)) +#define CZMQ_VERSION \ + CZMQ_MAKE_VERSION(CZMQ_VERSION_MAJOR, CZMQ_VERSION_MINOR, CZMQ_VERSION_PATCH) + +#if defined (__WINDOWS__) +# if defined CZMQ_STATIC +# define CZMQ_EXPORT +# elif defined CZMQ_INTERNAL_BUILD +# if defined DLL_EXPORT +# define CZMQ_EXPORT __declspec(dllexport) +# else +# define CZMQ_EXPORT +# endif +# elif defined CZMQ_EXPORTS +# define CZMQ_EXPORT __declspec(dllexport) +# else +# define CZMQ_EXPORT __declspec(dllimport) +# endif +#else +# define CZMQ_EXPORT +#endif + +// Opaque class structures to allow forward references +// These classes are stable or legacy and built in all releases +typedef struct _zactor_t zactor_t; +#define ZACTOR_T_DEFINED +typedef struct _zarmour_t zarmour_t; +#define ZARMOUR_T_DEFINED +typedef struct _zcert_t zcert_t; +#define ZCERT_T_DEFINED +typedef struct _zcertstore_t zcertstore_t; +#define ZCERTSTORE_T_DEFINED +typedef struct _zchunk_t zchunk_t; +#define ZCHUNK_T_DEFINED +typedef struct _zclock_t zclock_t; +#define ZCLOCK_T_DEFINED +typedef struct _zconfig_t zconfig_t; +#define ZCONFIG_T_DEFINED +typedef struct _zdigest_t zdigest_t; +#define ZDIGEST_T_DEFINED +typedef struct _zdir_t zdir_t; +#define ZDIR_T_DEFINED +typedef struct _zdir_patch_t zdir_patch_t; +#define ZDIR_PATCH_T_DEFINED +typedef struct _zfile_t zfile_t; +#define ZFILE_T_DEFINED +typedef struct _zframe_t zframe_t; +#define ZFRAME_T_DEFINED +typedef struct _zhash_t zhash_t; +#define ZHASH_T_DEFINED +typedef struct _zhashx_t zhashx_t; +#define ZHASHX_T_DEFINED +typedef struct _ziflist_t ziflist_t; +#define ZIFLIST_T_DEFINED +typedef struct _zlist_t zlist_t; +#define ZLIST_T_DEFINED +typedef struct _zlistx_t zlistx_t; +#define ZLISTX_T_DEFINED +typedef struct _zloop_t zloop_t; +#define ZLOOP_T_DEFINED +typedef struct _zmsg_t zmsg_t; +#define ZMSG_T_DEFINED +typedef struct _zpoller_t zpoller_t; +#define ZPOLLER_T_DEFINED +typedef struct _zsock_t zsock_t; +#define ZSOCK_T_DEFINED +typedef struct _zstr_t zstr_t; +#define ZSTR_T_DEFINED +typedef struct _zuuid_t zuuid_t; +#define ZUUID_T_DEFINED +typedef struct _zauth_t zauth_t; +#define ZAUTH_T_DEFINED +typedef struct _zbeacon_t zbeacon_t; +#define ZBEACON_T_DEFINED +typedef struct _zgossip_t zgossip_t; +#define ZGOSSIP_T_DEFINED +typedef struct _zmonitor_t zmonitor_t; +#define ZMONITOR_T_DEFINED +typedef struct _zproxy_t zproxy_t; +#define ZPROXY_T_DEFINED +typedef struct _zrex_t zrex_t; +#define ZREX_T_DEFINED +typedef struct _zsys_t zsys_t; +#define ZSYS_T_DEFINED +typedef struct _zauth_v2_t zauth_v2_t; +#define ZAUTH_V2_T_DEFINED +typedef struct _zbeacon_v2_t zbeacon_v2_t; +#define ZBEACON_V2_T_DEFINED +typedef struct _zctx_t zctx_t; +#define ZCTX_T_DEFINED +typedef struct _zmonitor_v2_t zmonitor_v2_t; +#define ZMONITOR_V2_T_DEFINED +typedef struct _zmutex_t zmutex_t; +#define ZMUTEX_T_DEFINED +typedef struct _zproxy_v2_t zproxy_v2_t; +#define ZPROXY_V2_T_DEFINED +typedef struct _zsocket_t zsocket_t; +#define ZSOCKET_T_DEFINED +typedef struct _zsockopt_t zsockopt_t; +#define ZSOCKOPT_T_DEFINED +typedef struct _zthread_t zthread_t; +#define ZTHREAD_T_DEFINED +// Draft classes are by default not built in stable releases +#ifdef CZMQ_BUILD_DRAFT_API +typedef struct _zproc_t zproc_t; +#define ZPROC_T_DEFINED +typedef struct _ztimerset_t ztimerset_t; +#define ZTIMERSET_T_DEFINED +typedef struct _ztrie_t ztrie_t; +#define ZTRIE_T_DEFINED +#endif // CZMQ_BUILD_DRAFT_API + + +// Public classes, each with its own header file +#include "zactor.h" +#include "zarmour.h" +#include "zcert.h" +#include "zcertstore.h" +#include "zchunk.h" +#include "zclock.h" +#include "zconfig.h" +#include "zdigest.h" +#include "zdir.h" +#include "zdir_patch.h" +#include "zfile.h" +#include "zframe.h" +#include "zhash.h" +#include "zhashx.h" +#include "ziflist.h" +#include "zlist.h" +#include "zlistx.h" +#include "zloop.h" +#include "zmsg.h" +#include "zpoller.h" +#include "zsock.h" +#include "zstr.h" +#include "zuuid.h" +#include "zauth.h" +#include "zbeacon.h" +#include "zgossip.h" +#include "zmonitor.h" +#include "zproxy.h" +#include "zrex.h" +#include "zsys.h" +#include "zauth_v2.h" +#include "zbeacon_v2.h" +#include "zctx.h" +#include "zmonitor_v2.h" +#include "zmutex.h" +#include "zproxy_v2.h" +#include "zsocket.h" +#include "zsockopt.h" +#include "zthread.h" +#ifdef CZMQ_BUILD_DRAFT_API +#include "zproc.h" +#include "ztimerset.h" +#include "ztrie.h" +#endif // CZMQ_BUILD_DRAFT_API + +#endif +/* +################################################################################ +# THIS FILE IS 100% GENERATED BY ZPROJECT; DO NOT EDIT EXCEPT EXPERIMENTALLY # +# Read the zproject/README.md for information about making permanent changes. # +################################################################################ +*/ diff --git a/phonelibs/zmq/arm/include/czmq_prelude.h b/phonelibs/zmq/arm/include/czmq_prelude.h new file mode 100644 index 00000000000000..e9ceb691e839ef --- /dev/null +++ b/phonelibs/zmq/arm/include/czmq_prelude.h @@ -0,0 +1,641 @@ +/* ========================================================================= + czmq_prelude.h - CZMQ environment + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __CZMQ_PRELUDE_H_INCLUDED__ +#define __CZMQ_PRELUDE_H_INCLUDED__ + +//- Establish the compiler and computer system ------------------------------ +/* + * Defines zero or more of these symbols, for use in any non-portable + * code: + * + * __WINDOWS__ Microsoft C/C++ with Windows calls + * __MSDOS__ System is MS-DOS (set if __WINDOWS__ set) + * __VMS__ System is VAX/VMS or Alpha/OpenVMS + * __UNIX__ System is UNIX + * __OS2__ System is OS/2 + * + * __IS_32BIT__ OS/compiler is 32 bits + * __IS_64BIT__ OS/compiler is 64 bits + * + * When __UNIX__ is defined, we also define exactly one of these: + * + * __UTYPE_AUX Apple AUX + * __UTYPE_BEOS BeOS + * __UTYPE_BSDOS BSD/OS + * __UTYPE_DECALPHA Digital UNIX (Alpha) + * __UTYPE_IBMAIX IBM RS/6000 AIX + * __UTYPE_FREEBSD FreeBSD + * __UTYPE_HPUX HP/UX + * __UTYPE_ANDROID Android + * __UTYPE_LINUX Linux + * __UTYPE_GNU GNU/Hurd + * __UTYPE_MIPS MIPS (BSD 4.3/System V mixture) + * __UTYPE_NETBSD NetBSD + * __UTYPE_NEXT NeXT + * __UTYPE_OPENBSD OpenBSD + * __UTYPE_OSX Apple Macintosh OS X + * __UTYPE_IOS Apple iOS + * __UTYPE_QNX QNX + * __UTYPE_IRIX Silicon Graphics IRIX + * __UTYPE_SINIX SINIX-N (Siemens-Nixdorf Unix) + * __UTYPE_SUNOS SunOS + * __UTYPE_SUNSOLARIS Sun Solaris + * __UTYPE_UNIXWARE SCO UnixWare + * ... these are the ones I know about so far. + * __UTYPE_GENERIC Any other UNIX + * + * When __VMS__ is defined, we may define one or more of these: + * + * __VMS_XOPEN Supports XOPEN functions + */ + +#if (defined (__64BIT__) || defined (__x86_64__)) +# define __IS_64BIT__ // May have 64-bit OS/compiler +#else +# define __IS_32BIT__ // Else assume 32-bit OS/compiler +#endif + +#if (defined WIN32 || defined _WIN32) +# undef __WINDOWS__ +# define __WINDOWS__ +# undef __MSDOS__ +# define __MSDOS__ +#endif + +#if (defined WINDOWS || defined _WINDOWS || defined __WINDOWS__) +# undef __WINDOWS__ +# define __WINDOWS__ +# undef __MSDOS__ +# define __MSDOS__ +// Stop cheeky warnings about "deprecated" functions like fopen +# if _MSC_VER >= 1500 +# undef _CRT_SECURE_NO_DEPRECATE +# define _CRT_SECURE_NO_DEPRECATE +# pragma warning(disable: 4996) +# endif +#endif + +// MSDOS Microsoft C +// _MSC_VER Microsoft C +#if (defined (MSDOS) || defined (_MSC_VER)) +# undef __MSDOS__ +# define __MSDOS__ +# if (defined (_DEBUG) && !defined (DEBUG)) +# define DEBUG +# endif +#endif + +#if (defined (__EMX__) && defined (__i386__)) +# undef __OS2__ +# define __OS2__ +#endif + +// VMS VAX C (VAX/VMS) +// __VMS Dec C (Alpha/OpenVMS) +// __vax__ gcc +#if (defined (VMS) || defined (__VMS) || defined (__vax__)) +# undef __VMS__ +# define __VMS__ +# if (__VMS_VER >= 70000000) +# define __VMS_XOPEN +# endif +#endif + +// Try to define a __UTYPE_xxx symbol... +// unix SunOS at least +// __unix__ gcc +// _POSIX_SOURCE is various UNIX systems, maybe also VAX/VMS +#if (defined (unix) || defined (__unix__) || defined (_POSIX_SOURCE)) +# if (!defined (__VMS__)) +# undef __UNIX__ +# define __UNIX__ +# if (defined (__alpha)) // Digital UNIX is 64-bit +# undef __IS_32BIT__ +# define __IS_64BIT__ +# define __UTYPE_DECALPHA +# endif +# endif +#endif + +#if (defined (_AUX)) +# define __UTYPE_AUX +# define __UNIX__ +#elif (defined (__BEOS__)) +# define __UTYPE_BEOS +# define __UNIX__ +#elif (defined (__hpux)) +# define __UTYPE_HPUX +# define __UNIX__ +# define _INCLUDE_HPUX_SOURCE +# define _INCLUDE_XOPEN_SOURCE +# define _INCLUDE_POSIX_SOURCE +#elif (defined (_AIX) || defined (AIX)) +# define __UTYPE_IBMAIX +# define __UNIX__ +#elif (defined (BSD) || defined (bsd)) +# define __UTYPE_BSDOS +# define __UNIX__ +#elif (defined (__ANDROID__)) +# define __UTYPE_ANDROID +# define __UNIX__ +#elif (defined (LINUX) || defined (linux) || defined (__linux__)) +# define __UTYPE_LINUX +# define __UNIX__ +# ifndef __NO_CTYPE +# define __NO_CTYPE // Suppress warnings on tolower() +# endif +# ifndef _DEFAULT_SOURCE +# define _DEFAULT_SOURCE // Include stuff from 4.3 BSD Unix +# endif +#elif (defined (__GNU__)) +# define __UTYPE_GNU +# define __UNIX__ +#elif (defined (Mips)) +# define __UTYPE_MIPS +# define __UNIX__ +#elif (defined (FreeBSD) || defined (__FreeBSD__)) +# define __UTYPE_FREEBSD +# define __UNIX__ +#elif (defined (NetBSD) || defined (__NetBSD__)) +# define __UTYPE_NETBSD +# define __UNIX__ +#elif (defined (OpenBSD) || defined (__OpenBSD__)) +# define __UTYPE_OPENBSD +# define __UNIX__ +#elif (defined (APPLE) || defined (__APPLE__)) +# include +# define __UNIX__ +# if TARGET_OS_IPHONE || TARGET_IPHONE_SIMULATOR +# define __UTYPE_IOS +# else +# define __UTYPE_OSX +# endif +#elif (defined (NeXT)) +# define __UTYPE_NEXT +# define __UNIX__ +#elif (defined (__QNX__)) +# define __UTYPE_QNX +# define __UNIX__ +#elif (defined (sgi)) +# define __UTYPE_IRIX +# define __UNIX__ +#elif (defined (sinix)) +# define __UTYPE_SINIX +# define __UNIX__ +#elif (defined (SOLARIS) || defined (__SRV4)) +# define __UTYPE_SUNSOLARIS +# define __UNIX__ +#elif (defined (SUNOS) || defined (SUN) || defined (sun)) +# define __UTYPE_SUNOS +# define __UNIX__ +#elif (defined (__USLC__) || defined (UnixWare)) +# define __UTYPE_UNIXWARE +# define __UNIX__ +#elif (defined (__CYGWIN__)) +# define __UTYPE_CYGWIN +# define __UNIX__ +#elif (defined (__UNIX__)) +# define __UTYPE_GENERIC +#endif + +//- Always include ZeroMQ headers ------------------------------------------- + +#include "zmq.h" +#if (ZMQ_VERSION < ZMQ_MAKE_VERSION (4, 2, 0)) +# include "zmq_utils.h" +#endif + +//- Standard ANSI include files --------------------------------------------- + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +//- System-specific include files ------------------------------------------- + +#if (defined (__MSDOS__)) +# if (defined (__WINDOWS__)) +# if (_WIN32_WINNT < 0x0501) +# undef _WIN32_WINNT +# define _WIN32_WINNT 0x0501 +# endif +# if (!defined (FD_SETSIZE)) +# define FD_SETSIZE 1024 // Max. filehandles/sockets +# endif +# include +# include +# include +# include +# include // For getnameinfo () +# include // For GetAdaptersAddresses () +# endif +# include +# include +# include +# include +# include +# include +# include +# include +#endif + +#if (defined (__UNIX__)) +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include // Let CZMQ build with libzmq/3.x +# include // Must come before arpa/inet.h +# if (!defined (__UTYPE_ANDROID)) && (!defined (__UTYPE_IBMAIX)) \ + && (!defined (__UTYPE_HPUX)) +# include +# endif +# if defined (__UTYPE_SUNSOLARIS) || defined (__UTYPE_SUNOS) +# include +# endif +# if (!defined (__UTYPE_BEOS)) +# include +# if (!defined (TCP_NODELAY)) +# include +# endif +# endif +# if (defined (__UTYPE_IBMAIX) || defined(__UTYPE_QNX)) +# include +# endif +# if (defined (__UTYPE_BEOS)) +# include +# endif +# if ((defined (_XOPEN_REALTIME) && (_XOPEN_REALTIME >= 1)) \ + || (defined (_POSIX_VERSION) && (_POSIX_VERSION >= 199309L))) +# include +# endif +# if (defined (__UTYPE_OSX) || defined (__UTYPE_IOS)) +# include +# include // For monotonic clocks +# endif +# if (defined (__UTYPE_OSX)) +# include // For _NSGetEnviron() +# endif +# if (defined (__UTYPE_ANDROID)) +# include +# endif +# if (defined (__UTYPE_LINUX) && defined (HAVE_LIBSYSTEMD)) +# include +# endif +#endif + +#if (defined (__VMS__)) +# if (!defined (vaxc)) +# include // Not provided by Vax C +# endif +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +#endif + +#if (defined (__OS2__)) +# include // Required near top +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include +# include // Must come before arpa/inet.h +# include +# include +# if (!defined (TCP_NODELAY)) +# include +# endif +#endif + +// Add missing defines for non-POSIX systems +#ifndef S_IRUSR +# define S_IRUSR S_IREAD +#endif +#ifndef S_IWUSR +# define S_IWUSR S_IWRITE +#endif +#ifndef S_ISDIR +# define S_ISDIR(m) (((m) & S_IFDIR) != 0) +#endif +#ifndef S_ISREG +# define S_ISREG(m) (((m) & S_IFREG) != 0) +#endif + + +//- Check compiler data type sizes ------------------------------------------ + +#if (UCHAR_MAX != 0xFF) +# error "Cannot compile: must change definition of 'byte'." +#endif +#if (USHRT_MAX != 0xFFFFU) +# error "Cannot compile: must change definition of 'dbyte'." +#endif +#if (UINT_MAX != 0xFFFFFFFFU) +# error "Cannot compile: must change definition of 'qbyte'." +#endif + +//- Data types -------------------------------------------------------------- + +typedef unsigned char byte; // Single unsigned byte = 8 bits +typedef unsigned short dbyte; // Double byte = 16 bits +typedef unsigned int qbyte; // Quad byte = 32 bits +typedef struct sockaddr_in inaddr_t; // Internet socket address structure +typedef struct sockaddr_in6 in6addr_t; // Internet 6 socket address structure + +// Common structure to hold inaddr_t and in6addr_t with length +typedef struct { + union { + inaddr_t __addr; // IPv4 address + in6addr_t __addr6; // IPv6 address + } __inaddr_u; +#define ipv4addr __inaddr_u.__addr +#define ipv6addr __inaddr_u.__addr6 + int inaddrlen; +} inaddr_storage_t; + +//- Inevitable macros ------------------------------------------------------- + +#define streq(s1,s2) (!strcmp ((s1), (s2))) +#define strneq(s1,s2) (strcmp ((s1), (s2))) + +// Provide random number from 0..(num-1) +#if (defined (__WINDOWS__)) || (defined (__UTYPE_IBMAIX)) \ + || (defined (__UTYPE_HPUX)) || (defined (__UTYPE_SUNOS)) +# define randof(num) (int) ((float) (num) * rand () / (RAND_MAX + 1.0)) +#else +# define randof(num) (int) ((float) (num) * random () / (RAND_MAX + 1.0)) +#endif + +// Windows MSVS doesn't have stdbool +#if (defined (_MSC_VER)) +# if (!defined (__cplusplus) && (!defined (true))) +# define true 1 +# define false 0 + typedef char bool; +# endif +#else +# include +#endif + +//- A number of POSIX and C99 keywords and data types ----------------------- +// CZMQ uses uint for array indices; equivalent to unsigned int, but more +// convenient in code. We define it in czmq_prelude.h on systems that do +// not define it by default. + +#if (defined (__WINDOWS__)) +# if (!defined (__cplusplus) && (!defined (inline))) +# define inline __inline +# endif +# define strtoull _strtoui64 +# define atoll _atoi64 +# define srandom srand +# define TIMEZONE _timezone +# if (!defined (__MINGW32__)) +# define snprintf _snprintf +# define vsnprintf _vsnprintf +# endif + typedef unsigned long ulong; + typedef unsigned int uint; +# if (!defined (__MINGW32__)) + typedef int mode_t; +# if !defined (_SSIZE_T_DEFINED) +typedef intptr_t ssize_t; +# define _SSIZE_T_DEFINED +# endif +# endif +# if ((!defined (__MINGW32__) \ + || (defined (__MINGW32__) && defined (__IS_64BIT__))) \ + && !defined (ZMQ_DEFINED_STDINT)) + typedef __int8 int8_t; + typedef __int16 int16_t; + typedef __int32 int32_t; + typedef __int64 int64_t; + typedef unsigned __int8 uint8_t; + typedef unsigned __int16 uint16_t; + typedef unsigned __int32 uint32_t; + typedef unsigned __int64 uint64_t; +# endif + typedef uint32_t in_addr_t; +# if (!defined (PRId8)) +# define PRId8 "d" +# endif +# if (!defined (PRId16)) +# define PRId16 "d" +# endif +# if (!defined (PRId32)) +# define PRId32 "d" +# endif +# if (!defined (PRId64)) +# define PRId64 "I64d" +# endif +# if (!defined (PRIu8)) +# define PRIu8 "u" +# endif +# if (!defined (PRIu16)) +# define PRIu16 "u" +# endif +# if (!defined (PRIu32)) +# define PRIu32 "u" +# endif +# if (!defined (PRIu64)) +# define PRIu64 "I64u" +# endif +# if (!defined (va_copy)) + // MSVC does not support C99's va_copy so we use a regular assignment +# define va_copy(dest,src) (dest) = (src) +# endif +#elif (defined (__UTYPE_OSX)) + typedef unsigned long ulong; + typedef unsigned int uint; + // This fixes header-order dependence problem with some Linux versions +#elif (defined (__UTYPE_LINUX)) +# if (__STDC_VERSION__ >= 199901L && !defined (__USE_MISC)) + typedef unsigned int uint; +# endif +#endif + +//- Non-portable declaration specifiers ------------------------------------- + +// For thread-local storage +#if defined (__WINDOWS__) +# define CZMQ_THREADLS __declspec(thread) +#else +# define CZMQ_THREADLS __thread +#endif + +// Replacement for malloc() which asserts if we run out of heap, and +// which zeroes the allocated block. +static inline void * +safe_malloc (size_t size, const char *file, unsigned line) +{ +// printf ("%s:%u %08d\n", file, line, (int) size); + void *mem = calloc (1, size); + if (mem == NULL) { + fprintf (stderr, "FATAL ERROR at %s:%u\n", file, line); + fprintf (stderr, "OUT OF MEMORY (malloc returned NULL)\n"); + fflush (stderr); + abort (); + } + return mem; +} + +// Define _ZMALLOC_DEBUG if you need to trace memory leaks using e.g. mtrace, +// otherwise all allocations will claim to come from czmq_prelude.h. For best +// results, compile all classes so you see dangling object allocations. +// _ZMALLOC_PEDANTIC does the same thing, but its intention is to propagate +// out of memory condition back up the call stack. +#if defined _ZMALLOC_DEBUG || _ZMALLOC_PEDANTIC +# define zmalloc(size) calloc(1,(size)) +#else +# define zmalloc(size) safe_malloc((size), __FILE__, __LINE__) +#endif + +// GCC supports validating format strings for functions that act like printf +#if defined (__GNUC__) && (__GNUC__ >= 2) +# define CHECK_PRINTF(a) __attribute__((format (printf, a, a + 1))) +#else +# define CHECK_PRINTF(a) +#endif + +// Lets us write code that compiles both on Windows and normal platforms +#if !defined (__WINDOWS__) +typedef int SOCKET; +# define closesocket close +# define INVALID_SOCKET -1 +# define SOCKET_ERROR -1 +# define O_BINARY 0 +#endif + +//- Include non-portable header files based on platform.h ------------------- + +#if defined (HAVE_LINUX_WIRELESS_H) +# include +// This would normally come from net/if.h +unsigned int if_nametoindex (const char *ifname); +#else +# if defined (HAVE_NET_IF_H) +# include +# endif +# if defined (HAVE_NET_IF_MEDIA_H) +# include +# endif +#endif + +#if defined (__WINDOWS__) && !defined (HAVE_UUID) +# define HAVE_UUID 1 +#endif +#if defined (__UTYPE_OSX) && !defined (HAVE_UUID) +# define HAVE_UUID 1 +#endif +#if defined (HAVE_UUID) +# if defined (__UTYPE_FREEBSD) || defined (__UTYPE_NETBSD) +# include +# elif defined __UTYPE_HPUX +# include +# elif defined (__UNIX__) +# include +# endif +#endif + +// ZMQ compatibility macros + +#if ZMQ_VERSION_MAJOR == 4 +# define ZMQ_POLL_MSEC 1 // zmq_poll is msec + +#elif ZMQ_VERSION_MAJOR == 3 +# define ZMQ_POLL_MSEC 1 // zmq_poll is msec +# if ZMQ_VERSION_MINOR < 2 +# define zmq_ctx_new zmq_init +# endif +# define zmq_ctx_term zmq_term + +#elif ZMQ_VERSION_MAJOR == 2 +# define ZMQ_POLL_MSEC 1000 // zmq_poll is usec +# define zmq_sendmsg zmq_send // Smooth out 2.x changes +# define zmq_recvmsg zmq_recv +# define zmq_ctx_new zmq_init +# define zmq_ctx_term zmq_term +# define zmq_msg_send(m,s,f) zmq_sendmsg ((s),(m),(f)) +# define zmq_msg_recv(m,s,f) zmq_recvmsg ((s),(m),(f)) + // Older libzmq APIs may be missing some aspects of libzmq v3.0 +# ifndef ZMQ_ROUTER +# define ZMQ_ROUTER ZMQ_XREP +# endif +# ifndef ZMQ_DEALER +# define ZMQ_DEALER ZMQ_XREQ +# endif +# ifndef ZMQ_DONTWAIT +# define ZMQ_DONTWAIT ZMQ_NOBLOCK +# endif +# ifndef ZMQ_XSUB +# error "please upgrade your libzmq from http://zeromq.org" +# endif +# if ZMQ_VERSION_MINOR == 0 \ + || (ZMQ_VERSION_MINOR == 1 && ZMQ_VERSION_PATCH < 7) +# error "CZMQ requires at least libzmq/2.1.7 stable" +# endif +#endif + +#endif diff --git a/phonelibs/zmq/arm/include/zactor.h b/phonelibs/zmq/arm/include/zactor.h new file mode 100644 index 00000000000000..c865c65daf1efa --- /dev/null +++ b/phonelibs/zmq/arm/include/zactor.h @@ -0,0 +1,76 @@ +/* ========================================================================= + zactor - actor + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZACTOR_H_INCLUDED__ +#define __ZACTOR_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/zactor.api" to make changes. +// @interface +// This is a stable class, and may not change except for emergencies. It +// is provided in stable builds. +// Actors get a pipe and arguments from caller +typedef void (zactor_fn) ( + zsock_t *pipe, void *args); + +// Create a new actor passing arbitrary arguments reference. +CZMQ_EXPORT zactor_t * + zactor_new (zactor_fn task, void *args); + +// Destroy an actor. +CZMQ_EXPORT void + zactor_destroy (zactor_t **self_p); + +// Send a zmsg message to the actor, take ownership of the message +// and destroy when it has been sent. +CZMQ_EXPORT int + zactor_send (zactor_t *self, zmsg_t **msg_p); + +// Receive a zmsg message from the actor. Returns NULL if the actor +// was interrupted before the message could be received, or if there +// was a timeout on the actor. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zmsg_t * + zactor_recv (zactor_t *self); + +// Probe the supplied object, and report if it looks like a zactor_t. +CZMQ_EXPORT bool + zactor_is (void *self); + +// Probe the supplied reference. If it looks like a zactor_t instance, +// return the underlying libzmq actor handle; else if it looks like +// a libzmq actor handle, return the supplied value. +CZMQ_EXPORT void * + zactor_resolve (void *self); + +// Return the actor's zsock handle. Use this when you absolutely need +// to work with the zsock instance rather than the actor. +CZMQ_EXPORT zsock_t * + zactor_sock (zactor_t *self); + +// Self test of this class. +CZMQ_EXPORT void + zactor_test (bool verbose); + +// @end + + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/arm/include/zarmour.h b/phonelibs/zmq/arm/include/zarmour.h new file mode 100644 index 00000000000000..c7f299f7afe989 --- /dev/null +++ b/phonelibs/zmq/arm/include/zarmour.h @@ -0,0 +1,114 @@ +/* ========================================================================= + zarmour - armoured text encoding and decoding + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZARMOUR_H_INCLUDED__ +#define __ZARMOUR_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/zarmour.api" to make changes. +// @interface +// This is a stable class, and may not change except for emergencies. It +// is provided in stable builds. +#define ZARMOUR_MODE_BASE64_STD 0 // Standard base 64 +#define ZARMOUR_MODE_BASE64_URL 1 // URL and filename friendly base 64 +#define ZARMOUR_MODE_BASE32_STD 2 // Standard base 32 +#define ZARMOUR_MODE_BASE32_HEX 3 // Extended hex base 32 +#define ZARMOUR_MODE_BASE16 4 // Standard base 16 +#define ZARMOUR_MODE_Z85 5 // Z85 from ZeroMQ RFC 32 + +// Create a new zarmour +CZMQ_EXPORT zarmour_t * + zarmour_new (void); + +// Destroy the zarmour +CZMQ_EXPORT void + zarmour_destroy (zarmour_t **self_p); + +// Encode a stream of bytes into an armoured string. Returns the armoured +// string, or NULL if there was insufficient memory available to allocate +// a new string. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT char * + zarmour_encode (zarmour_t *self, const byte *data, size_t size); + +// Decode an armoured string into a chunk. The decoded output is +// null-terminated, so it may be treated as a string, if that's what +// it was prior to encoding. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zchunk_t * + zarmour_decode (zarmour_t *self, const char *data); + +// Get the mode property. +CZMQ_EXPORT int + zarmour_mode (zarmour_t *self); + +// Get printable string for mode. +CZMQ_EXPORT const char * + zarmour_mode_str (zarmour_t *self); + +// Set the mode property. +CZMQ_EXPORT void + zarmour_set_mode (zarmour_t *self, int mode); + +// Return true if padding is turned on. +CZMQ_EXPORT bool + zarmour_pad (zarmour_t *self); + +// Turn padding on or off. Default is on. +CZMQ_EXPORT void + zarmour_set_pad (zarmour_t *self, bool pad); + +// Get the padding character. +CZMQ_EXPORT char + zarmour_pad_char (zarmour_t *self); + +// Set the padding character. +CZMQ_EXPORT void + zarmour_set_pad_char (zarmour_t *self, char pad_char); + +// Return if splitting output into lines is turned on. Default is off. +CZMQ_EXPORT bool + zarmour_line_breaks (zarmour_t *self); + +// Turn splitting output into lines on or off. +CZMQ_EXPORT void + zarmour_set_line_breaks (zarmour_t *self, bool line_breaks); + +// Get the line length used for splitting lines. +CZMQ_EXPORT size_t + zarmour_line_length (zarmour_t *self); + +// Set the line length used for splitting lines. +CZMQ_EXPORT void + zarmour_set_line_length (zarmour_t *self, size_t line_length); + +// Print properties of object +CZMQ_EXPORT void + zarmour_print (zarmour_t *self); + +// Self test of this class. +CZMQ_EXPORT void + zarmour_test (bool verbose); + +// @end + + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/arm/include/zauth.h b/phonelibs/zmq/arm/include/zauth.h new file mode 100644 index 00000000000000..ca6bb913c8f5aa --- /dev/null +++ b/phonelibs/zmq/arm/include/zauth.h @@ -0,0 +1,100 @@ +/* ========================================================================= + zauth - authentication for ZeroMQ security mechanisms + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZAUTH_H_INCLUDED__ +#define __ZAUTH_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @interface +#define CURVE_ALLOW_ANY "*" + +// CZMQ v3 API (for use with zsock, not zsocket, which is deprecated). +// +// Create new zauth actor instance. This installs authentication on all +// zsock sockets. Until you add policies, all incoming NULL connections are +// allowed (classic ZeroMQ behaviour), and all PLAIN and CURVE connections +// are denied: +// +// zactor_t *auth = zactor_new (zauth, NULL); +// +// Destroy zauth instance. This removes authentication and allows all +// connections to pass, without authentication: +// +// zactor_destroy (&auth); +// +// Note that all zauth commands are synchronous, so your application always +// waits for a signal from the actor after each command. +// +// Enable verbose logging of commands and activity. Verbose logging can help +// debug non-trivial authentication policies: +// +// zstr_send (auth, "VERBOSE"); +// zsock_wait (auth); +// +// Allow (whitelist) a list of IP addresses. For NULL, all clients from +// these addresses will be accepted. For PLAIN and CURVE, they will be +// allowed to continue with authentication. You can call this method +// multiple times to whitelist more IP addresses. If you whitelist one +// or nmore addresses, any non-whitelisted addresses are treated as +// blacklisted: +// +// zstr_sendx (auth, "ALLOW", "127.0.0.1", "127.0.0.2", NULL); +// zsock_wait (auth); +// +// Deny (blacklist) a list of IP addresses. For all security mechanisms, +// this rejects the connection without any further authentication. Use +// either a whitelist, or a blacklist, not not both. If you define both +// a whitelist and a blacklist, only the whitelist takes effect: +// +// zstr_sendx (auth, "DENY", "192.168.0.1", "192.168.0.2", NULL); +// zsock_wait (auth); +// +// Configure PLAIN authentication using a plain-text password file. You can +// modify the password file at any time; zauth will reload it automatically +// if modified externally: +// +// zstr_sendx (auth, "PLAIN", filename, NULL); +// zsock_wait (auth); +// +// Configure CURVE authentication, using a directory that holds all public +// client certificates, i.e. their public keys. The certificates must be in +// zcert_save format. You can add and remove certificates in that directory +// at any time. To allow all client keys without checking, specify +// CURVE_ALLOW_ANY for the directory name: +// +// zstr_sendx (auth, "CURVE", directory, NULL); +// zsock_wait (auth); +// +// Configure GSSAPI authentication, using an underlying mechanism (usually +// Kerberos) to establish a secure context and perform mutual authentication: +// +// zstr_sendx (auth, "GSSAPI", NULL); +// zsock_wait (auth); +// +// This is the zauth constructor as a zactor_fn: +CZMQ_EXPORT void + zauth (zsock_t *pipe, void *certstore); + +// Selftest +CZMQ_EXPORT void + zauth_test (bool verbose); +// @end + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/arm/include/zauth_v2.h b/phonelibs/zmq/arm/include/zauth_v2.h new file mode 100644 index 00000000000000..bbbee86b03e62d --- /dev/null +++ b/phonelibs/zmq/arm/include/zauth_v2.h @@ -0,0 +1,88 @@ +/* ========================================================================= + zauth_v2 - authentication for ZeroMQ servers (deprecated) + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZAUTH_V2_H_INCLUDED__ +#define __ZAUTH_V2_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @interface +#ifndef CURVE_ALLOW_ANY +# define CURVE_ALLOW_ANY "*" +#endif + +// Constructor +// Install authentication for the specified context. Returns a new zauth +// object that you can use to configure authentication. Note that until you +// add policies, all incoming NULL connections are allowed (classic ZeroMQ +// behaviour), and all PLAIN and CURVE connections are denied. If there was +// an error during initialization, returns NULL. +CZMQ_EXPORT zauth_t * + zauth_new (zctx_t *ctx); + +// Destructor +CZMQ_EXPORT void + zauth_destroy (zauth_t **self_p); + +// Allow (whitelist) a single IP address. For NULL, all clients from this +// address will be accepted. For PLAIN and CURVE, they will be allowed to +// continue with authentication. You can call this method multiple times +// to whitelist multiple IP addresses. If you whitelist a single address, +// any non-whitelisted addresses are treated as blacklisted. +CZMQ_EXPORT void + zauth_allow (zauth_t *self, const char *address); + +// Deny (blacklist) a single IP address. For all security mechanisms, this +// rejects the connection without any further authentication. Use either a +// whitelist, or a blacklist, not not both. If you define both a whitelist +// and a blacklist, only the whitelist takes effect. +CZMQ_EXPORT void + zauth_deny (zauth_t *self, const char *address); + +// Configure PLAIN authentication for a given domain. PLAIN authentication +// uses a plain-text password file. To cover all domains, use "*". You can +// modify the password file at any time; it is reloaded automatically. +CZMQ_EXPORT void + zauth_configure_plain (zauth_t *self, const char *domain, const char *filename); + +// Configure CURVE authentication for a given domain. CURVE authentication +// uses a directory that holds all public client certificates, i.e. their +// public keys. The certificates must be in zcert_save () format. To cover +// all domains, use "*". You can add and remove certificates in that +// directory at any time. To allow all client keys without checking, specify +// CURVE_ALLOW_ANY for the location. +CZMQ_EXPORT void + zauth_configure_curve (zauth_t *self, const char *domain, const char *location); + +// Configure GSSAPI authentication for a given domain. GSSAPI authentication +// uses an underlying mechanism (usually Kerberos) to establish a secure +// context and perform mutual authentication. To cover all domains, use "*". +CZMQ_EXPORT void + zauth_configure_gssapi (zauth_t *self, char *domain); + +// Enable verbose tracing of commands and activity +CZMQ_EXPORT void + zauth_set_verbose (zauth_t *self, bool verbose); + +// Selftest +CZMQ_EXPORT void + zauth_v2_test (bool verbose); +// @end + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/arm/include/zbeacon.h b/phonelibs/zmq/arm/include/zbeacon.h new file mode 100644 index 00000000000000..78917e9577e40f --- /dev/null +++ b/phonelibs/zmq/arm/include/zbeacon.h @@ -0,0 +1,86 @@ +/* ========================================================================= + zbeacon - LAN discovery and presence + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZBEACON_H_INCLUDED__ +#define __ZBEACON_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @interface +// Create new zbeacon actor instance: +// +// zactor_t *beacon = zactor_new (zbeacon, NULL); +// +// Destroy zbeacon instance: +// +// zactor_destroy (&beacon); +// +// Enable verbose logging of commands and activity: +// +// zstr_send (beacon, "VERBOSE"); +// +// Configure beacon to run on specified UDP port, and return the name of +// the host, which can be used as endpoint for incoming connections. To +// force the beacon to operate on a given interface, set the environment +// variable ZSYS_INTERFACE, or call zsys_set_interface() before creating +// the beacon. If the system does not support UDP broadcasts (lacking a +// workable interface), returns an empty hostname: +// +// // Pictures: 's' = C string, 'i' = int +// zsock_send (beacon, "si", "CONFIGURE", port_number); +// char *hostname = zstr_recv (beacon); +// +// Start broadcasting a beacon at a specified interval in msec. The beacon +// data can be at most UDP_FRAME_MAX bytes; this constant is defined in +// zsys.h to be 255: +// +// // Pictures: 'b' = byte * data + size_t size +// zsock_send (beacon, "sbi", "PUBLISH", data, size, interval); +// +// Stop broadcasting the beacon: +// +// zstr_sendx (beacon, "SILENCE", NULL); +// +// Start listening to beacons from peers. The filter is used to do a prefix +// match on received beacons, to remove junk. Note that any received data +// that is identical to our broadcast beacon_data is discarded in any case. +// If the filter size is zero, we get all peer beacons: +// +// zsock_send (beacon, "sb", "SUBSCRIBE", filter_data, filter_size); +// +// Stop listening to other peers +// +// zstr_sendx (beacon, "UNSUBSCRIBE", NULL); +// +// Receive next beacon from a peer. Received beacons are always a 2-frame +// message containing the ipaddress of the sender, and then the binary +// beacon data as published by the sender: +// +// zmsg_t *msg = zmsg_recv (beacon); +// +// This is the zbeacon constructor as a zactor_fn: +CZMQ_EXPORT void + zbeacon (zsock_t *pipe, void *unused); + +// Self test of this class +CZMQ_EXPORT void + zbeacon_test (bool verbose); +// @end + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/arm/include/zbeacon_v2.h b/phonelibs/zmq/arm/include/zbeacon_v2.h new file mode 100644 index 00000000000000..8e8f3b4cde9967 --- /dev/null +++ b/phonelibs/zmq/arm/include/zbeacon_v2.h @@ -0,0 +1,75 @@ +/* ========================================================================= + zbeacon - LAN discovery and presence (deprecated) + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZBEACON_V2_H_INCLUDED__ +#define __ZBEACON_V2_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @interface +// Create a new beacon on a certain UDP port. If the system does not +// support UDP broadcasts (lacking a useful interface), returns NULL. +// To force the beacon to operate on a given port, set the environment +// variable ZSYS_INTERFACE, or call zsys_set_interface() beforehand. +// If you are using the new zsock API then pass NULL as the ctx here. +CZMQ_EXPORT zbeacon_t * + zbeacon_new (zctx_t *ctx, int port_nbr); + +// Destroy a beacon +CZMQ_EXPORT void + zbeacon_destroy (zbeacon_t **self_p); + +// Return our own IP address as printable string +CZMQ_EXPORT char * + zbeacon_hostname (zbeacon_t *self); + +// Set broadcast interval in milliseconds (default is 1000 msec) +CZMQ_EXPORT void + zbeacon_set_interval (zbeacon_t *self, int interval); + +// Filter out any beacon that looks exactly like ours +CZMQ_EXPORT void + zbeacon_noecho (zbeacon_t *self); + +// Start broadcasting beacon to peers at the specified interval +CZMQ_EXPORT void + zbeacon_publish (zbeacon_t *self, byte *transmit, size_t size); + +// Stop broadcasting beacons +CZMQ_EXPORT void + zbeacon_silence (zbeacon_t *self); + +// Start listening to other peers; zero-sized filter means get everything +CZMQ_EXPORT void + zbeacon_subscribe (zbeacon_t *self, byte *filter, size_t size); + +// Stop listening to other peers +CZMQ_EXPORT void + zbeacon_unsubscribe (zbeacon_t *self); + +// Get beacon ZeroMQ socket, for polling or receiving messages +CZMQ_EXPORT void * + zbeacon_socket (zbeacon_t *self); + +// Self test of this class +CZMQ_EXPORT void + zbeacon_v2_test (bool verbose); +// @end + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/arm/include/zcert.h b/phonelibs/zmq/arm/include/zcert.h new file mode 100644 index 00000000000000..495b579cda9317 --- /dev/null +++ b/phonelibs/zmq/arm/include/zcert.h @@ -0,0 +1,139 @@ +/* ========================================================================= + zcert - work with CURVE security certificates + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZCERT_H_INCLUDED__ +#define __ZCERT_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/zcert.api" to make changes. +// @interface +// This is a stable class, and may not change except for emergencies. It +// is provided in stable builds. +// This class has draft methods, which may change over time. They are not +// in stable releases, by default. Use --enable-drafts to enable. +// This class has legacy methods, which will be removed over time. You +// should not use them, and migrate any code that is still using them. +// Create and initialize a new certificate in memory +CZMQ_EXPORT zcert_t * + zcert_new (void); + +// Accepts public/secret key pair from caller +CZMQ_EXPORT zcert_t * + zcert_new_from (const byte *public_key, const byte *secret_key); + +// Load certificate from file +CZMQ_EXPORT zcert_t * + zcert_load (const char *filename); + +// Destroy a certificate in memory +CZMQ_EXPORT void + zcert_destroy (zcert_t **self_p); + +// Return public part of key pair as 32-byte binary string +CZMQ_EXPORT const byte * + zcert_public_key (zcert_t *self); + +// Return secret part of key pair as 32-byte binary string +CZMQ_EXPORT const byte * + zcert_secret_key (zcert_t *self); + +// Return public part of key pair as Z85 armored string +CZMQ_EXPORT const char * + zcert_public_txt (zcert_t *self); + +// Return secret part of key pair as Z85 armored string +CZMQ_EXPORT const char * + zcert_secret_txt (zcert_t *self); + +// Set certificate metadata from formatted string. +CZMQ_EXPORT void + zcert_set_meta (zcert_t *self, const char *name, const char *format, ...); + +// Get metadata value from certificate; if the metadata value doesn't +// exist, returns NULL. +CZMQ_EXPORT const char * + zcert_meta (zcert_t *self, const char *name); + +// Get list of metadata fields from certificate. Caller is responsible for +// destroying list. Caller should not modify the values of list items. +CZMQ_EXPORT zlist_t * + zcert_meta_keys (zcert_t *self); + +// Save full certificate (public + secret) to file for persistent storage +// This creates one public file and one secret file (filename + "_secret"). +CZMQ_EXPORT int + zcert_save (zcert_t *self, const char *filename); + +// Save public certificate only to file for persistent storage +CZMQ_EXPORT int + zcert_save_public (zcert_t *self, const char *filename); + +// Save secret certificate only to file for persistent storage +CZMQ_EXPORT int + zcert_save_secret (zcert_t *self, const char *filename); + +// Apply certificate to socket, i.e. use for CURVE security on socket. +// If certificate was loaded from public file, the secret key will be +// undefined, and this certificate will not work successfully. +CZMQ_EXPORT void + zcert_apply (zcert_t *self, void *socket); + +// Return copy of certificate; if certificate is NULL or we exhausted +// heap memory, returns NULL. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zcert_t * + zcert_dup (zcert_t *self); + +// Return true if two certificates have the same keys +CZMQ_EXPORT bool + zcert_eq (zcert_t *self, zcert_t *compare); + +// Print certificate contents to stdout +CZMQ_EXPORT void + zcert_print (zcert_t *self); + +// *** Deprecated method, slated for removal: avoid using it *** +// Print certificate contents to open stream. This method is deprecated +// and you should use the print method. +CZMQ_EXPORT void + zcert_fprint (zcert_t *self, FILE *file); + +// Self test of this class +CZMQ_EXPORT void + zcert_test (bool verbose); + +#ifdef CZMQ_BUILD_DRAFT_API +// *** Draft method, for development use, may change without warning *** +// Unset certificate metadata. +CZMQ_EXPORT void + zcert_unset_meta (zcert_t *self, const char *name); + +#endif // CZMQ_BUILD_DRAFT_API +// @ignore +CZMQ_EXPORT void + zcert_set_meta (zcert_t *self, const char *name, const char *format, ...) CHECK_PRINTF (3); +// @end + + +#ifdef __cplusplus +} +#endif + +// Deprecated method aliases +#define zcert_dump(s) zcert_print(s) + +#endif diff --git a/phonelibs/zmq/arm/include/zcertstore.h b/phonelibs/zmq/arm/include/zcertstore.h new file mode 100644 index 00000000000000..c7f93c5a7d4604 --- /dev/null +++ b/phonelibs/zmq/arm/include/zcertstore.h @@ -0,0 +1,100 @@ +/* ========================================================================= + zcertstore - work with CURVE security certificate stores + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZCERTSTORE_H_INCLUDED__ +#define __ZCERTSTORE_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/zcertstore.api" to make changes. +// @interface +// This is a stable class, and may not change except for emergencies. It +// is provided in stable builds. +// This class has draft methods, which may change over time. They are not +// in stable releases, by default. Use --enable-drafts to enable. +// This class has legacy methods, which will be removed over time. You +// should not use them, and migrate any code that is still using them. +// Create a new certificate store from a disk directory, loading and +// indexing all certificates in that location. The directory itself may be +// absent, and created later, or modified at any time. The certificate store +// is automatically refreshed on any zcertstore_lookup() call. If the +// location is specified as NULL, creates a pure-memory store, which you +// can work with by inserting certificates at runtime. +CZMQ_EXPORT zcertstore_t * + zcertstore_new (const char *location); + +// Destroy a certificate store object in memory. Does not affect anything +// stored on disk. +CZMQ_EXPORT void + zcertstore_destroy (zcertstore_t **self_p); + +// Look up certificate by public key, returns zcert_t object if found, +// else returns NULL. The public key is provided in Z85 text format. +CZMQ_EXPORT zcert_t * + zcertstore_lookup (zcertstore_t *self, const char *public_key); + +// Insert certificate into certificate store in memory. Note that this +// does not save the certificate to disk. To do that, use zcert_save() +// directly on the certificate. Takes ownership of zcert_t object. +CZMQ_EXPORT void + zcertstore_insert (zcertstore_t *self, zcert_t **cert_p); + +// Print list of certificates in store to logging facility +CZMQ_EXPORT void + zcertstore_print (zcertstore_t *self); + +// *** Deprecated method, slated for removal: avoid using it *** +// Print list of certificates in store to open stream. This method is +// deprecated, and you should use the print method. +CZMQ_EXPORT void + zcertstore_fprint (zcertstore_t *self, FILE *file); + +// Self test of this class +CZMQ_EXPORT void + zcertstore_test (bool verbose); + +#ifdef CZMQ_BUILD_DRAFT_API +// Loaders retrieve certificates from an arbitrary source. +typedef void (zcertstore_loader) ( + zcertstore_t *self); + +// Destructor for loader state. +typedef void (zcertstore_destructor) ( + void **self_p); + +// *** Draft method, for development use, may change without warning *** +// Override the default disk loader with a custom loader fn. +CZMQ_EXPORT void + zcertstore_set_loader (zcertstore_t *self, zcertstore_loader loader, zcertstore_destructor destructor, void *state); + +// *** Draft method, for development use, may change without warning *** +// Empty certificate hashtable. This wrapper exists to be friendly to bindings, +// which don't usually have access to struct internals. +CZMQ_EXPORT void + zcertstore_empty (zcertstore_t *self); + +#endif // CZMQ_BUILD_DRAFT_API +// @end + + +#ifdef __cplusplus +} +#endif + +// Deprecated method aliases +#define zcertstore_dump(s) zcertstore_print(s) + +#endif diff --git a/phonelibs/zmq/arm/include/zchunk.h b/phonelibs/zmq/arm/include/zchunk.h new file mode 100644 index 00000000000000..56f29b161a37e5 --- /dev/null +++ b/phonelibs/zmq/arm/include/zchunk.h @@ -0,0 +1,163 @@ +/* ========================================================================= + zchunk - work with memory chunks + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZCHUNK_H_INCLUDED__ +#define __ZCHUNK_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/zchunk.api" to make changes. +// @interface +// This is a stable class, and may not change except for emergencies. It +// is provided in stable builds. +// Create a new chunk of the specified size. If you specify the data, it +// is copied into the chunk. If you do not specify the data, the chunk is +// allocated and left empty, and you can then add data using zchunk_append. +CZMQ_EXPORT zchunk_t * + zchunk_new (const void *data, size_t size); + +// Destroy a chunk +CZMQ_EXPORT void + zchunk_destroy (zchunk_t **self_p); + +// Resizes chunk max_size as requested; chunk_cur size is set to zero +CZMQ_EXPORT void + zchunk_resize (zchunk_t *self, size_t size); + +// Return chunk cur size +CZMQ_EXPORT size_t + zchunk_size (zchunk_t *self); + +// Return chunk max size +CZMQ_EXPORT size_t + zchunk_max_size (zchunk_t *self); + +// Return chunk data +CZMQ_EXPORT byte * + zchunk_data (zchunk_t *self); + +// Set chunk data from user-supplied data; truncate if too large. Data may +// be null. Returns actual size of chunk +CZMQ_EXPORT size_t + zchunk_set (zchunk_t *self, const void *data, size_t size); + +// Fill chunk data from user-supplied octet +CZMQ_EXPORT size_t + zchunk_fill (zchunk_t *self, byte filler, size_t size); + +// Append user-supplied data to chunk, return resulting chunk size. If the +// data would exceeded the available space, it is truncated. If you want to +// grow the chunk to accommodate new data, use the zchunk_extend method. +CZMQ_EXPORT size_t + zchunk_append (zchunk_t *self, const void *data, size_t size); + +// Append user-supplied data to chunk, return resulting chunk size. If the +// data would exceeded the available space, the chunk grows in size. +CZMQ_EXPORT size_t + zchunk_extend (zchunk_t *self, const void *data, size_t size); + +// Copy as much data from 'source' into the chunk as possible; returns the +// new size of chunk. If all data from 'source' is used, returns exhausted +// on the source chunk. Source can be consumed as many times as needed until +// it is exhausted. If source was already exhausted, does not change chunk. +CZMQ_EXPORT size_t + zchunk_consume (zchunk_t *self, zchunk_t *source); + +// Returns true if the chunk was exhausted by consume methods, or if the +// chunk has a size of zero. +CZMQ_EXPORT bool + zchunk_exhausted (zchunk_t *self); + +// Read chunk from an open file descriptor +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zchunk_t * + zchunk_read (FILE *handle, size_t bytes); + +// Write chunk to an open file descriptor +CZMQ_EXPORT int + zchunk_write (zchunk_t *self, FILE *handle); + +// Try to slurp an entire file into a chunk. Will read up to maxsize of +// the file. If maxsize is 0, will attempt to read the entire file and +// fail with an assertion if that cannot fit into memory. Returns a new +// chunk containing the file data, or NULL if the file could not be read. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zchunk_t * + zchunk_slurp (const char *filename, size_t maxsize); + +// Create copy of chunk, as new chunk object. Returns a fresh zchunk_t +// object, or null if there was not enough heap memory. If chunk is null, +// returns null. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zchunk_t * + zchunk_dup (zchunk_t *self); + +// Return chunk data encoded as printable hex string. Caller must free +// string when finished with it. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT char * + zchunk_strhex (zchunk_t *self); + +// Return chunk data copied into freshly allocated string +// Caller must free string when finished with it. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT char * + zchunk_strdup (zchunk_t *self); + +// Return TRUE if chunk body is equal to string, excluding terminator +CZMQ_EXPORT bool + zchunk_streq (zchunk_t *self, const char *string); + +// Transform zchunk into a zframe that can be sent in a message. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zframe_t * + zchunk_pack (zchunk_t *self); + +// Transform a zframe into a zchunk. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zchunk_t * + zchunk_unpack (zframe_t *frame); + +// Calculate SHA1 digest for chunk, using zdigest class. +CZMQ_EXPORT const char * + zchunk_digest (zchunk_t *self); + +// Dump chunk to FILE stream, for debugging and tracing. +CZMQ_EXPORT void + zchunk_fprint (zchunk_t *self, FILE *file); + +// Dump message to stderr, for debugging and tracing. +// See zchunk_fprint for details +CZMQ_EXPORT void + zchunk_print (zchunk_t *self); + +// Probe the supplied object, and report if it looks like a zchunk_t. +CZMQ_EXPORT bool + zchunk_is (void *self); + +// Self test of this class. +CZMQ_EXPORT void + zchunk_test (bool verbose); + +// @end + + +#ifdef __cplusplus +} +#endif + +#endif + diff --git a/phonelibs/zmq/arm/include/zclock.h b/phonelibs/zmq/arm/include/zclock.h new file mode 100644 index 00000000000000..eb064162c4722a --- /dev/null +++ b/phonelibs/zmq/arm/include/zclock.h @@ -0,0 +1,73 @@ +/* ========================================================================= + zclock - millisecond clocks and delays + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZCLOCK_H_INCLUDED__ +#define __ZCLOCK_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/zclock.api" to make changes. +// @interface +// This is a stable class, and may not change except for emergencies. It +// is provided in stable builds. +// Sleep for a number of milliseconds +CZMQ_EXPORT void + zclock_sleep (int msecs); + +// Return current system clock as milliseconds. Note that this clock can +// jump backwards (if the system clock is changed) so is unsafe to use for +// timers and time offsets. Use zclock_mono for that instead. +CZMQ_EXPORT int64_t + zclock_time (void); + +// Return current monotonic clock in milliseconds. Use this when you compute +// time offsets. The monotonic clock is not affected by system changes and +// so will never be reset backwards, unlike a system clock. +CZMQ_EXPORT int64_t + zclock_mono (void); + +// Return current monotonic clock in microseconds. Use this when you compute +// time offsets. The monotonic clock is not affected by system changes and +// so will never be reset backwards, unlike a system clock. +CZMQ_EXPORT int64_t + zclock_usecs (void); + +// Return formatted date/time as fresh string. Free using zstr_free(). +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT char * + zclock_timestr (void); + +// Self test of this class. +CZMQ_EXPORT void + zclock_test (bool verbose); + +// @end + + +// DEPRECATED in favor of zsys logging, see issue #519 +// Print formatted string to stdout, prefixed by date/time and +// terminated with a newline. +CZMQ_EXPORT void + zclock_log (const char *format, ...); + +// Compiler hints +CZMQ_EXPORT void zclock_log (const char *format, ...) CHECK_PRINTF (1); + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/arm/include/zconfig.h b/phonelibs/zmq/arm/include/zconfig.h new file mode 100644 index 00000000000000..4ec4e1c81f03e1 --- /dev/null +++ b/phonelibs/zmq/arm/include/zconfig.h @@ -0,0 +1,194 @@ +/* ========================================================================= + zconfig - work with config files written in rfc.zeromq.org/spec:4/ZPL. + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZCONFIG_H_INCLUDED__ +#define __ZCONFIG_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/zconfig.api" to make changes. +// @interface +// This is a stable class, and may not change except for emergencies. It +// is provided in stable builds. +// +typedef int (zconfig_fct) ( + zconfig_t *self, void *arg, int level); + +// Create new config item +CZMQ_EXPORT zconfig_t * + zconfig_new (const char *name, zconfig_t *parent); + +// Load a config tree from a specified ZPL text file; returns a zconfig_t +// reference for the root, if the file exists and is readable. Returns NULL +// if the file does not exist. +CZMQ_EXPORT zconfig_t * + zconfig_load (const char *filename); + +// Equivalent to zconfig_load, taking a format string instead of a fixed +// filename. +CZMQ_EXPORT zconfig_t * + zconfig_loadf (const char *format, ...); + +// Destroy a config item and all its children +CZMQ_EXPORT void + zconfig_destroy (zconfig_t **self_p); + +// Return name of config item +CZMQ_EXPORT char * + zconfig_name (zconfig_t *self); + +// Return value of config item +CZMQ_EXPORT char * + zconfig_value (zconfig_t *self); + +// Insert or update configuration key with value +CZMQ_EXPORT void + zconfig_put (zconfig_t *self, const char *path, const char *value); + +// Equivalent to zconfig_put, accepting a format specifier and variable +// argument list, instead of a single string value. +CZMQ_EXPORT void + zconfig_putf (zconfig_t *self, const char *path, const char *format, ...); + +// Get value for config item into a string value; leading slash is optional +// and ignored. +CZMQ_EXPORT char * + zconfig_get (zconfig_t *self, const char *path, const char *default_value); + +// Set config item name, name may be NULL +CZMQ_EXPORT void + zconfig_set_name (zconfig_t *self, const char *name); + +// Set new value for config item. The new value may be a string, a printf +// format, or NULL. Note that if string may possibly contain '%', or if it +// comes from an insecure source, you must use '%s' as the format, followed +// by the string. +CZMQ_EXPORT void + zconfig_set_value (zconfig_t *self, const char *format, ...); + +// Find our first child, if any +CZMQ_EXPORT zconfig_t * + zconfig_child (zconfig_t *self); + +// Find our first sibling, if any +CZMQ_EXPORT zconfig_t * + zconfig_next (zconfig_t *self); + +// Find a config item along a path; leading slash is optional and ignored. +CZMQ_EXPORT zconfig_t * + zconfig_locate (zconfig_t *self, const char *path); + +// Locate the last config item at a specified depth +CZMQ_EXPORT zconfig_t * + zconfig_at_depth (zconfig_t *self, int level); + +// Execute a callback for each config item in the tree; returns zero if +// successful, else -1. +CZMQ_EXPORT int + zconfig_execute (zconfig_t *self, zconfig_fct handler, void *arg); + +// Add comment to config item before saving to disk. You can add as many +// comment lines as you like. If you use a null format, all comments are +// deleted. +CZMQ_EXPORT void + zconfig_set_comment (zconfig_t *self, const char *format, ...); + +// Return comments of config item, as zlist. +CZMQ_EXPORT zlist_t * + zconfig_comments (zconfig_t *self); + +// Save a config tree to a specified ZPL text file, where a filename +// "-" means dump to standard output. +CZMQ_EXPORT int + zconfig_save (zconfig_t *self, const char *filename); + +// Equivalent to zconfig_save, taking a format string instead of a fixed +// filename. +CZMQ_EXPORT int + zconfig_savef (zconfig_t *self, const char *format, ...); + +// Report filename used during zconfig_load, or NULL if none +CZMQ_EXPORT const char * + zconfig_filename (zconfig_t *self); + +// Reload config tree from same file that it was previously loaded from. +// Returns 0 if OK, -1 if there was an error (and then does not change +// existing data). +CZMQ_EXPORT int + zconfig_reload (zconfig_t **self_p); + +// Load a config tree from a memory chunk +CZMQ_EXPORT zconfig_t * + zconfig_chunk_load (zchunk_t *chunk); + +// Save a config tree to a new memory chunk +CZMQ_EXPORT zchunk_t * + zconfig_chunk_save (zconfig_t *self); + +// Load a config tree from a null-terminated string +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zconfig_t * + zconfig_str_load (const char *string); + +// Save a config tree to a new null terminated string +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT char * + zconfig_str_save (zconfig_t *self); + +// Return true if a configuration tree was loaded from a file and that +// file has changed in since the tree was loaded. +CZMQ_EXPORT bool + zconfig_has_changed (zconfig_t *self); + +// Print the config file to open stream +CZMQ_EXPORT void + zconfig_fprint (zconfig_t *self, FILE *file); + +// Print properties of object +CZMQ_EXPORT void + zconfig_print (zconfig_t *self); + +// Self test of this class +CZMQ_EXPORT void + zconfig_test (bool verbose); + +// @ignore +CZMQ_EXPORT void + zconfig_putf (zconfig_t *self, const char *path, const char *format, ...) CHECK_PRINTF (3); +CZMQ_EXPORT void + zconfig_set_value (zconfig_t *self, const char *format, ...) CHECK_PRINTF (2); +CZMQ_EXPORT void + zconfig_set_comment (zconfig_t *self, const char *format, ...) CHECK_PRINTF (2); +CZMQ_EXPORT int + zconfig_savef (zconfig_t *self, const char *format, ...) CHECK_PRINTF (2); +// @end + +// Self test of this class +CZMQ_EXPORT void + zconfig_test (bool verbose); + +// Compiler hints +CZMQ_EXPORT void zconfig_set_value (zconfig_t *self, const char *format, ...) CHECK_PRINTF (2); + +#ifdef __cplusplus +} +#endif + +// Deprecated method aliases +#define zconfig_dump(s) zconfig_print(s) +#define zconfig_resolve(s,p,d) zconfig_get((s),(p),(d)) + +#endif diff --git a/phonelibs/zmq/arm/include/zctx.h b/phonelibs/zmq/arm/include/zctx.h new file mode 100644 index 00000000000000..88898410dc8e99 --- /dev/null +++ b/phonelibs/zmq/arm/include/zctx.h @@ -0,0 +1,107 @@ +/* ========================================================================= + zctx - working with 0MQ contexts + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZCTX_H_INCLUDED__ +#define __ZCTX_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + + +// @interface +// Create new context, returns context object, replaces zmq_init +CZMQ_EXPORT zctx_t * + zctx_new (void); + +// Destroy context and all sockets in it, replaces zmq_term +CZMQ_EXPORT void + zctx_destroy (zctx_t **self_p); + +// Create new shadow context, returns context object +CZMQ_EXPORT zctx_t * + zctx_shadow (zctx_t *self); +// @end + +// Create a new context by shadowing a plain zmq context +CZMQ_EXPORT zctx_t * +zctx_shadow_zmq_ctx (void *zmqctx); + +// @interface +// Raise default I/O threads from 1, for crazy heavy applications +// The rule of thumb is one I/O thread per gigabyte of traffic in +// or out. Call this method before creating any sockets on the context, +// or calling zctx_shadow, or the setting will have no effect. +CZMQ_EXPORT void + zctx_set_iothreads (zctx_t *self, int iothreads); + +// Set msecs to flush sockets when closing them, see the ZMQ_LINGER +// man page section for more details. By default, set to zero, so +// any in-transit messages are discarded when you destroy a socket or +// a context. +CZMQ_EXPORT void + zctx_set_linger (zctx_t *self, int linger); + +// Set initial high-water mark for inter-thread pipe sockets. Note that +// this setting is separate from the default for normal sockets. You +// should change the default for pipe sockets *with care*. Too low values +// will cause blocked threads, and an infinite setting can cause memory +// exhaustion. The default, no matter the underlying ZeroMQ version, is +// 1,000. +CZMQ_EXPORT void + zctx_set_pipehwm (zctx_t *self, int pipehwm); + +// Set initial send HWM for all new normal sockets created in context. +// You can set this per-socket after the socket is created. +// The default, no matter the underlying ZeroMQ version, is 1,000. +CZMQ_EXPORT void + zctx_set_sndhwm (zctx_t *self, int sndhwm); + +// Set initial receive HWM for all new normal sockets created in context. +// You can set this per-socket after the socket is created. +// The default, no matter the underlying ZeroMQ version, is 1,000. +CZMQ_EXPORT void + zctx_set_rcvhwm (zctx_t *self, int rcvhwm); + +// Return low-level 0MQ context object, will be NULL before first socket +// is created. Use with care. +CZMQ_EXPORT void * + zctx_underlying (zctx_t *self); + +// Self test of this class +CZMQ_EXPORT void + zctx_test (bool verbose); +// @end + +// Create socket within this context, for CZMQ use only +void * + zctx__socket_new (zctx_t *self, int type); + +// Create pipe socket within this context, for CZMQ use only +void * + zctx__socket_pipe (zctx_t *self); + +// Destroy socket within this context, for CZMQ use only +void + zctx__socket_destroy (zctx_t *self, void *socket); + +// Initialize the low-level 0MQ context object, for CZMQ use only +void + zctx__initialize_underlying(zctx_t *self); +// @end + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/arm/include/zdigest.h b/phonelibs/zmq/arm/include/zdigest.h new file mode 100644 index 00000000000000..def9e860537094 --- /dev/null +++ b/phonelibs/zmq/arm/include/zdigest.h @@ -0,0 +1,65 @@ +/* ========================================================================= + zdigest - provides hashing functions (SHA-1 at present) + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZDIGEST_H_INCLUDED__ +#define __ZDIGEST_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/zdigest.api" to make changes. +// @interface +// This is a stable class, and may not change except for emergencies. It +// is provided in stable builds. +// Constructor - creates new digest object, which you use to build up a +// digest by repeatedly calling zdigest_update() on chunks of data. +CZMQ_EXPORT zdigest_t * + zdigest_new (void); + +// Destroy a digest object +CZMQ_EXPORT void + zdigest_destroy (zdigest_t **self_p); + +// Add buffer into digest calculation +CZMQ_EXPORT void + zdigest_update (zdigest_t *self, const byte *buffer, size_t length); + +// Return final digest hash data. If built without crypto support, +// returns NULL. +CZMQ_EXPORT const byte * + zdigest_data (zdigest_t *self); + +// Return final digest hash size +CZMQ_EXPORT size_t + zdigest_size (zdigest_t *self); + +// Return digest as printable hex string; caller should not modify nor +// free this string. After calling this, you may not use zdigest_update() +// on the same digest. If built without crypto support, returns NULL. +CZMQ_EXPORT char * + zdigest_string (zdigest_t *self); + +// Self test of this class. +CZMQ_EXPORT void + zdigest_test (bool verbose); + +// @end + + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/arm/include/zdir.h b/phonelibs/zmq/arm/include/zdir.h new file mode 100644 index 00000000000000..6c5551b57eead4 --- /dev/null +++ b/phonelibs/zmq/arm/include/zdir.h @@ -0,0 +1,149 @@ +/* ========================================================================= + zdir - work with file-system directories + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZDIR_H_INCLUDED__ +#define __ZDIR_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/zdir.api" to make changes. +// @interface +// This is a stable class, and may not change except for emergencies. It +// is provided in stable builds. +// Create a new directory item that loads in the full tree of the specified +// path, optionally located under some parent path. If parent is "-", then +// loads only the top-level directory, and does not use parent as a path. +CZMQ_EXPORT zdir_t * + zdir_new (const char *path, const char *parent); + +// Destroy a directory tree and all children it contains. +CZMQ_EXPORT void + zdir_destroy (zdir_t **self_p); + +// Return directory path +CZMQ_EXPORT const char * + zdir_path (zdir_t *self); + +// Return last modification time for directory. +CZMQ_EXPORT time_t + zdir_modified (zdir_t *self); + +// Return total hierarchy size, in bytes of data contained in all files +// in the directory tree. +CZMQ_EXPORT off_t + zdir_cursize (zdir_t *self); + +// Return directory count +CZMQ_EXPORT size_t + zdir_count (zdir_t *self); + +// Returns a sorted list of zfile objects; Each entry in the list is a pointer +// to a zfile_t item already allocated in the zdir tree. Do not destroy the +// original zdir tree until you are done with this list. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zlist_t * + zdir_list (zdir_t *self); + +// Remove directory, optionally including all files that it contains, at +// all levels. If force is false, will only remove the directory if empty. +// If force is true, will remove all files and all subdirectories. +CZMQ_EXPORT void + zdir_remove (zdir_t *self, bool force); + +// Calculate differences between two versions of a directory tree. +// Returns a list of zdir_patch_t patches. Either older or newer may +// be null, indicating the directory is empty/absent. If alias is set, +// generates virtual filename (minus path, plus alias). +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zlist_t * + zdir_diff (zdir_t *older, zdir_t *newer, const char *alias); + +// Return full contents of directory as a zdir_patch list. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zlist_t * + zdir_resync (zdir_t *self, const char *alias); + +// Load directory cache; returns a hash table containing the SHA-1 digests +// of every file in the tree. The cache is saved between runs in .cache. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zhash_t * + zdir_cache (zdir_t *self); + +// Print contents of directory to open stream +CZMQ_EXPORT void + zdir_fprint (zdir_t *self, FILE *file, int indent); + +// Print contents of directory to stdout +CZMQ_EXPORT void + zdir_print (zdir_t *self, int indent); + +// Create a new zdir_watch actor instance: +// +// zactor_t *watch = zactor_new (zdir_watch, NULL); +// +// Destroy zdir_watch instance: +// +// zactor_destroy (&watch); +// +// Enable verbose logging of commands and activity: +// +// zstr_send (watch, "VERBOSE"); +// +// Subscribe to changes to a directory path: +// +// zsock_send (watch, "ss", "SUBSCRIBE", "directory_path"); +// +// Unsubscribe from changes to a directory path: +// +// zsock_send (watch, "ss", "UNSUBSCRIBE", "directory_path"); +// +// Receive directory changes: +// zsock_recv (watch, "sp", &path, &patches); +// +// // Delete the received data. +// free (path); +// zlist_destroy (&patches); +CZMQ_EXPORT void + zdir_watch (zsock_t *pipe, void *unused); + +// Self test of this class. +CZMQ_EXPORT void + zdir_test (bool verbose); + +// @end + + +// Returns a sorted array of zfile objects; returns a single block of memory, +// that you destroy by calling zstr_free(). Each entry in the array is a pointer +// to a zfile_t item already allocated in the zdir tree. The array ends with +// a null pointer. Do not destroy the original zdir tree until you are done +// with this array. +CZMQ_EXPORT zfile_t ** + zdir_flatten (zdir_t *self); + +// Free a provided string, and nullify the parent pointer. Safe to call on +// a null pointer. +CZMQ_EXPORT void + zdir_flatten_free (zfile_t ***files_p); + +#ifdef __cplusplus +} +#endif + +// Deprecated method aliases +#define zdir_dump(s,i) zdir_print(s,i) + +#endif diff --git a/phonelibs/zmq/arm/include/zdir_patch.h b/phonelibs/zmq/arm/include/zdir_patch.h new file mode 100644 index 00000000000000..8d15b9aeb40c42 --- /dev/null +++ b/phonelibs/zmq/arm/include/zdir_patch.h @@ -0,0 +1,82 @@ +/* ========================================================================= + zdir_patch - work with directory patches + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZDIR_PATCH_H_INCLUDED__ +#define __ZDIR_PATCH_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// un-namespaced enumeration values +#define patch_create ZDIR_PATCH_CREATE +#define patch_delete ZDIR_PATCH_DELETE + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/zdir_patch.api" to make changes. +// @interface +// This is a stable class, and may not change except for emergencies. It +// is provided in stable builds. +#define ZDIR_PATCH_CREATE 1 // Creates a new file +#define ZDIR_PATCH_DELETE 2 // Delete a file + +// Create new patch +CZMQ_EXPORT zdir_patch_t * + zdir_patch_new (const char *path, zfile_t *file, int op, const char *alias); + +// Destroy a patch +CZMQ_EXPORT void + zdir_patch_destroy (zdir_patch_t **self_p); + +// Create copy of a patch. If the patch is null, or memory was exhausted, +// returns null. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zdir_patch_t * + zdir_patch_dup (zdir_patch_t *self); + +// Return patch file directory path +CZMQ_EXPORT const char * + zdir_patch_path (zdir_patch_t *self); + +// Return patch file item +CZMQ_EXPORT zfile_t * + zdir_patch_file (zdir_patch_t *self); + +// Return operation +CZMQ_EXPORT int + zdir_patch_op (zdir_patch_t *self); + +// Return patch virtual file path +CZMQ_EXPORT const char * + zdir_patch_vpath (zdir_patch_t *self); + +// Calculate hash digest for file (create only) +CZMQ_EXPORT void + zdir_patch_digest_set (zdir_patch_t *self); + +// Return hash digest for patch file +CZMQ_EXPORT const char * + zdir_patch_digest (zdir_patch_t *self); + +// Self test of this class. +CZMQ_EXPORT void + zdir_patch_test (bool verbose); + +// @end + + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/arm/include/zfile.h b/phonelibs/zmq/arm/include/zfile.h new file mode 100644 index 00000000000000..75c35774b97fd1 --- /dev/null +++ b/phonelibs/zmq/arm/include/zfile.h @@ -0,0 +1,177 @@ +/* ========================================================================= + zfile - helper functions for working with files. + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZFILE_H_INCLUDED__ +#define __ZFILE_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/zfile.api" to make changes. +// @interface +// This is a stable class, and may not change except for emergencies. It +// is provided in stable builds. +// If file exists, populates properties. CZMQ supports portable symbolic +// links, which are files with the extension ".ln". A symbolic link is a +// text file containing one line, the filename of a target file. Reading +// data from the symbolic link actually reads from the target file. Path +// may be NULL, in which case it is not used. +CZMQ_EXPORT zfile_t * + zfile_new (const char *path, const char *name); + +// Destroy a file item +CZMQ_EXPORT void + zfile_destroy (zfile_t **self_p); + +// Duplicate a file item, returns a newly constructed item. If the file +// is null, or memory was exhausted, returns null. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zfile_t * + zfile_dup (zfile_t *self); + +// Return file name, remove path if provided +CZMQ_EXPORT const char * + zfile_filename (zfile_t *self, const char *path); + +// Refresh file properties from disk; this is not done automatically +// on access methods, otherwise it is not possible to compare directory +// snapshots. +CZMQ_EXPORT void + zfile_restat (zfile_t *self); + +// Return when the file was last modified. If you want this to reflect the +// current situation, call zfile_restat before checking this property. +CZMQ_EXPORT time_t + zfile_modified (zfile_t *self); + +// Return the last-known size of the file. If you want this to reflect the +// current situation, call zfile_restat before checking this property. +CZMQ_EXPORT off_t + zfile_cursize (zfile_t *self); + +// Return true if the file is a directory. If you want this to reflect +// any external changes, call zfile_restat before checking this property. +CZMQ_EXPORT bool + zfile_is_directory (zfile_t *self); + +// Return true if the file is a regular file. If you want this to reflect +// any external changes, call zfile_restat before checking this property. +CZMQ_EXPORT bool + zfile_is_regular (zfile_t *self); + +// Return true if the file is readable by this process. If you want this to +// reflect any external changes, call zfile_restat before checking this +// property. +CZMQ_EXPORT bool + zfile_is_readable (zfile_t *self); + +// Return true if the file is writeable by this process. If you want this +// to reflect any external changes, call zfile_restat before checking this +// property. +CZMQ_EXPORT bool + zfile_is_writeable (zfile_t *self); + +// Check if file has stopped changing and can be safely processed. +// Updates the file statistics from disk at every call. +CZMQ_EXPORT bool + zfile_is_stable (zfile_t *self); + +// Return true if the file was changed on disk since the zfile_t object +// was created, or the last zfile_restat() call made on it. +CZMQ_EXPORT bool + zfile_has_changed (zfile_t *self); + +// Remove the file from disk +CZMQ_EXPORT void + zfile_remove (zfile_t *self); + +// Open file for reading +// Returns 0 if OK, -1 if not found or not accessible +CZMQ_EXPORT int + zfile_input (zfile_t *self); + +// Open file for writing, creating directory if needed +// File is created if necessary; chunks can be written to file at any +// location. Returns 0 if OK, -1 if error. +CZMQ_EXPORT int + zfile_output (zfile_t *self); + +// Read chunk from file at specified position. If this was the last chunk, +// sets the eof property. Returns a null chunk in case of error. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zchunk_t * + zfile_read (zfile_t *self, size_t bytes, off_t offset); + +// Returns true if zfile_read() just read the last chunk in the file. +CZMQ_EXPORT bool + zfile_eof (zfile_t *self); + +// Write chunk to file at specified position +// Return 0 if OK, else -1 +CZMQ_EXPORT int + zfile_write (zfile_t *self, zchunk_t *chunk, off_t offset); + +// Read next line of text from file. Returns a pointer to the text line, +// or NULL if there was nothing more to read from the file. +CZMQ_EXPORT const char * + zfile_readln (zfile_t *self); + +// Close file, if open +CZMQ_EXPORT void + zfile_close (zfile_t *self); + +// Return file handle, if opened +CZMQ_EXPORT FILE * + zfile_handle (zfile_t *self); + +// Calculate SHA1 digest for file, using zdigest class. +CZMQ_EXPORT const char * + zfile_digest (zfile_t *self); + +// Self test of this class. +CZMQ_EXPORT void + zfile_test (bool verbose); + +// @end + + +// @interface +// These methods are deprecated, and now moved to zsys class. +CZMQ_EXPORT bool + zfile_exists (const char *filename); +CZMQ_EXPORT ssize_t + zfile_size (const char *filename); +CZMQ_EXPORT mode_t + zfile_mode (const char *filename); +CZMQ_EXPORT int + zfile_delete (const char *filename); +CZMQ_EXPORT bool + zfile_stable (const char *filename); +CZMQ_EXPORT int + zfile_mkdir (const char *pathname); +CZMQ_EXPORT int + zfile_rmdir (const char *pathname); +CZMQ_EXPORT void + zfile_mode_private (void); +CZMQ_EXPORT void + zfile_mode_default (void); +// @end + +#ifdef __cplusplus +} +#endif + + +#endif // __ZFILE_H_INCLUDED__ diff --git a/phonelibs/zmq/arm/include/zframe.h b/phonelibs/zmq/arm/include/zframe.h new file mode 100644 index 00000000000000..728093c36ce117 --- /dev/null +++ b/phonelibs/zmq/arm/include/zframe.h @@ -0,0 +1,176 @@ +/* ========================================================================= + zframe - working with single message frames + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZFRAME_H_INCLUDED__ +#define __ZFRAME_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/zframe.api" to make changes. +// @interface +// This is a stable class, and may not change except for emergencies. It +// is provided in stable builds. +// This class has draft methods, which may change over time. They are not +// in stable releases, by default. Use --enable-drafts to enable. +#define ZFRAME_MORE 1 // +#define ZFRAME_REUSE 2 // +#define ZFRAME_DONTWAIT 4 // + +// Create a new frame. If size is not null, allocates the frame data +// to the specified size. If additionally, data is not null, copies +// size octets from the specified data into the frame body. +CZMQ_EXPORT zframe_t * + zframe_new (const void *data, size_t size); + +// Create an empty (zero-sized) frame +CZMQ_EXPORT zframe_t * + zframe_new_empty (void); + +// Create a frame with a specified string content. +CZMQ_EXPORT zframe_t * + zframe_from (const char *string); + +// Receive frame from socket, returns zframe_t object or NULL if the recv +// was interrupted. Does a blocking recv, if you want to not block then use +// zpoller or zloop. +CZMQ_EXPORT zframe_t * + zframe_recv (void *source); + +// Destroy a frame +CZMQ_EXPORT void + zframe_destroy (zframe_t **self_p); + +// Send a frame to a socket, destroy frame after sending. +// Return -1 on error, 0 on success. +CZMQ_EXPORT int + zframe_send (zframe_t **self_p, void *dest, int flags); + +// Return number of bytes in frame data +CZMQ_EXPORT size_t + zframe_size (zframe_t *self); + +// Return address of frame data +CZMQ_EXPORT byte * + zframe_data (zframe_t *self); + +// Return meta data property for frame +// Caller must free string when finished with it. +CZMQ_EXPORT const char * + zframe_meta (zframe_t *self, const char *property); + +// Create a new frame that duplicates an existing frame. If frame is null, +// or memory was exhausted, returns null. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zframe_t * + zframe_dup (zframe_t *self); + +// Return frame data encoded as printable hex string, useful for 0MQ UUIDs. +// Caller must free string when finished with it. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT char * + zframe_strhex (zframe_t *self); + +// Return frame data copied into freshly allocated string +// Caller must free string when finished with it. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT char * + zframe_strdup (zframe_t *self); + +// Return TRUE if frame body is equal to string, excluding terminator +CZMQ_EXPORT bool + zframe_streq (zframe_t *self, const char *string); + +// Return frame MORE indicator (1 or 0), set when reading frame from socket +// or by the zframe_set_more() method +CZMQ_EXPORT int + zframe_more (zframe_t *self); + +// Set frame MORE indicator (1 or 0). Note this is NOT used when sending +// frame to socket, you have to specify flag explicitly. +CZMQ_EXPORT void + zframe_set_more (zframe_t *self, int more); + +// Return TRUE if two frames have identical size and data +// If either frame is NULL, equality is always false. +CZMQ_EXPORT bool + zframe_eq (zframe_t *self, zframe_t *other); + +// Set new contents for frame +CZMQ_EXPORT void + zframe_reset (zframe_t *self, const void *data, size_t size); + +// Send message to zsys log sink (may be stdout, or system facility as +// configured by zsys_set_logstream). Prefix shows before frame, if not null. +CZMQ_EXPORT void + zframe_print (zframe_t *self, const char *prefix); + +// Probe the supplied object, and report if it looks like a zframe_t. +CZMQ_EXPORT bool + zframe_is (void *self); + +// Self test of this class. +CZMQ_EXPORT void + zframe_test (bool verbose); + +#ifdef CZMQ_BUILD_DRAFT_API +// *** Draft method, for development use, may change without warning *** +// Return frame routing ID, if the frame came from a ZMQ_SERVER socket. +// Else returns zero. +CZMQ_EXPORT uint32_t + zframe_routing_id (zframe_t *self); + +// *** Draft method, for development use, may change without warning *** +// Set routing ID on frame. This is used if/when the frame is sent to a +// ZMQ_SERVER socket. +CZMQ_EXPORT void + zframe_set_routing_id (zframe_t *self, uint32_t routing_id); + +// *** Draft method, for development use, may change without warning *** +// Return frame group of radio-dish pattern. +CZMQ_EXPORT const char * + zframe_group (zframe_t *self); + +// *** Draft method, for development use, may change without warning *** +// Set group on frame. This is used if/when the frame is sent to a +// ZMQ_RADIO socket. +// Return -1 on error, 0 on success. +CZMQ_EXPORT int + zframe_set_group (zframe_t *self, const char *group); + +#endif // CZMQ_BUILD_DRAFT_API +// @end + + +// DEPRECATED as poor style -- callers should use zloop or zpoller +// Receive a new frame off the socket. Returns newly allocated frame, or +// NULL if there was no input waiting, or if the read was interrupted. +CZMQ_EXPORT zframe_t * + zframe_recv_nowait (void *source); + +// DEPRECATED as inconsistent; breaks principle that logging should all go +// to a single destination. +// Print contents of the frame to FILE stream. +CZMQ_EXPORT void + zframe_fprint (zframe_t *self, const char *prefix, FILE *file); + +// Deprecated method aliases +#define zframe_print_to_stream(s,p,F) zframe_fprint(s,p,F) + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/arm/include/zgossip.h b/phonelibs/zmq/arm/include/zgossip.h new file mode 100644 index 00000000000000..647cb28c080731 --- /dev/null +++ b/phonelibs/zmq/arm/include/zgossip.h @@ -0,0 +1,95 @@ +/* ========================================================================= + zgossip - zgossip server + + ** WARNING ************************************************************* + THIS SOURCE FILE IS 100% GENERATED. If you edit this file, you will lose + your changes at the next build cycle. This is great for temporary printf + statements. DO NOT MAKE ANY CHANGES YOU WISH TO KEEP. The correct places + for commits are: + + * The XML model used for this code generation: zgossip.xml, or + * The code generation script that built this file: zproto_server_c + ************************************************************************ + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef ZGOSSIP_H_INCLUDED +#define ZGOSSIP_H_INCLUDED + +#include "czmq.h" + +#ifdef __cplusplus +extern "C" { +#endif + +// @interface +// To work with zgossip, use the CZMQ zactor API: +// +// Create new zgossip instance, passing logging prefix: +// +// zactor_t *zgossip = zactor_new (zgossip, "myname"); +// +// Destroy zgossip instance +// +// zactor_destroy (&zgossip); +// +// Enable verbose logging of commands and activity: +// +// zstr_send (zgossip, "VERBOSE"); +// +// Bind zgossip to specified endpoint. TCP endpoints may specify +// the port number as "*" to aquire an ephemeral port: +// +// zstr_sendx (zgossip, "BIND", endpoint, NULL); +// +// Return assigned port number, specifically when BIND was done using an +// an ephemeral port: +// +// zstr_sendx (zgossip, "PORT", NULL); +// char *command, *port_str; +// zstr_recvx (zgossip, &command, &port_str, NULL); +// assert (streq (command, "PORT")); +// +// Specify configuration file to load, overwriting any previous loaded +// configuration file or options: +// +// zstr_sendx (zgossip, "LOAD", filename, NULL); +// +// Set configuration path value: +// +// zstr_sendx (zgossip, "SET", path, value, NULL); +// +// Save configuration data to config file on disk: +// +// zstr_sendx (zgossip, "SAVE", filename, NULL); +// +// Send zmsg_t instance to zgossip: +// +// zactor_send (zgossip, &msg); +// +// Receive zmsg_t instance from zgossip: +// +// zmsg_t *msg = zactor_recv (zgossip); +// +// This is the zgossip constructor as a zactor_fn: +// +CZMQ_EXPORT void + zgossip (zsock_t *pipe, void *args); + +// Self test of this class +CZMQ_EXPORT void + zgossip_test (bool verbose); +// @end + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/arm/include/zhash.h b/phonelibs/zmq/arm/include/zhash.h new file mode 100644 index 00000000000000..929bc2683aec36 --- /dev/null +++ b/phonelibs/zmq/arm/include/zhash.h @@ -0,0 +1,198 @@ +/* ========================================================================= + zhash - generic type-free hash container (simple) + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZHASH_H_INCLUDED__ +#define __ZHASH_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/zhash.api" to make changes. +// @interface +// This is a stable class, and may not change except for emergencies. It +// is provided in stable builds. +// This class has legacy methods, which will be removed over time. You +// should not use them, and migrate any code that is still using them. +// Callback function for zhash_freefn method +typedef void (zhash_free_fn) ( + void *data); + +// Callback function for zhash_foreach method. Deprecated. +typedef int (zhash_foreach_fn) ( + const char *key, void *item, void *argument); + +// Create a new, empty hash container +CZMQ_EXPORT zhash_t * + zhash_new (void); + +// Unpack binary frame into a new hash table. Packed data must follow format +// defined by zhash_pack. Hash table is set to autofree. An empty frame +// unpacks to an empty hash table. +CZMQ_EXPORT zhash_t * + zhash_unpack (zframe_t *frame); + +// Destroy a hash container and all items in it +CZMQ_EXPORT void + zhash_destroy (zhash_t **self_p); + +// Insert item into hash table with specified key and item. +// If key is already present returns -1 and leaves existing item unchanged +// Returns 0 on success. +CZMQ_EXPORT int + zhash_insert (zhash_t *self, const char *key, void *item); + +// Update item into hash table with specified key and item. +// If key is already present, destroys old item and inserts new one. +// Use free_fn method to ensure deallocator is properly called on item. +CZMQ_EXPORT void + zhash_update (zhash_t *self, const char *key, void *item); + +// Remove an item specified by key from the hash table. If there was no such +// item, this function does nothing. +CZMQ_EXPORT void + zhash_delete (zhash_t *self, const char *key); + +// Return the item at the specified key, or null +CZMQ_EXPORT void * + zhash_lookup (zhash_t *self, const char *key); + +// Reindexes an item from an old key to a new key. If there was no such +// item, does nothing. Returns 0 if successful, else -1. +CZMQ_EXPORT int + zhash_rename (zhash_t *self, const char *old_key, const char *new_key); + +// Set a free function for the specified hash table item. When the item is +// destroyed, the free function, if any, is called on that item. +// Use this when hash items are dynamically allocated, to ensure that +// you don't have memory leaks. You can pass 'free' or NULL as a free_fn. +// Returns the item, or NULL if there is no such item. +CZMQ_EXPORT void * + zhash_freefn (zhash_t *self, const char *key, zhash_free_fn free_fn); + +// Return the number of keys/items in the hash table +CZMQ_EXPORT size_t + zhash_size (zhash_t *self); + +// Make copy of hash table; if supplied table is null, returns null. +// Does not copy items themselves. Rebuilds new table so may be slow on +// very large tables. NOTE: only works with item values that are strings +// since there's no other way to know how to duplicate the item value. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zhash_t * + zhash_dup (zhash_t *self); + +// Return keys for items in table +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zlist_t * + zhash_keys (zhash_t *self); + +// Simple iterator; returns first item in hash table, in no given order, +// or NULL if the table is empty. This method is simpler to use than the +// foreach() method, which is deprecated. To access the key for this item +// use zhash_cursor(). NOTE: do NOT modify the table while iterating. +CZMQ_EXPORT void * + zhash_first (zhash_t *self); + +// Simple iterator; returns next item in hash table, in no given order, +// or NULL if the last item was already returned. Use this together with +// zhash_first() to process all items in a hash table. If you need the +// items in sorted order, use zhash_keys() and then zlist_sort(). To +// access the key for this item use zhash_cursor(). NOTE: do NOT modify +// the table while iterating. +CZMQ_EXPORT void * + zhash_next (zhash_t *self); + +// After a successful first/next method, returns the key for the item that +// was returned. This is a constant string that you may not modify or +// deallocate, and which lasts as long as the item in the hash. After an +// unsuccessful first/next, returns NULL. +CZMQ_EXPORT const char * + zhash_cursor (zhash_t *self); + +// Add a comment to hash table before saving to disk. You can add as many +// comment lines as you like. These comment lines are discarded when loading +// the file. If you use a null format, all comments are deleted. +CZMQ_EXPORT void + zhash_comment (zhash_t *self, const char *format, ...); + +// Serialize hash table to a binary frame that can be sent in a message. +// The packed format is compatible with the 'dictionary' type defined in +// http://rfc.zeromq.org/spec:35/FILEMQ, and implemented by zproto: +// +// ; A list of name/value pairs +// dictionary = dict-count *( dict-name dict-value ) +// dict-count = number-4 +// dict-value = longstr +// dict-name = string +// +// ; Strings are always length + text contents +// longstr = number-4 *VCHAR +// string = number-1 *VCHAR +// +// ; Numbers are unsigned integers in network byte order +// number-1 = 1OCTET +// number-4 = 4OCTET +// +// Comments are not included in the packed data. Item values MUST be +// strings. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zframe_t * + zhash_pack (zhash_t *self); + +// Save hash table to a text file in name=value format. Hash values must be +// printable strings; keys may not contain '=' character. Returns 0 if OK, +// else -1 if a file error occurred. +CZMQ_EXPORT int + zhash_save (zhash_t *self, const char *filename); + +// Load hash table from a text file in name=value format; hash table must +// already exist. Hash values must printable strings; keys may not contain +// '=' character. Returns 0 if OK, else -1 if a file was not readable. +CZMQ_EXPORT int + zhash_load (zhash_t *self, const char *filename); + +// When a hash table was loaded from a file by zhash_load, this method will +// reload the file if it has been modified since, and is "stable", i.e. not +// still changing. Returns 0 if OK, -1 if there was an error reloading the +// file. +CZMQ_EXPORT int + zhash_refresh (zhash_t *self); + +// Set hash for automatic value destruction +CZMQ_EXPORT void + zhash_autofree (zhash_t *self); + +// *** Deprecated method, slated for removal: avoid using it *** +// Apply function to each item in the hash table. Items are iterated in no +// defined order. Stops if callback function returns non-zero and returns +// final return code from callback function (zero = success). Deprecated. +CZMQ_EXPORT int + zhash_foreach (zhash_t *self, zhash_foreach_fn callback, void *argument); + +// Self test of this class. +CZMQ_EXPORT void + zhash_test (bool verbose); + +// @ignore +CZMQ_EXPORT void + zhash_comment (zhash_t *self, const char *format, ...) CHECK_PRINTF (2); +// @end + + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/arm/include/zhashx.h b/phonelibs/zmq/arm/include/zhashx.h new file mode 100644 index 00000000000000..8776073156cf3c --- /dev/null +++ b/phonelibs/zmq/arm/include/zhashx.h @@ -0,0 +1,301 @@ +/* ========================================================================= + zhashx - extended generic type-free hash container + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZHASHX_H_INCLUDED__ +#define __ZHASHX_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/zhashx.api" to make changes. +// @interface +// This is a stable class, and may not change except for emergencies. It +// is provided in stable builds. +// This class has draft methods, which may change over time. They are not +// in stable releases, by default. Use --enable-drafts to enable. +// This class has legacy methods, which will be removed over time. You +// should not use them, and migrate any code that is still using them. +// Destroy an item +typedef void (zhashx_destructor_fn) ( + void **item); + +// Duplicate an item +typedef void * (zhashx_duplicator_fn) ( + const void *item); + +// Compare two items, for sorting +typedef int (zhashx_comparator_fn) ( + const void *item1, const void *item2); + +// compare two items, for sorting +typedef void (zhashx_free_fn) ( + void *data); + +// compare two items, for sorting +typedef size_t (zhashx_hash_fn) ( + const void *key); + +// Serializes an item to a longstr. +// The caller takes ownership of the newly created object. +typedef char * (zhashx_serializer_fn) ( + const void *item); + +// Deserializes a longstr into an item. +// The caller takes ownership of the newly created object. +typedef void * (zhashx_deserializer_fn) ( + const char *item_str); + +// Callback function for zhashx_foreach method. +// This callback is deprecated and you should use zhashx_first/_next instead. +typedef int (zhashx_foreach_fn) ( + const char *key, void *item, void *argument); + +// Create a new, empty hash container +CZMQ_EXPORT zhashx_t * + zhashx_new (void); + +// Unpack binary frame into a new hash table. Packed data must follow format +// defined by zhashx_pack. Hash table is set to autofree. An empty frame +// unpacks to an empty hash table. +CZMQ_EXPORT zhashx_t * + zhashx_unpack (zframe_t *frame); + +// Destroy a hash container and all items in it +CZMQ_EXPORT void + zhashx_destroy (zhashx_t **self_p); + +// Insert item into hash table with specified key and item. +// If key is already present returns -1 and leaves existing item unchanged +// Returns 0 on success. +CZMQ_EXPORT int + zhashx_insert (zhashx_t *self, const void *key, void *item); + +// Update or insert item into hash table with specified key and item. If the +// key is already present, destroys old item and inserts new one. If you set +// a container item destructor, this is called on the old value. If the key +// was not already present, inserts a new item. Sets the hash cursor to the +// new item. +CZMQ_EXPORT void + zhashx_update (zhashx_t *self, const void *key, void *item); + +// Remove an item specified by key from the hash table. If there was no such +// item, this function does nothing. +CZMQ_EXPORT void + zhashx_delete (zhashx_t *self, const void *key); + +// Delete all items from the hash table. If the key destructor is +// set, calls it on every key. If the item destructor is set, calls +// it on every item. +CZMQ_EXPORT void + zhashx_purge (zhashx_t *self); + +// Return the item at the specified key, or null +CZMQ_EXPORT void * + zhashx_lookup (zhashx_t *self, const void *key); + +// Reindexes an item from an old key to a new key. If there was no such +// item, does nothing. Returns 0 if successful, else -1. +CZMQ_EXPORT int + zhashx_rename (zhashx_t *self, const void *old_key, const void *new_key); + +// Set a free function for the specified hash table item. When the item is +// destroyed, the free function, if any, is called on that item. +// Use this when hash items are dynamically allocated, to ensure that +// you don't have memory leaks. You can pass 'free' or NULL as a free_fn. +// Returns the item, or NULL if there is no such item. +CZMQ_EXPORT void * + zhashx_freefn (zhashx_t *self, const void *key, zhashx_free_fn free_fn); + +// Return the number of keys/items in the hash table +CZMQ_EXPORT size_t + zhashx_size (zhashx_t *self); + +// Return a zlistx_t containing the keys for the items in the +// table. Uses the key_duplicator to duplicate all keys and sets the +// key_destructor as destructor for the list. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zlistx_t * + zhashx_keys (zhashx_t *self); + +// Return a zlistx_t containing the values for the items in the +// table. Uses the duplicator to duplicate all items and sets the +// destructor as destructor for the list. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zlistx_t * + zhashx_values (zhashx_t *self); + +// Simple iterator; returns first item in hash table, in no given order, +// or NULL if the table is empty. This method is simpler to use than the +// foreach() method, which is deprecated. To access the key for this item +// use zhashx_cursor(). NOTE: do NOT modify the table while iterating. +CZMQ_EXPORT void * + zhashx_first (zhashx_t *self); + +// Simple iterator; returns next item in hash table, in no given order, +// or NULL if the last item was already returned. Use this together with +// zhashx_first() to process all items in a hash table. If you need the +// items in sorted order, use zhashx_keys() and then zlistx_sort(). To +// access the key for this item use zhashx_cursor(). NOTE: do NOT modify +// the table while iterating. +CZMQ_EXPORT void * + zhashx_next (zhashx_t *self); + +// After a successful first/next method, returns the key for the item that +// was returned. This is a constant string that you may not modify or +// deallocate, and which lasts as long as the item in the hash. After an +// unsuccessful first/next, returns NULL. +CZMQ_EXPORT const void * + zhashx_cursor (zhashx_t *self); + +// Add a comment to hash table before saving to disk. You can add as many +// comment lines as you like. These comment lines are discarded when loading +// the file. If you use a null format, all comments are deleted. +CZMQ_EXPORT void + zhashx_comment (zhashx_t *self, const char *format, ...); + +// Save hash table to a text file in name=value format. Hash values must be +// printable strings; keys may not contain '=' character. Returns 0 if OK, +// else -1 if a file error occurred. +CZMQ_EXPORT int + zhashx_save (zhashx_t *self, const char *filename); + +// Load hash table from a text file in name=value format; hash table must +// already exist. Hash values must printable strings; keys may not contain +// '=' character. Returns 0 if OK, else -1 if a file was not readable. +CZMQ_EXPORT int + zhashx_load (zhashx_t *self, const char *filename); + +// When a hash table was loaded from a file by zhashx_load, this method will +// reload the file if it has been modified since, and is "stable", i.e. not +// still changing. Returns 0 if OK, -1 if there was an error reloading the +// file. +CZMQ_EXPORT int + zhashx_refresh (zhashx_t *self); + +// Serialize hash table to a binary frame that can be sent in a message. +// The packed format is compatible with the 'dictionary' type defined in +// http://rfc.zeromq.org/spec:35/FILEMQ, and implemented by zproto: +// +// ; A list of name/value pairs +// dictionary = dict-count *( dict-name dict-value ) +// dict-count = number-4 +// dict-value = longstr +// dict-name = string +// +// ; Strings are always length + text contents +// longstr = number-4 *VCHAR +// string = number-1 *VCHAR +// +// ; Numbers are unsigned integers in network byte order +// number-1 = 1OCTET +// number-4 = 4OCTET +// +// Comments are not included in the packed data. Item values MUST be +// strings. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zframe_t * + zhashx_pack (zhashx_t *self); + +// Make a copy of the list; items are duplicated if you set a duplicator +// for the list, otherwise not. Copying a null reference returns a null +// reference. Note that this method's behavior changed slightly for CZMQ +// v3.x, as it does not set nor respect autofree. It does however let you +// duplicate any hash table safely. The old behavior is in zhashx_dup_v2. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zhashx_t * + zhashx_dup (zhashx_t *self); + +// Set a user-defined deallocator for hash items; by default items are not +// freed when the hash is destroyed. +CZMQ_EXPORT void + zhashx_set_destructor (zhashx_t *self, zhashx_destructor_fn destructor); + +// Set a user-defined duplicator for hash items; by default items are not +// copied when the hash is duplicated. +CZMQ_EXPORT void + zhashx_set_duplicator (zhashx_t *self, zhashx_duplicator_fn duplicator); + +// Set a user-defined deallocator for keys; by default keys are freed +// when the hash is destroyed using free(). +CZMQ_EXPORT void + zhashx_set_key_destructor (zhashx_t *self, zhashx_destructor_fn destructor); + +// Set a user-defined duplicator for keys; by default keys are duplicated +// using strdup. +CZMQ_EXPORT void + zhashx_set_key_duplicator (zhashx_t *self, zhashx_duplicator_fn duplicator); + +// Set a user-defined comparator for keys; by default keys are +// compared using strcmp. +CZMQ_EXPORT void + zhashx_set_key_comparator (zhashx_t *self, zhashx_comparator_fn comparator); + +// Set a user-defined comparator for keys; by default keys are +// compared using strcmp. +CZMQ_EXPORT void + zhashx_set_key_hasher (zhashx_t *self, zhashx_hash_fn hasher); + +// Make copy of hash table; if supplied table is null, returns null. +// Does not copy items themselves. Rebuilds new table so may be slow on +// very large tables. NOTE: only works with item values that are strings +// since there's no other way to know how to duplicate the item value. +CZMQ_EXPORT zhashx_t * + zhashx_dup_v2 (zhashx_t *self); + +// *** Deprecated method, slated for removal: avoid using it *** +// Set hash for automatic value destruction. This method is deprecated +// and you should use set_destructor instead. +CZMQ_EXPORT void + zhashx_autofree (zhashx_t *self); + +// *** Deprecated method, slated for removal: avoid using it *** +// Apply function to each item in the hash table. Items are iterated in no +// defined order. Stops if callback function returns non-zero and returns +// final return code from callback function (zero = success). This method +// is deprecated and you should use zhashx_first/_next instead. +CZMQ_EXPORT int + zhashx_foreach (zhashx_t *self, zhashx_foreach_fn callback, void *argument); + +// Self test of this class. +CZMQ_EXPORT void + zhashx_test (bool verbose); + +#ifdef CZMQ_BUILD_DRAFT_API +// *** Draft method, for development use, may change without warning *** +// Same as unpack but uses a user-defined deserializer function to convert +// a longstr back into item format. +CZMQ_EXPORT zhashx_t * + zhashx_unpack_own (zframe_t *frame, zhashx_deserializer_fn deserializer); + +// *** Draft method, for development use, may change without warning *** +// Same as pack but uses a user-defined serializer function to convert items +// into longstr. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zframe_t * + zhashx_pack_own (zhashx_t *self, zhashx_serializer_fn serializer); + +#endif // CZMQ_BUILD_DRAFT_API +// @ignore +CZMQ_EXPORT void + zhashx_comment (zhashx_t *self, const char *format, ...) CHECK_PRINTF (2); +// @end + + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/arm/include/ziflist.h b/phonelibs/zmq/arm/include/ziflist.h new file mode 100644 index 00000000000000..cb2b1448025f89 --- /dev/null +++ b/phonelibs/zmq/arm/include/ziflist.h @@ -0,0 +1,77 @@ +/* ========================================================================= + ziflist - List of network interfaces available on system + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZIFLIST_H_INCLUDED__ +#define __ZIFLIST_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/ziflist.api" to make changes. +// @interface +// This is a stable class, and may not change except for emergencies. It +// is provided in stable builds. +// Get a list of network interfaces currently defined on the system +CZMQ_EXPORT ziflist_t * + ziflist_new (void); + +// Destroy a ziflist instance +CZMQ_EXPORT void + ziflist_destroy (ziflist_t **self_p); + +// Reload network interfaces from system +CZMQ_EXPORT void + ziflist_reload (ziflist_t *self); + +// Return the number of network interfaces on system +CZMQ_EXPORT size_t + ziflist_size (ziflist_t *self); + +// Get first network interface, return NULL if there are none +CZMQ_EXPORT const char * + ziflist_first (ziflist_t *self); + +// Get next network interface, return NULL if we hit the last one +CZMQ_EXPORT const char * + ziflist_next (ziflist_t *self); + +// Return the current interface IP address as a printable string +CZMQ_EXPORT const char * + ziflist_address (ziflist_t *self); + +// Return the current interface broadcast address as a printable string +CZMQ_EXPORT const char * + ziflist_broadcast (ziflist_t *self); + +// Return the current interface network mask as a printable string +CZMQ_EXPORT const char * + ziflist_netmask (ziflist_t *self); + +// Return the list of interfaces. +CZMQ_EXPORT void + ziflist_print (ziflist_t *self); + +// Self test of this class. +CZMQ_EXPORT void + ziflist_test (bool verbose); + +// @end + + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/arm/include/zlist.h b/phonelibs/zmq/arm/include/zlist.h new file mode 100644 index 00000000000000..1dcd39b9955c9e --- /dev/null +++ b/phonelibs/zmq/arm/include/zlist.h @@ -0,0 +1,158 @@ +/* ========================================================================= + zlist - simple generic list container + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZLIST_H_INCLUDED__ +#define __ZLIST_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/zlist.api" to make changes. +// @interface +// This is a stable class, and may not change except for emergencies. It +// is provided in stable builds. +// Comparison function e.g. for sorting and removing. +typedef int (zlist_compare_fn) ( + void *item1, void *item2); + +// Callback function for zlist_freefn method +typedef void (zlist_free_fn) ( + void *data); + +// Create a new list container +CZMQ_EXPORT zlist_t * + zlist_new (void); + +// Destroy a list container +CZMQ_EXPORT void + zlist_destroy (zlist_t **self_p); + +// Return the item at the head of list. If the list is empty, returns NULL. +// Leaves cursor pointing at the head item, or NULL if the list is empty. +CZMQ_EXPORT void * + zlist_first (zlist_t *self); + +// Return the next item. If the list is empty, returns NULL. To move to +// the start of the list call zlist_first (). Advances the cursor. +CZMQ_EXPORT void * + zlist_next (zlist_t *self); + +// Return the item at the tail of list. If the list is empty, returns NULL. +// Leaves cursor pointing at the tail item, or NULL if the list is empty. +CZMQ_EXPORT void * + zlist_last (zlist_t *self); + +// Return first item in the list, or null, leaves the cursor +CZMQ_EXPORT void * + zlist_head (zlist_t *self); + +// Return last item in the list, or null, leaves the cursor +CZMQ_EXPORT void * + zlist_tail (zlist_t *self); + +// Return the current item of list. If the list is empty, returns NULL. +// Leaves cursor pointing at the current item, or NULL if the list is empty. +CZMQ_EXPORT void * + zlist_item (zlist_t *self); + +// Append an item to the end of the list, return 0 if OK or -1 if this +// failed for some reason (out of memory). Note that if a duplicator has +// been set, this method will also duplicate the item. +CZMQ_EXPORT int + zlist_append (zlist_t *self, void *item); + +// Push an item to the start of the list, return 0 if OK or -1 if this +// failed for some reason (out of memory). Note that if a duplicator has +// been set, this method will also duplicate the item. +CZMQ_EXPORT int + zlist_push (zlist_t *self, void *item); + +// Pop the item off the start of the list, if any +CZMQ_EXPORT void * + zlist_pop (zlist_t *self); + +// Checks if an item already is present. Uses compare method to determine if +// items are equal. If the compare method is NULL the check will only compare +// pointers. Returns true if item is present else false. +CZMQ_EXPORT bool + zlist_exists (zlist_t *self, void *item); + +// Remove the specified item from the list if present +CZMQ_EXPORT void + zlist_remove (zlist_t *self, void *item); + +// Make a copy of list. If the list has autofree set, the copied list will +// duplicate all items, which must be strings. Otherwise, the list will hold +// pointers back to the items in the original list. If list is null, returns +// NULL. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zlist_t * + zlist_dup (zlist_t *self); + +// Purge all items from list +CZMQ_EXPORT void + zlist_purge (zlist_t *self); + +// Return number of items in the list +CZMQ_EXPORT size_t + zlist_size (zlist_t *self); + +// Sort the list. If the compare function is null, sorts the list by +// ascending key value using a straight ASCII comparison. If you specify +// a compare function, this decides how items are sorted. The sort is not +// stable, so may reorder items with the same keys. The algorithm used is +// combsort, a compromise between performance and simplicity. +CZMQ_EXPORT void + zlist_sort (zlist_t *self, zlist_compare_fn compare); + +// Set list for automatic item destruction; item values MUST be strings. +// By default a list item refers to a value held elsewhere. When you set +// this, each time you append or push a list item, zlist will take a copy +// of the string value. Then, when you destroy the list, it will free all +// item values automatically. If you use any other technique to allocate +// list values, you must free them explicitly before destroying the list. +// The usual technique is to pop list items and destroy them, until the +// list is empty. +CZMQ_EXPORT void + zlist_autofree (zlist_t *self); + +// Sets a compare function for this list. The function compares two items. +// It returns an integer less than, equal to, or greater than zero if the +// first item is found, respectively, to be less than, to match, or be +// greater than the second item. +// This function is used for sorting, removal and exists checking. +CZMQ_EXPORT void + zlist_comparefn (zlist_t *self, zlist_compare_fn fn); + +// Set a free function for the specified list item. When the item is +// destroyed, the free function, if any, is called on that item. +// Use this when list items are dynamically allocated, to ensure that +// you don't have memory leaks. You can pass 'free' or NULL as a free_fn. +// Returns the item, or NULL if there is no such item. +CZMQ_EXPORT void * + zlist_freefn (zlist_t *self, void *item, zlist_free_fn fn, bool at_tail); + +// Self test of this class. +CZMQ_EXPORT void + zlist_test (bool verbose); + +// @end + + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/arm/include/zlistx.h b/phonelibs/zmq/arm/include/zlistx.h new file mode 100644 index 00000000000000..512637cef3bff5 --- /dev/null +++ b/phonelibs/zmq/arm/include/zlistx.h @@ -0,0 +1,205 @@ +/* ========================================================================= + zlistx - extended generic list container + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZLISTX_H_INCLUDED__ +#define __ZLISTX_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/zlistx.api" to make changes. +// @interface +// This is a stable class, and may not change except for emergencies. It +// is provided in stable builds. +// Destroy an item +typedef void (zlistx_destructor_fn) ( + void **item); + +// Duplicate an item +typedef void * (zlistx_duplicator_fn) ( + const void *item); + +// Compare two items, for sorting +typedef int (zlistx_comparator_fn) ( + const void *item1, const void *item2); + +// Create a new, empty list. +CZMQ_EXPORT zlistx_t * + zlistx_new (void); + +// Destroy a list. If an item destructor was specified, all items in the +// list are automatically destroyed as well. +CZMQ_EXPORT void + zlistx_destroy (zlistx_t **self_p); + +// Add an item to the head of the list. Calls the item duplicator, if any, +// on the item. Resets cursor to list head. Returns an item handle on +// success, NULL if memory was exhausted. +CZMQ_EXPORT void * + zlistx_add_start (zlistx_t *self, void *item); + +// Add an item to the tail of the list. Calls the item duplicator, if any, +// on the item. Resets cursor to list head. Returns an item handle on +// success, NULL if memory was exhausted. +CZMQ_EXPORT void * + zlistx_add_end (zlistx_t *self, void *item); + +// Return the number of items in the list +CZMQ_EXPORT size_t + zlistx_size (zlistx_t *self); + +// Return first item in the list, or null, leaves the cursor +CZMQ_EXPORT void * + zlistx_head (zlistx_t *self); + +// Return last item in the list, or null, leaves the cursor +CZMQ_EXPORT void * + zlistx_tail (zlistx_t *self); + +// Return the item at the head of list. If the list is empty, returns NULL. +// Leaves cursor pointing at the head item, or NULL if the list is empty. +CZMQ_EXPORT void * + zlistx_first (zlistx_t *self); + +// Return the next item. At the end of the list (or in an empty list), +// returns NULL. Use repeated zlistx_next () calls to work through the list +// from zlistx_first (). First time, acts as zlistx_first(). +CZMQ_EXPORT void * + zlistx_next (zlistx_t *self); + +// Return the previous item. At the start of the list (or in an empty list), +// returns NULL. Use repeated zlistx_prev () calls to work through the list +// backwards from zlistx_last (). First time, acts as zlistx_last(). +CZMQ_EXPORT void * + zlistx_prev (zlistx_t *self); + +// Return the item at the tail of list. If the list is empty, returns NULL. +// Leaves cursor pointing at the tail item, or NULL if the list is empty. +CZMQ_EXPORT void * + zlistx_last (zlistx_t *self); + +// Returns the value of the item at the cursor, or NULL if the cursor is +// not pointing to an item. +CZMQ_EXPORT void * + zlistx_item (zlistx_t *self); + +// Returns the handle of the item at the cursor, or NULL if the cursor is +// not pointing to an item. +CZMQ_EXPORT void * + zlistx_cursor (zlistx_t *self); + +// Returns the item associated with the given list handle, or NULL if passed +// in handle is NULL. Asserts that the passed in handle points to a list element. +CZMQ_EXPORT void * + zlistx_handle_item (void *handle); + +// Find an item in the list, searching from the start. Uses the item +// comparator, if any, else compares item values directly. Returns the +// item handle found, or NULL. Sets the cursor to the found item, if any. +CZMQ_EXPORT void * + zlistx_find (zlistx_t *self, void *item); + +// Detach an item from the list, using its handle. The item is not modified, +// and the caller is responsible for destroying it if necessary. If handle is +// null, detaches the first item on the list. Returns item that was detached, +// or null if none was. If cursor was at item, moves cursor to previous item, +// so you can detach items while iterating forwards through a list. +CZMQ_EXPORT void * + zlistx_detach (zlistx_t *self, void *handle); + +// Detach item at the cursor, if any, from the list. The item is not modified, +// and the caller is responsible for destroying it as necessary. Returns item +// that was detached, or null if none was. Moves cursor to previous item, so +// you can detach items while iterating forwards through a list. +CZMQ_EXPORT void * + zlistx_detach_cur (zlistx_t *self); + +// Delete an item, using its handle. Calls the item destructor is any is +// set. If handle is null, deletes the first item on the list. Returns 0 +// if an item was deleted, -1 if not. If cursor was at item, moves cursor +// to previous item, so you can delete items while iterating forwards +// through a list. +CZMQ_EXPORT int + zlistx_delete (zlistx_t *self, void *handle); + +// Move an item to the start of the list, via its handle. +CZMQ_EXPORT void + zlistx_move_start (zlistx_t *self, void *handle); + +// Move an item to the end of the list, via its handle. +CZMQ_EXPORT void + zlistx_move_end (zlistx_t *self, void *handle); + +// Remove all items from the list, and destroy them if the item destructor +// is set. +CZMQ_EXPORT void + zlistx_purge (zlistx_t *self); + +// Sort the list. If an item comparator was set, calls that to compare +// items, otherwise compares on item value. The sort is not stable, so may +// reorder equal items. +CZMQ_EXPORT void + zlistx_sort (zlistx_t *self); + +// Create a new node and insert it into a sorted list. Calls the item +// duplicator, if any, on the item. If low_value is true, starts searching +// from the start of the list, otherwise searches from the end. Use the item +// comparator, if any, to find where to place the new node. Returns a handle +// to the new node, or NULL if memory was exhausted. Resets the cursor to the +// list head. +CZMQ_EXPORT void * + zlistx_insert (zlistx_t *self, void *item, bool low_value); + +// Move an item, specified by handle, into position in a sorted list. Uses +// the item comparator, if any, to determine the new location. If low_value +// is true, starts searching from the start of the list, otherwise searches +// from the end. +CZMQ_EXPORT void + zlistx_reorder (zlistx_t *self, void *handle, bool low_value); + +// Make a copy of the list; items are duplicated if you set a duplicator +// for the list, otherwise not. Copying a null reference returns a null +// reference. +CZMQ_EXPORT zlistx_t * + zlistx_dup (zlistx_t *self); + +// Set a user-defined deallocator for list items; by default items are not +// freed when the list is destroyed. +CZMQ_EXPORT void + zlistx_set_destructor (zlistx_t *self, zlistx_destructor_fn destructor); + +// Set a user-defined duplicator for list items; by default items are not +// copied when the list is duplicated. +CZMQ_EXPORT void + zlistx_set_duplicator (zlistx_t *self, zlistx_duplicator_fn duplicator); + +// Set a user-defined comparator for zlistx_find and zlistx_sort; the method +// must return -1, 0, or 1 depending on whether item1 is less than, equal to, +// or greater than, item2. +CZMQ_EXPORT void + zlistx_set_comparator (zlistx_t *self, zlistx_comparator_fn comparator); + +// Self test of this class. +CZMQ_EXPORT void + zlistx_test (bool verbose); + +// @end + + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/arm/include/zloop.h b/phonelibs/zmq/arm/include/zloop.h new file mode 100644 index 00000000000000..bc58ea0530e7b3 --- /dev/null +++ b/phonelibs/zmq/arm/include/zloop.h @@ -0,0 +1,168 @@ +/* ========================================================================= + zloop - event-driven reactor + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZLOOP_H_INCLUDED__ +#define __ZLOOP_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/zloop.api" to make changes. +// @interface +// This is a stable class, and may not change except for emergencies. It +// is provided in stable builds. +// This class has draft methods, which may change over time. They are not +// in stable releases, by default. Use --enable-drafts to enable. +// Callback function for reactor socket activity +typedef int (zloop_reader_fn) ( + zloop_t *loop, zsock_t *reader, void *arg); + +// Callback function for reactor events (low-level) +typedef int (zloop_fn) ( + zloop_t *loop, zmq_pollitem_t *item, void *arg); + +// Callback for reactor timer events +typedef int (zloop_timer_fn) ( + zloop_t *loop, int timer_id, void *arg); + +// Create a new zloop reactor +CZMQ_EXPORT zloop_t * + zloop_new (void); + +// Destroy a reactor +CZMQ_EXPORT void + zloop_destroy (zloop_t **self_p); + +// Register socket reader with the reactor. When the reader has messages, +// the reactor will call the handler, passing the arg. Returns 0 if OK, -1 +// if there was an error. If you register the same socket more than once, +// each instance will invoke its corresponding handler. +CZMQ_EXPORT int + zloop_reader (zloop_t *self, zsock_t *sock, zloop_reader_fn handler, void *arg); + +// Cancel a socket reader from the reactor. If multiple readers exist for +// same socket, cancels ALL of them. +CZMQ_EXPORT void + zloop_reader_end (zloop_t *self, zsock_t *sock); + +// Configure a registered reader to ignore errors. If you do not set this, +// then readers that have errors are removed from the reactor silently. +CZMQ_EXPORT void + zloop_reader_set_tolerant (zloop_t *self, zsock_t *sock); + +// Register low-level libzmq pollitem with the reactor. When the pollitem +// is ready, will call the handler, passing the arg. Returns 0 if OK, -1 +// if there was an error. If you register the pollitem more than once, each +// instance will invoke its corresponding handler. A pollitem with +// socket=NULL and fd=0 means 'poll on FD zero'. +CZMQ_EXPORT int + zloop_poller (zloop_t *self, zmq_pollitem_t *item, zloop_fn handler, void *arg); + +// Cancel a pollitem from the reactor, specified by socket or FD. If both +// are specified, uses only socket. If multiple poll items exist for same +// socket/FD, cancels ALL of them. +CZMQ_EXPORT void + zloop_poller_end (zloop_t *self, zmq_pollitem_t *item); + +// Configure a registered poller to ignore errors. If you do not set this, +// then poller that have errors are removed from the reactor silently. +CZMQ_EXPORT void + zloop_poller_set_tolerant (zloop_t *self, zmq_pollitem_t *item); + +// Register a timer that expires after some delay and repeats some number of +// times. At each expiry, will call the handler, passing the arg. To run a +// timer forever, use 0 times. Returns a timer_id that is used to cancel the +// timer in the future. Returns -1 if there was an error. +CZMQ_EXPORT int + zloop_timer (zloop_t *self, size_t delay, size_t times, zloop_timer_fn handler, void *arg); + +// Cancel a specific timer identified by a specific timer_id (as returned by +// zloop_timer). +CZMQ_EXPORT int + zloop_timer_end (zloop_t *self, int timer_id); + +// Register a ticket timer. Ticket timers are very fast in the case where +// you use a lot of timers (thousands), and frequently remove and add them. +// The main use case is expiry timers for servers that handle many clients, +// and which reset the expiry timer for each message received from a client. +// Whereas normal timers perform poorly as the number of clients grows, the +// cost of ticket timers is constant, no matter the number of clients. You +// must set the ticket delay using zloop_set_ticket_delay before creating a +// ticket. Returns a handle to the timer that you should use in +// zloop_ticket_reset and zloop_ticket_delete. +CZMQ_EXPORT void * + zloop_ticket (zloop_t *self, zloop_timer_fn handler, void *arg); + +// Reset a ticket timer, which moves it to the end of the ticket list and +// resets its execution time. This is a very fast operation. +CZMQ_EXPORT void + zloop_ticket_reset (zloop_t *self, void *handle); + +// Delete a ticket timer. We do not actually delete the ticket here, as +// other code may still refer to the ticket. We mark as deleted, and remove +// later and safely. +CZMQ_EXPORT void + zloop_ticket_delete (zloop_t *self, void *handle); + +// Set the ticket delay, which applies to all tickets. If you lower the +// delay and there are already tickets created, the results are undefined. +CZMQ_EXPORT void + zloop_set_ticket_delay (zloop_t *self, size_t ticket_delay); + +// Set hard limit on number of timers allowed. Setting more than a small +// number of timers (10-100) can have a dramatic impact on the performance +// of the reactor. For high-volume cases, use ticket timers. If the hard +// limit is reached, the reactor stops creating new timers and logs an +// error. +CZMQ_EXPORT void + zloop_set_max_timers (zloop_t *self, size_t max_timers); + +// Set verbose tracing of reactor on/off. The default verbose setting is +// off (false). +CZMQ_EXPORT void + zloop_set_verbose (zloop_t *self, bool verbose); + +// Start the reactor. Takes control of the thread and returns when the 0MQ +// context is terminated or the process is interrupted, or any event handler +// returns -1. Event handlers may register new sockets and timers, and +// cancel sockets. Returns 0 if interrupted, -1 if canceled by a handler. +CZMQ_EXPORT int + zloop_start (zloop_t *self); + +// Self test of this class. +CZMQ_EXPORT void + zloop_test (bool verbose); + +#ifdef CZMQ_BUILD_DRAFT_API +// *** Draft method, for development use, may change without warning *** +// By default the reactor stops if the process receives a SIGINT or SIGTERM +// signal. This makes it impossible to shut-down message based architectures +// like zactors. This method lets you switch off break handling. The default +// nonstop setting is off (false). +CZMQ_EXPORT void + zloop_set_nonstop (zloop_t *self, bool nonstop); + +#endif // CZMQ_BUILD_DRAFT_API +// @end + + +// Deprecated method aliases +#define zloop_set_tolerant(s,i) zloop_poller_set_tolerant(s,i) + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/arm/include/zmonitor.h b/phonelibs/zmq/arm/include/zmonitor.h new file mode 100644 index 00000000000000..b490bcb1a0dfbc --- /dev/null +++ b/phonelibs/zmq/arm/include/zmonitor.h @@ -0,0 +1,73 @@ +/* ========================================================================= + zmonitor - socket event monitor + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZMONITOR_H_INCLUDED__ +#define __ZMONITOR_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @interface +// Create new zmonitor actor instance to monitor a zsock_t socket: +// +// zactor_t *monitor = zactor_new (zmonitor, mysocket); +// +// Destroy zmonitor instance. +// +// zactor_destroy (&monitor); +// +// Enable verbose logging of commands and activity. +// +// zstr_send (monitor, "VERBOSE"); +// +// Listen to monitor event type (zero or types, ending in NULL): +// zstr_sendx (monitor, "LISTEN", type, ..., NULL); +// +// Events: +// CONNECTED +// CONNECT_DELAYED +// CONNECT_RETRIED +// LISTENING +// BIND_FAILED +// ACCEPTED +// ACCEPT_FAILED +// CLOSED +// CLOSE_FAILED +// DISCONNECTED +// MONITOR_STOPPED +// ALL +// +// Start monitor; after this, any further LISTEN commands are ignored. +// +// zstr_send (monitor, "START"); +// zsock_wait (monitor); +// +// Receive next monitor event: +// +// zmsg_t *msg = zmsg_recv (monitor); +// +// This is the zmonitor constructor as a zactor_fn; the argument can be +// a zactor_t, zsock_t, or libzmq void * socket: +CZMQ_EXPORT void + zmonitor (zsock_t *pipe, void *sock); + +// Selftest +CZMQ_EXPORT void + zmonitor_test (bool verbose); +// @end +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/arm/include/zmonitor_v2.h b/phonelibs/zmq/arm/include/zmonitor_v2.h new file mode 100644 index 00000000000000..5780e0bcb785ae --- /dev/null +++ b/phonelibs/zmq/arm/include/zmonitor_v2.h @@ -0,0 +1,56 @@ +/* ========================================================================= + zmonitor_v2 - socket event monitor (deprecated) + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZMONITOR_V2_H_INCLUDED__ +#define __ZMONITOR_V2_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @interface +// This code needs backporting to work with ZMQ v3.2 +#if (ZMQ_VERSION_MAJOR == 4) + +// Create a new socket monitor +CZMQ_EXPORT zmonitor_t * + zmonitor_new (zctx_t *ctx, void *socket, int events); + +// Destroy a socket monitor +CZMQ_EXPORT void + zmonitor_destroy (zmonitor_t **self_p); + +// Receive a status message from the monitor; if no message arrives within +// 500 msec, or the call was interrupted, returns NULL. +CZMQ_EXPORT zmsg_t * + zmonitor_recv (zmonitor_t *self); + +// Get the ZeroMQ socket, for polling +CZMQ_EXPORT void * + zmonitor_socket (zmonitor_t *self); + +// Enable verbose tracing of commands and activity +CZMQ_EXPORT void + zmonitor_set_verbose (zmonitor_t *self, bool verbose); +#endif // ZeroMQ 4.0 or later + +// Self test of this class +CZMQ_EXPORT void + zmonitor_v2_test (bool verbose); +// @end + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/arm/include/zmq.h b/phonelibs/zmq/arm/include/zmq.h new file mode 100644 index 00000000000000..5f35d1915fcd92 --- /dev/null +++ b/phonelibs/zmq/arm/include/zmq.h @@ -0,0 +1,617 @@ +/* + Copyright (c) 2007-2016 Contributors as noted in the AUTHORS file + + This file is part of libzmq, the ZeroMQ core engine in C++. + + libzmq is free software; you can redistribute it and/or modify it under + the terms of the GNU Lesser General Public License (LGPL) as published + by the Free Software Foundation; either version 3 of the License, or + (at your option) any later version. + + As a special exception, the Contributors give you permission to link + this library with independent modules to produce an executable, + regardless of the license terms of these independent modules, and to + copy and distribute the resulting executable under terms of your choice, + provided that you also meet, for each linked independent module, the + terms and conditions of the license of that module. An independent + module is a module which is not derived from or based on this library. + If you modify this library, you must extend this exception to your + version of the library. + + libzmq 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 this program. If not, see . + + ************************************************************************* + NOTE to contributors. This file comprises the principal public contract + for ZeroMQ API users. Any change to this file supplied in a stable + release SHOULD not break existing applications. + In practice this means that the value of constants must not change, and + that old values may not be reused for new constants. + ************************************************************************* +*/ + +#ifndef __ZMQ_H_INCLUDED__ +#define __ZMQ_H_INCLUDED__ + +/* Version macros for compile-time API version detection */ +#define ZMQ_VERSION_MAJOR 4 +#define ZMQ_VERSION_MINOR 2 +#define ZMQ_VERSION_PATCH 0 + +#define ZMQ_MAKE_VERSION(major, minor, patch) \ + ((major) * 10000 + (minor) * 100 + (patch)) +#define ZMQ_VERSION \ + ZMQ_MAKE_VERSION(ZMQ_VERSION_MAJOR, ZMQ_VERSION_MINOR, ZMQ_VERSION_PATCH) + +#ifdef __cplusplus +extern "C" { +#endif + +#if !defined _WIN32_WCE +#include +#endif +#include +#include +#if defined _WIN32 +// Set target version to Windows Server 2008, Windows Vista or higher. +// Windows XP (0x0501) is supported but without client & server socket types. +#ifndef _WIN32_WINNT +#define _WIN32_WINNT 0x0600 +#endif + +#ifdef __MINGW32__ +// Require Windows XP or higher with MinGW for getaddrinfo(). +#if(_WIN32_WINNT >= 0x0600) +#else +#undef _WIN32_WINNT +#define _WIN32_WINNT 0x0600 +#endif +#endif +#include +#endif + +/* Handle DSO symbol visibility */ +#if defined _WIN32 +# if defined ZMQ_STATIC +# define ZMQ_EXPORT +# elif defined DLL_EXPORT +# define ZMQ_EXPORT __declspec(dllexport) +# else +# define ZMQ_EXPORT __declspec(dllimport) +# endif +#else +# if defined __SUNPRO_C || defined __SUNPRO_CC +# define ZMQ_EXPORT __global +# elif (defined __GNUC__ && __GNUC__ >= 4) || defined __INTEL_COMPILER +# define ZMQ_EXPORT __attribute__ ((visibility("default"))) +# else +# define ZMQ_EXPORT +# endif +#endif + +/* Define integer types needed for event interface */ +#define ZMQ_DEFINED_STDINT 1 +#if defined ZMQ_HAVE_SOLARIS || defined ZMQ_HAVE_OPENVMS +# include +#elif defined _MSC_VER && _MSC_VER < 1600 +# ifndef int32_t + typedef __int32 int32_t; +# endif +# ifndef uint16_t + typedef unsigned __int16 uint16_t; +# endif +# ifndef uint8_t + typedef unsigned __int8 uint8_t; +# endif +#else +# include +#endif + + +/******************************************************************************/ +/* 0MQ errors. */ +/******************************************************************************/ + +/* A number random enough not to collide with different errno ranges on */ +/* different OSes. The assumption is that error_t is at least 32-bit type. */ +#define ZMQ_HAUSNUMERO 156384712 + +/* On Windows platform some of the standard POSIX errnos are not defined. */ +#ifndef ENOTSUP +#define ENOTSUP (ZMQ_HAUSNUMERO + 1) +#endif +#ifndef EPROTONOSUPPORT +#define EPROTONOSUPPORT (ZMQ_HAUSNUMERO + 2) +#endif +#ifndef ENOBUFS +#define ENOBUFS (ZMQ_HAUSNUMERO + 3) +#endif +#ifndef ENETDOWN +#define ENETDOWN (ZMQ_HAUSNUMERO + 4) +#endif +#ifndef EADDRINUSE +#define EADDRINUSE (ZMQ_HAUSNUMERO + 5) +#endif +#ifndef EADDRNOTAVAIL +#define EADDRNOTAVAIL (ZMQ_HAUSNUMERO + 6) +#endif +#ifndef ECONNREFUSED +#define ECONNREFUSED (ZMQ_HAUSNUMERO + 7) +#endif +#ifndef EINPROGRESS +#define EINPROGRESS (ZMQ_HAUSNUMERO + 8) +#endif +#ifndef ENOTSOCK +#define ENOTSOCK (ZMQ_HAUSNUMERO + 9) +#endif +#ifndef EMSGSIZE +#define EMSGSIZE (ZMQ_HAUSNUMERO + 10) +#endif +#ifndef EAFNOSUPPORT +#define EAFNOSUPPORT (ZMQ_HAUSNUMERO + 11) +#endif +#ifndef ENETUNREACH +#define ENETUNREACH (ZMQ_HAUSNUMERO + 12) +#endif +#ifndef ECONNABORTED +#define ECONNABORTED (ZMQ_HAUSNUMERO + 13) +#endif +#ifndef ECONNRESET +#define ECONNRESET (ZMQ_HAUSNUMERO + 14) +#endif +#ifndef ENOTCONN +#define ENOTCONN (ZMQ_HAUSNUMERO + 15) +#endif +#ifndef ETIMEDOUT +#define ETIMEDOUT (ZMQ_HAUSNUMERO + 16) +#endif +#ifndef EHOSTUNREACH +#define EHOSTUNREACH (ZMQ_HAUSNUMERO + 17) +#endif +#ifndef ENETRESET +#define ENETRESET (ZMQ_HAUSNUMERO + 18) +#endif + +/* Native 0MQ error codes. */ +#define EFSM (ZMQ_HAUSNUMERO + 51) +#define ENOCOMPATPROTO (ZMQ_HAUSNUMERO + 52) +#define ETERM (ZMQ_HAUSNUMERO + 53) +#define EMTHREAD (ZMQ_HAUSNUMERO + 54) + +/* This function retrieves the errno as it is known to 0MQ library. The goal */ +/* of this function is to make the code 100% portable, including where 0MQ */ +/* compiled with certain CRT library (on Windows) is linked to an */ +/* application that uses different CRT library. */ +ZMQ_EXPORT int zmq_errno (void); + +/* Resolves system errors and 0MQ errors to human-readable string. */ +ZMQ_EXPORT const char *zmq_strerror (int errnum); + +/* Run-time API version detection */ +ZMQ_EXPORT void zmq_version (int *major, int *minor, int *patch); + +/******************************************************************************/ +/* 0MQ infrastructure (a.k.a. context) initialisation & termination. */ +/******************************************************************************/ + +/* Context options */ +#define ZMQ_IO_THREADS 1 +#define ZMQ_MAX_SOCKETS 2 +#define ZMQ_SOCKET_LIMIT 3 +#define ZMQ_THREAD_PRIORITY 3 +#define ZMQ_THREAD_SCHED_POLICY 4 +#define ZMQ_MAX_MSGSZ 5 + +/* Default for new contexts */ +#define ZMQ_IO_THREADS_DFLT 1 +#define ZMQ_MAX_SOCKETS_DFLT 1023 +#define ZMQ_THREAD_PRIORITY_DFLT -1 +#define ZMQ_THREAD_SCHED_POLICY_DFLT -1 + +ZMQ_EXPORT void *zmq_ctx_new (void); +ZMQ_EXPORT int zmq_ctx_term (void *context); +ZMQ_EXPORT int zmq_ctx_shutdown (void *context); +ZMQ_EXPORT int zmq_ctx_set (void *context, int option, int optval); +ZMQ_EXPORT int zmq_ctx_get (void *context, int option); + +/* Old (legacy) API */ +ZMQ_EXPORT void *zmq_init (int io_threads); +ZMQ_EXPORT int zmq_term (void *context); +ZMQ_EXPORT int zmq_ctx_destroy (void *context); + + +/******************************************************************************/ +/* 0MQ message definition. */ +/******************************************************************************/ + +/* union here ensures correct alignment on architectures that require it, e.g. + * SPARC + */ +typedef union zmq_msg_t {unsigned char _ [64]; void *p; } zmq_msg_t; + +typedef void (zmq_free_fn) (void *data, void *hint); + +ZMQ_EXPORT int zmq_msg_init (zmq_msg_t *msg); +ZMQ_EXPORT int zmq_msg_init_size (zmq_msg_t *msg, size_t size); +ZMQ_EXPORT int zmq_msg_init_data (zmq_msg_t *msg, void *data, + size_t size, zmq_free_fn *ffn, void *hint); +ZMQ_EXPORT int zmq_msg_send (zmq_msg_t *msg, void *s, int flags); +ZMQ_EXPORT int zmq_msg_recv (zmq_msg_t *msg, void *s, int flags); +ZMQ_EXPORT int zmq_msg_close (zmq_msg_t *msg); +ZMQ_EXPORT int zmq_msg_move (zmq_msg_t *dest, zmq_msg_t *src); +ZMQ_EXPORT int zmq_msg_copy (zmq_msg_t *dest, zmq_msg_t *src); +ZMQ_EXPORT void *zmq_msg_data (zmq_msg_t *msg); +ZMQ_EXPORT size_t zmq_msg_size (zmq_msg_t *msg); +ZMQ_EXPORT int zmq_msg_more (zmq_msg_t *msg); +ZMQ_EXPORT int zmq_msg_get (zmq_msg_t *msg, int property); +ZMQ_EXPORT int zmq_msg_set (zmq_msg_t *msg, int property, int optval); +ZMQ_EXPORT const char *zmq_msg_gets (zmq_msg_t *msg, const char *property); + +/******************************************************************************/ +/* 0MQ socket definition. */ +/******************************************************************************/ + +/* Socket types. */ +#define ZMQ_PAIR 0 +#define ZMQ_PUB 1 +#define ZMQ_SUB 2 +#define ZMQ_REQ 3 +#define ZMQ_REP 4 +#define ZMQ_DEALER 5 +#define ZMQ_ROUTER 6 +#define ZMQ_PULL 7 +#define ZMQ_PUSH 8 +#define ZMQ_XPUB 9 +#define ZMQ_XSUB 10 +#define ZMQ_STREAM 11 + +/* Deprecated aliases */ +#define ZMQ_XREQ ZMQ_DEALER +#define ZMQ_XREP ZMQ_ROUTER + +/* Socket options. */ +#define ZMQ_AFFINITY 4 +#define ZMQ_IDENTITY 5 +#define ZMQ_SUBSCRIBE 6 +#define ZMQ_UNSUBSCRIBE 7 +#define ZMQ_RATE 8 +#define ZMQ_RECOVERY_IVL 9 +#define ZMQ_SNDBUF 11 +#define ZMQ_RCVBUF 12 +#define ZMQ_RCVMORE 13 +#define ZMQ_FD 14 +#define ZMQ_EVENTS 15 +#define ZMQ_TYPE 16 +#define ZMQ_LINGER 17 +#define ZMQ_RECONNECT_IVL 18 +#define ZMQ_BACKLOG 19 +#define ZMQ_RECONNECT_IVL_MAX 21 +#define ZMQ_MAXMSGSIZE 22 +#define ZMQ_SNDHWM 23 +#define ZMQ_RCVHWM 24 +#define ZMQ_MULTICAST_HOPS 25 +#define ZMQ_RCVTIMEO 27 +#define ZMQ_SNDTIMEO 28 +#define ZMQ_LAST_ENDPOINT 32 +#define ZMQ_ROUTER_MANDATORY 33 +#define ZMQ_TCP_KEEPALIVE 34 +#define ZMQ_TCP_KEEPALIVE_CNT 35 +#define ZMQ_TCP_KEEPALIVE_IDLE 36 +#define ZMQ_TCP_KEEPALIVE_INTVL 37 +#define ZMQ_IMMEDIATE 39 +#define ZMQ_XPUB_VERBOSE 40 +#define ZMQ_ROUTER_RAW 41 +#define ZMQ_IPV6 42 +#define ZMQ_MECHANISM 43 +#define ZMQ_PLAIN_SERVER 44 +#define ZMQ_PLAIN_USERNAME 45 +#define ZMQ_PLAIN_PASSWORD 46 +#define ZMQ_CURVE_SERVER 47 +#define ZMQ_CURVE_PUBLICKEY 48 +#define ZMQ_CURVE_SECRETKEY 49 +#define ZMQ_CURVE_SERVERKEY 50 +#define ZMQ_PROBE_ROUTER 51 +#define ZMQ_REQ_CORRELATE 52 +#define ZMQ_REQ_RELAXED 53 +#define ZMQ_CONFLATE 54 +#define ZMQ_ZAP_DOMAIN 55 +#define ZMQ_ROUTER_HANDOVER 56 +#define ZMQ_TOS 57 +#define ZMQ_CONNECT_RID 61 +#define ZMQ_GSSAPI_SERVER 62 +#define ZMQ_GSSAPI_PRINCIPAL 63 +#define ZMQ_GSSAPI_SERVICE_PRINCIPAL 64 +#define ZMQ_GSSAPI_PLAINTEXT 65 +#define ZMQ_HANDSHAKE_IVL 66 +#define ZMQ_SOCKS_PROXY 68 +#define ZMQ_XPUB_NODROP 69 +// All options after this is for version 4.2 and still *draft* +// Subject to arbitrary change without notice +#define ZMQ_BLOCKY 70 +#define ZMQ_XPUB_MANUAL 71 +#define ZMQ_XPUB_WELCOME_MSG 72 +#define ZMQ_STREAM_NOTIFY 73 +#define ZMQ_INVERT_MATCHING 74 +#define ZMQ_HEARTBEAT_IVL 75 +#define ZMQ_HEARTBEAT_TTL 76 +#define ZMQ_HEARTBEAT_TIMEOUT 77 +#define ZMQ_XPUB_VERBOSER 78 +#define ZMQ_CONNECT_TIMEOUT 79 +#define ZMQ_TCP_MAXRT 80 +#define ZMQ_THREAD_SAFE 81 +#define ZMQ_MULTICAST_MAXTPDU 84 +#define ZMQ_VMCI_BUFFER_SIZE 85 +#define ZMQ_VMCI_BUFFER_MIN_SIZE 86 +#define ZMQ_VMCI_BUFFER_MAX_SIZE 87 +#define ZMQ_VMCI_CONNECT_TIMEOUT 88 +#define ZMQ_USE_FD 89 + +/* Message options */ +#define ZMQ_MORE 1 +#define ZMQ_SHARED 3 + +/* Send/recv options. */ +#define ZMQ_DONTWAIT 1 +#define ZMQ_SNDMORE 2 + +/* Security mechanisms */ +#define ZMQ_NULL 0 +#define ZMQ_PLAIN 1 +#define ZMQ_CURVE 2 +#define ZMQ_GSSAPI 3 + +/* RADIO-DISH protocol */ +#define ZMQ_GROUP_MAX_LENGTH 15 + +/* Deprecated options and aliases */ +#define ZMQ_TCP_ACCEPT_FILTER 38 +#define ZMQ_IPC_FILTER_PID 58 +#define ZMQ_IPC_FILTER_UID 59 +#define ZMQ_IPC_FILTER_GID 60 +#define ZMQ_IPV4ONLY 31 +#define ZMQ_DELAY_ATTACH_ON_CONNECT ZMQ_IMMEDIATE +#define ZMQ_NOBLOCK ZMQ_DONTWAIT +#define ZMQ_FAIL_UNROUTABLE ZMQ_ROUTER_MANDATORY +#define ZMQ_ROUTER_BEHAVIOR ZMQ_ROUTER_MANDATORY + +/* Deprecated Message options */ +#define ZMQ_SRCFD 2 + +/******************************************************************************/ +/* 0MQ socket events and monitoring */ +/******************************************************************************/ + +/* Socket transport events (TCP, IPC and TIPC only) */ + +#define ZMQ_EVENT_CONNECTED 0x0001 +#define ZMQ_EVENT_CONNECT_DELAYED 0x0002 +#define ZMQ_EVENT_CONNECT_RETRIED 0x0004 +#define ZMQ_EVENT_LISTENING 0x0008 +#define ZMQ_EVENT_BIND_FAILED 0x0010 +#define ZMQ_EVENT_ACCEPTED 0x0020 +#define ZMQ_EVENT_ACCEPT_FAILED 0x0040 +#define ZMQ_EVENT_CLOSED 0x0080 +#define ZMQ_EVENT_CLOSE_FAILED 0x0100 +#define ZMQ_EVENT_DISCONNECTED 0x0200 +#define ZMQ_EVENT_MONITOR_STOPPED 0x0400 +#define ZMQ_EVENT_ALL 0xFFFF + +ZMQ_EXPORT void *zmq_socket (void *, int type); +ZMQ_EXPORT int zmq_close (void *s); +ZMQ_EXPORT int zmq_setsockopt (void *s, int option, const void *optval, + size_t optvallen); +ZMQ_EXPORT int zmq_getsockopt (void *s, int option, void *optval, + size_t *optvallen); +ZMQ_EXPORT int zmq_bind (void *s, const char *addr); +ZMQ_EXPORT int zmq_connect (void *s, const char *addr); +ZMQ_EXPORT int zmq_unbind (void *s, const char *addr); +ZMQ_EXPORT int zmq_disconnect (void *s, const char *addr); +ZMQ_EXPORT int zmq_send (void *s, const void *buf, size_t len, int flags); +ZMQ_EXPORT int zmq_send_const (void *s, const void *buf, size_t len, int flags); +ZMQ_EXPORT int zmq_recv (void *s, void *buf, size_t len, int flags); +ZMQ_EXPORT int zmq_socket_monitor (void *s, const char *addr, int events); + + +/******************************************************************************/ +/* I/O multiplexing. */ +/******************************************************************************/ + +#define ZMQ_POLLIN 1 +#define ZMQ_POLLOUT 2 +#define ZMQ_POLLERR 4 +#define ZMQ_POLLPRI 8 + +typedef struct zmq_pollitem_t +{ + void *socket; +#if defined _WIN32 + SOCKET fd; +#else + int fd; +#endif + short events; + short revents; +} zmq_pollitem_t; + +#define ZMQ_POLLITEMS_DFLT 16 + +ZMQ_EXPORT int zmq_poll (zmq_pollitem_t *items, int nitems, long timeout); + +/******************************************************************************/ +/* Message proxying */ +/******************************************************************************/ + +ZMQ_EXPORT int zmq_proxy (void *frontend, void *backend, void *capture); +ZMQ_EXPORT int zmq_proxy_steerable (void *frontend, void *backend, void *capture, void *control); + +/******************************************************************************/ +/* Probe library capabilities */ +/******************************************************************************/ + +#define ZMQ_HAS_CAPABILITIES 1 +ZMQ_EXPORT int zmq_has (const char *capability); + +/* Deprecated aliases */ +#define ZMQ_STREAMER 1 +#define ZMQ_FORWARDER 2 +#define ZMQ_QUEUE 3 + +/* Deprecated methods */ +ZMQ_EXPORT int zmq_device (int type, void *frontend, void *backend); +ZMQ_EXPORT int zmq_sendmsg (void *s, zmq_msg_t *msg, int flags); +ZMQ_EXPORT int zmq_recvmsg (void *s, zmq_msg_t *msg, int flags); +struct iovec; +ZMQ_EXPORT int zmq_sendiov (void *s, struct iovec *iov, size_t count, int flags); +ZMQ_EXPORT int zmq_recviov (void *s, struct iovec *iov, size_t *count, int flags); + +/******************************************************************************/ +/* Encryption functions */ +/******************************************************************************/ + +/* Encode data with Z85 encoding. Returns encoded data */ +ZMQ_EXPORT char *zmq_z85_encode (char *dest, const uint8_t *data, size_t size); + +/* Decode data with Z85 encoding. Returns decoded data */ +ZMQ_EXPORT uint8_t *zmq_z85_decode (uint8_t *dest, const char *string); + +/* Generate z85-encoded public and private keypair with tweetnacl/libsodium. */ +/* Returns 0 on success. */ +ZMQ_EXPORT int zmq_curve_keypair (char *z85_public_key, char *z85_secret_key); + +/* Derive the z85-encoded public key from the z85-encoded secret key. */ +/* Returns 0 on success. */ +ZMQ_EXPORT int zmq_curve_public (char *z85_public_key, const char *z85_secret_key); + +/******************************************************************************/ +/* Atomic utility methods */ +/******************************************************************************/ + +ZMQ_EXPORT void *zmq_atomic_counter_new (void); +ZMQ_EXPORT void zmq_atomic_counter_set (void *counter, int value); +ZMQ_EXPORT int zmq_atomic_counter_inc (void *counter); +ZMQ_EXPORT int zmq_atomic_counter_dec (void *counter); +ZMQ_EXPORT int zmq_atomic_counter_value (void *counter); +ZMQ_EXPORT void zmq_atomic_counter_destroy (void **counter_p); + + +/******************************************************************************/ +/* These functions are not documented by man pages -- use at your own risk. */ +/* If you need these to be part of the formal ZMQ API, then (a) write a man */ +/* page, and (b) write a test case in tests. */ +/******************************************************************************/ + +/* Helper functions are used by perf tests so that they don't have to care */ +/* about minutiae of time-related functions on different OS platforms. */ + +/* Starts the stopwatch. Returns the handle to the watch. */ +ZMQ_EXPORT void *zmq_stopwatch_start (void); + +/* Stops the stopwatch. Returns the number of microseconds elapsed since */ +/* the stopwatch was started. */ +ZMQ_EXPORT unsigned long zmq_stopwatch_stop (void *watch_); + +/* Sleeps for specified number of seconds. */ +ZMQ_EXPORT void zmq_sleep (int seconds_); + +typedef void (zmq_thread_fn) (void*); + +/* Start a thread. Returns a handle to the thread. */ +ZMQ_EXPORT void *zmq_threadstart (zmq_thread_fn* func, void* arg); + +/* Wait for thread to complete then free up resources. */ +ZMQ_EXPORT void zmq_threadclose (void* thread); + + +/******************************************************************************/ +/* These functions are DRAFT and disabled in stable releases, and subject to */ +/* change at ANY time until declared stable. */ +/******************************************************************************/ + +#ifdef ZMQ_BUILD_DRAFT_API + +/* DRAFT Socket types. */ +#define ZMQ_SERVER 12 +#define ZMQ_CLIENT 13 +#define ZMQ_RADIO 14 +#define ZMQ_DISH 15 +#define ZMQ_GATHER 16 +#define ZMQ_SCATTER 17 +#define ZMQ_DGRAM 18 + +/* DRAFT Socket methods. */ +ZMQ_EXPORT int zmq_join (void *s, const char *group); +ZMQ_EXPORT int zmq_leave (void *s, const char *group); + +/* DRAFT Msg methods. */ +ZMQ_EXPORT int zmq_msg_set_routing_id(zmq_msg_t *msg, uint32_t routing_id); +ZMQ_EXPORT uint32_t zmq_msg_routing_id(zmq_msg_t *msg); +ZMQ_EXPORT int zmq_msg_set_group(zmq_msg_t *msg, const char *group); +ZMQ_EXPORT const char *zmq_msg_group(zmq_msg_t *msg); + +/******************************************************************************/ +/* Poller polling on sockets,fd and thread-safe sockets */ +/******************************************************************************/ + +#define ZMQ_HAVE_POLLER + +typedef struct zmq_poller_event_t +{ + void *socket; +#if defined _WIN32 + SOCKET fd; +#else + int fd; +#endif + void *user_data; + short events; +} zmq_poller_event_t; + +ZMQ_EXPORT void *zmq_poller_new (void); +ZMQ_EXPORT int zmq_poller_destroy (void **poller_p); +ZMQ_EXPORT int zmq_poller_add (void *poller, void *socket, void *user_data, short events); +ZMQ_EXPORT int zmq_poller_modify (void *poller, void *socket, short events); +ZMQ_EXPORT int zmq_poller_remove (void *poller, void *socket); +ZMQ_EXPORT int zmq_poller_wait (void *poller, zmq_poller_event_t *event, long timeout); + +#if defined _WIN32 +ZMQ_EXPORT int zmq_poller_add_fd (void *poller, SOCKET fd, void *user_data, short events); +ZMQ_EXPORT int zmq_poller_modify_fd (void *poller, SOCKET fd, short events); +ZMQ_EXPORT int zmq_poller_remove_fd (void *poller, SOCKET fd); +#else +ZMQ_EXPORT int zmq_poller_add_fd (void *poller, int fd, void *user_data, short events); +ZMQ_EXPORT int zmq_poller_modify_fd (void *poller, int fd, short events); +ZMQ_EXPORT int zmq_poller_remove_fd (void *poller, int fd); +#endif + +/******************************************************************************/ +/* Scheduling timers */ +/******************************************************************************/ + +#define ZMQ_HAVE_TIMERS + +typedef void (zmq_timer_fn)(int timer_id, void *arg); + +ZMQ_EXPORT void *zmq_timers_new (void); +ZMQ_EXPORT int zmq_timers_destroy (void **timers_p); +ZMQ_EXPORT int zmq_timers_add (void *timers, size_t interval, zmq_timer_fn handler, void *arg); +ZMQ_EXPORT int zmq_timers_cancel (void *timers, int timer_id); +ZMQ_EXPORT int zmq_timers_set_interval (void *timers, int timer_id, size_t interval); +ZMQ_EXPORT int zmq_timers_reset (void *timers, int timer_id); +ZMQ_EXPORT long zmq_timers_timeout (void *timers); +ZMQ_EXPORT int zmq_timers_execute (void *timers); + +#endif // ZMQ_BUILD_DRAFT_API + + +#undef ZMQ_EXPORT + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/arm/include/zmq_utils.h b/phonelibs/zmq/arm/include/zmq_utils.h new file mode 100644 index 00000000000000..f29638d5539414 --- /dev/null +++ b/phonelibs/zmq/arm/include/zmq_utils.h @@ -0,0 +1,48 @@ +/* + Copyright (c) 2007-2016 Contributors as noted in the AUTHORS file + + This file is part of libzmq, the ZeroMQ core engine in C++. + + libzmq is free software; you can redistribute it and/or modify it under + the terms of the GNU Lesser General Public License (LGPL) as published + by the Free Software Foundation; either version 3 of the License, or + (at your option) any later version. + + As a special exception, the Contributors give you permission to link + this library with independent modules to produce an executable, + regardless of the license terms of these independent modules, and to + copy and distribute the resulting executable under terms of your choice, + provided that you also meet, for each linked independent module, the + terms and conditions of the license of that module. An independent + module is a module which is not derived from or based on this library. + If you modify this library, you must extend this exception to your + version of the library. + + libzmq 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 this program. If not, see . +*/ + +/* This file is deprecated, and all its functionality provided by zmq.h */ +/* Note that -Wpedantic compilation requires GCC to avoid using its custom + extensions such as #warning, hence the trick below. Also, pragmas for + warnings or other messages are not standard, not portable, and not all + compilers even have an equivalent concept. + So in the worst case, this include file is treated as silently empty. */ + +#if defined(__clang__) || defined(__GNUC__) || defined(__GNUG__) || defined(_MSC_VER) +#if defined(__GNUC__) || defined(__GNUG__) +#pragma GCC diagnostic push +#pragma GCC diagnostic warning "-Wcpp" +#pragma GCC diagnostic ignored "-Werror" +#pragma GCC diagnostic ignored "-Wall" +#endif +#pragma message("Warning: zmq_utils.h is deprecated. All its functionality is provided by zmq.h.") +#if defined(__GNUC__) || defined(__GNUG__) +#pragma GCC diagnostic pop +#endif +#endif diff --git a/phonelibs/zmq/arm/include/zmsg.h b/phonelibs/zmq/arm/include/zmsg.h new file mode 100644 index 00000000000000..c6ab16c66e953c --- /dev/null +++ b/phonelibs/zmq/arm/include/zmsg.h @@ -0,0 +1,285 @@ +/* ========================================================================= + zmsg - working with multipart messages + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZMSG_H_INCLUDED__ +#define __ZMSG_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/zmsg.api" to make changes. +// @interface +// This is a stable class, and may not change except for emergencies. It +// is provided in stable builds. +// This class has draft methods, which may change over time. They are not +// in stable releases, by default. Use --enable-drafts to enable. +// Create a new empty message object +CZMQ_EXPORT zmsg_t * + zmsg_new (void); + +// Receive message from socket, returns zmsg_t object or NULL if the recv +// was interrupted. Does a blocking recv. If you want to not block then use +// the zloop class or zmsg_recv_nowait or zmq_poll to check for socket input +// before receiving. +CZMQ_EXPORT zmsg_t * + zmsg_recv (void *source); + +// Load/append an open file into new message, return the message. +// Returns NULL if the message could not be loaded. +CZMQ_EXPORT zmsg_t * + zmsg_load (FILE *file); + +// Decodes a serialized message frame created by zmsg_encode () and returns +// a new zmsg_t object. Returns NULL if the frame was badly formatted or +// there was insufficient memory to work. +CZMQ_EXPORT zmsg_t * + zmsg_decode (zframe_t *frame); + +// Generate a signal message encoding the given status. A signal is a short +// message carrying a 1-byte success/failure code (by convention, 0 means +// OK). Signals are encoded to be distinguishable from "normal" messages. +CZMQ_EXPORT zmsg_t * + zmsg_new_signal (byte status); + +// Destroy a message object and all frames it contains +CZMQ_EXPORT void + zmsg_destroy (zmsg_t **self_p); + +// Send message to destination socket, and destroy the message after sending +// it successfully. If the message has no frames, sends nothing but destroys +// the message anyhow. Nullifies the caller's reference to the message (as +// it is a destructor). +CZMQ_EXPORT int + zmsg_send (zmsg_t **self_p, void *dest); + +// Send message to destination socket as part of a multipart sequence, and +// destroy the message after sending it successfully. Note that after a +// zmsg_sendm, you must call zmsg_send or another method that sends a final +// message part. If the message has no frames, sends nothing but destroys +// the message anyhow. Nullifies the caller's reference to the message (as +// it is a destructor). +CZMQ_EXPORT int + zmsg_sendm (zmsg_t **self_p, void *dest); + +// Return size of message, i.e. number of frames (0 or more). +CZMQ_EXPORT size_t + zmsg_size (zmsg_t *self); + +// Return total size of all frames in message. +CZMQ_EXPORT size_t + zmsg_content_size (zmsg_t *self); + +// Push frame to the front of the message, i.e. before all other frames. +// Message takes ownership of frame, will destroy it when message is sent. +// Returns 0 on success, -1 on error. Deprecates zmsg_push, which did not +// nullify the caller's frame reference. +CZMQ_EXPORT int + zmsg_prepend (zmsg_t *self, zframe_t **frame_p); + +// Add frame to the end of the message, i.e. after all other frames. +// Message takes ownership of frame, will destroy it when message is sent. +// Returns 0 on success. Deprecates zmsg_add, which did not nullify the +// caller's frame reference. +CZMQ_EXPORT int + zmsg_append (zmsg_t *self, zframe_t **frame_p); + +// Remove first frame from message, if any. Returns frame, or NULL. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zframe_t * + zmsg_pop (zmsg_t *self); + +// Push block of memory to front of message, as a new frame. +// Returns 0 on success, -1 on error. +CZMQ_EXPORT int + zmsg_pushmem (zmsg_t *self, const void *data, size_t size); + +// Add block of memory to the end of the message, as a new frame. +// Returns 0 on success, -1 on error. +CZMQ_EXPORT int + zmsg_addmem (zmsg_t *self, const void *data, size_t size); + +// Push string as new frame to front of message. +// Returns 0 on success, -1 on error. +CZMQ_EXPORT int + zmsg_pushstr (zmsg_t *self, const char *string); + +// Push string as new frame to end of message. +// Returns 0 on success, -1 on error. +CZMQ_EXPORT int + zmsg_addstr (zmsg_t *self, const char *string); + +// Push formatted string as new frame to front of message. +// Returns 0 on success, -1 on error. +CZMQ_EXPORT int + zmsg_pushstrf (zmsg_t *self, const char *format, ...); + +// Push formatted string as new frame to end of message. +// Returns 0 on success, -1 on error. +CZMQ_EXPORT int + zmsg_addstrf (zmsg_t *self, const char *format, ...); + +// Pop frame off front of message, return as fresh string. If there were +// no more frames in the message, returns NULL. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT char * + zmsg_popstr (zmsg_t *self); + +// Push encoded message as a new frame. Message takes ownership of +// submessage, so the original is destroyed in this call. Returns 0 on +// success, -1 on error. +CZMQ_EXPORT int + zmsg_addmsg (zmsg_t *self, zmsg_t **msg_p); + +// Remove first submessage from message, if any. Returns zmsg_t, or NULL if +// decoding was not successful. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zmsg_t * + zmsg_popmsg (zmsg_t *self); + +// Remove specified frame from list, if present. Does not destroy frame. +CZMQ_EXPORT void + zmsg_remove (zmsg_t *self, zframe_t *frame); + +// Set cursor to first frame in message. Returns frame, or NULL, if the +// message is empty. Use this to navigate the frames as a list. +CZMQ_EXPORT zframe_t * + zmsg_first (zmsg_t *self); + +// Return the next frame. If there are no more frames, returns NULL. To move +// to the first frame call zmsg_first(). Advances the cursor. +CZMQ_EXPORT zframe_t * + zmsg_next (zmsg_t *self); + +// Return the last frame. If there are no frames, returns NULL. +CZMQ_EXPORT zframe_t * + zmsg_last (zmsg_t *self); + +// Save message to an open file, return 0 if OK, else -1. The message is +// saved as a series of frames, each with length and data. Note that the +// file is NOT guaranteed to be portable between operating systems, not +// versions of CZMQ. The file format is at present undocumented and liable +// to arbitrary change. +CZMQ_EXPORT int + zmsg_save (zmsg_t *self, FILE *file); + +// Serialize multipart message to a single message frame. Use this method +// to send structured messages across transports that do not support +// multipart data. Allocates and returns a new frame containing the +// serialized message. To decode a serialized message frame, use +// zmsg_decode (). +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zframe_t * + zmsg_encode (zmsg_t *self); + +// Create copy of message, as new message object. Returns a fresh zmsg_t +// object. If message is null, or memory was exhausted, returns null. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT zmsg_t * + zmsg_dup (zmsg_t *self); + +// Send message to zsys log sink (may be stdout, or system facility as +// configured by zsys_set_logstream). +CZMQ_EXPORT void + zmsg_print (zmsg_t *self); + +// Return true if the two messages have the same number of frames and each +// frame in the first message is identical to the corresponding frame in the +// other message. As with zframe_eq, return false if either message is NULL. +CZMQ_EXPORT bool + zmsg_eq (zmsg_t *self, zmsg_t *other); + +// Return signal value, 0 or greater, if message is a signal, -1 if not. +CZMQ_EXPORT int + zmsg_signal (zmsg_t *self); + +// Probe the supplied object, and report if it looks like a zmsg_t. +CZMQ_EXPORT bool + zmsg_is (void *self); + +// Self test of this class. +CZMQ_EXPORT void + zmsg_test (bool verbose); + +#ifdef CZMQ_BUILD_DRAFT_API +// *** Draft method, for development use, may change without warning *** +// Return message routing ID, if the message came from a ZMQ_SERVER socket. +// Else returns zero. +CZMQ_EXPORT uint32_t + zmsg_routing_id (zmsg_t *self); + +// *** Draft method, for development use, may change without warning *** +// Set routing ID on message. This is used if/when the message is sent to a +// ZMQ_SERVER socket. +CZMQ_EXPORT void + zmsg_set_routing_id (zmsg_t *self, uint32_t routing_id); + +#endif // CZMQ_BUILD_DRAFT_API +// @ignore +CZMQ_EXPORT int + zmsg_pushstrf (zmsg_t *self, const char *format, ...) CHECK_PRINTF (2); +CZMQ_EXPORT int + zmsg_addstrf (zmsg_t *self, const char *format, ...) CHECK_PRINTF (2); +// @end + + +// DEPRECATED as over-engineered, poor style +// Pop frame off front of message, caller now owns frame +// If next frame is empty, pops and destroys that empty frame. +CZMQ_EXPORT zframe_t * + zmsg_unwrap (zmsg_t *self); + +// DEPRECATED as poor style -- callers should use zloop or zpoller +// Receive message from socket, returns zmsg_t object, or NULL either if +// there was no input waiting, or the recv was interrupted. +CZMQ_EXPORT zmsg_t * + zmsg_recv_nowait (void *source); + +// DEPRECATED as unsafe -- does not nullify frame reference. +// Push frame plus empty frame to front of message, before first frame. +// Message takes ownership of frame, will destroy it when message is sent. +CZMQ_EXPORT void + zmsg_wrap (zmsg_t *self, zframe_t *frame); + +// DEPRECATED - will be removed for next + 1 stable release +// Add frame to the front of the message, i.e. before all other frames. +// Message takes ownership of frame, will destroy it when message is sent. +// Returns 0 on success, -1 on error. +CZMQ_EXPORT int + zmsg_push (zmsg_t *self, zframe_t *frame); + +// DEPRECATED - will be removed for next stable release +CZMQ_EXPORT int + zmsg_add (zmsg_t *self, zframe_t *frame); + +// DEPRECATED as inconsistent; breaks principle that logging should all go +// to a single destination. +// Print message to open stream +// Truncates to first 10 frames, for readability. +CZMQ_EXPORT void + zmsg_fprint (zmsg_t *self, FILE *file); + +// Compiler hints +CZMQ_EXPORT int zmsg_addstrf (zmsg_t *self, const char *format, ...) CHECK_PRINTF (2); +CZMQ_EXPORT int zmsg_pushstrf (zmsg_t *self, const char *format, ...) CHECK_PRINTF (2); + +#ifdef __cplusplus +} +#endif + +// Deprecated method aliases +#define zmsg_dump(s) zmsg_print(s) +#define zmsg_dump_to_stream(s,F) zmsg_fprint(s,F) + +#endif diff --git a/phonelibs/zmq/arm/include/zmutex.h b/phonelibs/zmq/arm/include/zmutex.h new file mode 100644 index 00000000000000..cba315999b7598 --- /dev/null +++ b/phonelibs/zmq/arm/include/zmutex.h @@ -0,0 +1,55 @@ +/* ========================================================================= + zmutex - working with mutexes + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZMUTEX_H_INCLUDED__ +#define __ZMUTEX_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @interface +// This is a deprecated class, and will be removed over time. It is +// provided in stable builds to support old applications. You should +// stop using this class, and migrate any code that is still using it. + +// Create a new mutex container +CZMQ_EXPORT zmutex_t * + zmutex_new (void); + +// Destroy a mutex container +CZMQ_EXPORT void + zmutex_destroy (zmutex_t **self_p); + +// Lock mutex +CZMQ_EXPORT void + zmutex_lock (zmutex_t *self); + +// Unlock mutex +CZMQ_EXPORT void + zmutex_unlock (zmutex_t *self); + +// Try to lock mutex +CZMQ_EXPORT int + zmutex_try_lock (zmutex_t *self); + +// Self test of this class. +CZMQ_EXPORT void + zmutex_test (bool verbose); +// @end + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/arm/include/zpoller.h b/phonelibs/zmq/arm/include/zpoller.h new file mode 100644 index 00000000000000..3756a935a64008 --- /dev/null +++ b/phonelibs/zmq/arm/include/zpoller.h @@ -0,0 +1,92 @@ +/* ========================================================================= + zpoller - trivial socket poller class + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __zpoller_H_INCLUDED__ +#define __zpoller_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/zpoller.api" to make changes. +// @interface +// This is a stable class, and may not change except for emergencies. It +// is provided in stable builds. +// This class has draft methods, which may change over time. They are not +// in stable releases, by default. Use --enable-drafts to enable. +// Create new poller, specifying zero or more readers. The list of +// readers ends in a NULL. Each reader can be a zsock_t instance, a +// zactor_t instance, a libzmq socket (void *), or a file handle. +CZMQ_EXPORT zpoller_t * + zpoller_new (void *reader, ...); + +// Destroy a poller +CZMQ_EXPORT void + zpoller_destroy (zpoller_t **self_p); + +// Add a reader to be polled. Returns 0 if OK, -1 on failure. The reader may +// be a libzmq void * socket, a zsock_t instance, or a zactor_t instance. +CZMQ_EXPORT int + zpoller_add (zpoller_t *self, void *reader); + +// Remove a reader from the poller; returns 0 if OK, -1 on failure. The reader +// must have been passed during construction, or in an zpoller_add () call. +CZMQ_EXPORT int + zpoller_remove (zpoller_t *self, void *reader); + +// Poll the registered readers for I/O, return first reader that has input. +// The reader will be a libzmq void * socket, or a zsock_t or zactor_t +// instance as specified in zpoller_new/zpoller_add. The timeout should be +// zero or greater, or -1 to wait indefinitely. Socket priority is defined +// by their order in the poll list. If you need a balanced poll, use the low +// level zmq_poll method directly. If the poll call was interrupted (SIGINT), +// or the ZMQ context was destroyed, or the timeout expired, returns NULL. +// You can test the actual exit condition by calling zpoller_expired () and +// zpoller_terminated (). The timeout is in msec. +CZMQ_EXPORT void * + zpoller_wait (zpoller_t *self, int timeout); + +// Return true if the last zpoller_wait () call ended because the timeout +// expired, without any error. +CZMQ_EXPORT bool + zpoller_expired (zpoller_t *self); + +// Return true if the last zpoller_wait () call ended because the process +// was interrupted, or the parent context was destroyed. +CZMQ_EXPORT bool + zpoller_terminated (zpoller_t *self); + +// Self test of this class. +CZMQ_EXPORT void + zpoller_test (bool verbose); + +#ifdef CZMQ_BUILD_DRAFT_API +// *** Draft method, for development use, may change without warning *** +// By default the poller stops if the process receives a SIGINT or SIGTERM +// signal. This makes it impossible to shut-down message based architectures +// like zactors. This method lets you switch off break handling. The default +// nonstop setting is off (false). +CZMQ_EXPORT void + zpoller_set_nonstop (zpoller_t *self, bool nonstop); + +#endif // CZMQ_BUILD_DRAFT_API +// @end + + +#ifdef __cplusplus +} +#endif + +#endif + diff --git a/phonelibs/zmq/arm/include/zproc.h b/phonelibs/zmq/arm/include/zproc.h new file mode 100644 index 00000000000000..a2e1b3dd9913c6 --- /dev/null +++ b/phonelibs/zmq/arm/include/zproc.h @@ -0,0 +1,179 @@ +/* ========================================================================= + zproc - process configuration and status + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef ZPROC_H_INCLUDED +#define ZPROC_H_INCLUDED + +#ifdef __cplusplus +extern "C" { +#endif + + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/zproc.api" to make changes. +// @interface +// This is a draft class, and may change without notice. It is disabled in +// stable builds by default. If you use this in applications, please ask +// for it to be pushed to stable state. Use --enable-drafts to enable. +#ifdef CZMQ_BUILD_DRAFT_API +// *** Draft method, for development use, may change without warning *** +// Returns CZMQ version as a single 6-digit integer encoding the major +// version (x 10000), the minor version (x 100) and the patch. +CZMQ_EXPORT int + zproc_czmq_version (void); + +// *** Draft method, for development use, may change without warning *** +// Returns true if the process received a SIGINT or SIGTERM signal. +// It is good practice to use this method to exit any infinite loop +// processing messages. +CZMQ_EXPORT bool + zproc_interrupted (void); + +// *** Draft method, for development use, may change without warning *** +// Returns true if the underlying libzmq supports CURVE security. +CZMQ_EXPORT bool + zproc_has_curve (void); + +// *** Draft method, for development use, may change without warning *** +// Return current host name, for use in public tcp:// endpoints. +// If the host name is not resolvable, returns NULL. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT char * + zproc_hostname (void); + +// *** Draft method, for development use, may change without warning *** +// Move the current process into the background. The precise effect +// depends on the operating system. On POSIX boxes, moves to a specified +// working directory (if specified), closes all file handles, reopens +// stdin, stdout, and stderr to the null device, and sets the process to +// ignore SIGHUP. On Windows, does nothing. Returns 0 if OK, -1 if there +// was an error. +CZMQ_EXPORT void + zproc_daemonize (const char *workdir); + +// *** Draft method, for development use, may change without warning *** +// Drop the process ID into the lockfile, with exclusive lock, and +// switch the process to the specified group and/or user. Any of the +// arguments may be null, indicating a no-op. Returns 0 on success, +// -1 on failure. Note if you combine this with zsys_daemonize, run +// after, not before that method, or the lockfile will hold the wrong +// process ID. +CZMQ_EXPORT void + zproc_run_as (const char *lockfile, const char *group, const char *user); + +// *** Draft method, for development use, may change without warning *** +// Configure the number of I/O threads that ZeroMQ will use. A good +// rule of thumb is one thread per gigabit of traffic in or out. The +// default is 1, sufficient for most applications. If the environment +// variable ZSYS_IO_THREADS is defined, that provides the default. +// Note that this method is valid only before any socket is created. +CZMQ_EXPORT void + zproc_set_io_threads (size_t io_threads); + +// *** Draft method, for development use, may change without warning *** +// Configure the number of sockets that ZeroMQ will allow. The default +// is 1024. The actual limit depends on the system, and you can query it +// by using zsys_socket_limit (). A value of zero means "maximum". +// Note that this method is valid only before any socket is created. +CZMQ_EXPORT void + zproc_set_max_sockets (size_t max_sockets); + +// *** Draft method, for development use, may change without warning *** +// Set network interface name to use for broadcasts, particularly zbeacon. +// This lets the interface be configured for test environments where required. +// For example, on Mac OS X, zbeacon cannot bind to 255.255.255.255 which is +// the default when there is no specified interface. If the environment +// variable ZSYS_INTERFACE is set, use that as the default interface name. +// Setting the interface to "*" means "use all available interfaces". +CZMQ_EXPORT void + zproc_set_biface (const char *value); + +// *** Draft method, for development use, may change without warning *** +// Return network interface to use for broadcasts, or "" if none was set. +CZMQ_EXPORT const char * + zproc_biface (void); + +// *** Draft method, for development use, may change without warning *** +// Set log identity, which is a string that prefixes all log messages sent +// by this process. The log identity defaults to the environment variable +// ZSYS_LOGIDENT, if that is set. +CZMQ_EXPORT void + zproc_set_log_ident (const char *value); + +// *** Draft method, for development use, may change without warning *** +// Sends log output to a PUB socket bound to the specified endpoint. To +// collect such log output, create a SUB socket, subscribe to the traffic +// you care about, and connect to the endpoint. Log traffic is sent as a +// single string frame, in the same format as when sent to stdout. The +// log system supports a single sender; multiple calls to this method will +// bind the same sender to multiple endpoints. To disable the sender, call +// this method with a null argument. +CZMQ_EXPORT void + zproc_set_log_sender (const char *endpoint); + +// *** Draft method, for development use, may change without warning *** +// Enable or disable logging to the system facility (syslog on POSIX boxes, +// event log on Windows). By default this is disabled. +CZMQ_EXPORT void + zproc_set_log_system (bool logsystem); + +// *** Draft method, for development use, may change without warning *** +// Log error condition - highest priority +CZMQ_EXPORT void + zproc_log_error (const char *format, ...); + +// *** Draft method, for development use, may change without warning *** +// Log warning condition - high priority +CZMQ_EXPORT void + zproc_log_warning (const char *format, ...); + +// *** Draft method, for development use, may change without warning *** +// Log normal, but significant, condition - normal priority +CZMQ_EXPORT void + zproc_log_notice (const char *format, ...); + +// *** Draft method, for development use, may change without warning *** +// Log informational message - low priority +CZMQ_EXPORT void + zproc_log_info (const char *format, ...); + +// *** Draft method, for development use, may change without warning *** +// Log debug-level message - lowest priority +CZMQ_EXPORT void + zproc_log_debug (const char *format, ...); + +// *** Draft method, for development use, may change without warning *** +// Self test of this class. +CZMQ_EXPORT void + zproc_test (bool verbose); + +#endif // CZMQ_BUILD_DRAFT_API +// @ignore +CZMQ_EXPORT void + zproc_log_error (const char *format, ...) CHECK_PRINTF (1); +CZMQ_EXPORT void + zproc_log_warning (const char *format, ...) CHECK_PRINTF (1); +CZMQ_EXPORT void + zproc_log_notice (const char *format, ...) CHECK_PRINTF (1); +CZMQ_EXPORT void + zproc_log_info (const char *format, ...) CHECK_PRINTF (1); +CZMQ_EXPORT void + zproc_log_debug (const char *format, ...) CHECK_PRINTF (1); +// @end + + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/arm/include/zproxy.h b/phonelibs/zmq/arm/include/zproxy.h new file mode 100644 index 00000000000000..f672c5e72417a5 --- /dev/null +++ b/phonelibs/zmq/arm/include/zproxy.h @@ -0,0 +1,111 @@ +/* ========================================================================= + zproxy - run a steerable proxy in the background + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZPROXY_H_INCLUDED__ +#define __ZPROXY_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @interface +// Create new zproxy actor instance. The proxy switches messages between +// a frontend socket and a backend socket; use the FRONTEND and BACKEND +// commands to configure these: +// +// zactor_t *proxy = zactor_new (zproxy, NULL); +// +// Destroy zproxy instance. This destroys the two sockets and stops any +// message flow between them: +// +// zactor_destroy (&proxy); +// +// Note that all zproxy commands are synchronous, so your application always +// waits for a signal from the actor after each command. +// +// Enable verbose logging of commands and activity: +// +// zstr_send (proxy, "VERBOSE"); +// zsock_wait (proxy); +// +// Specify frontend socket type -- see zsock_type_str () -- and attach to +// endpoints, see zsock_attach (). Note that a proxy socket is always +// serverish: +// +// zstr_sendx (proxy, "FRONTEND", "XSUB", endpoints, NULL); +// zsock_wait (proxy); +// +// Specify backend socket type -- see zsock_type_str () -- and attach to +// endpoints, see zsock_attach (). Note that a proxy socket is always +// serverish: +// +// zstr_sendx (proxy, "BACKEND", "XPUB", endpoints, NULL); +// zsock_wait (proxy); +// +// Capture all proxied messages; these are delivered to the application +// via an inproc PULL socket that you have already bound to the specified +// endpoint: +// +// zstr_sendx (proxy, "CAPTURE", endpoint, NULL); +// zsock_wait (proxy); +// +// Pause the proxy. A paused proxy will cease processing messages, causing +// them to be queued up and potentially hit the high-water mark on the +// frontend or backend socket, causing messages to be dropped, or writing +// applications to block: +// +// zstr_sendx (proxy, "PAUSE", NULL); +// zsock_wait (proxy); +// +// Resume the proxy. Note that the proxy starts automatically as soon as it +// has a properly attached frontend and backend socket: +// +// zstr_sendx (proxy, "RESUME", NULL); +// zsock_wait (proxy); +// +// Configure an authentication domain for the "FRONTEND" or "BACKEND" proxy +// socket -- see zsock_set_zap_domain (). Call before binding socket: +// +// zstr_sendx (proxy, "DOMAIN", "FRONTEND", "global", NULL); +// zsock_wait (proxy); +// +// Configure PLAIN authentication for the "FRONTEND" or "BACKEND" proxy +// socket -- see zsock_set_plain_server (). Call before binding socket: +// +// zstr_sendx (proxy, "PLAIN", "BACKEND", NULL); +// zsock_wait (proxy); +// +// Configure CURVE authentication for the "FRONTEND" or "BACKEND" proxy +// socket -- see zsock_set_curve_server () -- specifying both the public and +// secret keys of a certificate as Z85 armored strings -- see +// zcert_public_txt () and zcert_secret_txt (). Call before binding socket: +// +// zstr_sendx (proxy, "CURVE", "FRONTEND", public_txt, secret_txt, NULL); +// zsock_wait (proxy); +// +// This is the zproxy constructor as a zactor_fn; the argument is a +// character string specifying frontend and backend socket types as two +// uppercase strings separated by a hyphen: +CZMQ_EXPORT void + zproxy (zsock_t *pipe, void *unused); + +// Selftest +CZMQ_EXPORT void + zproxy_test (bool verbose); +// @end + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/arm/include/zproxy_v2.h b/phonelibs/zmq/arm/include/zproxy_v2.h new file mode 100644 index 00000000000000..4bde9515916935 --- /dev/null +++ b/phonelibs/zmq/arm/include/zproxy_v2.h @@ -0,0 +1,62 @@ +/* ========================================================================= + zproxy_v2 - run a steerable proxy in the background (deprecated) + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZPROXY_V2_H_INCLUDED__ +#define __ZPROXY_V2_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @interface + +// Constructor +// Create a new zproxy object. You must create the frontend and backend +// sockets, configure them, and connect or bind them, before you pass them +// to the constructor. Do NOT use the sockets again, after passing them to +// this method. +CZMQ_EXPORT zproxy_t * + zproxy_new (zctx_t *ctx, void *frontend, void *backend); + +// Destructor +// Destroy a zproxy object; note this first stops the proxy. +CZMQ_EXPORT void + zproxy_destroy (zproxy_t **self_p); + +// Copy all proxied messages to specified endpoint; if this is NULL, any +// in-progress capturing will be stopped. You must already have bound the +// endpoint to a PULL socket. +CZMQ_EXPORT void + zproxy_capture (zproxy_t *self, const char *endpoint); + +// Pauses a zproxy object; a paused proxy will cease processing messages, +// causing them to be queued up and potentially hit the high-water mark on +// the frontend socket, causing messages to be dropped, or writing +// applications to block. +CZMQ_EXPORT void + zproxy_pause (zproxy_t *self); + +// Resume a zproxy object +CZMQ_EXPORT void + zproxy_resume (zproxy_t *self); + +// Self test of this class +CZMQ_EXPORT void + zproxy_v2_test (bool verbose); +// @end + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/arm/include/zrex.h b/phonelibs/zmq/arm/include/zrex.h new file mode 100644 index 00000000000000..8b50618a34837c --- /dev/null +++ b/phonelibs/zmq/arm/include/zrex.h @@ -0,0 +1,82 @@ +/* ========================================================================= + zrex - work with regular expressions + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZREX_H_INCLUDED__ +#define __ZREX_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @interface +// Constructor. Optionally, sets an expression against which we can match +// text and capture hits. If there is an error in the expression, reports +// zrex_valid() as false and provides the error in zrex_strerror(). If you +// set a pattern, you can call zrex_matches() to test it against text. +CZMQ_EXPORT zrex_t * + zrex_new (const char *expression); + +// Destructor +CZMQ_EXPORT void + zrex_destroy (zrex_t **self_p); + +// Return true if the expression was valid and compiled without errors. +CZMQ_EXPORT bool + zrex_valid (zrex_t *self); + +// Return the error message generated during compilation of the expression. +CZMQ_EXPORT const char * + zrex_strerror (zrex_t *self); + +// Returns true if the text matches the previously compiled expression. +// Use this method to compare one expression against many strings. +CZMQ_EXPORT bool + zrex_matches (zrex_t *self, const char *text); + +// Returns true if the text matches the supplied expression. Use this +// method to compare one string against several expressions. +CZMQ_EXPORT bool + zrex_eq (zrex_t *self, const char *text, const char *expression); + +// Returns number of hits from last zrex_matches or zrex_eq. If the text +// matched, returns 1 plus the number of capture groups. If the text did +// not match, returns zero. To retrieve individual capture groups, call +// zrex_hit (). +CZMQ_EXPORT int + zrex_hits (zrex_t *self); + +// Returns the Nth capture group from the last expression match, where +// N is 0 to the value returned by zrex_hits(). Capture group 0 is the +// whole matching string. Sequence 1 is the first capture group, if any, +// and so on. +CZMQ_EXPORT const char * + zrex_hit (zrex_t *self, uint index); + +// Fetches hits into string variables provided by caller; this makes for +// nicer code than accessing hits by index. Caller should not modify nor +// free the returned values. Returns number of strings returned. This +// method starts at hit 1, i.e. first capture group, as hit 0 is always +// the original matched string. +CZMQ_EXPORT int + zrex_fetch (zrex_t *self, const char **string_p, ...); + +// Self test of this class +CZMQ_EXPORT void + zrex_test (bool verbose); +// @end + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/arm/include/zsock.h b/phonelibs/zmq/arm/include/zsock.h new file mode 100644 index 00000000000000..fc5c46e45e9810 --- /dev/null +++ b/phonelibs/zmq/arm/include/zsock.h @@ -0,0 +1,921 @@ +/* ========================================================================= + zsock - high-level socket API that hides libzmq contexts and sockets + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZSOCK_H_INCLUDED__ +#define __ZSOCK_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// This interface includes some smart constructors, which create sockets with +// additional set-up. In all of these, the endpoint is NULL, or starts with +// '@' (bind) or '>' (connect). Multiple endpoints are allowed, separated by +// commas. If endpoint does not start with '@' or '>', default action depends +// on socket type. + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/zsock.api" to make changes. +// @interface +// This is a stable class, and may not change except for emergencies. It +// is provided in stable builds. +// This class has draft methods, which may change over time. They are not +// in stable releases, by default. Use --enable-drafts to enable. +// Create a new socket. Returns the new socket, or NULL if the new socket +// could not be created. Note that the symbol zsock_new (and other +// constructors/destructors for zsock) are redirected to the *_checked +// variant, enabling intelligent socket leak detection. This can have +// performance implications if you use a LOT of sockets. To turn off this +// redirection behaviour, define ZSOCK_NOCHECK. +CZMQ_EXPORT zsock_t * + zsock_new (int type); + +// Create a PUB socket. Default action is bind. +CZMQ_EXPORT zsock_t * + zsock_new_pub (const char *endpoint); + +// Create a SUB socket, and optionally subscribe to some prefix string. Default +// action is connect. +CZMQ_EXPORT zsock_t * + zsock_new_sub (const char *endpoint, const char *subscribe); + +// Create a REQ socket. Default action is connect. +CZMQ_EXPORT zsock_t * + zsock_new_req (const char *endpoint); + +// Create a REP socket. Default action is bind. +CZMQ_EXPORT zsock_t * + zsock_new_rep (const char *endpoint); + +// Create a DEALER socket. Default action is connect. +CZMQ_EXPORT zsock_t * + zsock_new_dealer (const char *endpoint); + +// Create a ROUTER socket. Default action is bind. +CZMQ_EXPORT zsock_t * + zsock_new_router (const char *endpoint); + +// Create a PUSH socket. Default action is connect. +CZMQ_EXPORT zsock_t * + zsock_new_push (const char *endpoint); + +// Create a PULL socket. Default action is bind. +CZMQ_EXPORT zsock_t * + zsock_new_pull (const char *endpoint); + +// Create an XPUB socket. Default action is bind. +CZMQ_EXPORT zsock_t * + zsock_new_xpub (const char *endpoint); + +// Create an XSUB socket. Default action is connect. +CZMQ_EXPORT zsock_t * + zsock_new_xsub (const char *endpoint); + +// Create a PAIR socket. Default action is connect. +CZMQ_EXPORT zsock_t * + zsock_new_pair (const char *endpoint); + +// Create a STREAM socket. Default action is connect. +CZMQ_EXPORT zsock_t * + zsock_new_stream (const char *endpoint); + +// Destroy the socket. You must use this for any socket created via the +// zsock_new method. +CZMQ_EXPORT void + zsock_destroy (zsock_t **self_p); + +// Bind a socket to a formatted endpoint. For tcp:// endpoints, supports +// ephemeral ports, if you specify the port number as "*". By default +// zsock uses the IANA designated range from C000 (49152) to FFFF (65535). +// To override this range, follow the "*" with "[first-last]". Either or +// both first and last may be empty. To bind to a random port within the +// range, use "!" in place of "*". +// +// Examples: +// tcp://127.0.0.1:* bind to first free port from C000 up +// tcp://127.0.0.1:! bind to random port from C000 to FFFF +// tcp://127.0.0.1:*[60000-] bind to first free port from 60000 up +// tcp://127.0.0.1:![-60000] bind to random port from C000 to 60000 +// tcp://127.0.0.1:![55000-55999] +// bind to random port from 55000 to 55999 +// +// On success, returns the actual port number used, for tcp:// endpoints, +// and 0 for other transports. On failure, returns -1. Note that when using +// ephemeral ports, a port may be reused by different services without +// clients being aware. Protocols that run on ephemeral ports should take +// this into account. +CZMQ_EXPORT int + zsock_bind (zsock_t *self, const char *format, ...); + +// Returns last bound endpoint, if any. +CZMQ_EXPORT const char * + zsock_endpoint (zsock_t *self); + +// Unbind a socket from a formatted endpoint. +// Returns 0 if OK, -1 if the endpoint was invalid or the function +// isn't supported. +CZMQ_EXPORT int + zsock_unbind (zsock_t *self, const char *format, ...); + +// Connect a socket to a formatted endpoint +// Returns 0 if OK, -1 if the endpoint was invalid. +CZMQ_EXPORT int + zsock_connect (zsock_t *self, const char *format, ...); + +// Disconnect a socket from a formatted endpoint +// Returns 0 if OK, -1 if the endpoint was invalid or the function +// isn't supported. +CZMQ_EXPORT int + zsock_disconnect (zsock_t *self, const char *format, ...); + +// Attach a socket to zero or more endpoints. If endpoints is not null, +// parses as list of ZeroMQ endpoints, separated by commas, and prefixed by +// '@' (to bind the socket) or '>' (to connect the socket). Returns 0 if all +// endpoints were valid, or -1 if there was a syntax error. If the endpoint +// does not start with '@' or '>', the serverish argument defines whether +// it is used to bind (serverish = true) or connect (serverish = false). +CZMQ_EXPORT int + zsock_attach (zsock_t *self, const char *endpoints, bool serverish); + +// Returns socket type as printable constant string. +CZMQ_EXPORT const char * + zsock_type_str (zsock_t *self); + +// Send a 'picture' message to the socket (or actor). The picture is a +// string that defines the type of each frame. This makes it easy to send +// a complex multiframe message in one call. The picture can contain any +// of these characters, each corresponding to one or two arguments: +// +// i = int (signed) +// 1 = uint8_t +// 2 = uint16_t +// 4 = uint32_t +// 8 = uint64_t +// s = char * +// b = byte *, size_t (2 arguments) +// c = zchunk_t * +// f = zframe_t * +// h = zhashx_t * +// U = zuuid_t * +// p = void * (sends the pointer value, only meaningful over inproc) +// m = zmsg_t * (sends all frames in the zmsg) +// z = sends zero-sized frame (0 arguments) +// u = uint (deprecated) +// +// Note that s, b, c, and f are encoded the same way and the choice is +// offered as a convenience to the sender, which may or may not already +// have data in a zchunk or zframe. Does not change or take ownership of +// any arguments. Returns 0 if successful, -1 if sending failed for any +// reason. +CZMQ_EXPORT int + zsock_send (void *self, const char *picture, ...); + +// Send a 'picture' message to the socket (or actor). This is a va_list +// version of zsock_send (), so please consult its documentation for the +// details. +CZMQ_EXPORT int + zsock_vsend (void *self, const char *picture, va_list argptr); + +// Receive a 'picture' message to the socket (or actor). See zsock_send for +// the format and meaning of the picture. Returns the picture elements into +// a series of pointers as provided by the caller: +// +// i = int * (stores signed integer) +// 4 = uint32_t * (stores 32-bit unsigned integer) +// 8 = uint64_t * (stores 64-bit unsigned integer) +// s = char ** (allocates new string) +// b = byte **, size_t * (2 arguments) (allocates memory) +// c = zchunk_t ** (creates zchunk) +// f = zframe_t ** (creates zframe) +// U = zuuid_t * (creates a zuuid with the data) +// h = zhashx_t ** (creates zhashx) +// p = void ** (stores pointer) +// m = zmsg_t ** (creates a zmsg with the remaing frames) +// z = null, asserts empty frame (0 arguments) +// u = uint * (stores unsigned integer, deprecated) +// +// Note that zsock_recv creates the returned objects, and the caller must +// destroy them when finished with them. The supplied pointers do not need +// to be initialized. Returns 0 if successful, or -1 if it failed to recv +// a message, in which case the pointers are not modified. When message +// frames are truncated (a short message), sets return values to zero/null. +// If an argument pointer is NULL, does not store any value (skips it). +// An 'n' picture matches an empty frame; if the message does not match, +// the method will return -1. +CZMQ_EXPORT int + zsock_recv (void *self, const char *picture, ...); + +// Receive a 'picture' message from the socket (or actor). This is a +// va_list version of zsock_recv (), so please consult its documentation +// for the details. +CZMQ_EXPORT int + zsock_vrecv (void *self, const char *picture, va_list argptr); + +// Send a binary encoded 'picture' message to the socket (or actor). This +// method is similar to zsock_send, except the arguments are encoded in a +// binary format that is compatible with zproto, and is designed to reduce +// memory allocations. The pattern argument is a string that defines the +// type of each argument. Supports these argument types: +// +// pattern C type zproto type: +// 1 uint8_t type = "number" size = "1" +// 2 uint16_t type = "number" size = "2" +// 4 uint32_t type = "number" size = "3" +// 8 uint64_t type = "number" size = "4" +// s char *, 0-255 chars type = "string" +// S char *, 0-2^32-1 chars type = "longstr" +// c zchunk_t * type = "chunk" +// f zframe_t * type = "frame" +// u zuuid_t * type = "uuid" +// m zmsg_t * type = "msg" +// p void *, sends pointer value, only over inproc +// +// Does not change or take ownership of any arguments. Returns 0 if +// successful, -1 if sending failed for any reason. +CZMQ_EXPORT int + zsock_bsend (void *self, const char *picture, ...); + +// Receive a binary encoded 'picture' message from the socket (or actor). +// This method is similar to zsock_recv, except the arguments are encoded +// in a binary format that is compatible with zproto, and is designed to +// reduce memory allocations. The pattern argument is a string that defines +// the type of each argument. See zsock_bsend for the supported argument +// types. All arguments must be pointers; this call sets them to point to +// values held on a per-socket basis. +// Note that zsock_brecv creates the returned objects, and the caller must +// destroy them when finished with them. The supplied pointers do not need +// to be initialized. Returns 0 if successful, or -1 if it failed to read +// a message. +CZMQ_EXPORT int + zsock_brecv (void *self, const char *picture, ...); + +// Set socket to use unbounded pipes (HWM=0); use this in cases when you are +// totally certain the message volume can fit in memory. This method works +// across all versions of ZeroMQ. Takes a polymorphic socket reference. +CZMQ_EXPORT void + zsock_set_unbounded (void *self); + +// Send a signal over a socket. A signal is a short message carrying a +// success/failure code (by convention, 0 means OK). Signals are encoded +// to be distinguishable from "normal" messages. Accepts a zsock_t or a +// zactor_t argument, and returns 0 if successful, -1 if the signal could +// not be sent. Takes a polymorphic socket reference. +CZMQ_EXPORT int + zsock_signal (void *self, byte status); + +// Wait on a signal. Use this to coordinate between threads, over pipe +// pairs. Blocks until the signal is received. Returns -1 on error, 0 or +// greater on success. Accepts a zsock_t or a zactor_t as argument. +// Takes a polymorphic socket reference. +CZMQ_EXPORT int + zsock_wait (void *self); + +// If there is a partial message still waiting on the socket, remove and +// discard it. This is useful when reading partial messages, to get specific +// message types. +CZMQ_EXPORT void + zsock_flush (void *self); + +// Probe the supplied object, and report if it looks like a zsock_t. +// Takes a polymorphic socket reference. +CZMQ_EXPORT bool + zsock_is (void *self); + +// Probe the supplied reference. If it looks like a zsock_t instance, return +// the underlying libzmq socket handle; else if it looks like a file +// descriptor, return NULL; else if it looks like a libzmq socket handle, +// return the supplied value. Takes a polymorphic socket reference. +CZMQ_EXPORT void * + zsock_resolve (void *self); + +// Get socket option `tos`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_tos (void *self); + +// Set socket option `tos`. +CZMQ_EXPORT void + zsock_set_tos (void *self, int tos); + +// Set socket option `router_handover`. +CZMQ_EXPORT void + zsock_set_router_handover (void *self, int router_handover); + +// Set socket option `router_mandatory`. +CZMQ_EXPORT void + zsock_set_router_mandatory (void *self, int router_mandatory); + +// Set socket option `probe_router`. +CZMQ_EXPORT void + zsock_set_probe_router (void *self, int probe_router); + +// Set socket option `req_relaxed`. +CZMQ_EXPORT void + zsock_set_req_relaxed (void *self, int req_relaxed); + +// Set socket option `req_correlate`. +CZMQ_EXPORT void + zsock_set_req_correlate (void *self, int req_correlate); + +// Set socket option `conflate`. +CZMQ_EXPORT void + zsock_set_conflate (void *self, int conflate); + +// Get socket option `zap_domain`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT char * + zsock_zap_domain (void *self); + +// Set socket option `zap_domain`. +CZMQ_EXPORT void + zsock_set_zap_domain (void *self, const char *zap_domain); + +// Get socket option `mechanism`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_mechanism (void *self); + +// Get socket option `plain_server`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_plain_server (void *self); + +// Set socket option `plain_server`. +CZMQ_EXPORT void + zsock_set_plain_server (void *self, int plain_server); + +// Get socket option `plain_username`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT char * + zsock_plain_username (void *self); + +// Set socket option `plain_username`. +CZMQ_EXPORT void + zsock_set_plain_username (void *self, const char *plain_username); + +// Get socket option `plain_password`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT char * + zsock_plain_password (void *self); + +// Set socket option `plain_password`. +CZMQ_EXPORT void + zsock_set_plain_password (void *self, const char *plain_password); + +// Get socket option `curve_server`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_curve_server (void *self); + +// Set socket option `curve_server`. +CZMQ_EXPORT void + zsock_set_curve_server (void *self, int curve_server); + +// Get socket option `curve_publickey`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT char * + zsock_curve_publickey (void *self); + +// Set socket option `curve_publickey`. +CZMQ_EXPORT void + zsock_set_curve_publickey (void *self, const char *curve_publickey); + +// Set socket option `curve_publickey` from 32-octet binary +CZMQ_EXPORT void + zsock_set_curve_publickey_bin (void *self, const byte *curve_publickey); + +// Get socket option `curve_secretkey`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT char * + zsock_curve_secretkey (void *self); + +// Set socket option `curve_secretkey`. +CZMQ_EXPORT void + zsock_set_curve_secretkey (void *self, const char *curve_secretkey); + +// Set socket option `curve_secretkey` from 32-octet binary +CZMQ_EXPORT void + zsock_set_curve_secretkey_bin (void *self, const byte *curve_secretkey); + +// Get socket option `curve_serverkey`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT char * + zsock_curve_serverkey (void *self); + +// Set socket option `curve_serverkey`. +CZMQ_EXPORT void + zsock_set_curve_serverkey (void *self, const char *curve_serverkey); + +// Set socket option `curve_serverkey` from 32-octet binary +CZMQ_EXPORT void + zsock_set_curve_serverkey_bin (void *self, const byte *curve_serverkey); + +// Get socket option `gssapi_server`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_gssapi_server (void *self); + +// Set socket option `gssapi_server`. +CZMQ_EXPORT void + zsock_set_gssapi_server (void *self, int gssapi_server); + +// Get socket option `gssapi_plaintext`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_gssapi_plaintext (void *self); + +// Set socket option `gssapi_plaintext`. +CZMQ_EXPORT void + zsock_set_gssapi_plaintext (void *self, int gssapi_plaintext); + +// Get socket option `gssapi_principal`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT char * + zsock_gssapi_principal (void *self); + +// Set socket option `gssapi_principal`. +CZMQ_EXPORT void + zsock_set_gssapi_principal (void *self, const char *gssapi_principal); + +// Get socket option `gssapi_service_principal`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT char * + zsock_gssapi_service_principal (void *self); + +// Set socket option `gssapi_service_principal`. +CZMQ_EXPORT void + zsock_set_gssapi_service_principal (void *self, const char *gssapi_service_principal); + +// Get socket option `ipv6`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_ipv6 (void *self); + +// Set socket option `ipv6`. +CZMQ_EXPORT void + zsock_set_ipv6 (void *self, int ipv6); + +// Get socket option `immediate`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_immediate (void *self); + +// Set socket option `immediate`. +CZMQ_EXPORT void + zsock_set_immediate (void *self, int immediate); + +// Set socket option `router_raw`. +CZMQ_EXPORT void + zsock_set_router_raw (void *self, int router_raw); + +// Get socket option `ipv4only`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_ipv4only (void *self); + +// Set socket option `ipv4only`. +CZMQ_EXPORT void + zsock_set_ipv4only (void *self, int ipv4only); + +// Set socket option `delay_attach_on_connect`. +CZMQ_EXPORT void + zsock_set_delay_attach_on_connect (void *self, int delay_attach_on_connect); + +// Get socket option `type`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_type (void *self); + +// Get socket option `sndhwm`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_sndhwm (void *self); + +// Set socket option `sndhwm`. +CZMQ_EXPORT void + zsock_set_sndhwm (void *self, int sndhwm); + +// Get socket option `rcvhwm`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_rcvhwm (void *self); + +// Set socket option `rcvhwm`. +CZMQ_EXPORT void + zsock_set_rcvhwm (void *self, int rcvhwm); + +// Get socket option `affinity`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_affinity (void *self); + +// Set socket option `affinity`. +CZMQ_EXPORT void + zsock_set_affinity (void *self, int affinity); + +// Set socket option `subscribe`. +CZMQ_EXPORT void + zsock_set_subscribe (void *self, const char *subscribe); + +// Set socket option `unsubscribe`. +CZMQ_EXPORT void + zsock_set_unsubscribe (void *self, const char *unsubscribe); + +// Get socket option `identity`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT char * + zsock_identity (void *self); + +// Set socket option `identity`. +CZMQ_EXPORT void + zsock_set_identity (void *self, const char *identity); + +// Get socket option `rate`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_rate (void *self); + +// Set socket option `rate`. +CZMQ_EXPORT void + zsock_set_rate (void *self, int rate); + +// Get socket option `recovery_ivl`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_recovery_ivl (void *self); + +// Set socket option `recovery_ivl`. +CZMQ_EXPORT void + zsock_set_recovery_ivl (void *self, int recovery_ivl); + +// Get socket option `sndbuf`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_sndbuf (void *self); + +// Set socket option `sndbuf`. +CZMQ_EXPORT void + zsock_set_sndbuf (void *self, int sndbuf); + +// Get socket option `rcvbuf`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_rcvbuf (void *self); + +// Set socket option `rcvbuf`. +CZMQ_EXPORT void + zsock_set_rcvbuf (void *self, int rcvbuf); + +// Get socket option `linger`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_linger (void *self); + +// Set socket option `linger`. +CZMQ_EXPORT void + zsock_set_linger (void *self, int linger); + +// Get socket option `reconnect_ivl`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_reconnect_ivl (void *self); + +// Set socket option `reconnect_ivl`. +CZMQ_EXPORT void + zsock_set_reconnect_ivl (void *self, int reconnect_ivl); + +// Get socket option `reconnect_ivl_max`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_reconnect_ivl_max (void *self); + +// Set socket option `reconnect_ivl_max`. +CZMQ_EXPORT void + zsock_set_reconnect_ivl_max (void *self, int reconnect_ivl_max); + +// Get socket option `backlog`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_backlog (void *self); + +// Set socket option `backlog`. +CZMQ_EXPORT void + zsock_set_backlog (void *self, int backlog); + +// Get socket option `maxmsgsize`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_maxmsgsize (void *self); + +// Set socket option `maxmsgsize`. +CZMQ_EXPORT void + zsock_set_maxmsgsize (void *self, int maxmsgsize); + +// Get socket option `multicast_hops`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_multicast_hops (void *self); + +// Set socket option `multicast_hops`. +CZMQ_EXPORT void + zsock_set_multicast_hops (void *self, int multicast_hops); + +// Get socket option `rcvtimeo`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_rcvtimeo (void *self); + +// Set socket option `rcvtimeo`. +CZMQ_EXPORT void + zsock_set_rcvtimeo (void *self, int rcvtimeo); + +// Get socket option `sndtimeo`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_sndtimeo (void *self); + +// Set socket option `sndtimeo`. +CZMQ_EXPORT void + zsock_set_sndtimeo (void *self, int sndtimeo); + +// Set socket option `xpub_verbose`. +CZMQ_EXPORT void + zsock_set_xpub_verbose (void *self, int xpub_verbose); + +// Get socket option `tcp_keepalive`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_tcp_keepalive (void *self); + +// Set socket option `tcp_keepalive`. +CZMQ_EXPORT void + zsock_set_tcp_keepalive (void *self, int tcp_keepalive); + +// Get socket option `tcp_keepalive_idle`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_tcp_keepalive_idle (void *self); + +// Set socket option `tcp_keepalive_idle`. +CZMQ_EXPORT void + zsock_set_tcp_keepalive_idle (void *self, int tcp_keepalive_idle); + +// Get socket option `tcp_keepalive_cnt`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_tcp_keepalive_cnt (void *self); + +// Set socket option `tcp_keepalive_cnt`. +CZMQ_EXPORT void + zsock_set_tcp_keepalive_cnt (void *self, int tcp_keepalive_cnt); + +// Get socket option `tcp_keepalive_intvl`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_tcp_keepalive_intvl (void *self); + +// Set socket option `tcp_keepalive_intvl`. +CZMQ_EXPORT void + zsock_set_tcp_keepalive_intvl (void *self, int tcp_keepalive_intvl); + +// Get socket option `tcp_accept_filter`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT char * + zsock_tcp_accept_filter (void *self); + +// Set socket option `tcp_accept_filter`. +CZMQ_EXPORT void + zsock_set_tcp_accept_filter (void *self, const char *tcp_accept_filter); + +// Get socket option `rcvmore`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_rcvmore (void *self); + +// Get socket option `fd`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT SOCKET + zsock_fd (void *self); + +// Get socket option `events`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_events (void *self); + +// Get socket option `last_endpoint`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT char * + zsock_last_endpoint (void *self); + +// Self test of this class. +CZMQ_EXPORT void + zsock_test (bool verbose); + +#ifdef CZMQ_BUILD_DRAFT_API +// *** Draft method, for development use, may change without warning *** +// Create a SERVER socket. Default action is bind. +CZMQ_EXPORT zsock_t * + zsock_new_server (const char *endpoint); + +// *** Draft method, for development use, may change without warning *** +// Create a CLIENT socket. Default action is connect. +CZMQ_EXPORT zsock_t * + zsock_new_client (const char *endpoint); + +// *** Draft method, for development use, may change without warning *** +// Create a RADIO socket. Default action is bind. +CZMQ_EXPORT zsock_t * + zsock_new_radio (const char *endpoint); + +// *** Draft method, for development use, may change without warning *** +// Create a DISH socket. Default action is connect. +CZMQ_EXPORT zsock_t * + zsock_new_dish (const char *endpoint); + +// *** Draft method, for development use, may change without warning *** +// Create a GATHER socket. Default action is bind. +CZMQ_EXPORT zsock_t * + zsock_new_gather (const char *endpoint); + +// *** Draft method, for development use, may change without warning *** +// Create a SCATTER socket. Default action is connect. +CZMQ_EXPORT zsock_t * + zsock_new_scatter (const char *endpoint); + +// *** Draft method, for development use, may change without warning *** +// Return socket routing ID if any. This returns 0 if the socket is not +// of type ZMQ_SERVER or if no request was already received on it. +CZMQ_EXPORT uint32_t + zsock_routing_id (zsock_t *self); + +// *** Draft method, for development use, may change without warning *** +// Set routing ID on socket. The socket MUST be of type ZMQ_SERVER. +// This will be used when sending messages on the socket via the zsock API. +CZMQ_EXPORT void + zsock_set_routing_id (zsock_t *self, uint32_t routing_id); + +// *** Draft method, for development use, may change without warning *** +// Join a group for the RADIO-DISH pattern. Call only on ZMQ_DISH. +// Returns 0 if OK, -1 if failed. +CZMQ_EXPORT int + zsock_join (void *self, const char *group); + +// *** Draft method, for development use, may change without warning *** +// Leave a group for the RADIO-DISH pattern. Call only on ZMQ_DISH. +// Returns 0 if OK, -1 if failed. +CZMQ_EXPORT int + zsock_leave (void *self, const char *group); + +// *** Draft method, for development use, may change without warning *** +// Get socket option `heartbeat_ivl`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_heartbeat_ivl (void *self); + +// *** Draft method, for development use, may change without warning *** +// Set socket option `heartbeat_ivl`. +CZMQ_EXPORT void + zsock_set_heartbeat_ivl (void *self, int heartbeat_ivl); + +// *** Draft method, for development use, may change without warning *** +// Get socket option `heartbeat_ttl`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_heartbeat_ttl (void *self); + +// *** Draft method, for development use, may change without warning *** +// Set socket option `heartbeat_ttl`. +CZMQ_EXPORT void + zsock_set_heartbeat_ttl (void *self, int heartbeat_ttl); + +// *** Draft method, for development use, may change without warning *** +// Get socket option `heartbeat_timeout`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_heartbeat_timeout (void *self); + +// *** Draft method, for development use, may change without warning *** +// Set socket option `heartbeat_timeout`. +CZMQ_EXPORT void + zsock_set_heartbeat_timeout (void *self, int heartbeat_timeout); + +// *** Draft method, for development use, may change without warning *** +// Get socket option `use_fd`. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT int + zsock_use_fd (void *self); + +// *** Draft method, for development use, may change without warning *** +// Set socket option `use_fd`. +CZMQ_EXPORT void + zsock_set_use_fd (void *self, int use_fd); + +#endif // CZMQ_BUILD_DRAFT_API +// @ignore +CZMQ_EXPORT int + zsock_bind (zsock_t *self, const char *format, ...) CHECK_PRINTF (2); +CZMQ_EXPORT int + zsock_unbind (zsock_t *self, const char *format, ...) CHECK_PRINTF (2); +CZMQ_EXPORT int + zsock_connect (zsock_t *self, const char *format, ...) CHECK_PRINTF (2); +CZMQ_EXPORT int + zsock_disconnect (zsock_t *self, const char *format, ...) CHECK_PRINTF (2); +// @end + + +// zsock leak detection - not a part of the official interface to zsock. This +// enables CZMQ to report socket leaks intelligently. +#if defined ZSOCK_NOCHECK + // no checking active - use the above interface methods directly. +#else +# define zsock_new(t) zsock_new_checked((t), __FILE__, __LINE__) +# define zsock_new_pub(e) zsock_new_pub_checked((e), __FILE__, __LINE__) +# define zsock_new_sub(e,s) zsock_new_sub_checked((e), (s), __FILE__, __LINE__) +# define zsock_new_req(e) zsock_new_req_checked((e), __FILE__, __LINE__) +# define zsock_new_rep(e) zsock_new_rep_checked((e), __FILE__, __LINE__) +# define zsock_new_dealer(e) zsock_new_dealer_checked((e), __FILE__, __LINE__) +# define zsock_new_router(e) zsock_new_router_checked((e), __FILE__, __LINE__) +# define zsock_new_pull(e) zsock_new_pull_checked((e), __FILE__, __LINE__) +# define zsock_new_push(e) zsock_new_push_checked((e), __FILE__, __LINE__) +# define zsock_new_xpub(e) zsock_new_xpub_checked((e), __FILE__, __LINE__) +# define zsock_new_xsub(e) zsock_new_xsub_checked((e), __FILE__, __LINE__) +# define zsock_new_pair(e) zsock_new_pair_checked((e), __FILE__, __LINE__) +# define zsock_new_stream(e) zsock_new_stream_checked((e), __FILE__, __LINE__) +# define zsock_destroy(t) zsock_destroy_checked((t), __FILE__, __LINE__) +#endif + +CZMQ_EXPORT zsock_t * + zsock_new_checked (int type, const char *filename, size_t line_nbr); + +CZMQ_EXPORT void + zsock_destroy_checked (zsock_t **self_p, const char *filename, size_t line_nbr); + +CZMQ_EXPORT zsock_t * + zsock_new_pub_checked (const char *endpoint, const char *filename, size_t line_nbr); + +CZMQ_EXPORT zsock_t * + zsock_new_sub_checked (const char *endpoint, const char *subscribe, const char *filename, size_t line_nbr); + +CZMQ_EXPORT zsock_t * + zsock_new_req_checked (const char *endpoint, const char *filename, size_t line_nbr); + +CZMQ_EXPORT zsock_t * + zsock_new_rep_checked (const char *endpoint, const char *filename, size_t line_nbr); + +CZMQ_EXPORT zsock_t * + zsock_new_dealer_checked (const char *endpoint, const char *filename, size_t line_nbr); + +CZMQ_EXPORT zsock_t * + zsock_new_router_checked (const char *endpoint, const char *filename, size_t line_nbr); + +CZMQ_EXPORT zsock_t * + zsock_new_push_checked (const char *endpoint, const char *filename, size_t line_nbr); + +CZMQ_EXPORT zsock_t * + zsock_new_pull_checked (const char *endpoint, const char *filename, size_t line_nbr); + +CZMQ_EXPORT zsock_t * + zsock_new_xpub_checked (const char *endpoint, const char *filename, size_t line_nbr); + +CZMQ_EXPORT zsock_t * + zsock_new_xsub_checked (const char *endpoint, const char *filename, size_t line_nbr); + +CZMQ_EXPORT zsock_t * + zsock_new_pair_checked (const char *endpoint, const char *filename, size_t line_nbr); + +CZMQ_EXPORT zsock_t * + zsock_new_stream_checked (const char *endpoint, const char *filename, size_t line_nbr); + +CZMQ_EXPORT zsock_t * + zsock_new_server_checked (const char *endpoint, const char *filename, size_t line_nbr); + +CZMQ_EXPORT zsock_t * + zsock_new_client_checked (const char *endpoint, const char *filename, size_t line_nbr); + +CZMQ_EXPORT zsock_t * + zsock_new_radio_checked (const char *endpoint, const char *filename, size_t line_nbr); + +CZMQ_EXPORT zsock_t * + zsock_new_dish_checked (const char *endpoint, const char *filename, size_t line_nbr); + +CZMQ_EXPORT zsock_t * + zsock_new_gather_checked (const char *endpoint, const char *filename, size_t line_nbr); + +CZMQ_EXPORT zsock_t * + zsock_new_scatter_checked (const char *endpoint, const char *filename, size_t line_nbr); + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/arm/include/zsocket.h b/phonelibs/zmq/arm/include/zsocket.h new file mode 100644 index 00000000000000..a60a0d9db3e7da --- /dev/null +++ b/phonelibs/zmq/arm/include/zsocket.h @@ -0,0 +1,110 @@ +/* ========================================================================= + zsocket - working with 0MQ sockets + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZSOCKET_H_INCLUDED__ +#define __ZSOCKET_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @interface +// This port range is defined by IANA for dynamic or private ports +// We use this when choosing a port for dynamic binding. +#define ZSOCKET_DYNFROM 0xc000 +#define ZSOCKET_DYNTO 0xffff + +// Callback function for zero-copy methods +typedef void (zsocket_free_fn) (void *data, void *arg); + +// Create a new socket within our CZMQ context, replaces zmq_socket. +// Use this to get automatic management of the socket at shutdown. +// Note: SUB sockets do not automatically subscribe to everything; you +// must set filters explicitly. +CZMQ_EXPORT void * + zsocket_new (zctx_t *self, int type); + +// Destroy a socket within our CZMQ context, replaces zmq_close. +CZMQ_EXPORT void + zsocket_destroy (zctx_t *ctx, void *self); + +// Bind a socket to a formatted endpoint. If the port is specified as +// '*', binds to any free port from ZSOCKET_DYNFROM to ZSOCKET_DYNTO +// and returns the actual port number used. Otherwise asserts that the +// bind succeeded with the specified port number. Always returns the +// port number if successful. +CZMQ_EXPORT int + zsocket_bind (void *self, const char *format, ...); + +// Unbind a socket from a formatted endpoint. +// Returns 0 if OK, -1 if the endpoint was invalid or the function +// isn't supported. +CZMQ_EXPORT int + zsocket_unbind (void *self, const char *format, ...); + +// Connect a socket to a formatted endpoint +// Returns 0 if OK, -1 if the endpoint was invalid. +CZMQ_EXPORT int + zsocket_connect (void *self, const char *format, ...); + +// Disconnect a socket from a formatted endpoint +// Returns 0 if OK, -1 if the endpoint was invalid or the function +// isn't supported. +CZMQ_EXPORT int + zsocket_disconnect (void *self, const char *format, ...); + +// Poll for input events on the socket. Returns TRUE if there is input +// ready on the socket, else FALSE. +CZMQ_EXPORT bool + zsocket_poll (void *self, int msecs); + +// Returns socket type as printable constant string +CZMQ_EXPORT const char * + zsocket_type_str (void *self); + +// Send data over a socket as a single message frame. +// Accepts these flags: ZFRAME_MORE and ZFRAME_DONTWAIT. +// Returns -1 on error, 0 on success +CZMQ_EXPORT int + zsocket_sendmem (void *self, const void *data, size_t size, int flags); + +// Send a signal over a socket. A signal is a zero-byte message. +// Signals are used primarily between threads, over pipe sockets. +// Returns -1 if there was an error sending the signal. +CZMQ_EXPORT int + zsocket_signal (void *self); + +// Wait on a signal. Use this to coordinate between threads, over +// pipe pairs. Returns -1 on error, 0 on success. +CZMQ_EXPORT int + zsocket_wait (void *self); + +// Self test of this class +CZMQ_EXPORT void + zsocket_test (bool verbose); +// @end + +// Compiler hints +CZMQ_EXPORT int zsocket_bind (void *self, const char *format, ...) CHECK_PRINTF (2); +CZMQ_EXPORT int zsocket_unbind (void *self, const char *format, ...) CHECK_PRINTF (2); +CZMQ_EXPORT int zsocket_connect (void *self, const char *format, ...) CHECK_PRINTF (2); +CZMQ_EXPORT int zsocket_disconnect (void *self, const char *format, ...) CHECK_PRINTF (2); + +// Emulation of widely-used 2.x socket options +CZMQ_EXPORT void zsocket_set_hwm (void *self, int hwm); + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/arm/include/zsockopt.h b/phonelibs/zmq/arm/include/zsockopt.h new file mode 100644 index 00000000000000..5246986dd0b367 --- /dev/null +++ b/phonelibs/zmq/arm/include/zsockopt.h @@ -0,0 +1,256 @@ +/* ========================================================================= + zsockopt - get/set 0MQ socket options (deprecated) + + **************************************************** + * GENERATED SOURCE CODE, DO NOT EDIT!! * + * TO CHANGE THIS, EDIT src/zsockopt.gsl * + * AND RUN `gsl sockopts` in src/. * + **************************************************** + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZSOCKOPT_H_INCLUDED__ +#define __ZSOCKOPT_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @interface +#if (ZMQ_VERSION_MAJOR == 4) +// Get socket options +CZMQ_EXPORT int zsocket_heartbeat_ivl (void *zocket); +CZMQ_EXPORT int zsocket_heartbeat_ttl (void *zocket); +CZMQ_EXPORT int zsocket_heartbeat_timeout (void *zocket); +CZMQ_EXPORT int zsocket_use_fd (void *zocket); +CZMQ_EXPORT int zsocket_tos (void *zocket); +CZMQ_EXPORT char * zsocket_zap_domain (void *zocket); +CZMQ_EXPORT int zsocket_mechanism (void *zocket); +CZMQ_EXPORT int zsocket_plain_server (void *zocket); +CZMQ_EXPORT char * zsocket_plain_username (void *zocket); +CZMQ_EXPORT char * zsocket_plain_password (void *zocket); +CZMQ_EXPORT int zsocket_curve_server (void *zocket); +CZMQ_EXPORT char * zsocket_curve_publickey (void *zocket); +CZMQ_EXPORT char * zsocket_curve_secretkey (void *zocket); +CZMQ_EXPORT char * zsocket_curve_serverkey (void *zocket); +CZMQ_EXPORT int zsocket_gssapi_server (void *zocket); +CZMQ_EXPORT int zsocket_gssapi_plaintext (void *zocket); +CZMQ_EXPORT char * zsocket_gssapi_principal (void *zocket); +CZMQ_EXPORT char * zsocket_gssapi_service_principal (void *zocket); +CZMQ_EXPORT int zsocket_ipv6 (void *zocket); +CZMQ_EXPORT int zsocket_immediate (void *zocket); +CZMQ_EXPORT int zsocket_ipv4only (void *zocket); +CZMQ_EXPORT int zsocket_type (void *zocket); +CZMQ_EXPORT int zsocket_sndhwm (void *zocket); +CZMQ_EXPORT int zsocket_rcvhwm (void *zocket); +CZMQ_EXPORT int zsocket_affinity (void *zocket); +CZMQ_EXPORT char * zsocket_identity (void *zocket); +CZMQ_EXPORT int zsocket_rate (void *zocket); +CZMQ_EXPORT int zsocket_recovery_ivl (void *zocket); +CZMQ_EXPORT int zsocket_sndbuf (void *zocket); +CZMQ_EXPORT int zsocket_rcvbuf (void *zocket); +CZMQ_EXPORT int zsocket_linger (void *zocket); +CZMQ_EXPORT int zsocket_reconnect_ivl (void *zocket); +CZMQ_EXPORT int zsocket_reconnect_ivl_max (void *zocket); +CZMQ_EXPORT int zsocket_backlog (void *zocket); +CZMQ_EXPORT int zsocket_maxmsgsize (void *zocket); +CZMQ_EXPORT int zsocket_multicast_hops (void *zocket); +CZMQ_EXPORT int zsocket_rcvtimeo (void *zocket); +CZMQ_EXPORT int zsocket_sndtimeo (void *zocket); +CZMQ_EXPORT int zsocket_tcp_keepalive (void *zocket); +CZMQ_EXPORT int zsocket_tcp_keepalive_idle (void *zocket); +CZMQ_EXPORT int zsocket_tcp_keepalive_cnt (void *zocket); +CZMQ_EXPORT int zsocket_tcp_keepalive_intvl (void *zocket); +CZMQ_EXPORT char * zsocket_tcp_accept_filter (void *zocket); +CZMQ_EXPORT int zsocket_rcvmore (void *zocket); +CZMQ_EXPORT SOCKET zsocket_fd (void *zocket); +CZMQ_EXPORT int zsocket_events (void *zocket); +CZMQ_EXPORT char * zsocket_last_endpoint (void *zocket); + +// Set socket options +CZMQ_EXPORT void zsocket_set_heartbeat_ivl (void *zocket, int heartbeat_ivl); +CZMQ_EXPORT void zsocket_set_heartbeat_ttl (void *zocket, int heartbeat_ttl); +CZMQ_EXPORT void zsocket_set_heartbeat_timeout (void *zocket, int heartbeat_timeout); +CZMQ_EXPORT void zsocket_set_use_fd (void *zocket, int use_fd); +CZMQ_EXPORT void zsocket_set_tos (void *zocket, int tos); +CZMQ_EXPORT void zsocket_set_router_handover (void *zocket, int router_handover); +CZMQ_EXPORT void zsocket_set_router_mandatory (void *zocket, int router_mandatory); +CZMQ_EXPORT void zsocket_set_probe_router (void *zocket, int probe_router); +CZMQ_EXPORT void zsocket_set_req_relaxed (void *zocket, int req_relaxed); +CZMQ_EXPORT void zsocket_set_req_correlate (void *zocket, int req_correlate); +CZMQ_EXPORT void zsocket_set_conflate (void *zocket, int conflate); +CZMQ_EXPORT void zsocket_set_zap_domain (void *zocket, const char * zap_domain); +CZMQ_EXPORT void zsocket_set_plain_server (void *zocket, int plain_server); +CZMQ_EXPORT void zsocket_set_plain_username (void *zocket, const char * plain_username); +CZMQ_EXPORT void zsocket_set_plain_password (void *zocket, const char * plain_password); +CZMQ_EXPORT void zsocket_set_curve_server (void *zocket, int curve_server); +CZMQ_EXPORT void zsocket_set_curve_publickey (void *zocket, const char * curve_publickey); +CZMQ_EXPORT void zsocket_set_curve_publickey_bin (void *zocket, const byte *curve_publickey); +CZMQ_EXPORT void zsocket_set_curve_secretkey (void *zocket, const char * curve_secretkey); +CZMQ_EXPORT void zsocket_set_curve_secretkey_bin (void *zocket, const byte *curve_secretkey); +CZMQ_EXPORT void zsocket_set_curve_serverkey (void *zocket, const char * curve_serverkey); +CZMQ_EXPORT void zsocket_set_curve_serverkey_bin (void *zocket, const byte *curve_serverkey); +CZMQ_EXPORT void zsocket_set_gssapi_server (void *zocket, int gssapi_server); +CZMQ_EXPORT void zsocket_set_gssapi_plaintext (void *zocket, int gssapi_plaintext); +CZMQ_EXPORT void zsocket_set_gssapi_principal (void *zocket, const char * gssapi_principal); +CZMQ_EXPORT void zsocket_set_gssapi_service_principal (void *zocket, const char * gssapi_service_principal); +CZMQ_EXPORT void zsocket_set_ipv6 (void *zocket, int ipv6); +CZMQ_EXPORT void zsocket_set_immediate (void *zocket, int immediate); +CZMQ_EXPORT void zsocket_set_router_raw (void *zocket, int router_raw); +CZMQ_EXPORT void zsocket_set_ipv4only (void *zocket, int ipv4only); +CZMQ_EXPORT void zsocket_set_delay_attach_on_connect (void *zocket, int delay_attach_on_connect); +CZMQ_EXPORT void zsocket_set_sndhwm (void *zocket, int sndhwm); +CZMQ_EXPORT void zsocket_set_rcvhwm (void *zocket, int rcvhwm); +CZMQ_EXPORT void zsocket_set_affinity (void *zocket, int affinity); +CZMQ_EXPORT void zsocket_set_subscribe (void *zocket, const char * subscribe); +CZMQ_EXPORT void zsocket_set_unsubscribe (void *zocket, const char * unsubscribe); +CZMQ_EXPORT void zsocket_set_identity (void *zocket, const char * identity); +CZMQ_EXPORT void zsocket_set_rate (void *zocket, int rate); +CZMQ_EXPORT void zsocket_set_recovery_ivl (void *zocket, int recovery_ivl); +CZMQ_EXPORT void zsocket_set_sndbuf (void *zocket, int sndbuf); +CZMQ_EXPORT void zsocket_set_rcvbuf (void *zocket, int rcvbuf); +CZMQ_EXPORT void zsocket_set_linger (void *zocket, int linger); +CZMQ_EXPORT void zsocket_set_reconnect_ivl (void *zocket, int reconnect_ivl); +CZMQ_EXPORT void zsocket_set_reconnect_ivl_max (void *zocket, int reconnect_ivl_max); +CZMQ_EXPORT void zsocket_set_backlog (void *zocket, int backlog); +CZMQ_EXPORT void zsocket_set_maxmsgsize (void *zocket, int maxmsgsize); +CZMQ_EXPORT void zsocket_set_multicast_hops (void *zocket, int multicast_hops); +CZMQ_EXPORT void zsocket_set_rcvtimeo (void *zocket, int rcvtimeo); +CZMQ_EXPORT void zsocket_set_sndtimeo (void *zocket, int sndtimeo); +CZMQ_EXPORT void zsocket_set_xpub_verbose (void *zocket, int xpub_verbose); +CZMQ_EXPORT void zsocket_set_tcp_keepalive (void *zocket, int tcp_keepalive); +CZMQ_EXPORT void zsocket_set_tcp_keepalive_idle (void *zocket, int tcp_keepalive_idle); +CZMQ_EXPORT void zsocket_set_tcp_keepalive_cnt (void *zocket, int tcp_keepalive_cnt); +CZMQ_EXPORT void zsocket_set_tcp_keepalive_intvl (void *zocket, int tcp_keepalive_intvl); +CZMQ_EXPORT void zsocket_set_tcp_accept_filter (void *zocket, const char * tcp_accept_filter); +#endif + +#if (ZMQ_VERSION_MAJOR == 3) +// Get socket options +CZMQ_EXPORT int zsocket_ipv4only (void *zocket); +CZMQ_EXPORT int zsocket_type (void *zocket); +CZMQ_EXPORT int zsocket_sndhwm (void *zocket); +CZMQ_EXPORT int zsocket_rcvhwm (void *zocket); +CZMQ_EXPORT int zsocket_affinity (void *zocket); +CZMQ_EXPORT char * zsocket_identity (void *zocket); +CZMQ_EXPORT int zsocket_rate (void *zocket); +CZMQ_EXPORT int zsocket_recovery_ivl (void *zocket); +CZMQ_EXPORT int zsocket_sndbuf (void *zocket); +CZMQ_EXPORT int zsocket_rcvbuf (void *zocket); +CZMQ_EXPORT int zsocket_linger (void *zocket); +CZMQ_EXPORT int zsocket_reconnect_ivl (void *zocket); +CZMQ_EXPORT int zsocket_reconnect_ivl_max (void *zocket); +CZMQ_EXPORT int zsocket_backlog (void *zocket); +CZMQ_EXPORT int zsocket_maxmsgsize (void *zocket); +CZMQ_EXPORT int zsocket_multicast_hops (void *zocket); +CZMQ_EXPORT int zsocket_rcvtimeo (void *zocket); +CZMQ_EXPORT int zsocket_sndtimeo (void *zocket); +CZMQ_EXPORT int zsocket_tcp_keepalive (void *zocket); +CZMQ_EXPORT int zsocket_tcp_keepalive_idle (void *zocket); +CZMQ_EXPORT int zsocket_tcp_keepalive_cnt (void *zocket); +CZMQ_EXPORT int zsocket_tcp_keepalive_intvl (void *zocket); +CZMQ_EXPORT char * zsocket_tcp_accept_filter (void *zocket); +CZMQ_EXPORT int zsocket_rcvmore (void *zocket); +CZMQ_EXPORT SOCKET zsocket_fd (void *zocket); +CZMQ_EXPORT int zsocket_events (void *zocket); +CZMQ_EXPORT char * zsocket_last_endpoint (void *zocket); + +// Set socket options +CZMQ_EXPORT void zsocket_set_router_raw (void *zocket, int router_raw); +CZMQ_EXPORT void zsocket_set_ipv4only (void *zocket, int ipv4only); +CZMQ_EXPORT void zsocket_set_delay_attach_on_connect (void *zocket, int delay_attach_on_connect); +CZMQ_EXPORT void zsocket_set_sndhwm (void *zocket, int sndhwm); +CZMQ_EXPORT void zsocket_set_rcvhwm (void *zocket, int rcvhwm); +CZMQ_EXPORT void zsocket_set_affinity (void *zocket, int affinity); +CZMQ_EXPORT void zsocket_set_subscribe (void *zocket, const char * subscribe); +CZMQ_EXPORT void zsocket_set_unsubscribe (void *zocket, const char * unsubscribe); +CZMQ_EXPORT void zsocket_set_identity (void *zocket, const char * identity); +CZMQ_EXPORT void zsocket_set_rate (void *zocket, int rate); +CZMQ_EXPORT void zsocket_set_recovery_ivl (void *zocket, int recovery_ivl); +CZMQ_EXPORT void zsocket_set_sndbuf (void *zocket, int sndbuf); +CZMQ_EXPORT void zsocket_set_rcvbuf (void *zocket, int rcvbuf); +CZMQ_EXPORT void zsocket_set_linger (void *zocket, int linger); +CZMQ_EXPORT void zsocket_set_reconnect_ivl (void *zocket, int reconnect_ivl); +CZMQ_EXPORT void zsocket_set_reconnect_ivl_max (void *zocket, int reconnect_ivl_max); +CZMQ_EXPORT void zsocket_set_backlog (void *zocket, int backlog); +CZMQ_EXPORT void zsocket_set_maxmsgsize (void *zocket, int maxmsgsize); +CZMQ_EXPORT void zsocket_set_multicast_hops (void *zocket, int multicast_hops); +CZMQ_EXPORT void zsocket_set_rcvtimeo (void *zocket, int rcvtimeo); +CZMQ_EXPORT void zsocket_set_sndtimeo (void *zocket, int sndtimeo); +CZMQ_EXPORT void zsocket_set_xpub_verbose (void *zocket, int xpub_verbose); +CZMQ_EXPORT void zsocket_set_tcp_keepalive (void *zocket, int tcp_keepalive); +CZMQ_EXPORT void zsocket_set_tcp_keepalive_idle (void *zocket, int tcp_keepalive_idle); +CZMQ_EXPORT void zsocket_set_tcp_keepalive_cnt (void *zocket, int tcp_keepalive_cnt); +CZMQ_EXPORT void zsocket_set_tcp_keepalive_intvl (void *zocket, int tcp_keepalive_intvl); +CZMQ_EXPORT void zsocket_set_tcp_accept_filter (void *zocket, const char * tcp_accept_filter); +#endif + +#if (ZMQ_VERSION_MAJOR == 2) +// Get socket options +CZMQ_EXPORT int zsocket_hwm (void *zocket); +CZMQ_EXPORT int zsocket_swap (void *zocket); +CZMQ_EXPORT int zsocket_affinity (void *zocket); +CZMQ_EXPORT char * zsocket_identity (void *zocket); +CZMQ_EXPORT int zsocket_rate (void *zocket); +CZMQ_EXPORT int zsocket_recovery_ivl (void *zocket); +CZMQ_EXPORT int zsocket_recovery_ivl_msec (void *zocket); +CZMQ_EXPORT int zsocket_mcast_loop (void *zocket); +# if (ZMQ_VERSION_MINOR == 2) +CZMQ_EXPORT int zsocket_rcvtimeo (void *zocket); +# endif +# if (ZMQ_VERSION_MINOR == 2) +CZMQ_EXPORT int zsocket_sndtimeo (void *zocket); +# endif +CZMQ_EXPORT int zsocket_sndbuf (void *zocket); +CZMQ_EXPORT int zsocket_rcvbuf (void *zocket); +CZMQ_EXPORT int zsocket_linger (void *zocket); +CZMQ_EXPORT int zsocket_reconnect_ivl (void *zocket); +CZMQ_EXPORT int zsocket_reconnect_ivl_max (void *zocket); +CZMQ_EXPORT int zsocket_backlog (void *zocket); +CZMQ_EXPORT int zsocket_type (void *zocket); +CZMQ_EXPORT int zsocket_rcvmore (void *zocket); +CZMQ_EXPORT SOCKET zsocket_fd (void *zocket); +CZMQ_EXPORT int zsocket_events (void *zocket); + +// Set socket options +CZMQ_EXPORT void zsocket_set_hwm (void *zocket, int hwm); +CZMQ_EXPORT void zsocket_set_swap (void *zocket, int swap); +CZMQ_EXPORT void zsocket_set_affinity (void *zocket, int affinity); +CZMQ_EXPORT void zsocket_set_identity (void *zocket, const char * identity); +CZMQ_EXPORT void zsocket_set_rate (void *zocket, int rate); +CZMQ_EXPORT void zsocket_set_recovery_ivl (void *zocket, int recovery_ivl); +CZMQ_EXPORT void zsocket_set_recovery_ivl_msec (void *zocket, int recovery_ivl_msec); +CZMQ_EXPORT void zsocket_set_mcast_loop (void *zocket, int mcast_loop); +# if (ZMQ_VERSION_MINOR == 2) +CZMQ_EXPORT void zsocket_set_rcvtimeo (void *zocket, int rcvtimeo); +# endif +# if (ZMQ_VERSION_MINOR == 2) +CZMQ_EXPORT void zsocket_set_sndtimeo (void *zocket, int sndtimeo); +# endif +CZMQ_EXPORT void zsocket_set_sndbuf (void *zocket, int sndbuf); +CZMQ_EXPORT void zsocket_set_rcvbuf (void *zocket, int rcvbuf); +CZMQ_EXPORT void zsocket_set_linger (void *zocket, int linger); +CZMQ_EXPORT void zsocket_set_reconnect_ivl (void *zocket, int reconnect_ivl); +CZMQ_EXPORT void zsocket_set_reconnect_ivl_max (void *zocket, int reconnect_ivl_max); +CZMQ_EXPORT void zsocket_set_backlog (void *zocket, int backlog); +CZMQ_EXPORT void zsocket_set_subscribe (void *zocket, const char * subscribe); +CZMQ_EXPORT void zsocket_set_unsubscribe (void *zocket, const char * unsubscribe); +#endif + +// Self test of this class +CZMQ_EXPORT void zsockopt_test (bool verbose); +// @end + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/arm/include/zstr.h b/phonelibs/zmq/arm/include/zstr.h new file mode 100644 index 00000000000000..3d3f1a862ad7e5 --- /dev/null +++ b/phonelibs/zmq/arm/include/zstr.h @@ -0,0 +1,115 @@ +/* ========================================================================= + zstr - sending and receiving strings + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZSTR_H_INCLUDED__ +#define __ZSTR_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/zstr.api" to make changes. +// @interface +// This is a stable class, and may not change except for emergencies. It +// is provided in stable builds. +// This class has draft methods, which may change over time. They are not +// in stable releases, by default. Use --enable-drafts to enable. +// Receive C string from socket. Caller must free returned string using +// zstr_free(). Returns NULL if the context is being terminated or the +// process was interrupted. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT char * + zstr_recv (void *source); + +// Receive a series of strings (until NULL) from multipart data. +// Each string is allocated and filled with string data; if there +// are not enough frames, unallocated strings are set to NULL. +// Returns -1 if the message could not be read, else returns the +// number of strings filled, zero or more. Free each returned string +// using zstr_free(). If not enough strings are provided, remaining +// multipart frames in the message are dropped. +CZMQ_EXPORT int + zstr_recvx (void *source, char **string_p, ...); + +// Send a C string to a socket, as a frame. The string is sent without +// trailing null byte; to read this you can use zstr_recv, or a similar +// method that adds a null terminator on the received string. String +// may be NULL, which is sent as "". +CZMQ_EXPORT int + zstr_send (void *dest, const char *string); + +// Send a C string to a socket, as zstr_send(), with a MORE flag, so that +// you can send further strings in the same multi-part message. +CZMQ_EXPORT int + zstr_sendm (void *dest, const char *string); + +// Send a formatted string to a socket. Note that you should NOT use +// user-supplied strings in the format (they may contain '%' which +// will create security holes). +CZMQ_EXPORT int + zstr_sendf (void *dest, const char *format, ...); + +// Send a formatted string to a socket, as for zstr_sendf(), with a +// MORE flag, so that you can send further strings in the same multi-part +// message. +CZMQ_EXPORT int + zstr_sendfm (void *dest, const char *format, ...); + +// Send a series of strings (until NULL) as multipart data +// Returns 0 if the strings could be sent OK, or -1 on error. +CZMQ_EXPORT int + zstr_sendx (void *dest, const char *string, ...); + +// Free a provided string, and nullify the parent pointer. Safe to call on +// a null pointer. +CZMQ_EXPORT void + zstr_free (char **string_p); + +// Self test of this class. +CZMQ_EXPORT void + zstr_test (bool verbose); + +#ifdef CZMQ_BUILD_DRAFT_API +// *** Draft method, for development use, may change without warning *** +// Accepts a void pointer and returns a fresh character string. If source +// is null, returns an empty string. +// Caller owns return value and must destroy it when done. +CZMQ_EXPORT char * + zstr_str (void *source); + +#endif // CZMQ_BUILD_DRAFT_API +// @ignore +CZMQ_EXPORT int + zstr_sendf (void *dest, const char *format, ...) CHECK_PRINTF (2); +CZMQ_EXPORT int + zstr_sendfm (void *dest, const char *format, ...) CHECK_PRINTF (2); +// @end + + +// DEPRECATED as poor style -- callers should use zloop or zpoller +// Receive C string from socket, if socket had input ready. Caller must +// free returned string using zstr_free. Returns NULL if there was no input +// waiting, or if the context was terminated. Use zctx_interrupted to exit +// any loop that relies on this method. +CZMQ_EXPORT char * + zstr_recv_nowait (void *source); + +// Compiler hints +CZMQ_EXPORT int zstr_sendf (void *dest, const char *format, ...) CHECK_PRINTF (2); + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/arm/include/zsys.h b/phonelibs/zmq/arm/include/zsys.h new file mode 100644 index 00000000000000..97f88a9555b8e0 --- /dev/null +++ b/phonelibs/zmq/arm/include/zsys.h @@ -0,0 +1,386 @@ +/* ========================================================================= + zsys - system-level methods + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZSYS_H_INCLUDED__ +#define __ZSYS_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @interface +#define UDP_FRAME_MAX 255 // Max size of UDP frame + +// Callback for interrupt signal handler +typedef void (zsys_handler_fn) (int signal_value); + +// Initialize CZMQ zsys layer; this happens automatically when you create +// a socket or an actor; however this call lets you force initialization +// earlier, so e.g. logging is properly set-up before you start working. +// Not threadsafe, so call only from main thread. Safe to call multiple +// times. Returns global CZMQ context. +CZMQ_EXPORT void * + zsys_init (void); + +// Optionally shut down the CZMQ zsys layer; this normally happens automatically +// when the process exits; however this call lets you force a shutdown +// earlier, avoiding any potential problems with atexit() ordering, especially +// with Windows dlls. +CZMQ_EXPORT void + zsys_shutdown (void); + +// Get a new ZMQ socket, automagically creating a ZMQ context if this is +// the first time. Caller is responsible for destroying the ZMQ socket +// before process exits, to avoid a ZMQ deadlock. Note: you should not use +// this method in CZMQ apps, use zsock_new() instead. +// *** This is for CZMQ internal use only and may change arbitrarily *** +CZMQ_EXPORT void * + zsys_socket (int type, const char *filename, size_t line_nbr); + +// Destroy/close a ZMQ socket. You should call this for every socket you +// create using zsys_socket(). +// *** This is for CZMQ internal use only and may change arbitrarily *** +CZMQ_EXPORT int + zsys_close (void *handle, const char *filename, size_t line_nbr); + +// Return ZMQ socket name for socket type +// *** This is for CZMQ internal use only and may change arbitrarily *** +CZMQ_EXPORT char * + zsys_sockname (int socktype); + +// Create a pipe, which consists of two PAIR sockets connected over inproc. +// The pipe is configured to use the zsys_pipehwm setting. Returns the +// frontend socket successful, NULL if failed. +CZMQ_EXPORT zsock_t * + zsys_create_pipe (zsock_t **backend_p); + +// Set interrupt handler; this saves the default handlers so that a +// zsys_handler_reset () can restore them. If you call this multiple times +// then the last handler will take affect. If handler_fn is NULL, disables +// default SIGINT/SIGTERM handling in CZMQ. +CZMQ_EXPORT void + zsys_handler_set (zsys_handler_fn *handler_fn); + +// Reset interrupt handler, call this at exit if needed +CZMQ_EXPORT void + zsys_handler_reset (void); + +// Set default interrupt handler, so Ctrl-C or SIGTERM will set +// zsys_interrupted. Idempotent; safe to call multiple times. +// *** This is for CZMQ internal use only and may change arbitrarily *** +CZMQ_EXPORT void + zsys_catch_interrupts (void); + +// Return 1 if file exists, else zero +CZMQ_EXPORT bool + zsys_file_exists (const char *filename); + +// Return size of file, or -1 if not found +CZMQ_EXPORT ssize_t + zsys_file_size (const char *filename); + +// Return file modification time. Returns 0 if the file does not exist. +CZMQ_EXPORT time_t + zsys_file_modified (const char *filename); + +// Return file mode; provides at least support for the POSIX S_ISREG(m) +// and S_ISDIR(m) macros and the S_IRUSR and S_IWUSR bits, on all boxes. +// Returns a mode_t cast to int, or -1 in case of error. +CZMQ_EXPORT int + zsys_file_mode (const char *filename); + +// Delete file. Does not complain if the file is absent +CZMQ_EXPORT int + zsys_file_delete (const char *filename); + +// Check if file is 'stable' +CZMQ_EXPORT bool + zsys_file_stable (const char *filename); + +// Create a file path if it doesn't exist. The file path is treated as a +// printf format. +CZMQ_EXPORT int + zsys_dir_create (const char *pathname, ...); + +// Remove a file path if empty; the pathname is treated as printf format. +CZMQ_EXPORT int + zsys_dir_delete (const char *pathname, ...); + +// Move to a specified working directory. Returns 0 if OK, -1 if this failed. +CZMQ_EXPORT int + zsys_dir_change (const char *pathname); + +// Set private file creation mode; all files created from here will be +// readable/writable by the owner only. +CZMQ_EXPORT void + zsys_file_mode_private (void); + +// Reset default file creation mode; all files created from here will use +// process file mode defaults. +CZMQ_EXPORT void + zsys_file_mode_default (void); + +// Return the CZMQ version for run-time API detection; returns version +// number into provided fields, providing reference isn't null in each case. +CZMQ_EXPORT void + zsys_version (int *major, int *minor, int *patch); + +// Format a string using printf formatting, returning a freshly allocated +// buffer. If there was insufficient memory, returns NULL. Free the returned +// string using zstr_free(). +CZMQ_EXPORT char * + zsys_sprintf (const char *format, ...); + +// Format a string with a va_list argument, returning a freshly allocated +// buffer. If there was insufficient memory, returns NULL. Free the returned +// string using zstr_free(). +CZMQ_EXPORT char * + zsys_vprintf (const char *format, va_list argptr); + +// Create UDP beacon socket; if the routable option is true, uses +// multicast (not yet implemented), else uses broadcast. This method +// and related ones might _eventually_ be moved to a zudp class. +// *** This is for CZMQ internal use only and may change arbitrarily *** +CZMQ_EXPORT SOCKET + zsys_udp_new (bool routable); + +// Close a UDP socket +// *** This is for CZMQ internal use only and may change arbitrarily *** +CZMQ_EXPORT int + zsys_udp_close (SOCKET handle); + +// Send zframe to UDP socket, return -1 if sending failed due to +// interface having disappeared (happens easily with WiFi) +// *** This is for CZMQ internal use only and may change arbitrarily *** +CZMQ_EXPORT int + zsys_udp_send (SOCKET udpsock, zframe_t *frame, inaddr_t *address, int addrlen); + +// Receive zframe from UDP socket, and set address of peer that sent it +// The peername must be a char [INET_ADDRSTRLEN] array. +// *** This is for CZMQ internal use only and may change arbitrarily *** +CZMQ_EXPORT zframe_t * + zsys_udp_recv (SOCKET udpsock, char *peername, int peerlen); + +// Handle an I/O error on some socket operation; will report and die on +// fatal errors, and continue silently on "try again" errors. +// *** This is for CZMQ internal use only and may change arbitrarily *** +CZMQ_EXPORT void + zsys_socket_error (const char *reason); + +// Return current host name, for use in public tcp:// endpoints. Caller gets +// a freshly allocated string, should free it using zstr_free(). If the host +// name is not resolvable, returns NULL. +CZMQ_EXPORT char * + zsys_hostname (void); + +// Move the current process into the background. The precise effect depends +// on the operating system. On POSIX boxes, moves to a specified working +// directory (if specified), closes all file handles, reopens stdin, stdout, +// and stderr to the null device, and sets the process to ignore SIGHUP. On +// Windows, does nothing. Returns 0 if OK, -1 if there was an error. +CZMQ_EXPORT int + zsys_daemonize (const char *workdir); + +// Drop the process ID into the lockfile, with exclusive lock, and switch +// the process to the specified group and/or user. Any of the arguments +// may be null, indicating a no-op. Returns 0 on success, -1 on failure. +// Note if you combine this with zsys_daemonize, run after, not before +// that method, or the lockfile will hold the wrong process ID. +CZMQ_EXPORT int + zsys_run_as (const char *lockfile, const char *group, const char *user); + +// Returns true if the underlying libzmq supports CURVE security. +// Uses a heuristic probe according to the version of libzmq being used. +CZMQ_EXPORT bool + zsys_has_curve (void); + +// Configure the number of I/O threads that ZeroMQ will use. A good +// rule of thumb is one thread per gigabit of traffic in or out. The +// default is 1, sufficient for most applications. If the environment +// variable ZSYS_IO_THREADS is defined, that provides the default. +// Note that this method is valid only before any socket is created. +CZMQ_EXPORT void + zsys_set_io_threads (size_t io_threads); + +// Configure the number of sockets that ZeroMQ will allow. The default +// is 1024. The actual limit depends on the system, and you can query it +// by using zsys_socket_limit (). A value of zero means "maximum". +// Note that this method is valid only before any socket is created. +CZMQ_EXPORT void + zsys_set_max_sockets (size_t max_sockets); + +// Return maximum number of ZeroMQ sockets that the system will support. +CZMQ_EXPORT size_t + zsys_socket_limit (void); + +// Configure the default linger timeout in msecs for new zsock instances. +// You can also set this separately on each zsock_t instance. The default +// linger time is zero, i.e. any pending messages will be dropped. If the +// environment variable ZSYS_LINGER is defined, that provides the default. +// Note that process exit will typically be delayed by the linger time. +CZMQ_EXPORT void + zsys_set_linger (size_t linger); + +// Configure the default outgoing pipe limit (HWM) for new zsock instances. +// You can also set this separately on each zsock_t instance. The default +// HWM is 1,000, on all versions of ZeroMQ. If the environment variable +// ZSYS_SNDHWM is defined, that provides the default. Note that a value of +// zero means no limit, i.e. infinite memory consumption. +CZMQ_EXPORT void + zsys_set_sndhwm (size_t sndhwm); + +// Configure the default incoming pipe limit (HWM) for new zsock instances. +// You can also set this separately on each zsock_t instance. The default +// HWM is 1,000, on all versions of ZeroMQ. If the environment variable +// ZSYS_RCVHWM is defined, that provides the default. Note that a value of +// zero means no limit, i.e. infinite memory consumption. +CZMQ_EXPORT void + zsys_set_rcvhwm (size_t rcvhwm); + +// Configure the default HWM for zactor internal pipes; this is set on both +// ends of the pipe, for outgoing messages only (sndhwm). The default HWM is +// 1,000, on all versions of ZeroMQ. If the environment var ZSYS_ACTORHWM is +// defined, that provides the default. Note that a value of zero means no +// limit, i.e. infinite memory consumption. +CZMQ_EXPORT void + zsys_set_pipehwm (size_t pipehwm); + +// Return the HWM for zactor internal pipes. +CZMQ_EXPORT size_t + zsys_pipehwm (void); + +// Configure use of IPv6 for new zsock instances. By default sockets accept +// and make only IPv4 connections. When you enable IPv6, sockets will accept +// and connect to both IPv4 and IPv6 peers. You can override the setting on +// each zsock_t instance. The default is IPv4 only (ipv6 set to 0). If the +// environment variable ZSYS_IPV6 is defined (as 1 or 0), this provides the +// default. Note: has no effect on ZMQ v2. +CZMQ_EXPORT void + zsys_set_ipv6 (int ipv6); + +// Return use of IPv6 for zsock instances. +CZMQ_EXPORT int + zsys_ipv6 (void); + +// Set network interface name to use for broadcasts, particularly zbeacon. +// This lets the interface be configured for test environments where required. +// For example, on Mac OS X, zbeacon cannot bind to 255.255.255.255 which is +// the default when there is no specified interface. If the environment +// variable ZSYS_INTERFACE is set, use that as the default interface name. +// Setting the interface to "*" means "use all available interfaces". +CZMQ_EXPORT void + zsys_set_interface (const char *value); + +// Return network interface to use for broadcasts, or "" if none was set. +CZMQ_EXPORT const char * + zsys_interface (void); + +// Set IPv6 address to use zbeacon socket, particularly for receiving zbeacon. +// This needs to be set IPv6 is enabled as IPv6 can have multiple addresses +// on a given interface. If the environment variable ZSYS_IPV6_ADDRESS is set, +// use that as the default IPv6 address. +CZMQ_EXPORT void + zsys_set_ipv6_address (const char *value); + +// Return IPv6 address to use for zbeacon reception, or "" if none was set. +CZMQ_EXPORT const char * + zsys_ipv6_address (void); + +// Set IPv6 milticast address to use for sending zbeacon messages. This needs +// to be set if IPv6 is enabled. If the environment variable +// ZSYS_IPV6_MCAST_ADDRESS is set, use that as the default IPv6 multicast +// address. +CZMQ_EXPORT void + zsys_set_ipv6_mcast_address (const char *value); + +// Return IPv6 multicast address to use for sending zbeacon, or "" if none was +// set. +CZMQ_EXPORT const char * + zsys_ipv6_mcast_address (void); + +// Configure the automatic use of pre-allocated FDs when creating new sockets. +// If 0 (default), nothing will happen. Else, when a new socket is bound, the +// system API will be used to check if an existing pre-allocated FD with a +// matching port (if TCP) or path (if IPC) exists, and if it does it will be +// set via the ZMQ_USE_FD socket option so that the library will use it +// instead of creating a new socket. +CZMQ_EXPORT void + zsys_set_auto_use_fd (int auto_use_fd); + +// Return use of automatic pre-allocated FDs for zsock instances. +CZMQ_EXPORT int + zsys_auto_use_fd (void); + +// Set log identity, which is a string that prefixes all log messages sent +// by this process. The log identity defaults to the environment variable +// ZSYS_LOGIDENT, if that is set. +CZMQ_EXPORT void + zsys_set_logident (const char *value); + +// Set stream to receive log traffic. By default, log traffic is sent to +// stdout. If you set the stream to NULL, no stream will receive the log +// traffic (it may still be sent to the system facility). +CZMQ_EXPORT void + zsys_set_logstream (FILE *stream); + +// Sends log output to a PUB socket bound to the specified endpoint. To +// collect such log output, create a SUB socket, subscribe to the traffic +// you care about, and connect to the endpoint. Log traffic is sent as a +// single string frame, in the same format as when sent to stdout. The +// log system supports a single sender; multiple calls to this method will +// bind the same sender to multiple endpoints. To disable the sender, call +// this method with a null argument. +CZMQ_EXPORT void + zsys_set_logsender (const char *endpoint); + +// Enable or disable logging to the system facility (syslog on POSIX boxes, +// event log on Windows). By default this is disabled. +CZMQ_EXPORT void + zsys_set_logsystem (bool logsystem); + +// Log error condition - highest priority +CZMQ_EXPORT void + zsys_error (const char *format, ...); + +// Log warning condition - high priority +CZMQ_EXPORT void + zsys_warning (const char *format, ...); + +// Log normal, but significant, condition - normal priority +CZMQ_EXPORT void + zsys_notice (const char *format, ...); + +// Log informational message - low priority +CZMQ_EXPORT void + zsys_info (const char *format, ...); + +// Log debug-level message - lowest priority +CZMQ_EXPORT void + zsys_debug (const char *format, ...); + +// Self test of this class +CZMQ_EXPORT void + zsys_test (bool verbose); + +// Global signal indicator, TRUE when user presses Ctrl-C or the process +// gets a SIGTERM signal. +CZMQ_EXPORT extern volatile int zsys_interrupted; +// Deprecated name for this variable +CZMQ_EXPORT extern volatile int zctx_interrupted; +// @end + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/arm/include/zthread.h b/phonelibs/zmq/arm/include/zthread.h new file mode 100644 index 00000000000000..fc0602dd9ff483 --- /dev/null +++ b/phonelibs/zmq/arm/include/zthread.h @@ -0,0 +1,50 @@ +/* ========================================================================= + zthread - working with system threads (deprecated) + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZTHREAD_H_INCLUDED__ +#define __ZTHREAD_H_INCLUDED__ + +#ifdef __cplusplus +extern "C" { +#endif + +// @interface +// Detached threads follow POSIX pthreads API +typedef void *(zthread_detached_fn) (void *args); + +// Attached threads get context and pipe from parent +typedef void (zthread_attached_fn) (void *args, zctx_t *ctx, void *pipe); + +// Create a detached thread. A detached thread operates autonomously +// and is used to simulate a separate process. It gets no ctx, and no +// pipe. +CZMQ_EXPORT int + zthread_new (zthread_detached_fn *thread_fn, void *args); + +// Create an attached thread. An attached thread gets a ctx and a PAIR +// pipe back to its parent. It must monitor its pipe, and exit if the +// pipe becomes unreadable. Do not destroy the ctx, the thread does this +// automatically when it ends. +CZMQ_EXPORT void * + zthread_fork (zctx_t *ctx, zthread_attached_fn *thread_fn, void *args); + +// Self test of this class +CZMQ_EXPORT void + zthread_test (bool verbose); +// @end + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/arm/include/ztimerset.h b/phonelibs/zmq/arm/include/ztimerset.h new file mode 100644 index 00000000000000..29633fafdbdd30 --- /dev/null +++ b/phonelibs/zmq/arm/include/ztimerset.h @@ -0,0 +1,90 @@ +/* ========================================================================= + ztimerset - timer set + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef ZTIMERSET_H_INCLUDED +#define ZTIMERSET_H_INCLUDED + +#ifdef __cplusplus +extern "C" { +#endif + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/ztimerset.api" to make changes. +// @interface +// This is a draft class, and may change without notice. It is disabled in +// stable builds by default. If you use this in applications, please ask +// for it to be pushed to stable state. Use --enable-drafts to enable. +#ifdef CZMQ_BUILD_DRAFT_API +// Callback function for timer event. +typedef void (ztimerset_fn) ( + int timer_id, void *arg); + +// *** Draft method, for development use, may change without warning *** +// Create new timer set. +CZMQ_EXPORT ztimerset_t * + ztimerset_new (void); + +// *** Draft method, for development use, may change without warning *** +// Destroy a timer set +CZMQ_EXPORT void + ztimerset_destroy (ztimerset_t **self_p); + +// *** Draft method, for development use, may change without warning *** +// Add a timer to the set. Returns timer id if OK, -1 on failure. +CZMQ_EXPORT int + ztimerset_add (ztimerset_t *self, size_t interval, ztimerset_fn handler, void *arg); + +// *** Draft method, for development use, may change without warning *** +// Cancel a timer. Returns 0 if OK, -1 on failure. +CZMQ_EXPORT int + ztimerset_cancel (ztimerset_t *self, int timer_id); + +// *** Draft method, for development use, may change without warning *** +// Set timer interval. Returns 0 if OK, -1 on failure. +// This method is slow, canceling the timer and adding a new one yield better performance. +CZMQ_EXPORT int + ztimerset_set_interval (ztimerset_t *self, int timer_id, size_t interval); + +// *** Draft method, for development use, may change without warning *** +// Reset timer to start interval counting from current time. Returns 0 if OK, -1 on failure. +// This method is slow, canceling the timer and adding a new one yield better performance. +CZMQ_EXPORT int + ztimerset_reset (ztimerset_t *self, int timer_id); + +// *** Draft method, for development use, may change without warning *** +// Return the time until the next interval. +// Should be used as timeout parameter for the zpoller wait method. +// The timeout is in msec. +CZMQ_EXPORT int + ztimerset_timeout (ztimerset_t *self); + +// *** Draft method, for development use, may change without warning *** +// Invoke callback function of all timers which their interval has elapsed. +// Should be call after zpoller wait method. +// Returns 0 if OK, -1 on failure. +CZMQ_EXPORT int + ztimerset_execute (ztimerset_t *self); + +// *** Draft method, for development use, may change without warning *** +// Self test of this class. +CZMQ_EXPORT void + ztimerset_test (bool verbose); + +#endif // CZMQ_BUILD_DRAFT_API +// @end + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/arm/include/ztrie.h b/phonelibs/zmq/arm/include/ztrie.h new file mode 100644 index 00000000000000..6fd53234b1274c --- /dev/null +++ b/phonelibs/zmq/arm/include/ztrie.h @@ -0,0 +1,106 @@ +/* ========================================================================= + ztrie - simple trie for tokenizable strings + + Copyright (c) 1991-2012 iMatix Corporation -- http://www.imatix.com + Copyright other contributors as noted in the AUTHORS file. + + This file is part of CZMQ, the high-level C binding for 0MQ: http://czmq.zeromq.org + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef ZTRIE_H_INCLUDED +#define ZTRIE_H_INCLUDED + +#ifdef __cplusplus +extern "C" { +#endif + + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/ztrie.api" to make changes. +// @interface +// This is a draft class, and may change without notice. It is disabled in +// stable builds by default. If you use this in applications, please ask +// for it to be pushed to stable state. Use --enable-drafts to enable. +#ifdef CZMQ_BUILD_DRAFT_API +// Callback function for ztrie_node to destroy node data. +typedef void (ztrie_destroy_data_fn) ( + void **data); + +// *** Draft method, for development use, may change without warning *** +// Creates a new ztrie. +CZMQ_EXPORT ztrie_t * + ztrie_new (char delimiter); + +// *** Draft method, for development use, may change without warning *** +// Destroy the ztrie. +CZMQ_EXPORT void + ztrie_destroy (ztrie_t **self_p); + +// *** Draft method, for development use, may change without warning *** +// Inserts a new route into the tree and attaches the data. Returns -1 +// if the route already exists, otherwise 0. This method takes ownership of +// the provided data if a destroy_data_fn is provided. +CZMQ_EXPORT int + ztrie_insert_route (ztrie_t *self, const char *path, void *data, ztrie_destroy_data_fn destroy_data_fn); + +// *** Draft method, for development use, may change without warning *** +// Removes a route from the trie and destroys its data. Returns -1 if the +// route does not exists, otherwise 0. +// the start of the list call zlist_first (). Advances the cursor. +CZMQ_EXPORT int + ztrie_remove_route (ztrie_t *self, const char *path); + +// *** Draft method, for development use, may change without warning *** +// Returns true if the path matches a route in the tree, otherwise false. +CZMQ_EXPORT bool + ztrie_matches (ztrie_t *self, const char *path); + +// *** Draft method, for development use, may change without warning *** +// Returns the data of a matched route from last ztrie_matches. If the path +// did not match, returns NULL. Do not delete the data as it's owned by +// ztrie. +CZMQ_EXPORT void * + ztrie_hit_data (ztrie_t *self); + +// *** Draft method, for development use, may change without warning *** +// Returns the count of parameters that a matched route has. +CZMQ_EXPORT size_t + ztrie_hit_parameter_count (ztrie_t *self); + +// *** Draft method, for development use, may change without warning *** +// Returns the parameters of a matched route with named regexes from last +// ztrie_matches. If the path did not match or the route did not contain any +// named regexes, returns NULL. +CZMQ_EXPORT zhashx_t * + ztrie_hit_parameters (ztrie_t *self); + +// *** Draft method, for development use, may change without warning *** +// Returns the asterisk matched part of a route, if there has been no match +// or no asterisk match, returns NULL. +CZMQ_EXPORT const char * + ztrie_hit_asterisk_match (ztrie_t *self); + +// *** Draft method, for development use, may change without warning *** +// Print the trie +CZMQ_EXPORT void + ztrie_print (ztrie_t *self); + +// *** Draft method, for development use, may change without warning *** +// Self test of this class. +CZMQ_EXPORT void + ztrie_test (bool verbose); + +#endif // CZMQ_BUILD_DRAFT_API +// @end + + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/arm/include/zuuid.h b/phonelibs/zmq/arm/include/zuuid.h new file mode 100644 index 00000000000000..afc1104fea952b --- /dev/null +++ b/phonelibs/zmq/arm/include/zuuid.h @@ -0,0 +1,96 @@ +/* ========================================================================= + zuuid - UUID support class + + Copyright (c) the Contributors as noted in the AUTHORS file. + This file is part of CZMQ, the high-level C binding for 0MQ: + http://czmq.zeromq.org. + + This Source Code Form is subject to the terms of the Mozilla Public + License, v. 2.0. If a copy of the MPL was not distributed with this + file, You can obtain one at http://mozilla.org/MPL/2.0/. + ========================================================================= +*/ + +#ifndef __ZUUID_H_INCLUDED__ +#define __ZUUID_H_INCLUDED__ + +#define ZUUID_LEN 16 +#define ZUUID_STR_LEN (ZUUID_LEN * 2) + +#ifdef __cplusplus +extern "C" { +#endif + +// @warning THE FOLLOWING @INTERFACE BLOCK IS AUTO-GENERATED BY ZPROJECT +// @warning Please edit the model at "api/zuuid.api" to make changes. +// @interface +// This is a stable class, and may not change except for emergencies. It +// is provided in stable builds. +// Create a new UUID object. +CZMQ_EXPORT zuuid_t * + zuuid_new (void); + +// Create UUID object from supplied ZUUID_LEN-octet value. +CZMQ_EXPORT zuuid_t * + zuuid_new_from (const byte *source); + +// Destroy a specified UUID object. +CZMQ_EXPORT void + zuuid_destroy (zuuid_t **self_p); + +// Set UUID to new supplied ZUUID_LEN-octet value. +CZMQ_EXPORT void + zuuid_set (zuuid_t *self, const byte *source); + +// Set UUID to new supplied string value skipping '-' and '{' '}' +// optional delimiters. Return 0 if OK, else returns -1. +CZMQ_EXPORT int + zuuid_set_str (zuuid_t *self, const char *source); + +// Return UUID binary data. +CZMQ_EXPORT const byte * + zuuid_data (zuuid_t *self); + +// Return UUID binary size +CZMQ_EXPORT size_t + zuuid_size (zuuid_t *self); + +// Returns UUID as string +CZMQ_EXPORT const char * + zuuid_str (zuuid_t *self); + +// Return UUID in the canonical string format: 8-4-4-4-12, in lower +// case. Caller does not modify or free returned value. See +// http://en.wikipedia.org/wiki/Universally_unique_identifier +CZMQ_EXPORT const char * + zuuid_str_canonical (zuuid_t *self); + +// Store UUID blob in target array +CZMQ_EXPORT void + zuuid_export (zuuid_t *self, byte *target); + +// Check if UUID is same as supplied value +CZMQ_EXPORT bool + zuuid_eq (zuuid_t *self, const byte *compare); + +// Check if UUID is different from supplied value +CZMQ_EXPORT bool + zuuid_neq (zuuid_t *self, const byte *compare); + +// Make copy of UUID object; if uuid is null, or memory was exhausted, +// returns null. +CZMQ_EXPORT zuuid_t * + zuuid_dup (zuuid_t *self); + +// Self test of this class. +CZMQ_EXPORT void + zuuid_test (bool verbose); + +// @end + + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/phonelibs/zmq/arm/lib/libczmq.a b/phonelibs/zmq/arm/lib/libczmq.a new file mode 100644 index 00000000000000..cb78e4b8296463 Binary files /dev/null and b/phonelibs/zmq/arm/lib/libczmq.a differ diff --git a/phonelibs/zmq/arm/lib/libczmq.so b/phonelibs/zmq/arm/lib/libczmq.so new file mode 100755 index 00000000000000..87ee937f72ae09 Binary files /dev/null and b/phonelibs/zmq/arm/lib/libczmq.so differ diff --git a/phonelibs/zmq/arm/lib/libzmq.a b/phonelibs/zmq/arm/lib/libzmq.a new file mode 100644 index 00000000000000..cd523cd73e6ab5 Binary files /dev/null and b/phonelibs/zmq/arm/lib/libzmq.a differ diff --git a/phonelibs/zmq/arm/lib/libzmq.so b/phonelibs/zmq/arm/lib/libzmq.so new file mode 100755 index 00000000000000..27ec72d7bc815e Binary files /dev/null and b/phonelibs/zmq/arm/lib/libzmq.so differ diff --git a/phonelibs/zmq/build.sh b/phonelibs/zmq/build.sh new file mode 100755 index 00000000000000..8c4d9a50f1f4af --- /dev/null +++ b/phonelibs/zmq/build.sh @@ -0,0 +1,60 @@ +#!/bin/sh +set -e + +# aarch64 is actually built natively and copied in... + +SED=gsed + +git clone --depth 1 -b v4.2.2 git://github.com/zeromq/libzmq.git libzmq +git clone --depth 1 -b v4.0.2 git://github.com/zeromq/czmq.git czmq + +$SED -i 's/defined .HAVE_GETIFADDRS./0/' czmq/src/ziflist.c + +LIBZMQ_ROOT=$HOME/one/phonelibs/zmq/libzmq + +export ANDROID_NDK_ROOT=/opt/android-ndk + +export ANDROID_BUILD_EXTRA_CFLAGS='-std=gnu99 -O2' +export ANDROID_BUILD_EXTRA_CXXFLAGS='-O2' + +######## arm + +export TOOLCHAIN_PATH=${ANDROID_NDK_ROOT}/toolchains/arm-linux-androideabi-4.9/prebuilt/darwin-x86_64/bin +export TOOLCHAIN_NAME=arm-linux-androideabi-4.9 +export TOOLCHAIN_HOST=arm-linux-androideabi +export TOOLCHAIN_ARCH=arm +cd czmq/builds/android +./build.sh +cd ../../../ +cp czmq/builds/android/prefix/arm-linux-androideabi-4.9/lib/libczmq.a \ + czmq/builds/android/prefix/arm-linux-androideabi-4.9/lib/libczmq.so \ + czmq/builds/android/prefix/arm-linux-androideabi-4.9/lib/libzmq.a \ + czmq/builds/android/prefix/arm-linux-androideabi-4.9/lib/libzmq.so ./arm/lib/ +cp czmq/builds/android/prefix/arm-linux-androideabi-4.9/include/*.h ./arm/include/ + + +######## aarch64 + +(cd libzmq && patch -p0 <../build_aarch64.patch) +(cd czmq && patch -p0 <../build_aarch64.patch) + +# android-9 lacks aarch64. +$SED -i 's/android-9/android-24/' *zmq/builds/android/android_build_helper.sh +# For some reason gcc doesn't work for aarch64, but g++ does. +$SED -i 's/-lgnustl_shared/-l:libgnustl_static.a/' *zmq/builds/android/android_build_helper.sh + +export TOOLCHAIN_PATH=${ANDROID_NDK_ROOT}/toolchains/aarch64-linux-android-4.9/prebuilt/darwin-x86_64/bin +export TOOLCHAIN_NAME=aarch64-linux-android-4.9 +export TOOLCHAIN_HOST=aarch64-linux-android +export TOOLCHAIN_ARCH=arm64 +cd czmq/builds/android +./build.sh +cd ../../../ +cp czmq/builds/android/prefix/aarch64-linux-android-4.9/lib/libczmq.a \ + czmq/builds/android/prefix/aarch64-linux-android-4.9/lib/libczmq.so \ + czmq/builds/android/prefix/aarch64-linux-android-4.9/lib/libzmq.a \ + czmq/builds/android/prefix/aarch64-linux-android-4.9/lib/libzmq.so ./aarch64/lib/ +cp czmq/builds/android/prefix/aarch64-linux-android-4.9/include/*.h ./aarch64/include/ + +# rm -rf czmq +echo SUCCESS diff --git a/phonelibs/zmq/build_aarch64.patch b/phonelibs/zmq/build_aarch64.patch new file mode 100644 index 00000000000000..d689b99c51a4c6 --- /dev/null +++ b/phonelibs/zmq/build_aarch64.patch @@ -0,0 +1,15 @@ +diff --git builds/android/android_build_helper.sh builds/android/android_build_helper.sh +index 6263f70..d0b24c3 100755 +--- builds/android/android_build_helper.sh ++++ builds/android/android_build_helper.sh +@@ -202,6 +202,10 @@ function _android_build_opts_process_cxx_stl { + LDFLAGS+=" -L${ANDROID_NDK_ROOT}/sources/cxx-stl/gnu-libstdc++/4.9/libs/mips" + CPPFLAGS+=" -I${ANDROID_NDK_ROOT}/sources/cxx-stl/gnu-libstdc++/4.9/libs/mips/include" + ;; ++ arm64) ++ LDFLAGS+=" -L${ANDROID_NDK_ROOT}/sources/cxx-stl/gnu-libstdc++/4.9/libs/arm64-v8a" ++ CPPFLAGS+=" -I${ANDROID_NDK_ROOT}/sources/cxx-stl/gnu-libstdc++/4.9/libs/arm64-v8a/include" ++ ;; + *) + ANDROID_BUILD_FAIL+=("Unknown combination for ANDROID_BUILD_CXXSTL and TOOLCHAIN_ARCH") + ANDROID_BUILD_FAIL+=(" ${ANDROID_BUILD_CXXSTL}") diff --git a/phonelibs/zmq/build_linux.txt b/phonelibs/zmq/build_linux.txt new file mode 100644 index 00000000000000..54e3b2a340f33b --- /dev/null +++ b/phonelibs/zmq/build_linux.txt @@ -0,0 +1,7 @@ +https://github.com/zeromq/libzmq/releases/download/v4.2.2/zeromq-4.2.2.tar.gz +./configure --prefix="this_thingy" +make -j4 +make install + +czmq +see ~/one/external/zmq/build_czmq.sh diff --git a/phonelibs/zmq/mac/lib/libczmq.a b/phonelibs/zmq/mac/lib/libczmq.a new file mode 100644 index 00000000000000..061f2afabd4937 Binary files /dev/null and b/phonelibs/zmq/mac/lib/libczmq.a differ diff --git a/phonelibs/zmq/mac/lib/libczmq.dylib b/phonelibs/zmq/mac/lib/libczmq.dylib new file mode 100644 index 00000000000000..50d2167e9cb8ec Binary files /dev/null and b/phonelibs/zmq/mac/lib/libczmq.dylib differ diff --git a/phonelibs/zmq/mac/lib/libzmq.a b/phonelibs/zmq/mac/lib/libzmq.a new file mode 100644 index 00000000000000..3365d42e87733d Binary files /dev/null and b/phonelibs/zmq/mac/lib/libzmq.a differ diff --git a/phonelibs/zmq/mac/lib/libzmq.dylib b/phonelibs/zmq/mac/lib/libzmq.dylib new file mode 100755 index 00000000000000..19b751496071c6 Binary files /dev/null and b/phonelibs/zmq/mac/lib/libzmq.dylib differ diff --git a/pyextra/.gitignore b/pyextra/.gitignore new file mode 100644 index 00000000000000..0d20b6487c61e7 --- /dev/null +++ b/pyextra/.gitignore @@ -0,0 +1 @@ +*.pyc diff --git a/pyextra/Flask-1.0.2-py2.7.egg-info/PKG-INFO b/pyextra/Flask-1.0.2-py2.7.egg-info/PKG-INFO new file mode 100644 index 00000000000000..59a627f61ca490 --- /dev/null +++ b/pyextra/Flask-1.0.2-py2.7.egg-info/PKG-INFO @@ -0,0 +1,103 @@ +Metadata-Version: 1.1 +Name: Flask +Version: 1.0.2 +Summary: A simple framework for building complex web applications. +Home-page: https://www.palletsprojects.com/p/flask/ +Author: Pallets team +Author-email: contact@palletsprojects.com +License: BSD +Description: Flask + ===== + + Flask is a lightweight `WSGI`_ web application framework. It is designed + to make getting started quick and easy, with the ability to scale up to + complex applications. It began as a simple wrapper around `Werkzeug`_ + and `Jinja`_ and has become one of the most popular Python web + application frameworks. + + Flask offers suggestions, but doesn't enforce any dependencies or + project layout. It is up to the developer to choose the tools and + libraries they want to use. There are many extensions provided by the + community that make adding new functionality easy. + + + Installing + ---------- + + Install and update using `pip`_: + + .. code-block:: text + + pip install -U Flask + + + A Simple Example + ---------------- + + .. code-block:: python + + from flask import Flask + + app = Flask(__name__) + + @app.route('/') + def hello(): + return 'Hello, World!' + + .. code-block:: text + + $ FLASK_APP=hello.py flask run + * Serving Flask app "hello" + * Running on http://127.0.0.1:5000/ (Press CTRL+C to quit) + + + Donate + ------ + + The Pallets organization develops and supports Flask and the libraries + it uses. In order to grow the community of contributors and users, and + allow the maintainers to devote more time to the projects, `please + donate today`_. + + .. _please donate today: https://psfmember.org/civicrm/contribute/transact?reset=1&id=20 + + + Links + ----- + + * Website: https://www.palletsprojects.com/p/flask/ + * Documentation: http://flask.pocoo.org/docs/ + * License: `BSD `_ + * Releases: https://pypi.org/project/Flask/ + * Code: https://github.com/pallets/flask + * Issue tracker: https://github.com/pallets/flask/issues + * Test status: + + * Linux, Mac: https://travis-ci.org/pallets/flask + * Windows: https://ci.appveyor.com/project/pallets/flask + + * Test coverage: https://codecov.io/gh/pallets/flask + + .. _WSGI: https://wsgi.readthedocs.io + .. _Werkzeug: https://www.palletsprojects.com/p/werkzeug/ + .. _Jinja: https://www.palletsprojects.com/p/jinja/ + .. _pip: https://pip.pypa.io/en/stable/quickstart/ + +Platform: any +Classifier: Development Status :: 5 - Production/Stable +Classifier: Environment :: Web Environment +Classifier: Framework :: Flask +Classifier: Intended Audience :: Developers +Classifier: License :: OSI Approved :: BSD License +Classifier: Operating System :: OS Independent +Classifier: Programming Language :: Python +Classifier: Programming Language :: Python :: 2 +Classifier: Programming Language :: Python :: 2.7 +Classifier: Programming Language :: Python :: 3 +Classifier: Programming Language :: Python :: 3.4 +Classifier: Programming Language :: Python :: 3.5 +Classifier: Programming Language :: Python :: 3.6 +Classifier: Topic :: Internet :: WWW/HTTP :: Dynamic Content +Classifier: Topic :: Internet :: WWW/HTTP :: WSGI :: Application +Classifier: Topic :: Software Development :: Libraries :: Application Frameworks +Classifier: Topic :: Software Development :: Libraries :: Python Modules diff --git a/pyextra/Flask-1.0.2-py2.7.egg-info/SOURCES.txt b/pyextra/Flask-1.0.2-py2.7.egg-info/SOURCES.txt new file mode 100644 index 00000000000000..52f6db1918a045 --- /dev/null +++ b/pyextra/Flask-1.0.2-py2.7.egg-info/SOURCES.txt @@ -0,0 +1,223 @@ +AUTHORS +CHANGES.rst +LICENSE +MANIFEST.in +Makefile +README.rst +setup.cfg +setup.py +tox.ini +Flask.egg-info/PKG-INFO +Flask.egg-info/SOURCES.txt +Flask.egg-info/dependency_links.txt +Flask.egg-info/entry_points.txt +Flask.egg-info/not-zip-safe +Flask.egg-info/requires.txt +Flask.egg-info/top_level.txt +artwork/LICENSE +artwork/logo-full.svg +artwork/logo-lineart.svg +docs/Makefile +docs/advanced_foreword.rst +docs/api.rst +docs/appcontext.rst +docs/becomingbig.rst +docs/blueprints.rst +docs/changelog.rst +docs/cli.rst +docs/conf.py +docs/config.rst +docs/contents.rst.inc +docs/contributing.rst +docs/design.rst +docs/errorhandling.rst +docs/extensiondev.rst +docs/extensions.rst +docs/flaskstyle.sty +docs/foreword.rst +docs/htmlfaq.rst +docs/index.rst +docs/installation.rst +docs/latexindex.rst +docs/license.rst +docs/logging.rst +docs/logo.pdf +docs/make.bat +docs/quickstart.rst +docs/reqcontext.rst +docs/security.rst +docs/server.rst +docs/shell.rst +docs/signals.rst +docs/styleguide.rst +docs/templating.rst +docs/testing.rst +docs/unicode.rst +docs/upgrading.rst +docs/views.rst +docs/_static/debugger.png +docs/_static/flask-favicon.ico +docs/_static/flask.png +docs/_static/logo-full.png +docs/_static/no.png +docs/_static/pycharm-runconfig.png +docs/_static/touch-icon.png +docs/_static/yes.png +docs/deploying/cgi.rst +docs/deploying/fastcgi.rst +docs/deploying/index.rst +docs/deploying/mod_wsgi.rst +docs/deploying/uwsgi.rst +docs/deploying/wsgi-standalone.rst +docs/patterns/apierrors.rst +docs/patterns/appdispatch.rst +docs/patterns/appfactories.rst +docs/patterns/caching.rst +docs/patterns/celery.rst +docs/patterns/deferredcallbacks.rst +docs/patterns/distribute.rst +docs/patterns/errorpages.rst +docs/patterns/fabric.rst +docs/patterns/favicon.rst +docs/patterns/fileuploads.rst +docs/patterns/flashing.rst +docs/patterns/index.rst +docs/patterns/jquery.rst +docs/patterns/lazyloading.rst +docs/patterns/methodoverrides.rst +docs/patterns/mongokit.rst +docs/patterns/packages.rst +docs/patterns/requestchecksum.rst +docs/patterns/sqlalchemy.rst +docs/patterns/sqlite3.rst +docs/patterns/streaming.rst +docs/patterns/subclassing.rst +docs/patterns/templateinheritance.rst +docs/patterns/urlprocessors.rst +docs/patterns/viewdecorators.rst +docs/patterns/wtforms.rst +docs/tutorial/blog.rst +docs/tutorial/database.rst +docs/tutorial/deploy.rst +docs/tutorial/factory.rst +docs/tutorial/flaskr_edit.png +docs/tutorial/flaskr_index.png +docs/tutorial/flaskr_login.png +docs/tutorial/index.rst +docs/tutorial/install.rst +docs/tutorial/layout.rst +docs/tutorial/next.rst +docs/tutorial/static.rst +docs/tutorial/templates.rst +docs/tutorial/tests.rst +docs/tutorial/views.rst +examples/javascript/.gitignore +examples/javascript/LICENSE +examples/javascript/MANIFEST.in +examples/javascript/README.rst +examples/javascript/setup.cfg +examples/javascript/setup.py +examples/javascript/js_example/__init__.py +examples/javascript/js_example/views.py +examples/javascript/js_example/templates/base.html +examples/javascript/js_example/templates/fetch.html +examples/javascript/js_example/templates/jquery.html +examples/javascript/js_example/templates/plain.html +examples/javascript/tests/conftest.py +examples/javascript/tests/test_js_example.py +examples/tutorial/.gitignore +examples/tutorial/LICENSE +examples/tutorial/MANIFEST.in +examples/tutorial/README.rst +examples/tutorial/setup.cfg +examples/tutorial/setup.py +examples/tutorial/flaskr/__init__.py +examples/tutorial/flaskr/auth.py +examples/tutorial/flaskr/blog.py +examples/tutorial/flaskr/db.py +examples/tutorial/flaskr/schema.sql +examples/tutorial/flaskr/static/style.css +examples/tutorial/flaskr/templates/base.html +examples/tutorial/flaskr/templates/auth/login.html +examples/tutorial/flaskr/templates/auth/register.html +examples/tutorial/flaskr/templates/blog/create.html +examples/tutorial/flaskr/templates/blog/index.html +examples/tutorial/flaskr/templates/blog/update.html +examples/tutorial/tests/conftest.py +examples/tutorial/tests/data.sql +examples/tutorial/tests/test_auth.py +examples/tutorial/tests/test_blog.py +examples/tutorial/tests/test_db.py +examples/tutorial/tests/test_factory.py +flask/__init__.py +flask/__main__.py +flask/_compat.py +flask/app.py +flask/blueprints.py +flask/cli.py +flask/config.py +flask/ctx.py +flask/debughelpers.py +flask/globals.py +flask/helpers.py +flask/logging.py +flask/sessions.py +flask/signals.py +flask/templating.py +flask/testing.py +flask/views.py +flask/wrappers.py +flask/json/__init__.py +flask/json/tag.py +tests/conftest.py +tests/test_appctx.py +tests/test_basic.py +tests/test_blueprints.py +tests/test_cli.py +tests/test_config.py +tests/test_helpers.py +tests/test_instance_config.py +tests/test_json_tag.py +tests/test_logging.py +tests/test_regression.py +tests/test_reqctx.py +tests/test_signals.py +tests/test_subclassing.py +tests/test_templating.py +tests/test_testing.py +tests/test_user_error_handler.py +tests/test_views.py +tests/static/config.json +tests/static/index.html +tests/templates/_macro.html +tests/templates/context_template.html +tests/templates/escaping_template.html +tests/templates/mail.txt +tests/templates/non_escaping_template.txt +tests/templates/simple_template.html +tests/templates/template_filter.html +tests/templates/template_test.html +tests/templates/nested/nested.txt +tests/test_apps/.env +tests/test_apps/.flaskenv +tests/test_apps/blueprintapp/__init__.py +tests/test_apps/blueprintapp/apps/__init__.py +tests/test_apps/blueprintapp/apps/admin/__init__.py +tests/test_apps/blueprintapp/apps/admin/static/test.txt +tests/test_apps/blueprintapp/apps/admin/static/css/test.css +tests/test_apps/blueprintapp/apps/admin/templates/admin/index.html +tests/test_apps/blueprintapp/apps/frontend/__init__.py +tests/test_apps/blueprintapp/apps/frontend/templates/frontend/index.html +tests/test_apps/cliapp/__init__.py +tests/test_apps/cliapp/app.py +tests/test_apps/cliapp/factory.py +tests/test_apps/cliapp/importerrorapp.py +tests/test_apps/cliapp/message.txt +tests/test_apps/cliapp/multiapp.py +tests/test_apps/cliapp/inner1/__init__.py +tests/test_apps/cliapp/inner1/inner2/__init__.py +tests/test_apps/cliapp/inner1/inner2/flask.py +tests/test_apps/helloworld/hello.py +tests/test_apps/helloworld/wsgi.py +tests/test_apps/subdomaintestmodule/__init__.py +tests/test_apps/subdomaintestmodule/static/hello.txt \ No newline at end of file diff --git a/pyextra/Flask-1.0.2-py2.7.egg-info/dependency_links.txt b/pyextra/Flask-1.0.2-py2.7.egg-info/dependency_links.txt new file mode 100644 index 00000000000000..8b137891791fe9 --- /dev/null +++ b/pyextra/Flask-1.0.2-py2.7.egg-info/dependency_links.txt @@ -0,0 +1 @@ + diff --git a/pyextra/Flask-1.0.2-py2.7.egg-info/entry_points.txt b/pyextra/Flask-1.0.2-py2.7.egg-info/entry_points.txt new file mode 100644 index 00000000000000..1eb025200e62eb --- /dev/null +++ b/pyextra/Flask-1.0.2-py2.7.egg-info/entry_points.txt @@ -0,0 +1,3 @@ +[console_scripts] +flask = flask.cli:main + diff --git a/pyextra/Flask-1.0.2-py2.7.egg-info/installed-files.txt b/pyextra/Flask-1.0.2-py2.7.egg-info/installed-files.txt new file mode 100644 index 00000000000000..150041120d31e5 --- /dev/null +++ b/pyextra/Flask-1.0.2-py2.7.egg-info/installed-files.txt @@ -0,0 +1,48 @@ +../flask/testing.py +../flask/templating.py +../flask/__main__.py +../flask/sessions.py +../flask/signals.py +../flask/helpers.py +../flask/debughelpers.py +../flask/wrappers.py +../flask/app.py +../flask/ctx.py +../flask/config.py +../flask/logging.py +../flask/blueprints.py +../flask/views.py +../flask/cli.py +../flask/_compat.py +../flask/globals.py +../flask/__init__.py +../flask/json/tag.py +../flask/json/__init__.py +../flask/testing.pyc +../flask/templating.pyc +../flask/__main__.pyc +../flask/sessions.pyc +../flask/signals.pyc +../flask/helpers.pyc +../flask/debughelpers.pyc +../flask/wrappers.pyc +../flask/app.pyc +../flask/ctx.pyc +../flask/config.pyc +../flask/logging.pyc +../flask/blueprints.pyc +../flask/views.pyc +../flask/cli.pyc +../flask/_compat.pyc +../flask/globals.pyc +../flask/__init__.pyc +../flask/json/tag.pyc +../flask/json/__init__.pyc +not-zip-safe +entry_points.txt +dependency_links.txt +PKG-INFO +top_level.txt +requires.txt +SOURCES.txt +../../../../bin/flask diff --git a/pyextra/Flask-1.0.2-py2.7.egg-info/not-zip-safe b/pyextra/Flask-1.0.2-py2.7.egg-info/not-zip-safe new file mode 100644 index 00000000000000..8b137891791fe9 --- /dev/null +++ b/pyextra/Flask-1.0.2-py2.7.egg-info/not-zip-safe @@ -0,0 +1 @@ + diff --git a/pyextra/Flask-1.0.2-py2.7.egg-info/requires.txt b/pyextra/Flask-1.0.2-py2.7.egg-info/requires.txt new file mode 100644 index 00000000000000..f51579ea91ca2e --- /dev/null +++ b/pyextra/Flask-1.0.2-py2.7.egg-info/requires.txt @@ -0,0 +1,20 @@ +Werkzeug>=0.14 +Jinja2>=2.10 +itsdangerous>=0.24 +click>=5.1 + +[dev] +pytest>=3 +coverage +tox +sphinx +pallets-sphinx-themes +sphinxcontrib-log-cabinet + +[docs] +sphinx +pallets-sphinx-themes +sphinxcontrib-log-cabinet + +[dotenv] +python-dotenv diff --git a/pyextra/Flask-1.0.2-py2.7.egg-info/top_level.txt b/pyextra/Flask-1.0.2-py2.7.egg-info/top_level.txt new file mode 100644 index 00000000000000..7e1060246fd674 --- /dev/null +++ b/pyextra/Flask-1.0.2-py2.7.egg-info/top_level.txt @@ -0,0 +1 @@ +flask diff --git a/pyextra/Jinja2-2.10-py2.7.egg-info/PKG-INFO b/pyextra/Jinja2-2.10-py2.7.egg-info/PKG-INFO new file mode 100644 index 00000000000000..b4398d64900217 --- /dev/null +++ b/pyextra/Jinja2-2.10-py2.7.egg-info/PKG-INFO @@ -0,0 +1,62 @@ +Metadata-Version: 1.1 +Name: Jinja2 +Version: 2.10 +Summary: A small but fast and easy to use stand-alone template engine written in pure python. +Home-page: http://jinja.pocoo.org/ +Author: Armin Ronacher +Author-email: armin.ronacher@active-4.com +License: BSD +Description: + Jinja2 + ~~~~~~ + + Jinja2 is a template engine written in pure Python. It provides a + `Django`_ inspired non-XML syntax but supports inline expressions and + an optional `sandboxed`_ environment. + + Nutshell + -------- + + Here a small example of a Jinja template:: + + {% extends 'base.html' %} + {% block title %}Memberlist{% endblock %} + {% block content %} +
+ {% endblock %} + + Philosophy + ---------- + + Application logic is for the controller but don't try to make the life + for the template designer too hard by giving him too few functionality. + + For more informations visit the new `Jinja2 webpage`_ and `documentation`_. + + .. _sandboxed: https://en.wikipedia.org/wiki/Sandbox_(computer_security) + .. _Django: https://www.djangoproject.com/ + .. _Jinja2 webpage: http://jinja.pocoo.org/ + .. _documentation: http://jinja.pocoo.org/2/documentation/ + +Platform: UNKNOWN +Classifier: Development Status :: 5 - Production/Stable +Classifier: Environment :: Web Environment +Classifier: Intended Audience :: Developers +Classifier: License :: OSI Approved :: BSD License +Classifier: Operating System :: OS Independent +Classifier: Programming Language :: Python +Classifier: Programming Language :: Python :: 2 +Classifier: Programming Language :: Python :: 2.6 +Classifier: Programming Language :: Python :: 2.7 +Classifier: Programming Language :: Python :: 3 +Classifier: Programming Language :: Python :: 3.3 +Classifier: Programming Language :: Python :: 3.4 +Classifier: Programming Language :: Python :: 3.5 +Classifier: Programming Language :: Python :: 3.6 +Classifier: Topic :: Internet :: WWW/HTTP :: Dynamic Content +Classifier: Topic :: Software Development :: Libraries :: Python Modules +Classifier: Topic :: Text Processing :: Markup :: HTML diff --git a/pyextra/Jinja2-2.10-py2.7.egg-info/SOURCES.txt b/pyextra/Jinja2-2.10-py2.7.egg-info/SOURCES.txt new file mode 100644 index 00000000000000..93158e1f63bcee --- /dev/null +++ b/pyextra/Jinja2-2.10-py2.7.egg-info/SOURCES.txt @@ -0,0 +1,133 @@ +AUTHORS +CHANGES.rst +LICENSE +MANIFEST.in +README.rst +setup.cfg +setup.py +Jinja2.egg-info/PKG-INFO +Jinja2.egg-info/SOURCES.txt +Jinja2.egg-info/dependency_links.txt +Jinja2.egg-info/entry_points.txt +Jinja2.egg-info/not-zip-safe +Jinja2.egg-info/requires.txt +Jinja2.egg-info/top_level.txt +artwork/jinjalogo.svg +docs/Makefile +docs/api.rst +docs/cache_extension.py +docs/changelog.rst +docs/conf.py +docs/contents.rst.inc +docs/extensions.rst +docs/faq.rst +docs/index.rst +docs/integration.rst +docs/intro.rst +docs/jinjaext.py +docs/jinjastyle.sty +docs/latexindex.rst +docs/logo.pdf +docs/nativetypes.rst +docs/sandbox.rst +docs/switching.rst +docs/templates.rst +docs/tricks.rst +docs/_static/.ignore +docs/_static/jinja-small.png +docs/_templates/sidebarintro.html +docs/_templates/sidebarlogo.html +docs/_themes/LICENSE +docs/_themes/README +docs/_themes/jinja/layout.html +docs/_themes/jinja/relations.html +docs/_themes/jinja/theme.conf +docs/_themes/jinja/static/jinja.css_t +examples/bench.py +examples/profile.py +examples/basic/cycle.py +examples/basic/debugger.py +examples/basic/inheritance.py +examples/basic/test.py +examples/basic/test_filter_and_linestatements.py +examples/basic/test_loop_filter.py +examples/basic/translate.py +examples/basic/templates/broken.html +examples/basic/templates/subbroken.html +examples/rwbench/djangoext.py +examples/rwbench/rwbench.py +examples/rwbench/django/_form.html +examples/rwbench/django/_input_field.html +examples/rwbench/django/_textarea.html +examples/rwbench/django/index.html +examples/rwbench/django/layout.html +examples/rwbench/genshi/helpers.html +examples/rwbench/genshi/index.html +examples/rwbench/genshi/layout.html +examples/rwbench/jinja/helpers.html +examples/rwbench/jinja/index.html +examples/rwbench/jinja/layout.html +examples/rwbench/mako/helpers.html +examples/rwbench/mako/index.html +examples/rwbench/mako/layout.html +ext/djangojinja2.py +ext/inlinegettext.py +ext/jinja.el +ext/Vim/jinja.vim +ext/django2jinja/django2jinja.py +ext/django2jinja/example.py +ext/django2jinja/templates/index.html +ext/django2jinja/templates/layout.html +ext/django2jinja/templates/subtemplate.html +jinja2/__init__.py +jinja2/_compat.py +jinja2/_identifier.py +jinja2/asyncfilters.py +jinja2/asyncsupport.py +jinja2/bccache.py +jinja2/compiler.py +jinja2/constants.py +jinja2/debug.py +jinja2/defaults.py +jinja2/environment.py +jinja2/exceptions.py +jinja2/ext.py +jinja2/filters.py +jinja2/idtracking.py +jinja2/lexer.py +jinja2/loaders.py +jinja2/meta.py +jinja2/nativetypes.py +jinja2/nodes.py +jinja2/optimizer.py +jinja2/parser.py +jinja2/runtime.py +jinja2/sandbox.py +jinja2/tests.py +jinja2/utils.py +jinja2/visitor.py +tests/conftest.py +tests/test_api.py +tests/test_async.py +tests/test_asyncfilters.py +tests/test_bytecode_cache.py +tests/test_core_tags.py +tests/test_debug.py +tests/test_ext.py +tests/test_features.py +tests/test_filters.py +tests/test_idtracking.py +tests/test_imports.py +tests/test_inheritance.py +tests/test_lexnparse.py +tests/test_loader.py +tests/test_nativetypes.py +tests/test_regression.py +tests/test_security.py +tests/test_tests.py +tests/test_utils.py +tests/res/__init__.py +tests/res/templates/broken.html +tests/res/templates/syntaxerror.html +tests/res/templates/test.html +tests/res/templates/foo/test.html \ No newline at end of file diff --git a/pyextra/Jinja2-2.10-py2.7.egg-info/dependency_links.txt b/pyextra/Jinja2-2.10-py2.7.egg-info/dependency_links.txt new file mode 100644 index 00000000000000..8b137891791fe9 --- /dev/null +++ b/pyextra/Jinja2-2.10-py2.7.egg-info/dependency_links.txt @@ -0,0 +1 @@ + diff --git a/pyextra/Jinja2-2.10-py2.7.egg-info/entry_points.txt b/pyextra/Jinja2-2.10-py2.7.egg-info/entry_points.txt new file mode 100644 index 00000000000000..32e6b753028430 --- /dev/null +++ b/pyextra/Jinja2-2.10-py2.7.egg-info/entry_points.txt @@ -0,0 +1,4 @@ + + [babel.extractors] + jinja2 = jinja2.ext:babel_extract[i18n] + \ No newline at end of file diff --git a/pyextra/Jinja2-2.10-py2.7.egg-info/installed-files.txt b/pyextra/Jinja2-2.10-py2.7.egg-info/installed-files.txt new file mode 100644 index 00000000000000..c2af213acef197 --- /dev/null +++ b/pyextra/Jinja2-2.10-py2.7.egg-info/installed-files.txt @@ -0,0 +1,61 @@ +../jinja2/lexer.py +../jinja2/idtracking.py +../jinja2/_identifier.py +../jinja2/nodes.py +../jinja2/asyncfilters.py +../jinja2/loaders.py +../jinja2/defaults.py +../jinja2/meta.py +../jinja2/compiler.py +../jinja2/environment.py +../jinja2/tests.py +../jinja2/sandbox.py +../jinja2/filters.py +../jinja2/exceptions.py +../jinja2/asyncsupport.py +../jinja2/visitor.py +../jinja2/constants.py +../jinja2/utils.py +../jinja2/ext.py +../jinja2/optimizer.py +../jinja2/nativetypes.py +../jinja2/parser.py +../jinja2/runtime.py +../jinja2/debug.py +../jinja2/_compat.py +../jinja2/bccache.py +../jinja2/__init__.py +../jinja2/lexer.pyc +../jinja2/idtracking.pyc +../jinja2/_identifier.pyc +../jinja2/nodes.pyc +../jinja2/asyncfilters.pyc +../jinja2/loaders.pyc +../jinja2/defaults.pyc +../jinja2/meta.pyc +../jinja2/compiler.pyc +../jinja2/environment.pyc +../jinja2/tests.pyc +../jinja2/sandbox.pyc +../jinja2/filters.pyc +../jinja2/exceptions.pyc +../jinja2/asyncsupport.pyc +../jinja2/visitor.pyc +../jinja2/constants.pyc +../jinja2/utils.pyc +../jinja2/ext.pyc +../jinja2/optimizer.pyc +../jinja2/nativetypes.pyc +../jinja2/parser.pyc +../jinja2/runtime.pyc +../jinja2/debug.pyc +../jinja2/_compat.pyc +../jinja2/bccache.pyc +../jinja2/__init__.pyc +not-zip-safe +entry_points.txt +dependency_links.txt +PKG-INFO +top_level.txt +requires.txt +SOURCES.txt diff --git a/pyextra/Jinja2-2.10-py2.7.egg-info/not-zip-safe b/pyextra/Jinja2-2.10-py2.7.egg-info/not-zip-safe new file mode 100644 index 00000000000000..8b137891791fe9 --- /dev/null +++ b/pyextra/Jinja2-2.10-py2.7.egg-info/not-zip-safe @@ -0,0 +1 @@ + diff --git a/pyextra/Jinja2-2.10-py2.7.egg-info/requires.txt b/pyextra/Jinja2-2.10-py2.7.egg-info/requires.txt new file mode 100644 index 00000000000000..1d74a32c66fb4b --- /dev/null +++ b/pyextra/Jinja2-2.10-py2.7.egg-info/requires.txt @@ -0,0 +1,4 @@ +MarkupSafe>=0.23 + +[i18n] +Babel>=0.8 diff --git a/pyextra/Jinja2-2.10-py2.7.egg-info/top_level.txt b/pyextra/Jinja2-2.10-py2.7.egg-info/top_level.txt new file mode 100644 index 00000000000000..7f7afbf3bf54b3 --- /dev/null +++ b/pyextra/Jinja2-2.10-py2.7.egg-info/top_level.txt @@ -0,0 +1 @@ +jinja2 diff --git a/pyextra/Jinja2-2.9.6.dist-info/DESCRIPTION.rst b/pyextra/Jinja2-2.9.6.dist-info/DESCRIPTION.rst new file mode 100644 index 00000000000000..4421f046e25436 --- /dev/null +++ b/pyextra/Jinja2-2.9.6.dist-info/DESCRIPTION.rst @@ -0,0 +1,36 @@ +Jinja2 +~~~~~~ + +Jinja2 is a template engine written in pure Python. It provides a +`Django`_ inspired non-XML syntax but supports inline expressions and +an optional `sandboxed`_ environment. + +Nutshell +-------- + +Here a small example of a Jinja template:: + + {% extends 'base.html' %} + {% block title %}Memberlist{% endblock %} + {% block content %} + + {% endblock %} + +Philosophy +---------- + +Application logic is for the controller but don't try to make the life +for the template designer too hard by giving him too few functionality. + +For more informations visit the new `Jinja2 webpage`_ and `documentation`_. + +.. _sandboxed: http://en.wikipedia.org/wiki/Sandbox_(computer_security) +.. _Django: http://www.djangoproject.com/ +.. _Jinja2 webpage: http://jinja.pocoo.org/ +.. _documentation: http://jinja.pocoo.org/2/documentation/ + + diff --git a/pyextra/Jinja2-2.9.6.dist-info/INSTALLER b/pyextra/Jinja2-2.9.6.dist-info/INSTALLER new file mode 100644 index 00000000000000..a1b589e38a3204 --- /dev/null +++ b/pyextra/Jinja2-2.9.6.dist-info/INSTALLER @@ -0,0 +1 @@ +pip diff --git a/pyextra/Jinja2-2.9.6.dist-info/LICENSE.txt b/pyextra/Jinja2-2.9.6.dist-info/LICENSE.txt new file mode 100644 index 00000000000000..10145a264342b7 --- /dev/null +++ b/pyextra/Jinja2-2.9.6.dist-info/LICENSE.txt @@ -0,0 +1,31 @@ +Copyright (c) 2009 by the Jinja Team, see AUTHORS for more details. + +Some rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are +met: + + * Redistributions of source code must retain the above copyright + notice, this list of conditions and the following disclaimer. + + * Redistributions in binary form must reproduce the above + copyright notice, this list of conditions and the following + disclaimer in the documentation and/or other materials provided + with the distribution. + + * The names of the 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. diff --git a/pyextra/Jinja2-2.9.6.dist-info/METADATA b/pyextra/Jinja2-2.9.6.dist-info/METADATA new file mode 100644 index 00000000000000..ea69de1726d02c --- /dev/null +++ b/pyextra/Jinja2-2.9.6.dist-info/METADATA @@ -0,0 +1,65 @@ +Metadata-Version: 2.0 +Name: Jinja2 +Version: 2.9.6 +Summary: A small but fast and easy to use stand-alone template engine written in pure python. +Home-page: http://jinja.pocoo.org/ +Author: Armin Ronacher +Author-email: armin.ronacher@active-4.com +License: BSD +Platform: UNKNOWN +Classifier: Development Status :: 5 - Production/Stable +Classifier: Environment :: Web Environment +Classifier: Intended Audience :: Developers +Classifier: License :: OSI Approved :: BSD License +Classifier: Operating System :: OS Independent +Classifier: Programming Language :: Python +Classifier: Programming Language :: Python :: 2 +Classifier: Programming Language :: Python :: 2.6 +Classifier: Programming Language :: Python :: 2.7 +Classifier: Programming Language :: Python :: 3 +Classifier: Programming Language :: Python :: 3.3 +Classifier: Programming Language :: Python :: 3.4 +Classifier: Programming Language :: Python :: 3.5 +Classifier: Topic :: Internet :: WWW/HTTP :: Dynamic Content +Classifier: Topic :: Software Development :: Libraries :: Python Modules +Classifier: Topic :: Text Processing :: Markup :: HTML +Requires-Dist: MarkupSafe (>=0.23) +Provides-Extra: i18n +Requires-Dist: Babel (>=0.8); extra == 'i18n' + +Jinja2 +~~~~~~ + +Jinja2 is a template engine written in pure Python. It provides a +`Django`_ inspired non-XML syntax but supports inline expressions and +an optional `sandboxed`_ environment. + +Nutshell +-------- + +Here a small example of a Jinja template:: + + {% extends 'base.html' %} + {% block title %}Memberlist{% endblock %} + {% block content %} + + {% endblock %} + +Philosophy +---------- + +Application logic is for the controller but don't try to make the life +for the template designer too hard by giving him too few functionality. + +For more informations visit the new `Jinja2 webpage`_ and `documentation`_. + +.. _sandboxed: http://en.wikipedia.org/wiki/Sandbox_(computer_security) +.. _Django: http://www.djangoproject.com/ +.. _Jinja2 webpage: http://jinja.pocoo.org/ +.. _documentation: http://jinja.pocoo.org/2/documentation/ + + diff --git a/pyextra/Jinja2-2.9.6.dist-info/RECORD b/pyextra/Jinja2-2.9.6.dist-info/RECORD new file mode 100644 index 00000000000000..024e3899105f0d --- /dev/null +++ b/pyextra/Jinja2-2.9.6.dist-info/RECORD @@ -0,0 +1,59 @@ +jinja2/__init__.py,sha256=Cx_UnJO4i_GqvKQsOu__mvGE_eMJSsBqITa26irtg5A,2565 +jinja2/_compat.py,sha256=xP60CE5Qr8FTYcDE1f54tbZLKGvMwYml4-8T7Q4KG9k,2596 +jinja2/_stringdefs.py,sha256=PYtqTmmWIhjXlFBoH-eE6fJkQvlu7nxUyQ2YlFB97VA,589381 +jinja2/asyncfilters.py,sha256=cTDPvrS8Hp_IkwsZ1m9af_lr5nHysw7uTa5gV0NmZVE,4144 +jinja2/asyncsupport.py,sha256=ZJO1Fdd9R93sDLrk6TZNuMQGgtuDmpTlENNRkLwZF7c,7765 +jinja2/bccache.py,sha256=0xoVw0R9nj3vtzPl9g-zB5BKTLFJ7FFMq2ABbn1IkCI,12793 +jinja2/compiler.py,sha256=lE5owyPwT1cGGZxWyzQtZLW7Uj1g3Vw1oVtBU8Uc_uM,62929 +jinja2/constants.py,sha256=uwwV8ZUhHhacAuz5PTwckfsbqBaqM7aKfyJL7kGX5YQ,1626 +jinja2/debug.py,sha256=UqEbKb4zofBABwvyA77Kr0-5IAQawKqC9t8ZeTIzpGU,12038 +jinja2/defaults.py,sha256=GvVEQqIRvRMCbQF2NZSr0mlEN8lxvGixU5wIIAeRe1A,1323 +jinja2/environment.py,sha256=z91L_efdYs-KNs6DBxQWDyYncOwOqn_0J4M5CfFj0Q8,50848 +jinja2/exceptions.py,sha256=_Rj-NVi98Q6AiEjYQOsP8dEIdu5AlmRHzcSNOPdWix4,4428 +jinja2/ext.py,sha256=9xq8fd_QPBIe4Z7hE1XawB7f1EDHrVZjpb2JiRTiG94,23867 +jinja2/filters.py,sha256=1OYGhyN84yVmFUIOwJNRV_StqTCfPhnRLfJTmWbEe_8,33424 +jinja2/idtracking.py,sha256=HHcCOMsQhCrrjwYAmikKqq_XetXLovCjXAThh9WbRAc,8760 +jinja2/lexer.py,sha256=W4A830e-fj12zRT6rL7H91F4D6xwED5LjR8iMxjWuVQ,28238 +jinja2/loaders.py,sha256=xiTuURKAEObyym0nU8PCIXu_Qp8fn0AJ5oIADUUm-5Q,17382 +jinja2/meta.py,sha256=fmKHxkmZYAOm9QyWWy8EMd6eefAIh234rkBMW2X4ZR8,4340 +jinja2/nodes.py,sha256=4_Ucxbkohtj4BAlpV0w_MpVmIxJNaVXDTBb4EHBA2JI,29392 +jinja2/optimizer.py,sha256=MsdlFACJ0FRdPtjmCAdt7JQ9SGrXFaDNUaslsWQaG3M,1722 +jinja2/parser.py,sha256=3tc82qO1Ovs9och_PjirbAmnWNT77n4wWjIQ8pEVKvU,35465 +jinja2/runtime.py,sha256=axkTQXg2-oc_Cm35NEMDDas3Jbq3ATxNrDOEa5v3wIw,26835 +jinja2/sandbox.py,sha256=Jx4MTxly8KvdkSWyui_kHY1_ZZ0RAQL4ojAy1KDRyK0,16707 +jinja2/tests.py,sha256=iFuUTbUYv7TFffq2aTswCRdIhQ6wyrby1YevChVPqkE,4428 +jinja2/utils.py,sha256=BIFqeXXsCUSjWx6MEwYhY6V4tXzVNs9WRXfB60MA9HY,19941 +jinja2/visitor.py,sha256=JD1H1cANA29JcntFfN5fPyqQxB4bI4wC00BzZa-XHks,3316 +Jinja2-2.9.6.dist-info/DESCRIPTION.rst,sha256=CXIS1UnPSk5_lZBS6Lb8ko-3lqGfjsiUwNBLXCTj2lc,975 +Jinja2-2.9.6.dist-info/entry_points.txt,sha256=NdzVcOrqyNyKDxD09aERj__3bFx2paZhizFDsKmVhiA,72 +Jinja2-2.9.6.dist-info/LICENSE.txt,sha256=JvzUNv3Io51EiWrAPm8d_SXjhJnEjyDYvB3Tvwqqils,1554 +Jinja2-2.9.6.dist-info/METADATA,sha256=53LSXlqC86JTyLSPsDyAOmyV4pXIzzmmZoUXz7ogytA,2172 +Jinja2-2.9.6.dist-info/metadata.json,sha256=vzvX25T4hwMOe1EIOBo9rpfiZerOB_KVLcplGG_qYtE,1394 +Jinja2-2.9.6.dist-info/RECORD,, +Jinja2-2.9.6.dist-info/top_level.txt,sha256=PkeVWtLb3-CqjWi1fO29OCbj55EhX_chhKrCdrVe_zs,7 +Jinja2-2.9.6.dist-info/WHEEL,sha256=AvR0WeTpDaxT645bl5FQxUK6NPsTls2ttpcGJg3j1Xg,110 +Jinja2-2.9.6.dist-info/INSTALLER,sha256=zuuue4knoyJ-UwPPXg8fezS7VCrXJQrAP7zeNuwvFQg,4 +jinja2/_compat.pyc,, +jinja2/sandbox.pyc,, +jinja2/_stringdefs.pyc,, +jinja2/bccache.pyc,, +jinja2/runtime.pyc,, +jinja2/utils.pyc,, +jinja2/parser.pyc,, +jinja2/debug.pyc,, +jinja2/lexer.pyc,, +jinja2/defaults.pyc,, +jinja2/visitor.pyc,, +jinja2/nodes.pyc,, +jinja2/environment.pyc,, +jinja2/compiler.pyc,, +jinja2/exceptions.pyc,, +jinja2/filters.pyc,, +jinja2/__init__.pyc,, +jinja2/meta.pyc,, +jinja2/loaders.pyc,, +jinja2/ext.pyc,, +jinja2/optimizer.pyc,, +jinja2/constants.pyc,, +jinja2/tests.pyc,, +jinja2/idtracking.pyc,, diff --git a/pyextra/Jinja2-2.9.6.dist-info/WHEEL b/pyextra/Jinja2-2.9.6.dist-info/WHEEL new file mode 100644 index 00000000000000..9dff69d86102d3 --- /dev/null +++ b/pyextra/Jinja2-2.9.6.dist-info/WHEEL @@ -0,0 +1,6 @@ +Wheel-Version: 1.0 +Generator: bdist_wheel (0.24.0) +Root-Is-Purelib: true +Tag: py2-none-any +Tag: py3-none-any + diff --git a/pyextra/Jinja2-2.9.6.dist-info/entry_points.txt b/pyextra/Jinja2-2.9.6.dist-info/entry_points.txt new file mode 100644 index 00000000000000..32e6b753028430 --- /dev/null +++ b/pyextra/Jinja2-2.9.6.dist-info/entry_points.txt @@ -0,0 +1,4 @@ + + [babel.extractors] + jinja2 = jinja2.ext:babel_extract[i18n] + \ No newline at end of file diff --git a/pyextra/Jinja2-2.9.6.dist-info/metadata.json b/pyextra/Jinja2-2.9.6.dist-info/metadata.json new file mode 100644 index 00000000000000..9bbf942f131b6b --- /dev/null +++ b/pyextra/Jinja2-2.9.6.dist-info/metadata.json @@ -0,0 +1 @@ +{"license": "BSD", "name": "Jinja2", "metadata_version": "2.0", "generator": "bdist_wheel (0.24.0)", "summary": "A small but fast and easy to use stand-alone template engine written in pure python.", "run_requires": [{"requires": ["Babel (>=0.8)"], "extra": "i18n"}, {"requires": ["MarkupSafe (>=0.23)"]}], "version": "2.9.6", "extensions": {"python.details": {"project_urls": {"Home": "http://jinja.pocoo.org/"}, "document_names": {"description": "DESCRIPTION.rst", "license": "LICENSE.txt"}, "contacts": [{"role": "author", "email": "armin.ronacher@active-4.com", "name": "Armin Ronacher"}]}, "python.exports": {"babel.extractors": {"jinja2": "jinja2.ext:babel_extract [i18n]"}}}, "classifiers": ["Development Status :: 5 - Production/Stable", "Environment :: Web Environment", "Intended Audience :: Developers", "License :: OSI Approved :: BSD License", "Operating System :: OS Independent", "Programming Language :: Python", "Programming Language :: Python :: 2", "Programming Language :: Python :: 2.6", "Programming Language :: Python :: 2.7", "Programming Language :: Python :: 3", "Programming Language :: Python :: 3.3", "Programming Language :: Python :: 3.4", "Programming Language :: Python :: 3.5", "Topic :: Internet :: WWW/HTTP :: Dynamic Content", "Topic :: Software Development :: Libraries :: Python Modules", "Topic :: Text Processing :: Markup :: HTML"], "extras": ["i18n"]} \ No newline at end of file diff --git a/pyextra/Jinja2-2.9.6.dist-info/top_level.txt b/pyextra/Jinja2-2.9.6.dist-info/top_level.txt new file mode 100644 index 00000000000000..7f7afbf3bf54b3 --- /dev/null +++ b/pyextra/Jinja2-2.9.6.dist-info/top_level.txt @@ -0,0 +1 @@ +jinja2 diff --git a/pyextra/MarkupSafe-1.0-py2.7.egg-info/PKG-INFO b/pyextra/MarkupSafe-1.0-py2.7.egg-info/PKG-INFO new file mode 100644 index 00000000000000..6f2568f66ca65e --- /dev/null +++ b/pyextra/MarkupSafe-1.0-py2.7.egg-info/PKG-INFO @@ -0,0 +1,133 @@ +Metadata-Version: 1.1 +Name: MarkupSafe +Version: 1.0 +Summary: Implements a XML/HTML/XHTML Markup safe string for Python +Home-page: http://github.com/pallets/markupsafe +Author: Armin Ronacher +Author-email: armin.ronacher@active-4.com +License: BSD +Description: MarkupSafe + ========== + + Implements a unicode subclass that supports HTML strings: + + .. code-block:: python + + >>> from markupsafe import Markup, escape + >>> escape("") + Markup(u'<script>alert(document.cookie);</script>') + >>> tmpl = Markup("%s") + >>> tmpl % "Peter > Lustig" + Markup(u'Peter > Lustig') + + If you want to make an object unicode that is not yet unicode + but don't want to lose the taint information, you can use the + ``soft_unicode`` function. (On Python 3 you can also use ``soft_str`` which + is a different name for the same function). + + .. code-block:: python + + >>> from markupsafe import soft_unicode + >>> soft_unicode(42) + u'42' + >>> soft_unicode(Markup('foo')) + Markup(u'foo') + + HTML Representations + -------------------- + + Objects can customize their HTML markup equivalent by overriding + the ``__html__`` function: + + .. code-block:: python + + >>> class Foo(object): + ... def __html__(self): + ... return 'Nice' + ... + >>> escape(Foo()) + Markup(u'Nice') + >>> Markup(Foo()) + Markup(u'Nice') + + Silent Escapes + -------------- + + Since MarkupSafe 0.10 there is now also a separate escape function + called ``escape_silent`` that returns an empty string for ``None`` for + consistency with other systems that return empty strings for ``None`` + when escaping (for instance Pylons' webhelpers). + + If you also want to use this for the escape method of the Markup + object, you can create your own subclass that does that: + + .. code-block:: python + + from markupsafe import Markup, escape_silent as escape + + class SilentMarkup(Markup): + __slots__ = () + + @classmethod + def escape(cls, s): + return cls(escape(s)) + + New-Style String Formatting + --------------------------- + + Starting with MarkupSafe 0.21 new style string formats from Python 2.6 and + 3.x are now fully supported. Previously the escape behavior of those + functions was spotty at best. The new implementations operates under the + following algorithm: + + 1. if an object has an ``__html_format__`` method it is called as + replacement for ``__format__`` with the format specifier. It either + has to return a string or markup object. + 2. if an object has an ``__html__`` method it is called. + 3. otherwise the default format system of Python kicks in and the result + is HTML escaped. + + Here is how you can implement your own formatting: + + .. code-block:: python + + class User(object): + + def __init__(self, id, username): + self.id = id + self.username = username + + def __html_format__(self, format_spec): + if format_spec == 'link': + return Markup('{1}').format( + self.id, + self.__html__(), + ) + elif format_spec: + raise ValueError('Invalid format spec') + return self.__html__() + + def __html__(self): + return Markup('{0}').format(self.username) + + And to format that user: + + .. code-block:: python + + >>> user = User(1, 'foo') + >>> Markup('

User: {0:link}').format(user) + Markup(u'

User: foo') + + Markupsafe supports Python 2.6, 2.7 and Python 3.3 and higher. + +Platform: UNKNOWN +Classifier: Development Status :: 5 - Production/Stable +Classifier: Environment :: Web Environment +Classifier: Intended Audience :: Developers +Classifier: License :: OSI Approved :: BSD License +Classifier: Operating System :: OS Independent +Classifier: Programming Language :: Python +Classifier: Programming Language :: Python :: 3 +Classifier: Topic :: Internet :: WWW/HTTP :: Dynamic Content +Classifier: Topic :: Software Development :: Libraries :: Python Modules +Classifier: Topic :: Text Processing :: Markup :: HTML diff --git a/pyextra/MarkupSafe-1.0-py2.7.egg-info/SOURCES.txt b/pyextra/MarkupSafe-1.0-py2.7.egg-info/SOURCES.txt new file mode 100644 index 00000000000000..210b339ced2829 --- /dev/null +++ b/pyextra/MarkupSafe-1.0-py2.7.egg-info/SOURCES.txt @@ -0,0 +1,18 @@ +AUTHORS +CHANGES +LICENSE +MANIFEST.in +README.rst +setup.cfg +setup.py +tests.py +MarkupSafe.egg-info/PKG-INFO +MarkupSafe.egg-info/SOURCES.txt +MarkupSafe.egg-info/dependency_links.txt +MarkupSafe.egg-info/not-zip-safe +MarkupSafe.egg-info/top_level.txt +markupsafe/__init__.py +markupsafe/_compat.py +markupsafe/_constants.py +markupsafe/_native.py +markupsafe/_speedups.c \ No newline at end of file diff --git a/pyextra/MarkupSafe-1.0-py2.7.egg-info/dependency_links.txt b/pyextra/MarkupSafe-1.0-py2.7.egg-info/dependency_links.txt new file mode 100644 index 00000000000000..8b137891791fe9 --- /dev/null +++ b/pyextra/MarkupSafe-1.0-py2.7.egg-info/dependency_links.txt @@ -0,0 +1 @@ + diff --git a/pyextra/MarkupSafe-1.0-py2.7.egg-info/installed-files.txt b/pyextra/MarkupSafe-1.0-py2.7.egg-info/installed-files.txt new file mode 100644 index 00000000000000..0fcc7c5405c935 --- /dev/null +++ b/pyextra/MarkupSafe-1.0-py2.7.egg-info/installed-files.txt @@ -0,0 +1,15 @@ +../markupsafe/__init__.py +../markupsafe/_compat.py +../markupsafe/_constants.py +../markupsafe/_native.py +../markupsafe/_speedups.c +../markupsafe/__init__.pyc +../markupsafe/_compat.pyc +../markupsafe/_constants.pyc +../markupsafe/_native.pyc +../markupsafe/_speedups.so +dependency_links.txt +not-zip-safe +PKG-INFO +SOURCES.txt +top_level.txt diff --git a/pyextra/MarkupSafe-1.0-py2.7.egg-info/not-zip-safe b/pyextra/MarkupSafe-1.0-py2.7.egg-info/not-zip-safe new file mode 100644 index 00000000000000..8b137891791fe9 --- /dev/null +++ b/pyextra/MarkupSafe-1.0-py2.7.egg-info/not-zip-safe @@ -0,0 +1 @@ + diff --git a/pyextra/MarkupSafe-1.0-py2.7.egg-info/top_level.txt b/pyextra/MarkupSafe-1.0-py2.7.egg-info/top_level.txt new file mode 100644 index 00000000000000..75bf729258f9da --- /dev/null +++ b/pyextra/MarkupSafe-1.0-py2.7.egg-info/top_level.txt @@ -0,0 +1 @@ +markupsafe diff --git a/pyextra/Werkzeug-0.14.1-py2.7.egg-info/PKG-INFO b/pyextra/Werkzeug-0.14.1-py2.7.egg-info/PKG-INFO new file mode 100644 index 00000000000000..a0a627684d17d0 --- /dev/null +++ b/pyextra/Werkzeug-0.14.1-py2.7.egg-info/PKG-INFO @@ -0,0 +1,104 @@ +Metadata-Version: 1.1 +Name: Werkzeug +Version: 0.14.1 +Summary: The comprehensive WSGI web application library. +Home-page: https://www.palletsprojects.org/p/werkzeug/ +Author: Armin Ronacher +Author-email: armin.ronacher@active-4.com +License: BSD +Description: Werkzeug + ======== + + Werkzeug is a comprehensive `WSGI`_ web application library. It began as + a simple collection of various utilities for WSGI applications and has + become one of the most advanced WSGI utility libraries. + + It includes: + + * An interactive debugger that allows inspecting stack traces and source + code in the browser with an interactive interpreter for any frame in + the stack. + * A full-featured request object with objects to interact with headers, + query args, form data, files, and cookies. + * A response object that can wrap other WSGI applications and handle + streaming data. + * A routing system for matching URLs to endpoints and generating URLs + for endpoints, with an extensible system for capturing variables from + URLs. + * HTTP utilities to handle entity tags, cache control, dates, user + agents, cookies, files, and more. + * A threaded WSGI server for use while developing applications locally. + * A test client for simulating HTTP requests during testing without + requiring running a server. + + Werkzeug is Unicode aware and doesn't enforce any dependencies. It is up + to the developer to choose a template engine, database adapter, and even + how to handle requests. It can be used to build all sorts of end user + applications such as blogs, wikis, or bulletin boards. + + `Flask`_ wraps Werkzeug, using it to handle the details of WSGI while + providing more structure and patterns for defining powerful + applications. + + + Installing + ---------- + + Install and update using `pip`_: + + .. code-block:: text + + pip install -U Werkzeug + + + A Simple Example + ---------------- + + .. code-block:: python + + from werkzeug.wrappers import Request, Response + + @Request.application + def application(request): + return Response('Hello, World!') + + if __name__ == '__main__': + from werkzeug.serving import run_simple + run_simple('localhost', 4000, application) + + + Links + ----- + + * Website: https://www.palletsprojects.com/p/werkzeug/ + * Releases: https://pypi.org/project/Werkzeug/ + * Code: https://github.com/pallets/werkzeug + * Issue tracker: https://github.com/pallets/werkzeug/issues + * Test status: + + * Linux, Mac: https://travis-ci.org/pallets/werkzeug + * Windows: https://ci.appveyor.com/project/davidism/werkzeug + + * Test coverage: https://codecov.io/gh/pallets/werkzeug + + .. _WSGI: https://wsgi.readthedocs.io/en/latest/ + .. _Flask: https://www.palletsprojects.com/p/flask/ + .. _pip: https://pip.pypa.io/en/stable/quickstart/ + +Platform: any +Classifier: Development Status :: 5 - Production/Stable +Classifier: Environment :: Web Environment +Classifier: Intended Audience :: Developers +Classifier: License :: OSI Approved :: BSD License +Classifier: Operating System :: OS Independent +Classifier: Programming Language :: Python +Classifier: Programming Language :: Python :: 2 +Classifier: Programming Language :: Python :: 2.6 +Classifier: Programming Language :: Python :: 2.7 +Classifier: Programming Language :: Python :: 3 +Classifier: Programming Language :: Python :: 3.3 +Classifier: Programming Language :: Python :: 3.4 +Classifier: Programming Language :: Python :: 3.5 +Classifier: Programming Language :: Python :: 3.6 +Classifier: Topic :: Internet :: WWW/HTTP :: Dynamic Content +Classifier: Topic :: Software Development :: Libraries :: Python Modules diff --git a/pyextra/Werkzeug-0.14.1-py2.7.egg-info/SOURCES.txt b/pyextra/Werkzeug-0.14.1-py2.7.egg-info/SOURCES.txt new file mode 100644 index 00000000000000..9d3b7690895811 --- /dev/null +++ b/pyextra/Werkzeug-0.14.1-py2.7.egg-info/SOURCES.txt @@ -0,0 +1,299 @@ +AUTHORS +CHANGES.rst +LICENSE +MANIFEST.in +Makefile +README.rst +setup.cfg +setup.py +tox.ini +Werkzeug.egg-info/PKG-INFO +Werkzeug.egg-info/SOURCES.txt +Werkzeug.egg-info/dependency_links.txt +Werkzeug.egg-info/not-zip-safe +Werkzeug.egg-info/requires.txt +Werkzeug.egg-info/top_level.txt +artwork/.DS_Store +artwork/logo.png +artwork/logo.svg +docs/.DS_Store +docs/Makefile +docs/changes.rst +docs/conf.py +docs/contents.rst.inc +docs/datastructures.rst +docs/debug.rst +docs/exceptions.rst +docs/filesystem.rst +docs/http.rst +docs/index.rst +docs/installation.rst +docs/latexindex.rst +docs/levels.rst +docs/local.rst +docs/logo.pdf +docs/make.bat +docs/makearchive.py +docs/middlewares.rst +docs/python3.rst +docs/quickstart.rst +docs/request_data.rst +docs/routing.rst +docs/serving.rst +docs/terms.rst +docs/test.rst +docs/transition.rst +docs/tutorial.rst +docs/unicode.rst +docs/urls.rst +docs/utils.rst +docs/werkzeugext.py +docs/werkzeugstyle.sty +docs/wrappers.rst +docs/wsgi.rst +docs/_static/background.png +docs/_static/codebackground.png +docs/_static/contents.png +docs/_static/debug-screenshot.png +docs/_static/favicon.ico +docs/_static/header.png +docs/_static/navigation.png +docs/_static/navigation_active.png +docs/_static/shortly.png +docs/_static/shorty-screenshot.png +docs/_static/style.css +docs/_static/werkzeug.js +docs/_static/werkzeug.png +docs/_templates/sidebarintro.html +docs/_templates/sidebarlogo.html +docs/contrib/atom.rst +docs/contrib/cache.rst +docs/contrib/fixers.rst +docs/contrib/index.rst +docs/contrib/iterio.rst +docs/contrib/lint.rst +docs/contrib/profiler.rst +docs/contrib/securecookie.rst +docs/contrib/sessions.rst +docs/contrib/wrappers.rst +docs/deployment/cgi.rst +docs/deployment/fastcgi.rst +docs/deployment/index.rst +docs/deployment/mod_wsgi.rst +docs/deployment/proxying.rst +examples/README +examples/cookieauth.py +examples/httpbasicauth.py +examples/manage-coolmagic.py +examples/manage-couchy.py +examples/manage-cupoftee.py +examples/manage-i18nurls.py +examples/manage-plnt.py +examples/manage-shorty.py +examples/manage-simplewiki.py +examples/manage-webpylike.py +examples/upload.py +examples/contrib/README +examples/contrib/securecookie.py +examples/contrib/sessions.py +examples/coolmagic/__init__.py +examples/coolmagic/application.py +examples/coolmagic/helpers.py +examples/coolmagic/utils.py +examples/coolmagic/public/style.css +examples/coolmagic/templates/layout.html +examples/coolmagic/templates/static/about.html +examples/coolmagic/templates/static/index.html +examples/coolmagic/templates/static/not_found.html +examples/coolmagic/views/__init__.py +examples/coolmagic/views/static.py +examples/couchy/README +examples/couchy/__init__.py +examples/couchy/application.py +examples/couchy/models.py +examples/couchy/utils.py +examples/couchy/views.py +examples/couchy/static/style.css +examples/couchy/templates/display.html +examples/couchy/templates/layout.html +examples/couchy/templates/list.html +examples/couchy/templates/new.html +examples/couchy/templates/not_found.html +examples/cupoftee/__init__.py +examples/cupoftee/application.py +examples/cupoftee/db.py +examples/cupoftee/network.py +examples/cupoftee/pages.py +examples/cupoftee/utils.py +examples/cupoftee/shared/content.png +examples/cupoftee/shared/down.png +examples/cupoftee/shared/favicon.ico +examples/cupoftee/shared/header.png +examples/cupoftee/shared/logo.png +examples/cupoftee/shared/style.css +examples/cupoftee/shared/up.png +examples/cupoftee/templates/layout.html +examples/cupoftee/templates/missingpage.html +examples/cupoftee/templates/search.html +examples/cupoftee/templates/server.html +examples/cupoftee/templates/serverlist.html +examples/i18nurls/__init__.py +examples/i18nurls/application.py +examples/i18nurls/urls.py +examples/i18nurls/views.py +examples/i18nurls/templates/about.html +examples/i18nurls/templates/blog.html +examples/i18nurls/templates/index.html +examples/i18nurls/templates/layout.html +examples/partial/README +examples/partial/complex_routing.py +examples/plnt/__init__.py +examples/plnt/database.py +examples/plnt/sync.py +examples/plnt/utils.py +examples/plnt/views.py +examples/plnt/webapp.py +examples/plnt/shared/style.css +examples/plnt/templates/about.html +examples/plnt/templates/index.html +examples/plnt/templates/layout.html +examples/shortly/shortly.py +examples/shortly/static/style.css +examples/shortly/templates/404.html +examples/shortly/templates/layout.html +examples/shortly/templates/new_url.html +examples/shortly/templates/short_link_details.html +examples/shorty/__init__.py +examples/shorty/application.py +examples/shorty/models.py +examples/shorty/utils.py +examples/shorty/views.py +examples/shorty/static/style.css +examples/shorty/templates/display.html +examples/shorty/templates/layout.html +examples/shorty/templates/list.html +examples/shorty/templates/new.html +examples/shorty/templates/not_found.html +examples/simplewiki/__init__.py +examples/simplewiki/actions.py +examples/simplewiki/application.py +examples/simplewiki/database.py +examples/simplewiki/specialpages.py +examples/simplewiki/utils.py +examples/simplewiki/shared/style.css +examples/simplewiki/templates/action_diff.html +examples/simplewiki/templates/action_edit.html +examples/simplewiki/templates/action_log.html +examples/simplewiki/templates/action_revert.html +examples/simplewiki/templates/action_show.html +examples/simplewiki/templates/layout.html +examples/simplewiki/templates/macros.xml +examples/simplewiki/templates/missing_action.html +examples/simplewiki/templates/page_index.html +examples/simplewiki/templates/page_missing.html +examples/simplewiki/templates/recent_changes.html +examples/webpylike/example.py +examples/webpylike/webpylike.py +tests/__init__.py +tests/conftest.py +tests/test_compat.py +tests/test_datastructures.py +tests/test_debug.py +tests/test_exceptions.py +tests/test_formparser.py +tests/test_http.py +tests/test_internal.py +tests/test_local.py +tests/test_routing.py +tests/test_security.py +tests/test_serving.py +tests/test_test.py +tests/test_urls.py +tests/test_utils.py +tests/test_wrappers.py +tests/test_wsgi.py +tests/contrib/__init__.py +tests/contrib/test_atom.py +tests/contrib/test_cache.py +tests/contrib/test_fixers.py +tests/contrib/test_iterio.py +tests/contrib/test_securecookie.py +tests/contrib/test_sessions.py +tests/contrib/test_wrappers.py +tests/contrib/cache/conftest.py +tests/contrib/cache/test_cache.py +tests/hypothesis/__init__.py +tests/hypothesis/test_urls.py +tests/multipart/__init__.py +tests/multipart/ie7_full_path_request.txt +tests/multipart/test_collect.py +tests/multipart/firefox3-2png1txt/file1.png +tests/multipart/firefox3-2png1txt/file2.png +tests/multipart/firefox3-2png1txt/request.txt +tests/multipart/firefox3-2png1txt/text.txt +tests/multipart/firefox3-2pnglongtext/file1.png +tests/multipart/firefox3-2pnglongtext/file2.png +tests/multipart/firefox3-2pnglongtext/request.txt +tests/multipart/firefox3-2pnglongtext/text.txt +tests/multipart/ie6-2png1txt/file1.png +tests/multipart/ie6-2png1txt/file2.png +tests/multipart/ie6-2png1txt/request.txt +tests/multipart/ie6-2png1txt/text.txt +tests/multipart/opera8-2png1txt/file1.png +tests/multipart/opera8-2png1txt/file2.png +tests/multipart/opera8-2png1txt/request.txt +tests/multipart/opera8-2png1txt/text.txt +tests/multipart/webkit3-2png1txt/file1.png +tests/multipart/webkit3-2png1txt/file2.png +tests/multipart/webkit3-2png1txt/request.txt +tests/multipart/webkit3-2png1txt/text.txt +tests/res/chunked.txt +tests/res/test.txt +werkzeug/__init__.py +werkzeug/_compat.py +werkzeug/_internal.py +werkzeug/_reloader.py +werkzeug/datastructures.py +werkzeug/exceptions.py +werkzeug/filesystem.py +werkzeug/formparser.py +werkzeug/http.py +werkzeug/local.py +werkzeug/posixemulation.py +werkzeug/routing.py +werkzeug/security.py +werkzeug/serving.py +werkzeug/test.py +werkzeug/testapp.py +werkzeug/urls.py +werkzeug/useragents.py +werkzeug/utils.py +werkzeug/websocket.py +werkzeug/wrappers.py +werkzeug/wsgi.py +werkzeug/contrib/__init__.py +werkzeug/contrib/atom.py +werkzeug/contrib/cache.py +werkzeug/contrib/fixers.py +werkzeug/contrib/iterio.py +werkzeug/contrib/jsrouting.py +werkzeug/contrib/limiter.py +werkzeug/contrib/lint.py +werkzeug/contrib/profiler.py +werkzeug/contrib/securecookie.py +werkzeug/contrib/sessions.py +werkzeug/contrib/testtools.py +werkzeug/contrib/wrappers.py +werkzeug/debug/__init__.py +werkzeug/debug/console.py +werkzeug/debug/repr.py +werkzeug/debug/tbtools.py +werkzeug/debug/shared/FONT_LICENSE +werkzeug/debug/shared/console.png +werkzeug/debug/shared/debugger.js +werkzeug/debug/shared/jquery.js +werkzeug/debug/shared/less.png +werkzeug/debug/shared/more.png +werkzeug/debug/shared/source.png +werkzeug/debug/shared/style.css +werkzeug/debug/shared/ubuntu.ttf \ No newline at end of file diff --git a/pyextra/Werkzeug-0.14.1-py2.7.egg-info/dependency_links.txt b/pyextra/Werkzeug-0.14.1-py2.7.egg-info/dependency_links.txt new file mode 100644 index 00000000000000..8b137891791fe9 --- /dev/null +++ b/pyextra/Werkzeug-0.14.1-py2.7.egg-info/dependency_links.txt @@ -0,0 +1 @@ + diff --git a/pyextra/Werkzeug-0.14.1-py2.7.egg-info/installed-files.txt b/pyextra/Werkzeug-0.14.1-py2.7.egg-info/installed-files.txt new file mode 100644 index 00000000000000..105fb3c0b60939 --- /dev/null +++ b/pyextra/Werkzeug-0.14.1-py2.7.egg-info/installed-files.txt @@ -0,0 +1,93 @@ +../werkzeug/_reloader.py +../werkzeug/_internal.py +../werkzeug/serving.py +../werkzeug/local.py +../werkzeug/filesystem.py +../werkzeug/security.py +../werkzeug/__init__.py +../werkzeug/test.py +../werkzeug/formparser.py +../werkzeug/posixemulation.py +../werkzeug/utils.py +../werkzeug/wrappers.py +../werkzeug/routing.py +../werkzeug/http.py +../werkzeug/useragents.py +../werkzeug/exceptions.py +../werkzeug/_compat.py +../werkzeug/datastructures.py +../werkzeug/urls.py +../werkzeug/websocket.py +../werkzeug/wsgi.py +../werkzeug/testapp.py +../werkzeug/contrib/sessions.py +../werkzeug/contrib/cache.py +../werkzeug/contrib/__init__.py +../werkzeug/contrib/testtools.py +../werkzeug/contrib/wrappers.py +../werkzeug/contrib/jsrouting.py +../werkzeug/contrib/fixers.py +../werkzeug/contrib/profiler.py +../werkzeug/contrib/iterio.py +../werkzeug/contrib/atom.py +../werkzeug/contrib/securecookie.py +../werkzeug/contrib/limiter.py +../werkzeug/contrib/lint.py +../werkzeug/debug/console.py +../werkzeug/debug/tbtools.py +../werkzeug/debug/__init__.py +../werkzeug/debug/repr.py +../werkzeug/debug/shared/FONT_LICENSE +../werkzeug/debug/shared/console.png +../werkzeug/debug/shared/debugger.js +../werkzeug/debug/shared/jquery.js +../werkzeug/debug/shared/less.png +../werkzeug/debug/shared/more.png +../werkzeug/debug/shared/source.png +../werkzeug/debug/shared/style.css +../werkzeug/debug/shared/ubuntu.ttf +../werkzeug/_reloader.pyc +../werkzeug/_internal.pyc +../werkzeug/serving.pyc +../werkzeug/local.pyc +../werkzeug/filesystem.pyc +../werkzeug/security.pyc +../werkzeug/__init__.pyc +../werkzeug/test.pyc +../werkzeug/formparser.pyc +../werkzeug/posixemulation.pyc +../werkzeug/utils.pyc +../werkzeug/wrappers.pyc +../werkzeug/routing.pyc +../werkzeug/http.pyc +../werkzeug/useragents.pyc +../werkzeug/exceptions.pyc +../werkzeug/_compat.pyc +../werkzeug/datastructures.pyc +../werkzeug/urls.pyc +../werkzeug/websocket.pyc +../werkzeug/wsgi.pyc +../werkzeug/testapp.pyc +../werkzeug/contrib/sessions.pyc +../werkzeug/contrib/cache.pyc +../werkzeug/contrib/__init__.pyc +../werkzeug/contrib/testtools.pyc +../werkzeug/contrib/wrappers.pyc +../werkzeug/contrib/jsrouting.pyc +../werkzeug/contrib/fixers.pyc +../werkzeug/contrib/profiler.pyc +../werkzeug/contrib/iterio.pyc +../werkzeug/contrib/atom.pyc +../werkzeug/contrib/securecookie.pyc +../werkzeug/contrib/limiter.pyc +../werkzeug/contrib/lint.pyc +../werkzeug/debug/console.pyc +../werkzeug/debug/tbtools.pyc +../werkzeug/debug/__init__.pyc +../werkzeug/debug/repr.pyc +PKG-INFO +not-zip-safe +SOURCES.txt +requires.txt +top_level.txt +dependency_links.txt diff --git a/pyextra/Werkzeug-0.14.1-py2.7.egg-info/not-zip-safe b/pyextra/Werkzeug-0.14.1-py2.7.egg-info/not-zip-safe new file mode 100644 index 00000000000000..8b137891791fe9 --- /dev/null +++ b/pyextra/Werkzeug-0.14.1-py2.7.egg-info/not-zip-safe @@ -0,0 +1 @@ + diff --git a/pyextra/Werkzeug-0.14.1-py2.7.egg-info/requires.txt b/pyextra/Werkzeug-0.14.1-py2.7.egg-info/requires.txt new file mode 100644 index 00000000000000..dd8c7c51f12455 --- /dev/null +++ b/pyextra/Werkzeug-0.14.1-py2.7.egg-info/requires.txt @@ -0,0 +1,12 @@ + +[dev] +pytest +coverage +tox +sphinx + +[termcolor] +termcolor + +[watchdog] +watchdog diff --git a/pyextra/Werkzeug-0.14.1-py2.7.egg-info/top_level.txt b/pyextra/Werkzeug-0.14.1-py2.7.egg-info/top_level.txt new file mode 100644 index 00000000000000..6fe8da8499399d --- /dev/null +++ b/pyextra/Werkzeug-0.14.1-py2.7.egg-info/top_level.txt @@ -0,0 +1 @@ +werkzeug diff --git a/pyextra/bin/flask b/pyextra/bin/flask new file mode 100755 index 00000000000000..2adb78c4a57b77 --- /dev/null +++ b/pyextra/bin/flask @@ -0,0 +1,10 @@ +#!/usr/local/bin/python +# EASY-INSTALL-ENTRY-SCRIPT: 'Flask==1.0.2','console_scripts','flask' +__requires__ = 'Flask==1.0.2' +import sys +from pkg_resources import load_entry_point + +if __name__ == '__main__': + sys.exit( + load_entry_point('Flask==1.0.2', 'console_scripts', 'flask')() + ) diff --git a/pyextra/click-6.7-py2.7.egg-info/PKG-INFO b/pyextra/click-6.7-py2.7.egg-info/PKG-INFO new file mode 100644 index 00000000000000..bbb17b38331c58 --- /dev/null +++ b/pyextra/click-6.7-py2.7.egg-info/PKG-INFO @@ -0,0 +1,13 @@ +Metadata-Version: 1.1 +Name: click +Version: 6.7 +Summary: A simple wrapper around optparse for powerful command line utilities. +Home-page: http://github.com/mitsuhiko/click +Author: Armin Ronacher +Author-email: armin.ronacher@active-4.com +License: UNKNOWN +Description: UNKNOWN +Platform: UNKNOWN +Classifier: License :: OSI Approved :: BSD License +Classifier: Programming Language :: Python +Classifier: Programming Language :: Python :: 3 diff --git a/pyextra/click-6.7-py2.7.egg-info/SOURCES.txt b/pyextra/click-6.7-py2.7.egg-info/SOURCES.txt new file mode 100644 index 00000000000000..5eed4349ef6793 --- /dev/null +++ b/pyextra/click-6.7-py2.7.egg-info/SOURCES.txt @@ -0,0 +1,114 @@ +CHANGES +LICENSE +MANIFEST.in +Makefile +README +setup.cfg +setup.py +artwork/logo.svg +click/__init__.py +click/_bashcomplete.py +click/_compat.py +click/_termui_impl.py +click/_textwrap.py +click/_unicodefun.py +click/_winconsole.py +click/core.py +click/decorators.py +click/exceptions.py +click/formatting.py +click/globals.py +click/parser.py +click/termui.py +click/testing.py +click/types.py +click/utils.py +click.egg-info/PKG-INFO +click.egg-info/SOURCES.txt +click.egg-info/dependency_links.txt +click.egg-info/top_level.txt +docs/Makefile +docs/advanced.rst +docs/api.rst +docs/arguments.rst +docs/bashcomplete.rst +docs/changelog.rst +docs/clickdoctools.py +docs/commands.rst +docs/complex.rst +docs/conf.py +docs/contrib.rst +docs/documentation.rst +docs/exceptions.rst +docs/index.rst +docs/license.rst +docs/make.bat +docs/options.rst +docs/parameters.rst +docs/prompts.rst +docs/python3.rst +docs/quickstart.rst +docs/setuptools.rst +docs/testing.rst +docs/upgrading.rst +docs/utils.rst +docs/why.rst +docs/wincmd.rst +docs/_static/click-small.png +docs/_static/click-small@2x.png +docs/_static/click.png +docs/_static/click@2x.png +docs/_templates/sidebarintro.html +docs/_templates/sidebarlogo.html +examples/README +examples/aliases/README +examples/aliases/aliases.ini +examples/aliases/aliases.py +examples/aliases/setup.py +examples/colors/README +examples/colors/colors.py +examples/colors/setup.py +examples/complex/README +examples/complex/setup.py +examples/complex/complex/__init__.py +examples/complex/complex/cli.py +examples/complex/complex/commands/__init__.py +examples/complex/complex/commands/cmd_init.py +examples/complex/complex/commands/cmd_status.py +examples/imagepipe/.gitignore +examples/imagepipe/README +examples/imagepipe/example01.jpg +examples/imagepipe/example02.jpg +examples/imagepipe/imagepipe.py +examples/imagepipe/setup.py +examples/inout/README +examples/inout/inout.py +examples/inout/setup.py +examples/naval/README +examples/naval/naval.py +examples/naval/setup.py +examples/repo/README +examples/repo/repo.py +examples/repo/setup.py +examples/termui/README +examples/termui/setup.py +examples/termui/termui.py +examples/validation/README +examples/validation/setup.py +examples/validation/validation.py +tests/conftest.py +tests/test_arguments.py +tests/test_bashcomplete.py +tests/test_basic.py +tests/test_chain.py +tests/test_commands.py +tests/test_compat.py +tests/test_context.py +tests/test_defaults.py +tests/test_formatting.py +tests/test_imports.py +tests/test_normalization.py +tests/test_options.py +tests/test_termui.py +tests/test_testing.py +tests/test_utils.py \ No newline at end of file diff --git a/pyextra/click-6.7-py2.7.egg-info/dependency_links.txt b/pyextra/click-6.7-py2.7.egg-info/dependency_links.txt new file mode 100644 index 00000000000000..8b137891791fe9 --- /dev/null +++ b/pyextra/click-6.7-py2.7.egg-info/dependency_links.txt @@ -0,0 +1 @@ + diff --git a/pyextra/click-6.7-py2.7.egg-info/installed-files.txt b/pyextra/click-6.7-py2.7.egg-info/installed-files.txt new file mode 100644 index 00000000000000..63d1b52c135353 --- /dev/null +++ b/pyextra/click-6.7-py2.7.egg-info/installed-files.txt @@ -0,0 +1,38 @@ +../click/exceptions.py +../click/testing.py +../click/decorators.py +../click/parser.py +../click/formatting.py +../click/globals.py +../click/_termui_impl.py +../click/__init__.py +../click/_compat.py +../click/_winconsole.py +../click/_unicodefun.py +../click/_textwrap.py +../click/_bashcomplete.py +../click/core.py +../click/types.py +../click/termui.py +../click/utils.py +../click/exceptions.pyc +../click/testing.pyc +../click/decorators.pyc +../click/parser.pyc +../click/formatting.pyc +../click/globals.pyc +../click/_termui_impl.pyc +../click/__init__.pyc +../click/_compat.pyc +../click/_winconsole.pyc +../click/_unicodefun.pyc +../click/_textwrap.pyc +../click/_bashcomplete.pyc +../click/core.pyc +../click/types.pyc +../click/termui.pyc +../click/utils.pyc +SOURCES.txt +top_level.txt +PKG-INFO +dependency_links.txt diff --git a/pyextra/click-6.7-py2.7.egg-info/top_level.txt b/pyextra/click-6.7-py2.7.egg-info/top_level.txt new file mode 100644 index 00000000000000..dca9a909647e3b --- /dev/null +++ b/pyextra/click-6.7-py2.7.egg-info/top_level.txt @@ -0,0 +1 @@ +click diff --git a/pyextra/click/__init__.py b/pyextra/click/__init__.py new file mode 100644 index 00000000000000..971e55d0a8c6de --- /dev/null +++ b/pyextra/click/__init__.py @@ -0,0 +1,98 @@ +# -*- coding: utf-8 -*- +""" + click + ~~~~~ + + Click is a simple Python module that wraps the stdlib's optparse to make + writing command line scripts fun. Unlike other modules, it's based around + a simple API that does not come with too much magic and is composable. + + In case optparse ever gets removed from the stdlib, it will be shipped by + this module. + + :copyright: (c) 2014 by Armin Ronacher. + :license: BSD, see LICENSE for more details. +""" + +# Core classes +from .core import Context, BaseCommand, Command, MultiCommand, Group, \ + CommandCollection, Parameter, Option, Argument + +# Globals +from .globals import get_current_context + +# Decorators +from .decorators import pass_context, pass_obj, make_pass_decorator, \ + command, group, argument, option, confirmation_option, \ + password_option, version_option, help_option + +# Types +from .types import ParamType, File, Path, Choice, IntRange, Tuple, \ + STRING, INT, FLOAT, BOOL, UUID, UNPROCESSED + +# Utilities +from .utils import echo, get_binary_stream, get_text_stream, open_file, \ + format_filename, get_app_dir, get_os_args + +# Terminal functions +from .termui import prompt, confirm, get_terminal_size, echo_via_pager, \ + progressbar, clear, style, unstyle, secho, edit, launch, getchar, \ + pause + +# Exceptions +from .exceptions import ClickException, UsageError, BadParameter, \ + FileError, Abort, NoSuchOption, BadOptionUsage, BadArgumentUsage, \ + MissingParameter + +# Formatting +from .formatting import HelpFormatter, wrap_text + +# Parsing +from .parser import OptionParser + + +__all__ = [ + # Core classes + 'Context', 'BaseCommand', 'Command', 'MultiCommand', 'Group', + 'CommandCollection', 'Parameter', 'Option', 'Argument', + + # Globals + 'get_current_context', + + # Decorators + 'pass_context', 'pass_obj', 'make_pass_decorator', 'command', 'group', + 'argument', 'option', 'confirmation_option', 'password_option', + 'version_option', 'help_option', + + # Types + 'ParamType', 'File', 'Path', 'Choice', 'IntRange', 'Tuple', 'STRING', + 'INT', 'FLOAT', 'BOOL', 'UUID', 'UNPROCESSED', + + # Utilities + 'echo', 'get_binary_stream', 'get_text_stream', 'open_file', + 'format_filename', 'get_app_dir', 'get_os_args', + + # Terminal functions + 'prompt', 'confirm', 'get_terminal_size', 'echo_via_pager', + 'progressbar', 'clear', 'style', 'unstyle', 'secho', 'edit', 'launch', + 'getchar', 'pause', + + # Exceptions + 'ClickException', 'UsageError', 'BadParameter', 'FileError', + 'Abort', 'NoSuchOption', 'BadOptionUsage', 'BadArgumentUsage', + 'MissingParameter', + + # Formatting + 'HelpFormatter', 'wrap_text', + + # Parsing + 'OptionParser', +] + + +# Controls if click should emit the warning about the use of unicode +# literals. +disable_unicode_literals_warning = False + + +__version__ = '6.7' diff --git a/pyextra/click/_bashcomplete.py b/pyextra/click/_bashcomplete.py new file mode 100644 index 00000000000000..d9d26d28b053de --- /dev/null +++ b/pyextra/click/_bashcomplete.py @@ -0,0 +1,83 @@ +import os +import re +from .utils import echo +from .parser import split_arg_string +from .core import MultiCommand, Option + + +COMPLETION_SCRIPT = ''' +%(complete_func)s() { + COMPREPLY=( $( env COMP_WORDS="${COMP_WORDS[*]}" \\ + COMP_CWORD=$COMP_CWORD \\ + %(autocomplete_var)s=complete $1 ) ) + return 0 +} + +complete -F %(complete_func)s -o default %(script_names)s +''' + +_invalid_ident_char_re = re.compile(r'[^a-zA-Z0-9_]') + + +def get_completion_script(prog_name, complete_var): + cf_name = _invalid_ident_char_re.sub('', prog_name.replace('-', '_')) + return (COMPLETION_SCRIPT % { + 'complete_func': '_%s_completion' % cf_name, + 'script_names': prog_name, + 'autocomplete_var': complete_var, + }).strip() + ';' + + +def resolve_ctx(cli, prog_name, args): + ctx = cli.make_context(prog_name, args, resilient_parsing=True) + while ctx.protected_args + ctx.args and isinstance(ctx.command, MultiCommand): + a = ctx.protected_args + ctx.args + cmd = ctx.command.get_command(ctx, a[0]) + if cmd is None: + return None + ctx = cmd.make_context(a[0], a[1:], parent=ctx, resilient_parsing=True) + return ctx + + +def get_choices(cli, prog_name, args, incomplete): + ctx = resolve_ctx(cli, prog_name, args) + if ctx is None: + return + + choices = [] + if incomplete and not incomplete[:1].isalnum(): + for param in ctx.command.params: + if not isinstance(param, Option): + continue + choices.extend(param.opts) + choices.extend(param.secondary_opts) + elif isinstance(ctx.command, MultiCommand): + choices.extend(ctx.command.list_commands(ctx)) + + for item in choices: + if item.startswith(incomplete): + yield item + + +def do_complete(cli, prog_name): + cwords = split_arg_string(os.environ['COMP_WORDS']) + cword = int(os.environ['COMP_CWORD']) + args = cwords[1:cword] + try: + incomplete = cwords[cword] + except IndexError: + incomplete = '' + + for item in get_choices(cli, prog_name, args, incomplete): + echo(item) + + return True + + +def bashcomplete(cli, prog_name, complete_var, complete_instr): + if complete_instr == 'source': + echo(get_completion_script(prog_name, complete_var)) + return True + elif complete_instr == 'complete': + return do_complete(cli, prog_name) + return False diff --git a/pyextra/click/_compat.py b/pyextra/click/_compat.py new file mode 100644 index 00000000000000..2b43412c4d6026 --- /dev/null +++ b/pyextra/click/_compat.py @@ -0,0 +1,648 @@ +import re +import io +import os +import sys +import codecs +from weakref import WeakKeyDictionary + + +PY2 = sys.version_info[0] == 2 +WIN = sys.platform.startswith('win') +DEFAULT_COLUMNS = 80 + + +_ansi_re = re.compile('\033\[((?:\d|;)*)([a-zA-Z])') + + +def get_filesystem_encoding(): + return sys.getfilesystemencoding() or sys.getdefaultencoding() + + +def _make_text_stream(stream, encoding, errors): + if encoding is None: + encoding = get_best_encoding(stream) + if errors is None: + errors = 'replace' + return _NonClosingTextIOWrapper(stream, encoding, errors, + line_buffering=True) + + +def is_ascii_encoding(encoding): + """Checks if a given encoding is ascii.""" + try: + return codecs.lookup(encoding).name == 'ascii' + except LookupError: + return False + + +def get_best_encoding(stream): + """Returns the default stream encoding if not found.""" + rv = getattr(stream, 'encoding', None) or sys.getdefaultencoding() + if is_ascii_encoding(rv): + return 'utf-8' + return rv + + +class _NonClosingTextIOWrapper(io.TextIOWrapper): + + def __init__(self, stream, encoding, errors, **extra): + self._stream = stream = _FixupStream(stream) + io.TextIOWrapper.__init__(self, stream, encoding, errors, **extra) + + # The io module is a place where the Python 3 text behavior + # was forced upon Python 2, so we need to unbreak + # it to look like Python 2. + if PY2: + def write(self, x): + if isinstance(x, str) or is_bytes(x): + try: + self.flush() + except Exception: + pass + return self.buffer.write(str(x)) + return io.TextIOWrapper.write(self, x) + + def writelines(self, lines): + for line in lines: + self.write(line) + + def __del__(self): + try: + self.detach() + except Exception: + pass + + def isatty(self): + # https://bitbucket.org/pypy/pypy/issue/1803 + return self._stream.isatty() + + +class _FixupStream(object): + """The new io interface needs more from streams than streams + traditionally implement. As such, this fix-up code is necessary in + some circumstances. + """ + + def __init__(self, stream): + self._stream = stream + + def __getattr__(self, name): + return getattr(self._stream, name) + + def read1(self, size): + f = getattr(self._stream, 'read1', None) + if f is not None: + return f(size) + # We only dispatch to readline instead of read in Python 2 as we + # do not want cause problems with the different implementation + # of line buffering. + if PY2: + return self._stream.readline(size) + return self._stream.read(size) + + def readable(self): + x = getattr(self._stream, 'readable', None) + if x is not None: + return x() + try: + self._stream.read(0) + except Exception: + return False + return True + + def writable(self): + x = getattr(self._stream, 'writable', None) + if x is not None: + return x() + try: + self._stream.write('') + except Exception: + try: + self._stream.write(b'') + except Exception: + return False + return True + + def seekable(self): + x = getattr(self._stream, 'seekable', None) + if x is not None: + return x() + try: + self._stream.seek(self._stream.tell()) + except Exception: + return False + return True + + +if PY2: + text_type = unicode + bytes = str + raw_input = raw_input + string_types = (str, unicode) + iteritems = lambda x: x.iteritems() + range_type = xrange + + def is_bytes(x): + return isinstance(x, (buffer, bytearray)) + + _identifier_re = re.compile(r'^[a-zA-Z_][a-zA-Z0-9_]*$') + + # For Windows, we need to force stdout/stdin/stderr to binary if it's + # fetched for that. This obviously is not the most correct way to do + # it as it changes global state. Unfortunately, there does not seem to + # be a clear better way to do it as just reopening the file in binary + # mode does not change anything. + # + # An option would be to do what Python 3 does and to open the file as + # binary only, patch it back to the system, and then use a wrapper + # stream that converts newlines. It's not quite clear what's the + # correct option here. + # + # This code also lives in _winconsole for the fallback to the console + # emulation stream. + # + # There are also Windows environments where the `msvcrt` module is not + # available (which is why we use try-catch instead of the WIN variable + # here), such as the Google App Engine development server on Windows. In + # those cases there is just nothing we can do. + try: + import msvcrt + except ImportError: + set_binary_mode = lambda x: x + else: + def set_binary_mode(f): + try: + fileno = f.fileno() + except Exception: + pass + else: + msvcrt.setmode(fileno, os.O_BINARY) + return f + + def isidentifier(x): + return _identifier_re.search(x) is not None + + def get_binary_stdin(): + return set_binary_mode(sys.stdin) + + def get_binary_stdout(): + return set_binary_mode(sys.stdout) + + def get_binary_stderr(): + return set_binary_mode(sys.stderr) + + def get_text_stdin(encoding=None, errors=None): + rv = _get_windows_console_stream(sys.stdin, encoding, errors) + if rv is not None: + return rv + return _make_text_stream(sys.stdin, encoding, errors) + + def get_text_stdout(encoding=None, errors=None): + rv = _get_windows_console_stream(sys.stdout, encoding, errors) + if rv is not None: + return rv + return _make_text_stream(sys.stdout, encoding, errors) + + def get_text_stderr(encoding=None, errors=None): + rv = _get_windows_console_stream(sys.stderr, encoding, errors) + if rv is not None: + return rv + return _make_text_stream(sys.stderr, encoding, errors) + + def filename_to_ui(value): + if isinstance(value, bytes): + value = value.decode(get_filesystem_encoding(), 'replace') + return value +else: + import io + text_type = str + raw_input = input + string_types = (str,) + range_type = range + isidentifier = lambda x: x.isidentifier() + iteritems = lambda x: iter(x.items()) + + def is_bytes(x): + return isinstance(x, (bytes, memoryview, bytearray)) + + def _is_binary_reader(stream, default=False): + try: + return isinstance(stream.read(0), bytes) + except Exception: + return default + # This happens in some cases where the stream was already + # closed. In this case, we assume the default. + + def _is_binary_writer(stream, default=False): + try: + stream.write(b'') + except Exception: + try: + stream.write('') + return False + except Exception: + pass + return default + return True + + def _find_binary_reader(stream): + # We need to figure out if the given stream is already binary. + # This can happen because the official docs recommend detaching + # the streams to get binary streams. Some code might do this, so + # we need to deal with this case explicitly. + if _is_binary_reader(stream, False): + return stream + + buf = getattr(stream, 'buffer', None) + + # Same situation here; this time we assume that the buffer is + # actually binary in case it's closed. + if buf is not None and _is_binary_reader(buf, True): + return buf + + def _find_binary_writer(stream): + # We need to figure out if the given stream is already binary. + # This can happen because the official docs recommend detatching + # the streams to get binary streams. Some code might do this, so + # we need to deal with this case explicitly. + if _is_binary_writer(stream, False): + return stream + + buf = getattr(stream, 'buffer', None) + + # Same situation here; this time we assume that the buffer is + # actually binary in case it's closed. + if buf is not None and _is_binary_writer(buf, True): + return buf + + def _stream_is_misconfigured(stream): + """A stream is misconfigured if its encoding is ASCII.""" + # If the stream does not have an encoding set, we assume it's set + # to ASCII. This appears to happen in certain unittest + # environments. It's not quite clear what the correct behavior is + # but this at least will force Click to recover somehow. + return is_ascii_encoding(getattr(stream, 'encoding', None) or 'ascii') + + def _is_compatible_text_stream(stream, encoding, errors): + stream_encoding = getattr(stream, 'encoding', None) + stream_errors = getattr(stream, 'errors', None) + + # Perfect match. + if stream_encoding == encoding and stream_errors == errors: + return True + + # Otherwise, it's only a compatible stream if we did not ask for + # an encoding. + if encoding is None: + return stream_encoding is not None + + return False + + def _force_correct_text_reader(text_reader, encoding, errors): + if _is_binary_reader(text_reader, False): + binary_reader = text_reader + else: + # If there is no target encoding set, we need to verify that the + # reader is not actually misconfigured. + if encoding is None and not _stream_is_misconfigured(text_reader): + return text_reader + + if _is_compatible_text_stream(text_reader, encoding, errors): + return text_reader + + # If the reader has no encoding, we try to find the underlying + # binary reader for it. If that fails because the environment is + # misconfigured, we silently go with the same reader because this + # is too common to happen. In that case, mojibake is better than + # exceptions. + binary_reader = _find_binary_reader(text_reader) + if binary_reader is None: + return text_reader + + # At this point, we default the errors to replace instead of strict + # because nobody handles those errors anyways and at this point + # we're so fundamentally fucked that nothing can repair it. + if errors is None: + errors = 'replace' + return _make_text_stream(binary_reader, encoding, errors) + + def _force_correct_text_writer(text_writer, encoding, errors): + if _is_binary_writer(text_writer, False): + binary_writer = text_writer + else: + # If there is no target encoding set, we need to verify that the + # writer is not actually misconfigured. + if encoding is None and not _stream_is_misconfigured(text_writer): + return text_writer + + if _is_compatible_text_stream(text_writer, encoding, errors): + return text_writer + + # If the writer has no encoding, we try to find the underlying + # binary writer for it. If that fails because the environment is + # misconfigured, we silently go with the same writer because this + # is too common to happen. In that case, mojibake is better than + # exceptions. + binary_writer = _find_binary_writer(text_writer) + if binary_writer is None: + return text_writer + + # At this point, we default the errors to replace instead of strict + # because nobody handles those errors anyways and at this point + # we're so fundamentally fucked that nothing can repair it. + if errors is None: + errors = 'replace' + return _make_text_stream(binary_writer, encoding, errors) + + def get_binary_stdin(): + reader = _find_binary_reader(sys.stdin) + if reader is None: + raise RuntimeError('Was not able to determine binary ' + 'stream for sys.stdin.') + return reader + + def get_binary_stdout(): + writer = _find_binary_writer(sys.stdout) + if writer is None: + raise RuntimeError('Was not able to determine binary ' + 'stream for sys.stdout.') + return writer + + def get_binary_stderr(): + writer = _find_binary_writer(sys.stderr) + if writer is None: + raise RuntimeError('Was not able to determine binary ' + 'stream for sys.stderr.') + return writer + + def get_text_stdin(encoding=None, errors=None): + rv = _get_windows_console_stream(sys.stdin, encoding, errors) + if rv is not None: + return rv + return _force_correct_text_reader(sys.stdin, encoding, errors) + + def get_text_stdout(encoding=None, errors=None): + rv = _get_windows_console_stream(sys.stdout, encoding, errors) + if rv is not None: + return rv + return _force_correct_text_writer(sys.stdout, encoding, errors) + + def get_text_stderr(encoding=None, errors=None): + rv = _get_windows_console_stream(sys.stderr, encoding, errors) + if rv is not None: + return rv + return _force_correct_text_writer(sys.stderr, encoding, errors) + + def filename_to_ui(value): + if isinstance(value, bytes): + value = value.decode(get_filesystem_encoding(), 'replace') + else: + value = value.encode('utf-8', 'surrogateescape') \ + .decode('utf-8', 'replace') + return value + + +def get_streerror(e, default=None): + if hasattr(e, 'strerror'): + msg = e.strerror + else: + if default is not None: + msg = default + else: + msg = str(e) + if isinstance(msg, bytes): + msg = msg.decode('utf-8', 'replace') + return msg + + +def open_stream(filename, mode='r', encoding=None, errors='strict', + atomic=False): + # Standard streams first. These are simple because they don't need + # special handling for the atomic flag. It's entirely ignored. + if filename == '-': + if 'w' in mode: + if 'b' in mode: + return get_binary_stdout(), False + return get_text_stdout(encoding=encoding, errors=errors), False + if 'b' in mode: + return get_binary_stdin(), False + return get_text_stdin(encoding=encoding, errors=errors), False + + # Non-atomic writes directly go out through the regular open functions. + if not atomic: + if encoding is None: + return open(filename, mode), True + return io.open(filename, mode, encoding=encoding, errors=errors), True + + # Some usability stuff for atomic writes + if 'a' in mode: + raise ValueError( + 'Appending to an existing file is not supported, because that ' + 'would involve an expensive `copy`-operation to a temporary ' + 'file. Open the file in normal `w`-mode and copy explicitly ' + 'if that\'s what you\'re after.' + ) + if 'x' in mode: + raise ValueError('Use the `overwrite`-parameter instead.') + if 'w' not in mode: + raise ValueError('Atomic writes only make sense with `w`-mode.') + + # Atomic writes are more complicated. They work by opening a file + # as a proxy in the same folder and then using the fdopen + # functionality to wrap it in a Python file. Then we wrap it in an + # atomic file that moves the file over on close. + import tempfile + fd, tmp_filename = tempfile.mkstemp(dir=os.path.dirname(filename), + prefix='.__atomic-write') + + if encoding is not None: + f = io.open(fd, mode, encoding=encoding, errors=errors) + else: + f = os.fdopen(fd, mode) + + return _AtomicFile(f, tmp_filename, filename), True + + +# Used in a destructor call, needs extra protection from interpreter cleanup. +if hasattr(os, 'replace'): + _replace = os.replace + _can_replace = True +else: + _replace = os.rename + _can_replace = not WIN + + +class _AtomicFile(object): + + def __init__(self, f, tmp_filename, real_filename): + self._f = f + self._tmp_filename = tmp_filename + self._real_filename = real_filename + self.closed = False + + @property + def name(self): + return self._real_filename + + def close(self, delete=False): + if self.closed: + return + self._f.close() + if not _can_replace: + try: + os.remove(self._real_filename) + except OSError: + pass + _replace(self._tmp_filename, self._real_filename) + self.closed = True + + def __getattr__(self, name): + return getattr(self._f, name) + + def __enter__(self): + return self + + def __exit__(self, exc_type, exc_value, tb): + self.close(delete=exc_type is not None) + + def __repr__(self): + return repr(self._f) + + +auto_wrap_for_ansi = None +colorama = None +get_winterm_size = None + + +def strip_ansi(value): + return _ansi_re.sub('', value) + + +def should_strip_ansi(stream=None, color=None): + if color is None: + if stream is None: + stream = sys.stdin + return not isatty(stream) + return not color + + +# If we're on Windows, we provide transparent integration through +# colorama. This will make ANSI colors through the echo function +# work automatically. +if WIN: + # Windows has a smaller terminal + DEFAULT_COLUMNS = 79 + + from ._winconsole import _get_windows_console_stream + + def _get_argv_encoding(): + import locale + return locale.getpreferredencoding() + + if PY2: + def raw_input(prompt=''): + sys.stderr.flush() + if prompt: + stdout = _default_text_stdout() + stdout.write(prompt) + stdin = _default_text_stdin() + return stdin.readline().rstrip('\r\n') + + try: + import colorama + except ImportError: + pass + else: + _ansi_stream_wrappers = WeakKeyDictionary() + + def auto_wrap_for_ansi(stream, color=None): + """This function wraps a stream so that calls through colorama + are issued to the win32 console API to recolor on demand. It + also ensures to reset the colors if a write call is interrupted + to not destroy the console afterwards. + """ + try: + cached = _ansi_stream_wrappers.get(stream) + except Exception: + cached = None + if cached is not None: + return cached + strip = should_strip_ansi(stream, color) + ansi_wrapper = colorama.AnsiToWin32(stream, strip=strip) + rv = ansi_wrapper.stream + _write = rv.write + + def _safe_write(s): + try: + return _write(s) + except: + ansi_wrapper.reset_all() + raise + + rv.write = _safe_write + try: + _ansi_stream_wrappers[stream] = rv + except Exception: + pass + return rv + + def get_winterm_size(): + win = colorama.win32.GetConsoleScreenBufferInfo( + colorama.win32.STDOUT).srWindow + return win.Right - win.Left, win.Bottom - win.Top +else: + def _get_argv_encoding(): + return getattr(sys.stdin, 'encoding', None) or get_filesystem_encoding() + + _get_windows_console_stream = lambda *x: None + + +def term_len(x): + return len(strip_ansi(x)) + + +def isatty(stream): + try: + return stream.isatty() + except Exception: + return False + + +def _make_cached_stream_func(src_func, wrapper_func): + cache = WeakKeyDictionary() + def func(): + stream = src_func() + try: + rv = cache.get(stream) + except Exception: + rv = None + if rv is not None: + return rv + rv = wrapper_func() + try: + cache[stream] = rv + except Exception: + pass + return rv + return func + + +_default_text_stdin = _make_cached_stream_func( + lambda: sys.stdin, get_text_stdin) +_default_text_stdout = _make_cached_stream_func( + lambda: sys.stdout, get_text_stdout) +_default_text_stderr = _make_cached_stream_func( + lambda: sys.stderr, get_text_stderr) + + +binary_streams = { + 'stdin': get_binary_stdin, + 'stdout': get_binary_stdout, + 'stderr': get_binary_stderr, +} + +text_streams = { + 'stdin': get_text_stdin, + 'stdout': get_text_stdout, + 'stderr': get_text_stderr, +} diff --git a/pyextra/click/_termui_impl.py b/pyextra/click/_termui_impl.py new file mode 100644 index 00000000000000..7cfd3d5c4a058b --- /dev/null +++ b/pyextra/click/_termui_impl.py @@ -0,0 +1,547 @@ +""" + click._termui_impl + ~~~~~~~~~~~~~~~~~~ + + This module contains implementations for the termui module. To keep the + import time of Click down, some infrequently used functionality is placed + in this module and only imported as needed. + + :copyright: (c) 2014 by Armin Ronacher. + :license: BSD, see LICENSE for more details. +""" +import os +import sys +import time +import math +from ._compat import _default_text_stdout, range_type, PY2, isatty, \ + open_stream, strip_ansi, term_len, get_best_encoding, WIN +from .utils import echo +from .exceptions import ClickException + + +if os.name == 'nt': + BEFORE_BAR = '\r' + AFTER_BAR = '\n' +else: + BEFORE_BAR = '\r\033[?25l' + AFTER_BAR = '\033[?25h\n' + + +def _length_hint(obj): + """Returns the length hint of an object.""" + try: + return len(obj) + except (AttributeError, TypeError): + try: + get_hint = type(obj).__length_hint__ + except AttributeError: + return None + try: + hint = get_hint(obj) + except TypeError: + return None + if hint is NotImplemented or \ + not isinstance(hint, (int, long)) or \ + hint < 0: + return None + return hint + + +class ProgressBar(object): + + def __init__(self, iterable, length=None, fill_char='#', empty_char=' ', + bar_template='%(bar)s', info_sep=' ', show_eta=True, + show_percent=None, show_pos=False, item_show_func=None, + label=None, file=None, color=None, width=30): + self.fill_char = fill_char + self.empty_char = empty_char + self.bar_template = bar_template + self.info_sep = info_sep + self.show_eta = show_eta + self.show_percent = show_percent + self.show_pos = show_pos + self.item_show_func = item_show_func + self.label = label or '' + if file is None: + file = _default_text_stdout() + self.file = file + self.color = color + self.width = width + self.autowidth = width == 0 + + if length is None: + length = _length_hint(iterable) + if iterable is None: + if length is None: + raise TypeError('iterable or length is required') + iterable = range_type(length) + self.iter = iter(iterable) + self.length = length + self.length_known = length is not None + self.pos = 0 + self.avg = [] + self.start = self.last_eta = time.time() + self.eta_known = False + self.finished = False + self.max_width = None + self.entered = False + self.current_item = None + self.is_hidden = not isatty(self.file) + self._last_line = None + + def __enter__(self): + self.entered = True + self.render_progress() + return self + + def __exit__(self, exc_type, exc_value, tb): + self.render_finish() + + def __iter__(self): + if not self.entered: + raise RuntimeError('You need to use progress bars in a with block.') + self.render_progress() + return self + + def render_finish(self): + if self.is_hidden: + return + self.file.write(AFTER_BAR) + self.file.flush() + + @property + def pct(self): + if self.finished: + return 1.0 + return min(self.pos / (float(self.length) or 1), 1.0) + + @property + def time_per_iteration(self): + if not self.avg: + return 0.0 + return sum(self.avg) / float(len(self.avg)) + + @property + def eta(self): + if self.length_known and not self.finished: + return self.time_per_iteration * (self.length - self.pos) + return 0.0 + + def format_eta(self): + if self.eta_known: + t = self.eta + 1 + seconds = t % 60 + t /= 60 + minutes = t % 60 + t /= 60 + hours = t % 24 + t /= 24 + if t > 0: + days = t + return '%dd %02d:%02d:%02d' % (days, hours, minutes, seconds) + else: + return '%02d:%02d:%02d' % (hours, minutes, seconds) + return '' + + def format_pos(self): + pos = str(self.pos) + if self.length_known: + pos += '/%s' % self.length + return pos + + def format_pct(self): + return ('% 4d%%' % int(self.pct * 100))[1:] + + def format_progress_line(self): + show_percent = self.show_percent + + info_bits = [] + if self.length_known: + bar_length = int(self.pct * self.width) + bar = self.fill_char * bar_length + bar += self.empty_char * (self.width - bar_length) + if show_percent is None: + show_percent = not self.show_pos + else: + if self.finished: + bar = self.fill_char * self.width + else: + bar = list(self.empty_char * (self.width or 1)) + if self.time_per_iteration != 0: + bar[int((math.cos(self.pos * self.time_per_iteration) + / 2.0 + 0.5) * self.width)] = self.fill_char + bar = ''.join(bar) + + if self.show_pos: + info_bits.append(self.format_pos()) + if show_percent: + info_bits.append(self.format_pct()) + if self.show_eta and self.eta_known and not self.finished: + info_bits.append(self.format_eta()) + if self.item_show_func is not None: + item_info = self.item_show_func(self.current_item) + if item_info is not None: + info_bits.append(item_info) + + return (self.bar_template % { + 'label': self.label, + 'bar': bar, + 'info': self.info_sep.join(info_bits) + }).rstrip() + + def render_progress(self): + from .termui import get_terminal_size + nl = False + + if self.is_hidden: + buf = [self.label] + nl = True + else: + buf = [] + # Update width in case the terminal has been resized + if self.autowidth: + old_width = self.width + self.width = 0 + clutter_length = term_len(self.format_progress_line()) + new_width = max(0, get_terminal_size()[0] - clutter_length) + if new_width < old_width: + buf.append(BEFORE_BAR) + buf.append(' ' * self.max_width) + self.max_width = new_width + self.width = new_width + + clear_width = self.width + if self.max_width is not None: + clear_width = self.max_width + + buf.append(BEFORE_BAR) + line = self.format_progress_line() + line_len = term_len(line) + if self.max_width is None or self.max_width < line_len: + self.max_width = line_len + buf.append(line) + + buf.append(' ' * (clear_width - line_len)) + line = ''.join(buf) + + # Render the line only if it changed. + if line != self._last_line: + self._last_line = line + echo(line, file=self.file, color=self.color, nl=nl) + self.file.flush() + + def make_step(self, n_steps): + self.pos += n_steps + if self.length_known and self.pos >= self.length: + self.finished = True + + if (time.time() - self.last_eta) < 1.0: + return + + self.last_eta = time.time() + self.avg = self.avg[-6:] + [-(self.start - time.time()) / (self.pos)] + + self.eta_known = self.length_known + + def update(self, n_steps): + self.make_step(n_steps) + self.render_progress() + + def finish(self): + self.eta_known = 0 + self.current_item = None + self.finished = True + + def next(self): + if self.is_hidden: + return next(self.iter) + try: + rv = next(self.iter) + self.current_item = rv + except StopIteration: + self.finish() + self.render_progress() + raise StopIteration() + else: + self.update(1) + return rv + + if not PY2: + __next__ = next + del next + + +def pager(text, color=None): + """Decide what method to use for paging through text.""" + stdout = _default_text_stdout() + if not isatty(sys.stdin) or not isatty(stdout): + return _nullpager(stdout, text, color) + pager_cmd = (os.environ.get('PAGER', None) or '').strip() + if pager_cmd: + if WIN: + return _tempfilepager(text, pager_cmd, color) + return _pipepager(text, pager_cmd, color) + if os.environ.get('TERM') in ('dumb', 'emacs'): + return _nullpager(stdout, text, color) + if WIN or sys.platform.startswith('os2'): + return _tempfilepager(text, 'more <', color) + if hasattr(os, 'system') and os.system('(less) 2>/dev/null') == 0: + return _pipepager(text, 'less', color) + + import tempfile + fd, filename = tempfile.mkstemp() + os.close(fd) + try: + if hasattr(os, 'system') and os.system('more "%s"' % filename) == 0: + return _pipepager(text, 'more', color) + return _nullpager(stdout, text, color) + finally: + os.unlink(filename) + + +def _pipepager(text, cmd, color): + """Page through text by feeding it to another program. Invoking a + pager through this might support colors. + """ + import subprocess + env = dict(os.environ) + + # If we're piping to less we might support colors under the + # condition that + cmd_detail = cmd.rsplit('/', 1)[-1].split() + if color is None and cmd_detail[0] == 'less': + less_flags = os.environ.get('LESS', '') + ' '.join(cmd_detail[1:]) + if not less_flags: + env['LESS'] = '-R' + color = True + elif 'r' in less_flags or 'R' in less_flags: + color = True + + if not color: + text = strip_ansi(text) + + c = subprocess.Popen(cmd, shell=True, stdin=subprocess.PIPE, + env=env) + encoding = get_best_encoding(c.stdin) + try: + c.stdin.write(text.encode(encoding, 'replace')) + c.stdin.close() + except (IOError, KeyboardInterrupt): + pass + + # Less doesn't respect ^C, but catches it for its own UI purposes (aborting + # search or other commands inside less). + # + # That means when the user hits ^C, the parent process (click) terminates, + # but less is still alive, paging the output and messing up the terminal. + # + # If the user wants to make the pager exit on ^C, they should set + # `LESS='-K'`. It's not our decision to make. + while True: + try: + c.wait() + except KeyboardInterrupt: + pass + else: + break + + +def _tempfilepager(text, cmd, color): + """Page through text by invoking a program on a temporary file.""" + import tempfile + filename = tempfile.mktemp() + if not color: + text = strip_ansi(text) + encoding = get_best_encoding(sys.stdout) + with open_stream(filename, 'wb')[0] as f: + f.write(text.encode(encoding)) + try: + os.system(cmd + ' "' + filename + '"') + finally: + os.unlink(filename) + + +def _nullpager(stream, text, color): + """Simply print unformatted text. This is the ultimate fallback.""" + if not color: + text = strip_ansi(text) + stream.write(text) + + +class Editor(object): + + def __init__(self, editor=None, env=None, require_save=True, + extension='.txt'): + self.editor = editor + self.env = env + self.require_save = require_save + self.extension = extension + + def get_editor(self): + if self.editor is not None: + return self.editor + for key in 'VISUAL', 'EDITOR': + rv = os.environ.get(key) + if rv: + return rv + if WIN: + return 'notepad' + for editor in 'vim', 'nano': + if os.system('which %s >/dev/null 2>&1' % editor) == 0: + return editor + return 'vi' + + def edit_file(self, filename): + import subprocess + editor = self.get_editor() + if self.env: + environ = os.environ.copy() + environ.update(self.env) + else: + environ = None + try: + c = subprocess.Popen('%s "%s"' % (editor, filename), + env=environ, shell=True) + exit_code = c.wait() + if exit_code != 0: + raise ClickException('%s: Editing failed!' % editor) + except OSError as e: + raise ClickException('%s: Editing failed: %s' % (editor, e)) + + def edit(self, text): + import tempfile + + text = text or '' + if text and not text.endswith('\n'): + text += '\n' + + fd, name = tempfile.mkstemp(prefix='editor-', suffix=self.extension) + try: + if WIN: + encoding = 'utf-8-sig' + text = text.replace('\n', '\r\n') + else: + encoding = 'utf-8' + text = text.encode(encoding) + + f = os.fdopen(fd, 'wb') + f.write(text) + f.close() + timestamp = os.path.getmtime(name) + + self.edit_file(name) + + if self.require_save \ + and os.path.getmtime(name) == timestamp: + return None + + f = open(name, 'rb') + try: + rv = f.read() + finally: + f.close() + return rv.decode('utf-8-sig').replace('\r\n', '\n') + finally: + os.unlink(name) + + +def open_url(url, wait=False, locate=False): + import subprocess + + def _unquote_file(url): + try: + import urllib + except ImportError: + import urllib + if url.startswith('file://'): + url = urllib.unquote(url[7:]) + return url + + if sys.platform == 'darwin': + args = ['open'] + if wait: + args.append('-W') + if locate: + args.append('-R') + args.append(_unquote_file(url)) + null = open('/dev/null', 'w') + try: + return subprocess.Popen(args, stderr=null).wait() + finally: + null.close() + elif WIN: + if locate: + url = _unquote_file(url) + args = 'explorer /select,"%s"' % _unquote_file( + url.replace('"', '')) + else: + args = 'start %s "" "%s"' % ( + wait and '/WAIT' or '', url.replace('"', '')) + return os.system(args) + + try: + if locate: + url = os.path.dirname(_unquote_file(url)) or '.' + else: + url = _unquote_file(url) + c = subprocess.Popen(['xdg-open', url]) + if wait: + return c.wait() + return 0 + except OSError: + if url.startswith(('http://', 'https://')) and not locate and not wait: + import webbrowser + webbrowser.open(url) + return 0 + return 1 + + +def _translate_ch_to_exc(ch): + if ch == '\x03': + raise KeyboardInterrupt() + if ch == '\x04': + raise EOFError() + + +if WIN: + import msvcrt + + def getchar(echo): + rv = msvcrt.getch() + if echo: + msvcrt.putchar(rv) + _translate_ch_to_exc(rv) + if PY2: + enc = getattr(sys.stdin, 'encoding', None) + if enc is not None: + rv = rv.decode(enc, 'replace') + else: + rv = rv.decode('cp1252', 'replace') + return rv +else: + import tty + import termios + + def getchar(echo): + if not isatty(sys.stdin): + f = open('/dev/tty') + fd = f.fileno() + else: + fd = sys.stdin.fileno() + f = None + try: + old_settings = termios.tcgetattr(fd) + try: + tty.setraw(fd) + ch = os.read(fd, 32) + if echo and isatty(sys.stdout): + sys.stdout.write(ch) + finally: + termios.tcsetattr(fd, termios.TCSADRAIN, old_settings) + sys.stdout.flush() + if f is not None: + f.close() + except termios.error: + pass + _translate_ch_to_exc(ch) + return ch.decode(get_best_encoding(sys.stdin), 'replace') diff --git a/pyextra/click/_textwrap.py b/pyextra/click/_textwrap.py new file mode 100644 index 00000000000000..7e776031eaa929 --- /dev/null +++ b/pyextra/click/_textwrap.py @@ -0,0 +1,38 @@ +import textwrap +from contextlib import contextmanager + + +class TextWrapper(textwrap.TextWrapper): + + def _handle_long_word(self, reversed_chunks, cur_line, cur_len, width): + space_left = max(width - cur_len, 1) + + if self.break_long_words: + last = reversed_chunks[-1] + cut = last[:space_left] + res = last[space_left:] + cur_line.append(cut) + reversed_chunks[-1] = res + elif not cur_line: + cur_line.append(reversed_chunks.pop()) + + @contextmanager + def extra_indent(self, indent): + old_initial_indent = self.initial_indent + old_subsequent_indent = self.subsequent_indent + self.initial_indent += indent + self.subsequent_indent += indent + try: + yield + finally: + self.initial_indent = old_initial_indent + self.subsequent_indent = old_subsequent_indent + + def indent_only(self, text): + rv = [] + for idx, line in enumerate(text.splitlines()): + indent = self.initial_indent + if idx > 0: + indent = self.subsequent_indent + rv.append(indent + line) + return '\n'.join(rv) diff --git a/pyextra/click/_unicodefun.py b/pyextra/click/_unicodefun.py new file mode 100644 index 00000000000000..9e17a384eff036 --- /dev/null +++ b/pyextra/click/_unicodefun.py @@ -0,0 +1,118 @@ +import os +import sys +import codecs + +from ._compat import PY2 + + +# If someone wants to vendor click, we want to ensure the +# correct package is discovered. Ideally we could use a +# relative import here but unfortunately Python does not +# support that. +click = sys.modules[__name__.rsplit('.', 1)[0]] + + +def _find_unicode_literals_frame(): + import __future__ + frm = sys._getframe(1) + idx = 1 + while frm is not None: + if frm.f_globals.get('__name__', '').startswith('click.'): + frm = frm.f_back + idx += 1 + elif frm.f_code.co_flags & __future__.unicode_literals.compiler_flag: + return idx + else: + break + return 0 + + +def _check_for_unicode_literals(): + if not __debug__: + return + if not PY2 or click.disable_unicode_literals_warning: + return + bad_frame = _find_unicode_literals_frame() + if bad_frame <= 0: + return + from warnings import warn + warn(Warning('Click detected the use of the unicode_literals ' + '__future__ import. This is heavily discouraged ' + 'because it can introduce subtle bugs in your ' + 'code. You should instead use explicit u"" literals ' + 'for your unicode strings. For more information see ' + 'http://click.pocoo.org/python3/'), + stacklevel=bad_frame) + + +def _verify_python3_env(): + """Ensures that the environment is good for unicode on Python 3.""" + if PY2: + return + try: + import locale + fs_enc = codecs.lookup(locale.getpreferredencoding()).name + except Exception: + fs_enc = 'ascii' + if fs_enc != 'ascii': + return + + extra = '' + if os.name == 'posix': + import subprocess + rv = subprocess.Popen(['locale', '-a'], stdout=subprocess.PIPE, + stderr=subprocess.PIPE).communicate()[0] + good_locales = set() + has_c_utf8 = False + + # Make sure we're operating on text here. + if isinstance(rv, bytes): + rv = rv.decode('ascii', 'replace') + + for line in rv.splitlines(): + locale = line.strip() + if locale.lower().endswith(('.utf-8', '.utf8')): + good_locales.add(locale) + if locale.lower() in ('c.utf8', 'c.utf-8'): + has_c_utf8 = True + + extra += '\n\n' + if not good_locales: + extra += ( + 'Additional information: on this system no suitable UTF-8\n' + 'locales were discovered. This most likely requires resolving\n' + 'by reconfiguring the locale system.' + ) + elif has_c_utf8: + extra += ( + 'This system supports the C.UTF-8 locale which is recommended.\n' + 'You might be able to resolve your issue by exporting the\n' + 'following environment variables:\n\n' + ' export LC_ALL=C.UTF-8\n' + ' export LANG=C.UTF-8' + ) + else: + extra += ( + 'This system lists a couple of UTF-8 supporting locales that\n' + 'you can pick from. The following suitable locales where\n' + 'discovered: %s' + ) % ', '.join(sorted(good_locales)) + + bad_locale = None + for locale in os.environ.get('LC_ALL'), os.environ.get('LANG'): + if locale and locale.lower().endswith(('.utf-8', '.utf8')): + bad_locale = locale + if locale is not None: + break + if bad_locale is not None: + extra += ( + '\n\nClick discovered that you exported a UTF-8 locale\n' + 'but the locale system could not pick up from it because\n' + 'it does not exist. The exported locale is "%s" but it\n' + 'is not supported' + ) % bad_locale + + raise RuntimeError('Click will abort further execution because Python 3 ' + 'was configured to use ASCII as encoding for the ' + 'environment. Consult http://click.pocoo.org/python3/' + 'for mitigation steps.' + extra) diff --git a/pyextra/click/_winconsole.py b/pyextra/click/_winconsole.py new file mode 100644 index 00000000000000..9aed942162bbdd --- /dev/null +++ b/pyextra/click/_winconsole.py @@ -0,0 +1,273 @@ +# -*- coding: utf-8 -*- +# This module is based on the excellent work by Adam Bartoš who +# provided a lot of what went into the implementation here in +# the discussion to issue1602 in the Python bug tracker. +# +# There are some general differences in regards to how this works +# compared to the original patches as we do not need to patch +# the entire interpreter but just work in our little world of +# echo and prmopt. + +import io +import os +import sys +import zlib +import time +import ctypes +import msvcrt +from click._compat import _NonClosingTextIOWrapper, text_type, PY2 +from ctypes import byref, POINTER, c_int, c_char, c_char_p, \ + c_void_p, py_object, c_ssize_t, c_ulong, windll, WINFUNCTYPE +try: + from ctypes import pythonapi + PyObject_GetBuffer = pythonapi.PyObject_GetBuffer + PyBuffer_Release = pythonapi.PyBuffer_Release +except ImportError: + pythonapi = None +from ctypes.wintypes import LPWSTR, LPCWSTR + + +c_ssize_p = POINTER(c_ssize_t) + +kernel32 = windll.kernel32 +GetStdHandle = kernel32.GetStdHandle +ReadConsoleW = kernel32.ReadConsoleW +WriteConsoleW = kernel32.WriteConsoleW +GetLastError = kernel32.GetLastError +GetCommandLineW = WINFUNCTYPE(LPWSTR)( + ('GetCommandLineW', windll.kernel32)) +CommandLineToArgvW = WINFUNCTYPE( + POINTER(LPWSTR), LPCWSTR, POINTER(c_int))( + ('CommandLineToArgvW', windll.shell32)) + + +STDIN_HANDLE = GetStdHandle(-10) +STDOUT_HANDLE = GetStdHandle(-11) +STDERR_HANDLE = GetStdHandle(-12) + + +PyBUF_SIMPLE = 0 +PyBUF_WRITABLE = 1 + +ERROR_SUCCESS = 0 +ERROR_NOT_ENOUGH_MEMORY = 8 +ERROR_OPERATION_ABORTED = 995 + +STDIN_FILENO = 0 +STDOUT_FILENO = 1 +STDERR_FILENO = 2 + +EOF = b'\x1a' +MAX_BYTES_WRITTEN = 32767 + + +class Py_buffer(ctypes.Structure): + _fields_ = [ + ('buf', c_void_p), + ('obj', py_object), + ('len', c_ssize_t), + ('itemsize', c_ssize_t), + ('readonly', c_int), + ('ndim', c_int), + ('format', c_char_p), + ('shape', c_ssize_p), + ('strides', c_ssize_p), + ('suboffsets', c_ssize_p), + ('internal', c_void_p) + ] + + if PY2: + _fields_.insert(-1, ('smalltable', c_ssize_t * 2)) + + +# On PyPy we cannot get buffers so our ability to operate here is +# serverly limited. +if pythonapi is None: + get_buffer = None +else: + def get_buffer(obj, writable=False): + buf = Py_buffer() + flags = PyBUF_WRITABLE if writable else PyBUF_SIMPLE + PyObject_GetBuffer(py_object(obj), byref(buf), flags) + try: + buffer_type = c_char * buf.len + return buffer_type.from_address(buf.buf) + finally: + PyBuffer_Release(byref(buf)) + + +class _WindowsConsoleRawIOBase(io.RawIOBase): + + def __init__(self, handle): + self.handle = handle + + def isatty(self): + io.RawIOBase.isatty(self) + return True + + +class _WindowsConsoleReader(_WindowsConsoleRawIOBase): + + def readable(self): + return True + + def readinto(self, b): + bytes_to_be_read = len(b) + if not bytes_to_be_read: + return 0 + elif bytes_to_be_read % 2: + raise ValueError('cannot read odd number of bytes from ' + 'UTF-16-LE encoded console') + + buffer = get_buffer(b, writable=True) + code_units_to_be_read = bytes_to_be_read // 2 + code_units_read = c_ulong() + + rv = ReadConsoleW(self.handle, buffer, code_units_to_be_read, + byref(code_units_read), None) + if GetLastError() == ERROR_OPERATION_ABORTED: + # wait for KeyboardInterrupt + time.sleep(0.1) + if not rv: + raise OSError('Windows error: %s' % GetLastError()) + + if buffer[0] == EOF: + return 0 + return 2 * code_units_read.value + + +class _WindowsConsoleWriter(_WindowsConsoleRawIOBase): + + def writable(self): + return True + + @staticmethod + def _get_error_message(errno): + if errno == ERROR_SUCCESS: + return 'ERROR_SUCCESS' + elif errno == ERROR_NOT_ENOUGH_MEMORY: + return 'ERROR_NOT_ENOUGH_MEMORY' + return 'Windows error %s' % errno + + def write(self, b): + bytes_to_be_written = len(b) + buf = get_buffer(b) + code_units_to_be_written = min(bytes_to_be_written, + MAX_BYTES_WRITTEN) // 2 + code_units_written = c_ulong() + + WriteConsoleW(self.handle, buf, code_units_to_be_written, + byref(code_units_written), None) + bytes_written = 2 * code_units_written.value + + if bytes_written == 0 and bytes_to_be_written > 0: + raise OSError(self._get_error_message(GetLastError())) + return bytes_written + + +class ConsoleStream(object): + + def __init__(self, text_stream, byte_stream): + self._text_stream = text_stream + self.buffer = byte_stream + + @property + def name(self): + return self.buffer.name + + def write(self, x): + if isinstance(x, text_type): + return self._text_stream.write(x) + try: + self.flush() + except Exception: + pass + return self.buffer.write(x) + + def writelines(self, lines): + for line in lines: + self.write(line) + + def __getattr__(self, name): + return getattr(self._text_stream, name) + + def isatty(self): + return self.buffer.isatty() + + def __repr__(self): + return '' % ( + self.name, + self.encoding, + ) + + +def _get_text_stdin(buffer_stream): + text_stream = _NonClosingTextIOWrapper( + io.BufferedReader(_WindowsConsoleReader(STDIN_HANDLE)), + 'utf-16-le', 'strict', line_buffering=True) + return ConsoleStream(text_stream, buffer_stream) + + +def _get_text_stdout(buffer_stream): + text_stream = _NonClosingTextIOWrapper( + _WindowsConsoleWriter(STDOUT_HANDLE), + 'utf-16-le', 'strict', line_buffering=True) + return ConsoleStream(text_stream, buffer_stream) + + +def _get_text_stderr(buffer_stream): + text_stream = _NonClosingTextIOWrapper( + _WindowsConsoleWriter(STDERR_HANDLE), + 'utf-16-le', 'strict', line_buffering=True) + return ConsoleStream(text_stream, buffer_stream) + + +if PY2: + def _hash_py_argv(): + return zlib.crc32('\x00'.join(sys.argv[1:])) + + _initial_argv_hash = _hash_py_argv() + + def _get_windows_argv(): + argc = c_int(0) + argv_unicode = CommandLineToArgvW(GetCommandLineW(), byref(argc)) + argv = [argv_unicode[i] for i in range(0, argc.value)] + + if not hasattr(sys, 'frozen'): + argv = argv[1:] + while len(argv) > 0: + arg = argv[0] + if not arg.startswith('-') or arg == '-': + break + argv = argv[1:] + if arg.startswith(('-c', '-m')): + break + + return argv[1:] + + +_stream_factories = { + 0: _get_text_stdin, + 1: _get_text_stdout, + 2: _get_text_stderr, +} + + +def _get_windows_console_stream(f, encoding, errors): + if get_buffer is not None and \ + encoding in ('utf-16-le', None) \ + and errors in ('strict', None) and \ + hasattr(f, 'isatty') and f.isatty(): + func = _stream_factories.get(f.fileno()) + if func is not None: + if not PY2: + f = getattr(f, 'buffer') + if f is None: + return None + else: + # If we are on Python 2 we need to set the stream that we + # deal with to binary mode as otherwise the exercise if a + # bit moot. The same problems apply as for + # get_binary_stdin and friends from _compat. + msvcrt.setmode(f.fileno(), os.O_BINARY) + return func(f) diff --git a/pyextra/click/core.py b/pyextra/click/core.py new file mode 100644 index 00000000000000..74564514753131 --- /dev/null +++ b/pyextra/click/core.py @@ -0,0 +1,1744 @@ +import errno +import os +import sys +from contextlib import contextmanager +from itertools import repeat +from functools import update_wrapper + +from .types import convert_type, IntRange, BOOL +from .utils import make_str, make_default_short_help, echo, get_os_args +from .exceptions import ClickException, UsageError, BadParameter, Abort, \ + MissingParameter +from .termui import prompt, confirm +from .formatting import HelpFormatter, join_options +from .parser import OptionParser, split_opt +from .globals import push_context, pop_context + +from ._compat import PY2, isidentifier, iteritems +from ._unicodefun import _check_for_unicode_literals, _verify_python3_env + + +_missing = object() + + +SUBCOMMAND_METAVAR = 'COMMAND [ARGS]...' +SUBCOMMANDS_METAVAR = 'COMMAND1 [ARGS]... [COMMAND2 [ARGS]...]...' + + +def _bashcomplete(cmd, prog_name, complete_var=None): + """Internal handler for the bash completion support.""" + if complete_var is None: + complete_var = '_%s_COMPLETE' % (prog_name.replace('-', '_')).upper() + complete_instr = os.environ.get(complete_var) + if not complete_instr: + return + + from ._bashcomplete import bashcomplete + if bashcomplete(cmd, prog_name, complete_var, complete_instr): + sys.exit(1) + + +def _check_multicommand(base_command, cmd_name, cmd, register=False): + if not base_command.chain or not isinstance(cmd, MultiCommand): + return + if register: + hint = 'It is not possible to add multi commands as children to ' \ + 'another multi command that is in chain mode' + else: + hint = 'Found a multi command as subcommand to a multi command ' \ + 'that is in chain mode. This is not supported' + raise RuntimeError('%s. Command "%s" is set to chain and "%s" was ' + 'added as subcommand but it in itself is a ' + 'multi command. ("%s" is a %s within a chained ' + '%s named "%s"). This restriction was supposed to ' + 'be lifted in 6.0 but the fix was flawed. This ' + 'will be fixed in Click 7.0' % ( + hint, base_command.name, cmd_name, + cmd_name, cmd.__class__.__name__, + base_command.__class__.__name__, + base_command.name)) + + +def batch(iterable, batch_size): + return list(zip(*repeat(iter(iterable), batch_size))) + + +def invoke_param_callback(callback, ctx, param, value): + code = getattr(callback, '__code__', None) + args = getattr(code, 'co_argcount', 3) + + if args < 3: + # This will become a warning in Click 3.0: + from warnings import warn + warn(Warning('Invoked legacy parameter callback "%s". The new ' + 'signature for such callbacks starting with ' + 'click 2.0 is (ctx, param, value).' + % callback), stacklevel=3) + return callback(ctx, value) + return callback(ctx, param, value) + + +@contextmanager +def augment_usage_errors(ctx, param=None): + """Context manager that attaches extra information to exceptions that + fly. + """ + try: + yield + except BadParameter as e: + if e.ctx is None: + e.ctx = ctx + if param is not None and e.param is None: + e.param = param + raise + except UsageError as e: + if e.ctx is None: + e.ctx = ctx + raise + + +def iter_params_for_processing(invocation_order, declaration_order): + """Given a sequence of parameters in the order as should be considered + for processing and an iterable of parameters that exist, this returns + a list in the correct order as they should be processed. + """ + def sort_key(item): + try: + idx = invocation_order.index(item) + except ValueError: + idx = float('inf') + return (not item.is_eager, idx) + + return sorted(declaration_order, key=sort_key) + + +class Context(object): + """The context is a special internal object that holds state relevant + for the script execution at every single level. It's normally invisible + to commands unless they opt-in to getting access to it. + + The context is useful as it can pass internal objects around and can + control special execution features such as reading data from + environment variables. + + A context can be used as context manager in which case it will call + :meth:`close` on teardown. + + .. versionadded:: 2.0 + Added the `resilient_parsing`, `help_option_names`, + `token_normalize_func` parameters. + + .. versionadded:: 3.0 + Added the `allow_extra_args` and `allow_interspersed_args` + parameters. + + .. versionadded:: 4.0 + Added the `color`, `ignore_unknown_options`, and + `max_content_width` parameters. + + :param command: the command class for this context. + :param parent: the parent context. + :param info_name: the info name for this invocation. Generally this + is the most descriptive name for the script or + command. For the toplevel script it is usually + the name of the script, for commands below it it's + the name of the script. + :param obj: an arbitrary object of user data. + :param auto_envvar_prefix: the prefix to use for automatic environment + variables. If this is `None` then reading + from environment variables is disabled. This + does not affect manually set environment + variables which are always read. + :param default_map: a dictionary (like object) with default values + for parameters. + :param terminal_width: the width of the terminal. The default is + inherit from parent context. If no context + defines the terminal width then auto + detection will be applied. + :param max_content_width: the maximum width for content rendered by + Click (this currently only affects help + pages). This defaults to 80 characters if + not overridden. In other words: even if the + terminal is larger than that, Click will not + format things wider than 80 characters by + default. In addition to that, formatters might + add some safety mapping on the right. + :param resilient_parsing: if this flag is enabled then Click will + parse without any interactivity or callback + invocation. This is useful for implementing + things such as completion support. + :param allow_extra_args: if this is set to `True` then extra arguments + at the end will not raise an error and will be + kept on the context. The default is to inherit + from the command. + :param allow_interspersed_args: if this is set to `False` then options + and arguments cannot be mixed. The + default is to inherit from the command. + :param ignore_unknown_options: instructs click to ignore options it does + not know and keeps them for later + processing. + :param help_option_names: optionally a list of strings that define how + the default help parameter is named. The + default is ``['--help']``. + :param token_normalize_func: an optional function that is used to + normalize tokens (options, choices, + etc.). This for instance can be used to + implement case insensitive behavior. + :param color: controls if the terminal supports ANSI colors or not. The + default is autodetection. This is only needed if ANSI + codes are used in texts that Click prints which is by + default not the case. This for instance would affect + help output. + """ + + def __init__(self, command, parent=None, info_name=None, obj=None, + auto_envvar_prefix=None, default_map=None, + terminal_width=None, max_content_width=None, + resilient_parsing=False, allow_extra_args=None, + allow_interspersed_args=None, + ignore_unknown_options=None, help_option_names=None, + token_normalize_func=None, color=None): + #: the parent context or `None` if none exists. + self.parent = parent + #: the :class:`Command` for this context. + self.command = command + #: the descriptive information name + self.info_name = info_name + #: the parsed parameters except if the value is hidden in which + #: case it's not remembered. + self.params = {} + #: the leftover arguments. + self.args = [] + #: protected arguments. These are arguments that are prepended + #: to `args` when certain parsing scenarios are encountered but + #: must be never propagated to another arguments. This is used + #: to implement nested parsing. + self.protected_args = [] + if obj is None and parent is not None: + obj = parent.obj + #: the user object stored. + self.obj = obj + self._meta = getattr(parent, 'meta', {}) + + #: A dictionary (-like object) with defaults for parameters. + if default_map is None \ + and parent is not None \ + and parent.default_map is not None: + default_map = parent.default_map.get(info_name) + self.default_map = default_map + + #: This flag indicates if a subcommand is going to be executed. A + #: group callback can use this information to figure out if it's + #: being executed directly or because the execution flow passes + #: onwards to a subcommand. By default it's None, but it can be + #: the name of the subcommand to execute. + #: + #: If chaining is enabled this will be set to ``'*'`` in case + #: any commands are executed. It is however not possible to + #: figure out which ones. If you require this knowledge you + #: should use a :func:`resultcallback`. + self.invoked_subcommand = None + + if terminal_width is None and parent is not None: + terminal_width = parent.terminal_width + #: The width of the terminal (None is autodetection). + self.terminal_width = terminal_width + + if max_content_width is None and parent is not None: + max_content_width = parent.max_content_width + #: The maximum width of formatted content (None implies a sensible + #: default which is 80 for most things). + self.max_content_width = max_content_width + + if allow_extra_args is None: + allow_extra_args = command.allow_extra_args + #: Indicates if the context allows extra args or if it should + #: fail on parsing. + #: + #: .. versionadded:: 3.0 + self.allow_extra_args = allow_extra_args + + if allow_interspersed_args is None: + allow_interspersed_args = command.allow_interspersed_args + #: Indicates if the context allows mixing of arguments and + #: options or not. + #: + #: .. versionadded:: 3.0 + self.allow_interspersed_args = allow_interspersed_args + + if ignore_unknown_options is None: + ignore_unknown_options = command.ignore_unknown_options + #: Instructs click to ignore options that a command does not + #: understand and will store it on the context for later + #: processing. This is primarily useful for situations where you + #: want to call into external programs. Generally this pattern is + #: strongly discouraged because it's not possibly to losslessly + #: forward all arguments. + #: + #: .. versionadded:: 4.0 + self.ignore_unknown_options = ignore_unknown_options + + if help_option_names is None: + if parent is not None: + help_option_names = parent.help_option_names + else: + help_option_names = ['--help'] + + #: The names for the help options. + self.help_option_names = help_option_names + + if token_normalize_func is None and parent is not None: + token_normalize_func = parent.token_normalize_func + + #: An optional normalization function for tokens. This is + #: options, choices, commands etc. + self.token_normalize_func = token_normalize_func + + #: Indicates if resilient parsing is enabled. In that case Click + #: will do its best to not cause any failures. + self.resilient_parsing = resilient_parsing + + # If there is no envvar prefix yet, but the parent has one and + # the command on this level has a name, we can expand the envvar + # prefix automatically. + if auto_envvar_prefix is None: + if parent is not None \ + and parent.auto_envvar_prefix is not None and \ + self.info_name is not None: + auto_envvar_prefix = '%s_%s' % (parent.auto_envvar_prefix, + self.info_name.upper()) + else: + self.auto_envvar_prefix = auto_envvar_prefix.upper() + self.auto_envvar_prefix = auto_envvar_prefix + + if color is None and parent is not None: + color = parent.color + + #: Controls if styling output is wanted or not. + self.color = color + + self._close_callbacks = [] + self._depth = 0 + + def __enter__(self): + self._depth += 1 + push_context(self) + return self + + def __exit__(self, exc_type, exc_value, tb): + self._depth -= 1 + if self._depth == 0: + self.close() + pop_context() + + @contextmanager + def scope(self, cleanup=True): + """This helper method can be used with the context object to promote + it to the current thread local (see :func:`get_current_context`). + The default behavior of this is to invoke the cleanup functions which + can be disabled by setting `cleanup` to `False`. The cleanup + functions are typically used for things such as closing file handles. + + If the cleanup is intended the context object can also be directly + used as a context manager. + + Example usage:: + + with ctx.scope(): + assert get_current_context() is ctx + + This is equivalent:: + + with ctx: + assert get_current_context() is ctx + + .. versionadded:: 5.0 + + :param cleanup: controls if the cleanup functions should be run or + not. The default is to run these functions. In + some situations the context only wants to be + temporarily pushed in which case this can be disabled. + Nested pushes automatically defer the cleanup. + """ + if not cleanup: + self._depth += 1 + try: + with self as rv: + yield rv + finally: + if not cleanup: + self._depth -= 1 + + @property + def meta(self): + """This is a dictionary which is shared with all the contexts + that are nested. It exists so that click utiltiies can store some + state here if they need to. It is however the responsibility of + that code to manage this dictionary well. + + The keys are supposed to be unique dotted strings. For instance + module paths are a good choice for it. What is stored in there is + irrelevant for the operation of click. However what is important is + that code that places data here adheres to the general semantics of + the system. + + Example usage:: + + LANG_KEY = __name__ + '.lang' + + def set_language(value): + ctx = get_current_context() + ctx.meta[LANG_KEY] = value + + def get_language(): + return get_current_context().meta.get(LANG_KEY, 'en_US') + + .. versionadded:: 5.0 + """ + return self._meta + + def make_formatter(self): + """Creates the formatter for the help and usage output.""" + return HelpFormatter(width=self.terminal_width, + max_width=self.max_content_width) + + def call_on_close(self, f): + """This decorator remembers a function as callback that should be + executed when the context tears down. This is most useful to bind + resource handling to the script execution. For instance, file objects + opened by the :class:`File` type will register their close callbacks + here. + + :param f: the function to execute on teardown. + """ + self._close_callbacks.append(f) + return f + + def close(self): + """Invokes all close callbacks.""" + for cb in self._close_callbacks: + cb() + self._close_callbacks = [] + + @property + def command_path(self): + """The computed command path. This is used for the ``usage`` + information on the help page. It's automatically created by + combining the info names of the chain of contexts to the root. + """ + rv = '' + if self.info_name is not None: + rv = self.info_name + if self.parent is not None: + rv = self.parent.command_path + ' ' + rv + return rv.lstrip() + + def find_root(self): + """Finds the outermost context.""" + node = self + while node.parent is not None: + node = node.parent + return node + + def find_object(self, object_type): + """Finds the closest object of a given type.""" + node = self + while node is not None: + if isinstance(node.obj, object_type): + return node.obj + node = node.parent + + def ensure_object(self, object_type): + """Like :meth:`find_object` but sets the innermost object to a + new instance of `object_type` if it does not exist. + """ + rv = self.find_object(object_type) + if rv is None: + self.obj = rv = object_type() + return rv + + def lookup_default(self, name): + """Looks up the default for a parameter name. This by default + looks into the :attr:`default_map` if available. + """ + if self.default_map is not None: + rv = self.default_map.get(name) + if callable(rv): + rv = rv() + return rv + + def fail(self, message): + """Aborts the execution of the program with a specific error + message. + + :param message: the error message to fail with. + """ + raise UsageError(message, self) + + def abort(self): + """Aborts the script.""" + raise Abort() + + def exit(self, code=0): + """Exits the application with a given exit code.""" + sys.exit(code) + + def get_usage(self): + """Helper method to get formatted usage string for the current + context and command. + """ + return self.command.get_usage(self) + + def get_help(self): + """Helper method to get formatted help page for the current + context and command. + """ + return self.command.get_help(self) + + def invoke(*args, **kwargs): + """Invokes a command callback in exactly the way it expects. There + are two ways to invoke this method: + + 1. the first argument can be a callback and all other arguments and + keyword arguments are forwarded directly to the function. + 2. the first argument is a click command object. In that case all + arguments are forwarded as well but proper click parameters + (options and click arguments) must be keyword arguments and Click + will fill in defaults. + + Note that before Click 3.2 keyword arguments were not properly filled + in against the intention of this code and no context was created. For + more information about this change and why it was done in a bugfix + release see :ref:`upgrade-to-3.2`. + """ + self, callback = args[:2] + ctx = self + + # It's also possible to invoke another command which might or + # might not have a callback. In that case we also fill + # in defaults and make a new context for this command. + if isinstance(callback, Command): + other_cmd = callback + callback = other_cmd.callback + ctx = Context(other_cmd, info_name=other_cmd.name, parent=self) + if callback is None: + raise TypeError('The given command does not have a ' + 'callback that can be invoked.') + + for param in other_cmd.params: + if param.name not in kwargs and param.expose_value: + kwargs[param.name] = param.get_default(ctx) + + args = args[2:] + with augment_usage_errors(self): + with ctx: + return callback(*args, **kwargs) + + def forward(*args, **kwargs): + """Similar to :meth:`invoke` but fills in default keyword + arguments from the current context if the other command expects + it. This cannot invoke callbacks directly, only other commands. + """ + self, cmd = args[:2] + + # It's also possible to invoke another command which might or + # might not have a callback. + if not isinstance(cmd, Command): + raise TypeError('Callback is not a command.') + + for param in self.params: + if param not in kwargs: + kwargs[param] = self.params[param] + + return self.invoke(cmd, **kwargs) + + +class BaseCommand(object): + """The base command implements the minimal API contract of commands. + Most code will never use this as it does not implement a lot of useful + functionality but it can act as the direct subclass of alternative + parsing methods that do not depend on the Click parser. + + For instance, this can be used to bridge Click and other systems like + argparse or docopt. + + Because base commands do not implement a lot of the API that other + parts of Click take for granted, they are not supported for all + operations. For instance, they cannot be used with the decorators + usually and they have no built-in callback system. + + .. versionchanged:: 2.0 + Added the `context_settings` parameter. + + :param name: the name of the command to use unless a group overrides it. + :param context_settings: an optional dictionary with defaults that are + passed to the context object. + """ + #: the default for the :attr:`Context.allow_extra_args` flag. + allow_extra_args = False + #: the default for the :attr:`Context.allow_interspersed_args` flag. + allow_interspersed_args = True + #: the default for the :attr:`Context.ignore_unknown_options` flag. + ignore_unknown_options = False + + def __init__(self, name, context_settings=None): + #: the name the command thinks it has. Upon registering a command + #: on a :class:`Group` the group will default the command name + #: with this information. You should instead use the + #: :class:`Context`\'s :attr:`~Context.info_name` attribute. + self.name = name + if context_settings is None: + context_settings = {} + #: an optional dictionary with defaults passed to the context. + self.context_settings = context_settings + + def get_usage(self, ctx): + raise NotImplementedError('Base commands cannot get usage') + + def get_help(self, ctx): + raise NotImplementedError('Base commands cannot get help') + + def make_context(self, info_name, args, parent=None, **extra): + """This function when given an info name and arguments will kick + off the parsing and create a new :class:`Context`. It does not + invoke the actual command callback though. + + :param info_name: the info name for this invokation. Generally this + is the most descriptive name for the script or + command. For the toplevel script it's usually + the name of the script, for commands below it it's + the name of the script. + :param args: the arguments to parse as list of strings. + :param parent: the parent context if available. + :param extra: extra keyword arguments forwarded to the context + constructor. + """ + for key, value in iteritems(self.context_settings): + if key not in extra: + extra[key] = value + ctx = Context(self, info_name=info_name, parent=parent, **extra) + with ctx.scope(cleanup=False): + self.parse_args(ctx, args) + return ctx + + def parse_args(self, ctx, args): + """Given a context and a list of arguments this creates the parser + and parses the arguments, then modifies the context as necessary. + This is automatically invoked by :meth:`make_context`. + """ + raise NotImplementedError('Base commands do not know how to parse ' + 'arguments.') + + def invoke(self, ctx): + """Given a context, this invokes the command. The default + implementation is raising a not implemented error. + """ + raise NotImplementedError('Base commands are not invokable by default') + + def main(self, args=None, prog_name=None, complete_var=None, + standalone_mode=True, **extra): + """This is the way to invoke a script with all the bells and + whistles as a command line application. This will always terminate + the application after a call. If this is not wanted, ``SystemExit`` + needs to be caught. + + This method is also available by directly calling the instance of + a :class:`Command`. + + .. versionadded:: 3.0 + Added the `standalone_mode` flag to control the standalone mode. + + :param args: the arguments that should be used for parsing. If not + provided, ``sys.argv[1:]`` is used. + :param prog_name: the program name that should be used. By default + the program name is constructed by taking the file + name from ``sys.argv[0]``. + :param complete_var: the environment variable that controls the + bash completion support. The default is + ``"__COMPLETE"`` with prog name in + uppercase. + :param standalone_mode: the default behavior is to invoke the script + in standalone mode. Click will then + handle exceptions and convert them into + error messages and the function will never + return but shut down the interpreter. If + this is set to `False` they will be + propagated to the caller and the return + value of this function is the return value + of :meth:`invoke`. + :param extra: extra keyword arguments are forwarded to the context + constructor. See :class:`Context` for more information. + """ + # If we are in Python 3, we will verify that the environment is + # sane at this point of reject further execution to avoid a + # broken script. + if not PY2: + _verify_python3_env() + else: + _check_for_unicode_literals() + + if args is None: + args = get_os_args() + else: + args = list(args) + + if prog_name is None: + prog_name = make_str(os.path.basename( + sys.argv and sys.argv[0] or __file__)) + + # Hook for the Bash completion. This only activates if the Bash + # completion is actually enabled, otherwise this is quite a fast + # noop. + _bashcomplete(self, prog_name, complete_var) + + try: + try: + with self.make_context(prog_name, args, **extra) as ctx: + rv = self.invoke(ctx) + if not standalone_mode: + return rv + ctx.exit() + except (EOFError, KeyboardInterrupt): + echo(file=sys.stderr) + raise Abort() + except ClickException as e: + if not standalone_mode: + raise + e.show() + sys.exit(e.exit_code) + except IOError as e: + if e.errno == errno.EPIPE: + sys.exit(1) + else: + raise + except Abort: + if not standalone_mode: + raise + echo('Aborted!', file=sys.stderr) + sys.exit(1) + + def __call__(self, *args, **kwargs): + """Alias for :meth:`main`.""" + return self.main(*args, **kwargs) + + +class Command(BaseCommand): + """Commands are the basic building block of command line interfaces in + Click. A basic command handles command line parsing and might dispatch + more parsing to commands nested below it. + + .. versionchanged:: 2.0 + Added the `context_settings` parameter. + + :param name: the name of the command to use unless a group overrides it. + :param context_settings: an optional dictionary with defaults that are + passed to the context object. + :param callback: the callback to invoke. This is optional. + :param params: the parameters to register with this command. This can + be either :class:`Option` or :class:`Argument` objects. + :param help: the help string to use for this command. + :param epilog: like the help string but it's printed at the end of the + help page after everything else. + :param short_help: the short help to use for this command. This is + shown on the command listing of the parent command. + :param add_help_option: by default each command registers a ``--help`` + option. This can be disabled by this parameter. + """ + + def __init__(self, name, context_settings=None, callback=None, + params=None, help=None, epilog=None, short_help=None, + options_metavar='[OPTIONS]', add_help_option=True): + BaseCommand.__init__(self, name, context_settings) + #: the callback to execute when the command fires. This might be + #: `None` in which case nothing happens. + self.callback = callback + #: the list of parameters for this command in the order they + #: should show up in the help page and execute. Eager parameters + #: will automatically be handled before non eager ones. + self.params = params or [] + self.help = help + self.epilog = epilog + self.options_metavar = options_metavar + if short_help is None and help: + short_help = make_default_short_help(help) + self.short_help = short_help + self.add_help_option = add_help_option + + def get_usage(self, ctx): + formatter = ctx.make_formatter() + self.format_usage(ctx, formatter) + return formatter.getvalue().rstrip('\n') + + def get_params(self, ctx): + rv = self.params + help_option = self.get_help_option(ctx) + if help_option is not None: + rv = rv + [help_option] + return rv + + def format_usage(self, ctx, formatter): + """Writes the usage line into the formatter.""" + pieces = self.collect_usage_pieces(ctx) + formatter.write_usage(ctx.command_path, ' '.join(pieces)) + + def collect_usage_pieces(self, ctx): + """Returns all the pieces that go into the usage line and returns + it as a list of strings. + """ + rv = [self.options_metavar] + for param in self.get_params(ctx): + rv.extend(param.get_usage_pieces(ctx)) + return rv + + def get_help_option_names(self, ctx): + """Returns the names for the help option.""" + all_names = set(ctx.help_option_names) + for param in self.params: + all_names.difference_update(param.opts) + all_names.difference_update(param.secondary_opts) + return all_names + + def get_help_option(self, ctx): + """Returns the help option object.""" + help_options = self.get_help_option_names(ctx) + if not help_options or not self.add_help_option: + return + + def show_help(ctx, param, value): + if value and not ctx.resilient_parsing: + echo(ctx.get_help(), color=ctx.color) + ctx.exit() + return Option(help_options, is_flag=True, + is_eager=True, expose_value=False, + callback=show_help, + help='Show this message and exit.') + + def make_parser(self, ctx): + """Creates the underlying option parser for this command.""" + parser = OptionParser(ctx) + parser.allow_interspersed_args = ctx.allow_interspersed_args + parser.ignore_unknown_options = ctx.ignore_unknown_options + for param in self.get_params(ctx): + param.add_to_parser(parser, ctx) + return parser + + def get_help(self, ctx): + """Formats the help into a string and returns it. This creates a + formatter and will call into the following formatting methods: + """ + formatter = ctx.make_formatter() + self.format_help(ctx, formatter) + return formatter.getvalue().rstrip('\n') + + def format_help(self, ctx, formatter): + """Writes the help into the formatter if it exists. + + This calls into the following methods: + + - :meth:`format_usage` + - :meth:`format_help_text` + - :meth:`format_options` + - :meth:`format_epilog` + """ + self.format_usage(ctx, formatter) + self.format_help_text(ctx, formatter) + self.format_options(ctx, formatter) + self.format_epilog(ctx, formatter) + + def format_help_text(self, ctx, formatter): + """Writes the help text to the formatter if it exists.""" + if self.help: + formatter.write_paragraph() + with formatter.indentation(): + formatter.write_text(self.help) + + def format_options(self, ctx, formatter): + """Writes all the options into the formatter if they exist.""" + opts = [] + for param in self.get_params(ctx): + rv = param.get_help_record(ctx) + if rv is not None: + opts.append(rv) + + if opts: + with formatter.section('Options'): + formatter.write_dl(opts) + + def format_epilog(self, ctx, formatter): + """Writes the epilog into the formatter if it exists.""" + if self.epilog: + formatter.write_paragraph() + with formatter.indentation(): + formatter.write_text(self.epilog) + + def parse_args(self, ctx, args): + parser = self.make_parser(ctx) + opts, args, param_order = parser.parse_args(args=args) + + for param in iter_params_for_processing( + param_order, self.get_params(ctx)): + value, args = param.handle_parse_result(ctx, opts, args) + + if args and not ctx.allow_extra_args and not ctx.resilient_parsing: + ctx.fail('Got unexpected extra argument%s (%s)' + % (len(args) != 1 and 's' or '', + ' '.join(map(make_str, args)))) + + ctx.args = args + return args + + def invoke(self, ctx): + """Given a context, this invokes the attached callback (if it exists) + in the right way. + """ + if self.callback is not None: + return ctx.invoke(self.callback, **ctx.params) + + +class MultiCommand(Command): + """A multi command is the basic implementation of a command that + dispatches to subcommands. The most common version is the + :class:`Group`. + + :param invoke_without_command: this controls how the multi command itself + is invoked. By default it's only invoked + if a subcommand is provided. + :param no_args_is_help: this controls what happens if no arguments are + provided. This option is enabled by default if + `invoke_without_command` is disabled or disabled + if it's enabled. If enabled this will add + ``--help`` as argument if no arguments are + passed. + :param subcommand_metavar: the string that is used in the documentation + to indicate the subcommand place. + :param chain: if this is set to `True` chaining of multiple subcommands + is enabled. This restricts the form of commands in that + they cannot have optional arguments but it allows + multiple commands to be chained together. + :param result_callback: the result callback to attach to this multi + command. + """ + allow_extra_args = True + allow_interspersed_args = False + + def __init__(self, name=None, invoke_without_command=False, + no_args_is_help=None, subcommand_metavar=None, + chain=False, result_callback=None, **attrs): + Command.__init__(self, name, **attrs) + if no_args_is_help is None: + no_args_is_help = not invoke_without_command + self.no_args_is_help = no_args_is_help + self.invoke_without_command = invoke_without_command + if subcommand_metavar is None: + if chain: + subcommand_metavar = SUBCOMMANDS_METAVAR + else: + subcommand_metavar = SUBCOMMAND_METAVAR + self.subcommand_metavar = subcommand_metavar + self.chain = chain + #: The result callback that is stored. This can be set or + #: overridden with the :func:`resultcallback` decorator. + self.result_callback = result_callback + + if self.chain: + for param in self.params: + if isinstance(param, Argument) and not param.required: + raise RuntimeError('Multi commands in chain mode cannot ' + 'have optional arguments.') + + def collect_usage_pieces(self, ctx): + rv = Command.collect_usage_pieces(self, ctx) + rv.append(self.subcommand_metavar) + return rv + + def format_options(self, ctx, formatter): + Command.format_options(self, ctx, formatter) + self.format_commands(ctx, formatter) + + def resultcallback(self, replace=False): + """Adds a result callback to the chain command. By default if a + result callback is already registered this will chain them but + this can be disabled with the `replace` parameter. The result + callback is invoked with the return value of the subcommand + (or the list of return values from all subcommands if chaining + is enabled) as well as the parameters as they would be passed + to the main callback. + + Example:: + + @click.group() + @click.option('-i', '--input', default=23) + def cli(input): + return 42 + + @cli.resultcallback() + def process_result(result, input): + return result + input + + .. versionadded:: 3.0 + + :param replace: if set to `True` an already existing result + callback will be removed. + """ + def decorator(f): + old_callback = self.result_callback + if old_callback is None or replace: + self.result_callback = f + return f + def function(__value, *args, **kwargs): + return f(old_callback(__value, *args, **kwargs), + *args, **kwargs) + self.result_callback = rv = update_wrapper(function, f) + return rv + return decorator + + def format_commands(self, ctx, formatter): + """Extra format methods for multi methods that adds all the commands + after the options. + """ + rows = [] + for subcommand in self.list_commands(ctx): + cmd = self.get_command(ctx, subcommand) + # What is this, the tool lied about a command. Ignore it + if cmd is None: + continue + + help = cmd.short_help or '' + rows.append((subcommand, help)) + + if rows: + with formatter.section('Commands'): + formatter.write_dl(rows) + + def parse_args(self, ctx, args): + if not args and self.no_args_is_help and not ctx.resilient_parsing: + echo(ctx.get_help(), color=ctx.color) + ctx.exit() + + rest = Command.parse_args(self, ctx, args) + if self.chain: + ctx.protected_args = rest + ctx.args = [] + elif rest: + ctx.protected_args, ctx.args = rest[:1], rest[1:] + + return ctx.args + + def invoke(self, ctx): + def _process_result(value): + if self.result_callback is not None: + value = ctx.invoke(self.result_callback, value, + **ctx.params) + return value + + if not ctx.protected_args: + # If we are invoked without command the chain flag controls + # how this happens. If we are not in chain mode, the return + # value here is the return value of the command. + # If however we are in chain mode, the return value is the + # return value of the result processor invoked with an empty + # list (which means that no subcommand actually was executed). + if self.invoke_without_command: + if not self.chain: + return Command.invoke(self, ctx) + with ctx: + Command.invoke(self, ctx) + return _process_result([]) + ctx.fail('Missing command.') + + # Fetch args back out + args = ctx.protected_args + ctx.args + ctx.args = [] + ctx.protected_args = [] + + # If we're not in chain mode, we only allow the invocation of a + # single command but we also inform the current context about the + # name of the command to invoke. + if not self.chain: + # Make sure the context is entered so we do not clean up + # resources until the result processor has worked. + with ctx: + cmd_name, cmd, args = self.resolve_command(ctx, args) + ctx.invoked_subcommand = cmd_name + Command.invoke(self, ctx) + sub_ctx = cmd.make_context(cmd_name, args, parent=ctx) + with sub_ctx: + return _process_result(sub_ctx.command.invoke(sub_ctx)) + + # In chain mode we create the contexts step by step, but after the + # base command has been invoked. Because at that point we do not + # know the subcommands yet, the invoked subcommand attribute is + # set to ``*`` to inform the command that subcommands are executed + # but nothing else. + with ctx: + ctx.invoked_subcommand = args and '*' or None + Command.invoke(self, ctx) + + # Otherwise we make every single context and invoke them in a + # chain. In that case the return value to the result processor + # is the list of all invoked subcommand's results. + contexts = [] + while args: + cmd_name, cmd, args = self.resolve_command(ctx, args) + sub_ctx = cmd.make_context(cmd_name, args, parent=ctx, + allow_extra_args=True, + allow_interspersed_args=False) + contexts.append(sub_ctx) + args, sub_ctx.args = sub_ctx.args, [] + + rv = [] + for sub_ctx in contexts: + with sub_ctx: + rv.append(sub_ctx.command.invoke(sub_ctx)) + return _process_result(rv) + + def resolve_command(self, ctx, args): + cmd_name = make_str(args[0]) + original_cmd_name = cmd_name + + # Get the command + cmd = self.get_command(ctx, cmd_name) + + # If we can't find the command but there is a normalization + # function available, we try with that one. + if cmd is None and ctx.token_normalize_func is not None: + cmd_name = ctx.token_normalize_func(cmd_name) + cmd = self.get_command(ctx, cmd_name) + + # If we don't find the command we want to show an error message + # to the user that it was not provided. However, there is + # something else we should do: if the first argument looks like + # an option we want to kick off parsing again for arguments to + # resolve things like --help which now should go to the main + # place. + if cmd is None: + if split_opt(cmd_name)[0]: + self.parse_args(ctx, ctx.args) + ctx.fail('No such command "%s".' % original_cmd_name) + + return cmd_name, cmd, args[1:] + + def get_command(self, ctx, cmd_name): + """Given a context and a command name, this returns a + :class:`Command` object if it exists or returns `None`. + """ + raise NotImplementedError() + + def list_commands(self, ctx): + """Returns a list of subcommand names in the order they should + appear. + """ + return [] + + +class Group(MultiCommand): + """A group allows a command to have subcommands attached. This is the + most common way to implement nesting in Click. + + :param commands: a dictionary of commands. + """ + + def __init__(self, name=None, commands=None, **attrs): + MultiCommand.__init__(self, name, **attrs) + #: the registered subcommands by their exported names. + self.commands = commands or {} + + def add_command(self, cmd, name=None): + """Registers another :class:`Command` with this group. If the name + is not provided, the name of the command is used. + """ + name = name or cmd.name + if name is None: + raise TypeError('Command has no name.') + _check_multicommand(self, name, cmd, register=True) + self.commands[name] = cmd + + def command(self, *args, **kwargs): + """A shortcut decorator for declaring and attaching a command to + the group. This takes the same arguments as :func:`command` but + immediately registers the created command with this instance by + calling into :meth:`add_command`. + """ + def decorator(f): + cmd = command(*args, **kwargs)(f) + self.add_command(cmd) + return cmd + return decorator + + def group(self, *args, **kwargs): + """A shortcut decorator for declaring and attaching a group to + the group. This takes the same arguments as :func:`group` but + immediately registers the created command with this instance by + calling into :meth:`add_command`. + """ + def decorator(f): + cmd = group(*args, **kwargs)(f) + self.add_command(cmd) + return cmd + return decorator + + def get_command(self, ctx, cmd_name): + return self.commands.get(cmd_name) + + def list_commands(self, ctx): + return sorted(self.commands) + + +class CommandCollection(MultiCommand): + """A command collection is a multi command that merges multiple multi + commands together into one. This is a straightforward implementation + that accepts a list of different multi commands as sources and + provides all the commands for each of them. + """ + + def __init__(self, name=None, sources=None, **attrs): + MultiCommand.__init__(self, name, **attrs) + #: The list of registered multi commands. + self.sources = sources or [] + + def add_source(self, multi_cmd): + """Adds a new multi command to the chain dispatcher.""" + self.sources.append(multi_cmd) + + def get_command(self, ctx, cmd_name): + for source in self.sources: + rv = source.get_command(ctx, cmd_name) + if rv is not None: + if self.chain: + _check_multicommand(self, cmd_name, rv) + return rv + + def list_commands(self, ctx): + rv = set() + for source in self.sources: + rv.update(source.list_commands(ctx)) + return sorted(rv) + + +class Parameter(object): + """A parameter to a command comes in two versions: they are either + :class:`Option`\s or :class:`Argument`\s. Other subclasses are currently + not supported by design as some of the internals for parsing are + intentionally not finalized. + + Some settings are supported by both options and arguments. + + .. versionchanged:: 2.0 + Changed signature for parameter callback to also be passed the + parameter. In Click 2.0, the old callback format will still work, + but it will raise a warning to give you change to migrate the + code easier. + + :param param_decls: the parameter declarations for this option or + argument. This is a list of flags or argument + names. + :param type: the type that should be used. Either a :class:`ParamType` + or a Python type. The later is converted into the former + automatically if supported. + :param required: controls if this is optional or not. + :param default: the default value if omitted. This can also be a callable, + in which case it's invoked when the default is needed + without any arguments. + :param callback: a callback that should be executed after the parameter + was matched. This is called as ``fn(ctx, param, + value)`` and needs to return the value. Before Click + 2.0, the signature was ``(ctx, value)``. + :param nargs: the number of arguments to match. If not ``1`` the return + value is a tuple instead of single value. The default for + nargs is ``1`` (except if the type is a tuple, then it's + the arity of the tuple). + :param metavar: how the value is represented in the help page. + :param expose_value: if this is `True` then the value is passed onwards + to the command callback and stored on the context, + otherwise it's skipped. + :param is_eager: eager values are processed before non eager ones. This + should not be set for arguments or it will inverse the + order of processing. + :param envvar: a string or list of strings that are environment variables + that should be checked. + """ + param_type_name = 'parameter' + + def __init__(self, param_decls=None, type=None, required=False, + default=None, callback=None, nargs=None, metavar=None, + expose_value=True, is_eager=False, envvar=None): + self.name, self.opts, self.secondary_opts = \ + self._parse_decls(param_decls or (), expose_value) + + self.type = convert_type(type, default) + + # Default nargs to what the type tells us if we have that + # information available. + if nargs is None: + if self.type.is_composite: + nargs = self.type.arity + else: + nargs = 1 + + self.required = required + self.callback = callback + self.nargs = nargs + self.multiple = False + self.expose_value = expose_value + self.default = default + self.is_eager = is_eager + self.metavar = metavar + self.envvar = envvar + + @property + def human_readable_name(self): + """Returns the human readable name of this parameter. This is the + same as the name for options, but the metavar for arguments. + """ + return self.name + + def make_metavar(self): + if self.metavar is not None: + return self.metavar + metavar = self.type.get_metavar(self) + if metavar is None: + metavar = self.type.name.upper() + if self.nargs != 1: + metavar += '...' + return metavar + + def get_default(self, ctx): + """Given a context variable this calculates the default value.""" + # Otherwise go with the regular default. + if callable(self.default): + rv = self.default() + else: + rv = self.default + return self.type_cast_value(ctx, rv) + + def add_to_parser(self, parser, ctx): + pass + + def consume_value(self, ctx, opts): + value = opts.get(self.name) + if value is None: + value = ctx.lookup_default(self.name) + if value is None: + value = self.value_from_envvar(ctx) + return value + + def type_cast_value(self, ctx, value): + """Given a value this runs it properly through the type system. + This automatically handles things like `nargs` and `multiple` as + well as composite types. + """ + if self.type.is_composite: + if self.nargs <= 1: + raise TypeError('Attempted to invoke composite type ' + 'but nargs has been set to %s. This is ' + 'not supported; nargs needs to be set to ' + 'a fixed value > 1.' % self.nargs) + if self.multiple: + return tuple(self.type(x or (), self, ctx) for x in value or ()) + return self.type(value or (), self, ctx) + + def _convert(value, level): + if level == 0: + return self.type(value, self, ctx) + return tuple(_convert(x, level - 1) for x in value or ()) + return _convert(value, (self.nargs != 1) + bool(self.multiple)) + + def process_value(self, ctx, value): + """Given a value and context this runs the logic to convert the + value as necessary. + """ + # If the value we were given is None we do nothing. This way + # code that calls this can easily figure out if something was + # not provided. Otherwise it would be converted into an empty + # tuple for multiple invocations which is inconvenient. + if value is not None: + return self.type_cast_value(ctx, value) + + def value_is_missing(self, value): + if value is None: + return True + if (self.nargs != 1 or self.multiple) and value == (): + return True + return False + + def full_process_value(self, ctx, value): + value = self.process_value(ctx, value) + + if value is None: + value = self.get_default(ctx) + + if self.required and self.value_is_missing(value): + raise MissingParameter(ctx=ctx, param=self) + + return value + + def resolve_envvar_value(self, ctx): + if self.envvar is None: + return + if isinstance(self.envvar, (tuple, list)): + for envvar in self.envvar: + rv = os.environ.get(envvar) + if rv is not None: + return rv + else: + return os.environ.get(self.envvar) + + def value_from_envvar(self, ctx): + rv = self.resolve_envvar_value(ctx) + if rv is not None and self.nargs != 1: + rv = self.type.split_envvar_value(rv) + return rv + + def handle_parse_result(self, ctx, opts, args): + with augment_usage_errors(ctx, param=self): + value = self.consume_value(ctx, opts) + try: + value = self.full_process_value(ctx, value) + except Exception: + if not ctx.resilient_parsing: + raise + value = None + if self.callback is not None: + try: + value = invoke_param_callback( + self.callback, ctx, self, value) + except Exception: + if not ctx.resilient_parsing: + raise + + if self.expose_value: + ctx.params[self.name] = value + return value, args + + def get_help_record(self, ctx): + pass + + def get_usage_pieces(self, ctx): + return [] + + +class Option(Parameter): + """Options are usually optional values on the command line and + have some extra features that arguments don't have. + + All other parameters are passed onwards to the parameter constructor. + + :param show_default: controls if the default value should be shown on the + help page. Normally, defaults are not shown. + :param prompt: if set to `True` or a non empty string then the user will + be prompted for input if not set. If set to `True` the + prompt will be the option name capitalized. + :param confirmation_prompt: if set then the value will need to be confirmed + if it was prompted for. + :param hide_input: if this is `True` then the input on the prompt will be + hidden from the user. This is useful for password + input. + :param is_flag: forces this option to act as a flag. The default is + auto detection. + :param flag_value: which value should be used for this flag if it's + enabled. This is set to a boolean automatically if + the option string contains a slash to mark two options. + :param multiple: if this is set to `True` then the argument is accepted + multiple times and recorded. This is similar to ``nargs`` + in how it works but supports arbitrary number of + arguments. + :param count: this flag makes an option increment an integer. + :param allow_from_autoenv: if this is enabled then the value of this + parameter will be pulled from an environment + variable in case a prefix is defined on the + context. + :param help: the help string. + """ + param_type_name = 'option' + + def __init__(self, param_decls=None, show_default=False, + prompt=False, confirmation_prompt=False, + hide_input=False, is_flag=None, flag_value=None, + multiple=False, count=False, allow_from_autoenv=True, + type=None, help=None, **attrs): + default_is_missing = attrs.get('default', _missing) is _missing + Parameter.__init__(self, param_decls, type=type, **attrs) + + if prompt is True: + prompt_text = self.name.replace('_', ' ').capitalize() + elif prompt is False: + prompt_text = None + else: + prompt_text = prompt + self.prompt = prompt_text + self.confirmation_prompt = confirmation_prompt + self.hide_input = hide_input + + # Flags + if is_flag is None: + if flag_value is not None: + is_flag = True + else: + is_flag = bool(self.secondary_opts) + if is_flag and default_is_missing: + self.default = False + if flag_value is None: + flag_value = not self.default + self.is_flag = is_flag + self.flag_value = flag_value + if self.is_flag and isinstance(self.flag_value, bool) \ + and type is None: + self.type = BOOL + self.is_bool_flag = True + else: + self.is_bool_flag = False + + # Counting + self.count = count + if count: + if type is None: + self.type = IntRange(min=0) + if default_is_missing: + self.default = 0 + + self.multiple = multiple + self.allow_from_autoenv = allow_from_autoenv + self.help = help + self.show_default = show_default + + # Sanity check for stuff we don't support + if __debug__: + if self.nargs < 0: + raise TypeError('Options cannot have nargs < 0') + if self.prompt and self.is_flag and not self.is_bool_flag: + raise TypeError('Cannot prompt for flags that are not bools.') + if not self.is_bool_flag and self.secondary_opts: + raise TypeError('Got secondary option for non boolean flag.') + if self.is_bool_flag and self.hide_input \ + and self.prompt is not None: + raise TypeError('Hidden input does not work with boolean ' + 'flag prompts.') + if self.count: + if self.multiple: + raise TypeError('Options cannot be multiple and count ' + 'at the same time.') + elif self.is_flag: + raise TypeError('Options cannot be count and flags at ' + 'the same time.') + + def _parse_decls(self, decls, expose_value): + opts = [] + secondary_opts = [] + name = None + possible_names = [] + + for decl in decls: + if isidentifier(decl): + if name is not None: + raise TypeError('Name defined twice') + name = decl + else: + split_char = decl[:1] == '/' and ';' or '/' + if split_char in decl: + first, second = decl.split(split_char, 1) + first = first.rstrip() + if first: + possible_names.append(split_opt(first)) + opts.append(first) + second = second.lstrip() + if second: + secondary_opts.append(second.lstrip()) + else: + possible_names.append(split_opt(decl)) + opts.append(decl) + + if name is None and possible_names: + possible_names.sort(key=lambda x: len(x[0])) + name = possible_names[-1][1].replace('-', '_').lower() + if not isidentifier(name): + name = None + + if name is None: + if not expose_value: + return None, opts, secondary_opts + raise TypeError('Could not determine name for option') + + if not opts and not secondary_opts: + raise TypeError('No options defined but a name was passed (%s). ' + 'Did you mean to declare an argument instead ' + 'of an option?' % name) + + return name, opts, secondary_opts + + def add_to_parser(self, parser, ctx): + kwargs = { + 'dest': self.name, + 'nargs': self.nargs, + 'obj': self, + } + + if self.multiple: + action = 'append' + elif self.count: + action = 'count' + else: + action = 'store' + + if self.is_flag: + kwargs.pop('nargs', None) + if self.is_bool_flag and self.secondary_opts: + parser.add_option(self.opts, action=action + '_const', + const=True, **kwargs) + parser.add_option(self.secondary_opts, action=action + + '_const', const=False, **kwargs) + else: + parser.add_option(self.opts, action=action + '_const', + const=self.flag_value, + **kwargs) + else: + kwargs['action'] = action + parser.add_option(self.opts, **kwargs) + + def get_help_record(self, ctx): + any_prefix_is_slash = [] + + def _write_opts(opts): + rv, any_slashes = join_options(opts) + if any_slashes: + any_prefix_is_slash[:] = [True] + if not self.is_flag and not self.count: + rv += ' ' + self.make_metavar() + return rv + + rv = [_write_opts(self.opts)] + if self.secondary_opts: + rv.append(_write_opts(self.secondary_opts)) + + help = self.help or '' + extra = [] + if self.default is not None and self.show_default: + extra.append('default: %s' % ( + ', '.join('%s' % d for d in self.default) + if isinstance(self.default, (list, tuple)) + else self.default, )) + if self.required: + extra.append('required') + if extra: + help = '%s[%s]' % (help and help + ' ' or '', '; '.join(extra)) + + return ((any_prefix_is_slash and '; ' or ' / ').join(rv), help) + + def get_default(self, ctx): + # If we're a non boolean flag out default is more complex because + # we need to look at all flags in the same group to figure out + # if we're the the default one in which case we return the flag + # value as default. + if self.is_flag and not self.is_bool_flag: + for param in ctx.command.params: + if param.name == self.name and param.default: + return param.flag_value + return None + return Parameter.get_default(self, ctx) + + def prompt_for_value(self, ctx): + """This is an alternative flow that can be activated in the full + value processing if a value does not exist. It will prompt the + user until a valid value exists and then returns the processed + value as result. + """ + # Calculate the default before prompting anything to be stable. + default = self.get_default(ctx) + + # If this is a prompt for a flag we need to handle this + # differently. + if self.is_bool_flag: + return confirm(self.prompt, default) + + return prompt(self.prompt, default=default, + hide_input=self.hide_input, + confirmation_prompt=self.confirmation_prompt, + value_proc=lambda x: self.process_value(ctx, x)) + + def resolve_envvar_value(self, ctx): + rv = Parameter.resolve_envvar_value(self, ctx) + if rv is not None: + return rv + if self.allow_from_autoenv and \ + ctx.auto_envvar_prefix is not None: + envvar = '%s_%s' % (ctx.auto_envvar_prefix, self.name.upper()) + return os.environ.get(envvar) + + def value_from_envvar(self, ctx): + rv = self.resolve_envvar_value(ctx) + if rv is None: + return None + value_depth = (self.nargs != 1) + bool(self.multiple) + if value_depth > 0 and rv is not None: + rv = self.type.split_envvar_value(rv) + if self.multiple and self.nargs != 1: + rv = batch(rv, self.nargs) + return rv + + def full_process_value(self, ctx, value): + if value is None and self.prompt is not None \ + and not ctx.resilient_parsing: + return self.prompt_for_value(ctx) + return Parameter.full_process_value(self, ctx, value) + + +class Argument(Parameter): + """Arguments are positional parameters to a command. They generally + provide fewer features than options but can have infinite ``nargs`` + and are required by default. + + All parameters are passed onwards to the parameter constructor. + """ + param_type_name = 'argument' + + def __init__(self, param_decls, required=None, **attrs): + if required is None: + if attrs.get('default') is not None: + required = False + else: + required = attrs.get('nargs', 1) > 0 + Parameter.__init__(self, param_decls, required=required, **attrs) + if self.default is not None and self.nargs < 0: + raise TypeError('nargs=-1 in combination with a default value ' + 'is not supported.') + + @property + def human_readable_name(self): + if self.metavar is not None: + return self.metavar + return self.name.upper() + + def make_metavar(self): + if self.metavar is not None: + return self.metavar + var = self.name.upper() + if not self.required: + var = '[%s]' % var + if self.nargs != 1: + var += '...' + return var + + def _parse_decls(self, decls, expose_value): + if not decls: + if not expose_value: + return None, [], [] + raise TypeError('Could not determine name for argument') + if len(decls) == 1: + name = arg = decls[0] + name = name.replace('-', '_').lower() + elif len(decls) == 2: + name, arg = decls + else: + raise TypeError('Arguments take exactly one or two ' + 'parameter declarations, got %d' % len(decls)) + return name, [arg], [] + + def get_usage_pieces(self, ctx): + return [self.make_metavar()] + + def add_to_parser(self, parser, ctx): + parser.add_argument(dest=self.name, nargs=self.nargs, + obj=self) + + +# Circular dependency between decorators and core +from .decorators import command, group diff --git a/pyextra/click/decorators.py b/pyextra/click/decorators.py new file mode 100644 index 00000000000000..9893452650ba0a --- /dev/null +++ b/pyextra/click/decorators.py @@ -0,0 +1,304 @@ +import sys +import inspect + +from functools import update_wrapper + +from ._compat import iteritems +from ._unicodefun import _check_for_unicode_literals +from .utils import echo +from .globals import get_current_context + + +def pass_context(f): + """Marks a callback as wanting to receive the current context + object as first argument. + """ + def new_func(*args, **kwargs): + return f(get_current_context(), *args, **kwargs) + return update_wrapper(new_func, f) + + +def pass_obj(f): + """Similar to :func:`pass_context`, but only pass the object on the + context onwards (:attr:`Context.obj`). This is useful if that object + represents the state of a nested system. + """ + def new_func(*args, **kwargs): + return f(get_current_context().obj, *args, **kwargs) + return update_wrapper(new_func, f) + + +def make_pass_decorator(object_type, ensure=False): + """Given an object type this creates a decorator that will work + similar to :func:`pass_obj` but instead of passing the object of the + current context, it will find the innermost context of type + :func:`object_type`. + + This generates a decorator that works roughly like this:: + + from functools import update_wrapper + + def decorator(f): + @pass_context + def new_func(ctx, *args, **kwargs): + obj = ctx.find_object(object_type) + return ctx.invoke(f, obj, *args, **kwargs) + return update_wrapper(new_func, f) + return decorator + + :param object_type: the type of the object to pass. + :param ensure: if set to `True`, a new object will be created and + remembered on the context if it's not there yet. + """ + def decorator(f): + def new_func(*args, **kwargs): + ctx = get_current_context() + if ensure: + obj = ctx.ensure_object(object_type) + else: + obj = ctx.find_object(object_type) + if obj is None: + raise RuntimeError('Managed to invoke callback without a ' + 'context object of type %r existing' + % object_type.__name__) + return ctx.invoke(f, obj, *args[1:], **kwargs) + return update_wrapper(new_func, f) + return decorator + + +def _make_command(f, name, attrs, cls): + if isinstance(f, Command): + raise TypeError('Attempted to convert a callback into a ' + 'command twice.') + try: + params = f.__click_params__ + params.reverse() + del f.__click_params__ + except AttributeError: + params = [] + help = attrs.get('help') + if help is None: + help = inspect.getdoc(f) + if isinstance(help, bytes): + help = help.decode('utf-8') + else: + help = inspect.cleandoc(help) + attrs['help'] = help + _check_for_unicode_literals() + return cls(name=name or f.__name__.lower(), + callback=f, params=params, **attrs) + + +def command(name=None, cls=None, **attrs): + """Creates a new :class:`Command` and uses the decorated function as + callback. This will also automatically attach all decorated + :func:`option`\s and :func:`argument`\s as parameters to the command. + + The name of the command defaults to the name of the function. If you + want to change that, you can pass the intended name as the first + argument. + + All keyword arguments are forwarded to the underlying command class. + + Once decorated the function turns into a :class:`Command` instance + that can be invoked as a command line utility or be attached to a + command :class:`Group`. + + :param name: the name of the command. This defaults to the function + name. + :param cls: the command class to instantiate. This defaults to + :class:`Command`. + """ + if cls is None: + cls = Command + def decorator(f): + cmd = _make_command(f, name, attrs, cls) + cmd.__doc__ = f.__doc__ + return cmd + return decorator + + +def group(name=None, **attrs): + """Creates a new :class:`Group` with a function as callback. This + works otherwise the same as :func:`command` just that the `cls` + parameter is set to :class:`Group`. + """ + attrs.setdefault('cls', Group) + return command(name, **attrs) + + +def _param_memo(f, param): + if isinstance(f, Command): + f.params.append(param) + else: + if not hasattr(f, '__click_params__'): + f.__click_params__ = [] + f.__click_params__.append(param) + + +def argument(*param_decls, **attrs): + """Attaches an argument to the command. All positional arguments are + passed as parameter declarations to :class:`Argument`; all keyword + arguments are forwarded unchanged (except ``cls``). + This is equivalent to creating an :class:`Argument` instance manually + and attaching it to the :attr:`Command.params` list. + + :param cls: the argument class to instantiate. This defaults to + :class:`Argument`. + """ + def decorator(f): + ArgumentClass = attrs.pop('cls', Argument) + _param_memo(f, ArgumentClass(param_decls, **attrs)) + return f + return decorator + + +def option(*param_decls, **attrs): + """Attaches an option to the command. All positional arguments are + passed as parameter declarations to :class:`Option`; all keyword + arguments are forwarded unchanged (except ``cls``). + This is equivalent to creating an :class:`Option` instance manually + and attaching it to the :attr:`Command.params` list. + + :param cls: the option class to instantiate. This defaults to + :class:`Option`. + """ + def decorator(f): + if 'help' in attrs: + attrs['help'] = inspect.cleandoc(attrs['help']) + OptionClass = attrs.pop('cls', Option) + _param_memo(f, OptionClass(param_decls, **attrs)) + return f + return decorator + + +def confirmation_option(*param_decls, **attrs): + """Shortcut for confirmation prompts that can be ignored by passing + ``--yes`` as parameter. + + This is equivalent to decorating a function with :func:`option` with + the following parameters:: + + def callback(ctx, param, value): + if not value: + ctx.abort() + + @click.command() + @click.option('--yes', is_flag=True, callback=callback, + expose_value=False, prompt='Do you want to continue?') + def dropdb(): + pass + """ + def decorator(f): + def callback(ctx, param, value): + if not value: + ctx.abort() + attrs.setdefault('is_flag', True) + attrs.setdefault('callback', callback) + attrs.setdefault('expose_value', False) + attrs.setdefault('prompt', 'Do you want to continue?') + attrs.setdefault('help', 'Confirm the action without prompting.') + return option(*(param_decls or ('--yes',)), **attrs)(f) + return decorator + + +def password_option(*param_decls, **attrs): + """Shortcut for password prompts. + + This is equivalent to decorating a function with :func:`option` with + the following parameters:: + + @click.command() + @click.option('--password', prompt=True, confirmation_prompt=True, + hide_input=True) + def changeadmin(password): + pass + """ + def decorator(f): + attrs.setdefault('prompt', True) + attrs.setdefault('confirmation_prompt', True) + attrs.setdefault('hide_input', True) + return option(*(param_decls or ('--password',)), **attrs)(f) + return decorator + + +def version_option(version=None, *param_decls, **attrs): + """Adds a ``--version`` option which immediately ends the program + printing out the version number. This is implemented as an eager + option that prints the version and exits the program in the callback. + + :param version: the version number to show. If not provided Click + attempts an auto discovery via setuptools. + :param prog_name: the name of the program (defaults to autodetection) + :param message: custom message to show instead of the default + (``'%(prog)s, version %(version)s'``) + :param others: everything else is forwarded to :func:`option`. + """ + if version is None: + module = sys._getframe(1).f_globals.get('__name__') + def decorator(f): + prog_name = attrs.pop('prog_name', None) + message = attrs.pop('message', '%(prog)s, version %(version)s') + + def callback(ctx, param, value): + if not value or ctx.resilient_parsing: + return + prog = prog_name + if prog is None: + prog = ctx.find_root().info_name + ver = version + if ver is None: + try: + import pkg_resources + except ImportError: + pass + else: + for dist in pkg_resources.working_set: + scripts = dist.get_entry_map().get('console_scripts') or {} + for script_name, entry_point in iteritems(scripts): + if entry_point.module_name == module: + ver = dist.version + break + if ver is None: + raise RuntimeError('Could not determine version') + echo(message % { + 'prog': prog, + 'version': ver, + }, color=ctx.color) + ctx.exit() + + attrs.setdefault('is_flag', True) + attrs.setdefault('expose_value', False) + attrs.setdefault('is_eager', True) + attrs.setdefault('help', 'Show the version and exit.') + attrs['callback'] = callback + return option(*(param_decls or ('--version',)), **attrs)(f) + return decorator + + +def help_option(*param_decls, **attrs): + """Adds a ``--help`` option which immediately ends the program + printing out the help page. This is usually unnecessary to add as + this is added by default to all commands unless suppressed. + + Like :func:`version_option`, this is implemented as eager option that + prints in the callback and exits. + + All arguments are forwarded to :func:`option`. + """ + def decorator(f): + def callback(ctx, param, value): + if value and not ctx.resilient_parsing: + echo(ctx.get_help(), color=ctx.color) + ctx.exit() + attrs.setdefault('is_flag', True) + attrs.setdefault('expose_value', False) + attrs.setdefault('help', 'Show this message and exit.') + attrs.setdefault('is_eager', True) + attrs['callback'] = callback + return option(*(param_decls or ('--help',)), **attrs)(f) + return decorator + + +# Circular dependencies between core and decorators +from .core import Command, Group, Argument, Option diff --git a/pyextra/click/exceptions.py b/pyextra/click/exceptions.py new file mode 100644 index 00000000000000..74a4542bb57f29 --- /dev/null +++ b/pyextra/click/exceptions.py @@ -0,0 +1,201 @@ +from ._compat import PY2, filename_to_ui, get_text_stderr +from .utils import echo + + +class ClickException(Exception): + """An exception that Click can handle and show to the user.""" + + #: The exit code for this exception + exit_code = 1 + + def __init__(self, message): + if PY2: + if message is not None: + message = message.encode('utf-8') + Exception.__init__(self, message) + self.message = message + + def format_message(self): + return self.message + + def show(self, file=None): + if file is None: + file = get_text_stderr() + echo('Error: %s' % self.format_message(), file=file) + + +class UsageError(ClickException): + """An internal exception that signals a usage error. This typically + aborts any further handling. + + :param message: the error message to display. + :param ctx: optionally the context that caused this error. Click will + fill in the context automatically in some situations. + """ + exit_code = 2 + + def __init__(self, message, ctx=None): + ClickException.__init__(self, message) + self.ctx = ctx + + def show(self, file=None): + if file is None: + file = get_text_stderr() + color = None + if self.ctx is not None: + color = self.ctx.color + echo(self.ctx.get_usage() + '\n', file=file, color=color) + echo('Error: %s' % self.format_message(), file=file, color=color) + + +class BadParameter(UsageError): + """An exception that formats out a standardized error message for a + bad parameter. This is useful when thrown from a callback or type as + Click will attach contextual information to it (for instance, which + parameter it is). + + .. versionadded:: 2.0 + + :param param: the parameter object that caused this error. This can + be left out, and Click will attach this info itself + if possible. + :param param_hint: a string that shows up as parameter name. This + can be used as alternative to `param` in cases + where custom validation should happen. If it is + a string it's used as such, if it's a list then + each item is quoted and separated. + """ + + def __init__(self, message, ctx=None, param=None, + param_hint=None): + UsageError.__init__(self, message, ctx) + self.param = param + self.param_hint = param_hint + + def format_message(self): + if self.param_hint is not None: + param_hint = self.param_hint + elif self.param is not None: + param_hint = self.param.opts or [self.param.human_readable_name] + else: + return 'Invalid value: %s' % self.message + if isinstance(param_hint, (tuple, list)): + param_hint = ' / '.join('"%s"' % x for x in param_hint) + return 'Invalid value for %s: %s' % (param_hint, self.message) + + +class MissingParameter(BadParameter): + """Raised if click required an option or argument but it was not + provided when invoking the script. + + .. versionadded:: 4.0 + + :param param_type: a string that indicates the type of the parameter. + The default is to inherit the parameter type from + the given `param`. Valid values are ``'parameter'``, + ``'option'`` or ``'argument'``. + """ + + def __init__(self, message=None, ctx=None, param=None, + param_hint=None, param_type=None): + BadParameter.__init__(self, message, ctx, param, param_hint) + self.param_type = param_type + + def format_message(self): + if self.param_hint is not None: + param_hint = self.param_hint + elif self.param is not None: + param_hint = self.param.opts or [self.param.human_readable_name] + else: + param_hint = None + if isinstance(param_hint, (tuple, list)): + param_hint = ' / '.join('"%s"' % x for x in param_hint) + + param_type = self.param_type + if param_type is None and self.param is not None: + param_type = self.param.param_type_name + + msg = self.message + if self.param is not None: + msg_extra = self.param.type.get_missing_message(self.param) + if msg_extra: + if msg: + msg += '. ' + msg_extra + else: + msg = msg_extra + + return 'Missing %s%s%s%s' % ( + param_type, + param_hint and ' %s' % param_hint or '', + msg and '. ' or '.', + msg or '', + ) + + +class NoSuchOption(UsageError): + """Raised if click attempted to handle an option that does not + exist. + + .. versionadded:: 4.0 + """ + + def __init__(self, option_name, message=None, possibilities=None, + ctx=None): + if message is None: + message = 'no such option: %s' % option_name + UsageError.__init__(self, message, ctx) + self.option_name = option_name + self.possibilities = possibilities + + def format_message(self): + bits = [self.message] + if self.possibilities: + if len(self.possibilities) == 1: + bits.append('Did you mean %s?' % self.possibilities[0]) + else: + possibilities = sorted(self.possibilities) + bits.append('(Possible options: %s)' % ', '.join(possibilities)) + return ' '.join(bits) + + +class BadOptionUsage(UsageError): + """Raised if an option is generally supplied but the use of the option + was incorrect. This is for instance raised if the number of arguments + for an option is not correct. + + .. versionadded:: 4.0 + """ + + def __init__(self, message, ctx=None): + UsageError.__init__(self, message, ctx) + + +class BadArgumentUsage(UsageError): + """Raised if an argument is generally supplied but the use of the argument + was incorrect. This is for instance raised if the number of values + for an argument is not correct. + + .. versionadded:: 6.0 + """ + + def __init__(self, message, ctx=None): + UsageError.__init__(self, message, ctx) + + +class FileError(ClickException): + """Raised if a file cannot be opened.""" + + def __init__(self, filename, hint=None): + ui_filename = filename_to_ui(filename) + if hint is None: + hint = 'unknown error' + ClickException.__init__(self, hint) + self.ui_filename = ui_filename + self.filename = filename + + def format_message(self): + return 'Could not open file %s: %s' % (self.ui_filename, self.message) + + +class Abort(RuntimeError): + """An internal signalling exception that signals Click to abort.""" diff --git a/pyextra/click/formatting.py b/pyextra/click/formatting.py new file mode 100644 index 00000000000000..a3d6a4d389019c --- /dev/null +++ b/pyextra/click/formatting.py @@ -0,0 +1,256 @@ +from contextlib import contextmanager +from .termui import get_terminal_size +from .parser import split_opt +from ._compat import term_len + + +# Can force a width. This is used by the test system +FORCED_WIDTH = None + + +def measure_table(rows): + widths = {} + for row in rows: + for idx, col in enumerate(row): + widths[idx] = max(widths.get(idx, 0), term_len(col)) + return tuple(y for x, y in sorted(widths.items())) + + +def iter_rows(rows, col_count): + for row in rows: + row = tuple(row) + yield row + ('',) * (col_count - len(row)) + + +def wrap_text(text, width=78, initial_indent='', subsequent_indent='', + preserve_paragraphs=False): + """A helper function that intelligently wraps text. By default, it + assumes that it operates on a single paragraph of text but if the + `preserve_paragraphs` parameter is provided it will intelligently + handle paragraphs (defined by two empty lines). + + If paragraphs are handled, a paragraph can be prefixed with an empty + line containing the ``\\b`` character (``\\x08``) to indicate that + no rewrapping should happen in that block. + + :param text: the text that should be rewrapped. + :param width: the maximum width for the text. + :param initial_indent: the initial indent that should be placed on the + first line as a string. + :param subsequent_indent: the indent string that should be placed on + each consecutive line. + :param preserve_paragraphs: if this flag is set then the wrapping will + intelligently handle paragraphs. + """ + from ._textwrap import TextWrapper + text = text.expandtabs() + wrapper = TextWrapper(width, initial_indent=initial_indent, + subsequent_indent=subsequent_indent, + replace_whitespace=False) + if not preserve_paragraphs: + return wrapper.fill(text) + + p = [] + buf = [] + indent = None + + def _flush_par(): + if not buf: + return + if buf[0].strip() == '\b': + p.append((indent or 0, True, '\n'.join(buf[1:]))) + else: + p.append((indent or 0, False, ' '.join(buf))) + del buf[:] + + for line in text.splitlines(): + if not line: + _flush_par() + indent = None + else: + if indent is None: + orig_len = term_len(line) + line = line.lstrip() + indent = orig_len - term_len(line) + buf.append(line) + _flush_par() + + rv = [] + for indent, raw, text in p: + with wrapper.extra_indent(' ' * indent): + if raw: + rv.append(wrapper.indent_only(text)) + else: + rv.append(wrapper.fill(text)) + + return '\n\n'.join(rv) + + +class HelpFormatter(object): + """This class helps with formatting text-based help pages. It's + usually just needed for very special internal cases, but it's also + exposed so that developers can write their own fancy outputs. + + At present, it always writes into memory. + + :param indent_increment: the additional increment for each level. + :param width: the width for the text. This defaults to the terminal + width clamped to a maximum of 78. + """ + + def __init__(self, indent_increment=2, width=None, max_width=None): + self.indent_increment = indent_increment + if max_width is None: + max_width = 80 + if width is None: + width = FORCED_WIDTH + if width is None: + width = max(min(get_terminal_size()[0], max_width) - 2, 50) + self.width = width + self.current_indent = 0 + self.buffer = [] + + def write(self, string): + """Writes a unicode string into the internal buffer.""" + self.buffer.append(string) + + def indent(self): + """Increases the indentation.""" + self.current_indent += self.indent_increment + + def dedent(self): + """Decreases the indentation.""" + self.current_indent -= self.indent_increment + + def write_usage(self, prog, args='', prefix='Usage: '): + """Writes a usage line into the buffer. + + :param prog: the program name. + :param args: whitespace separated list of arguments. + :param prefix: the prefix for the first line. + """ + usage_prefix = '%*s%s ' % (self.current_indent, prefix, prog) + text_width = self.width - self.current_indent + + if text_width >= (term_len(usage_prefix) + 20): + # The arguments will fit to the right of the prefix. + indent = ' ' * term_len(usage_prefix) + self.write(wrap_text(args, text_width, + initial_indent=usage_prefix, + subsequent_indent=indent)) + else: + # The prefix is too long, put the arguments on the next line. + self.write(usage_prefix) + self.write('\n') + indent = ' ' * (max(self.current_indent, term_len(prefix)) + 4) + self.write(wrap_text(args, text_width, + initial_indent=indent, + subsequent_indent=indent)) + + self.write('\n') + + def write_heading(self, heading): + """Writes a heading into the buffer.""" + self.write('%*s%s:\n' % (self.current_indent, '', heading)) + + def write_paragraph(self): + """Writes a paragraph into the buffer.""" + if self.buffer: + self.write('\n') + + def write_text(self, text): + """Writes re-indented text into the buffer. This rewraps and + preserves paragraphs. + """ + text_width = max(self.width - self.current_indent, 11) + indent = ' ' * self.current_indent + self.write(wrap_text(text, text_width, + initial_indent=indent, + subsequent_indent=indent, + preserve_paragraphs=True)) + self.write('\n') + + def write_dl(self, rows, col_max=30, col_spacing=2): + """Writes a definition list into the buffer. This is how options + and commands are usually formatted. + + :param rows: a list of two item tuples for the terms and values. + :param col_max: the maximum width of the first column. + :param col_spacing: the number of spaces between the first and + second column. + """ + rows = list(rows) + widths = measure_table(rows) + if len(widths) != 2: + raise TypeError('Expected two columns for definition list') + + first_col = min(widths[0], col_max) + col_spacing + + for first, second in iter_rows(rows, len(widths)): + self.write('%*s%s' % (self.current_indent, '', first)) + if not second: + self.write('\n') + continue + if term_len(first) <= first_col - col_spacing: + self.write(' ' * (first_col - term_len(first))) + else: + self.write('\n') + self.write(' ' * (first_col + self.current_indent)) + + text_width = max(self.width - first_col - 2, 10) + lines = iter(wrap_text(second, text_width).splitlines()) + if lines: + self.write(next(lines) + '\n') + for line in lines: + self.write('%*s%s\n' % ( + first_col + self.current_indent, '', line)) + else: + self.write('\n') + + @contextmanager + def section(self, name): + """Helpful context manager that writes a paragraph, a heading, + and the indents. + + :param name: the section name that is written as heading. + """ + self.write_paragraph() + self.write_heading(name) + self.indent() + try: + yield + finally: + self.dedent() + + @contextmanager + def indentation(self): + """A context manager that increases the indentation.""" + self.indent() + try: + yield + finally: + self.dedent() + + def getvalue(self): + """Returns the buffer contents.""" + return ''.join(self.buffer) + + +def join_options(options): + """Given a list of option strings this joins them in the most appropriate + way and returns them in the form ``(formatted_string, + any_prefix_is_slash)`` where the second item in the tuple is a flag that + indicates if any of the option prefixes was a slash. + """ + rv = [] + any_prefix_is_slash = False + for opt in options: + prefix = split_opt(opt)[0] + if prefix == '/': + any_prefix_is_slash = True + rv.append((len(prefix), opt)) + + rv.sort(key=lambda x: x[0]) + + rv = ', '.join(x[1] for x in rv) + return rv, any_prefix_is_slash diff --git a/pyextra/click/globals.py b/pyextra/click/globals.py new file mode 100644 index 00000000000000..14338e6bb8434b --- /dev/null +++ b/pyextra/click/globals.py @@ -0,0 +1,48 @@ +from threading import local + + +_local = local() + + +def get_current_context(silent=False): + """Returns the current click context. This can be used as a way to + access the current context object from anywhere. This is a more implicit + alternative to the :func:`pass_context` decorator. This function is + primarily useful for helpers such as :func:`echo` which might be + interested in changing it's behavior based on the current context. + + To push the current context, :meth:`Context.scope` can be used. + + .. versionadded:: 5.0 + + :param silent: is set to `True` the return value is `None` if no context + is available. The default behavior is to raise a + :exc:`RuntimeError`. + """ + try: + return getattr(_local, 'stack')[-1] + except (AttributeError, IndexError): + if not silent: + raise RuntimeError('There is no active click context.') + + +def push_context(ctx): + """Pushes a new context to the current stack.""" + _local.__dict__.setdefault('stack', []).append(ctx) + + +def pop_context(): + """Removes the top level from the stack.""" + _local.stack.pop() + + +def resolve_color_default(color=None): + """"Internal helper to get the default value of the color flag. If a + value is passed it's returned unchanged, otherwise it's looked up from + the current context. + """ + if color is not None: + return color + ctx = get_current_context(silent=True) + if ctx is not None: + return ctx.color diff --git a/pyextra/click/parser.py b/pyextra/click/parser.py new file mode 100644 index 00000000000000..9775c9ff9b99d8 --- /dev/null +++ b/pyextra/click/parser.py @@ -0,0 +1,426 @@ +# -*- coding: utf-8 -*- +""" + click.parser + ~~~~~~~~~~~~ + + This module started out as largely a copy paste from the stdlib's + optparse module with the features removed that we do not need from + optparse because we implement them in Click on a higher level (for + instance type handling, help formatting and a lot more). + + The plan is to remove more and more from here over time. + + The reason this is a different module and not optparse from the stdlib + is that there are differences in 2.x and 3.x about the error messages + generated and optparse in the stdlib uses gettext for no good reason + and might cause us issues. +""" +import re +from collections import deque +from .exceptions import UsageError, NoSuchOption, BadOptionUsage, \ + BadArgumentUsage + + +def _unpack_args(args, nargs_spec): + """Given an iterable of arguments and an iterable of nargs specifications, + it returns a tuple with all the unpacked arguments at the first index + and all remaining arguments as the second. + + The nargs specification is the number of arguments that should be consumed + or `-1` to indicate that this position should eat up all the remainders. + + Missing items are filled with `None`. + """ + args = deque(args) + nargs_spec = deque(nargs_spec) + rv = [] + spos = None + + def _fetch(c): + try: + if spos is None: + return c.popleft() + else: + return c.pop() + except IndexError: + return None + + while nargs_spec: + nargs = _fetch(nargs_spec) + if nargs == 1: + rv.append(_fetch(args)) + elif nargs > 1: + x = [_fetch(args) for _ in range(nargs)] + # If we're reversed, we're pulling in the arguments in reverse, + # so we need to turn them around. + if spos is not None: + x.reverse() + rv.append(tuple(x)) + elif nargs < 0: + if spos is not None: + raise TypeError('Cannot have two nargs < 0') + spos = len(rv) + rv.append(None) + + # spos is the position of the wildcard (star). If it's not `None`, + # we fill it with the remainder. + if spos is not None: + rv[spos] = tuple(args) + args = [] + rv[spos + 1:] = reversed(rv[spos + 1:]) + + return tuple(rv), list(args) + + +def _error_opt_args(nargs, opt): + if nargs == 1: + raise BadOptionUsage('%s option requires an argument' % opt) + raise BadOptionUsage('%s option requires %d arguments' % (opt, nargs)) + + +def split_opt(opt): + first = opt[:1] + if first.isalnum(): + return '', opt + if opt[1:2] == first: + return opt[:2], opt[2:] + return first, opt[1:] + + +def normalize_opt(opt, ctx): + if ctx is None or ctx.token_normalize_func is None: + return opt + prefix, opt = split_opt(opt) + return prefix + ctx.token_normalize_func(opt) + + +def split_arg_string(string): + """Given an argument string this attempts to split it into small parts.""" + rv = [] + for match in re.finditer(r"('([^'\\]*(?:\\.[^'\\]*)*)'" + r'|"([^"\\]*(?:\\.[^"\\]*)*)"' + r'|\S+)\s*', string, re.S): + arg = match.group().strip() + if arg[:1] == arg[-1:] and arg[:1] in '"\'': + arg = arg[1:-1].encode('ascii', 'backslashreplace') \ + .decode('unicode-escape') + try: + arg = type(string)(arg) + except UnicodeError: + pass + rv.append(arg) + return rv + + +class Option(object): + + def __init__(self, opts, dest, action=None, nargs=1, const=None, obj=None): + self._short_opts = [] + self._long_opts = [] + self.prefixes = set() + + for opt in opts: + prefix, value = split_opt(opt) + if not prefix: + raise ValueError('Invalid start character for option (%s)' + % opt) + self.prefixes.add(prefix[0]) + if len(prefix) == 1 and len(value) == 1: + self._short_opts.append(opt) + else: + self._long_opts.append(opt) + self.prefixes.add(prefix) + + if action is None: + action = 'store' + + self.dest = dest + self.action = action + self.nargs = nargs + self.const = const + self.obj = obj + + @property + def takes_value(self): + return self.action in ('store', 'append') + + def process(self, value, state): + if self.action == 'store': + state.opts[self.dest] = value + elif self.action == 'store_const': + state.opts[self.dest] = self.const + elif self.action == 'append': + state.opts.setdefault(self.dest, []).append(value) + elif self.action == 'append_const': + state.opts.setdefault(self.dest, []).append(self.const) + elif self.action == 'count': + state.opts[self.dest] = state.opts.get(self.dest, 0) + 1 + else: + raise ValueError('unknown action %r' % self.action) + state.order.append(self.obj) + + +class Argument(object): + + def __init__(self, dest, nargs=1, obj=None): + self.dest = dest + self.nargs = nargs + self.obj = obj + + def process(self, value, state): + if self.nargs > 1: + holes = sum(1 for x in value if x is None) + if holes == len(value): + value = None + elif holes != 0: + raise BadArgumentUsage('argument %s takes %d values' + % (self.dest, self.nargs)) + state.opts[self.dest] = value + state.order.append(self.obj) + + +class ParsingState(object): + + def __init__(self, rargs): + self.opts = {} + self.largs = [] + self.rargs = rargs + self.order = [] + + +class OptionParser(object): + """The option parser is an internal class that is ultimately used to + parse options and arguments. It's modelled after optparse and brings + a similar but vastly simplified API. It should generally not be used + directly as the high level Click classes wrap it for you. + + It's not nearly as extensible as optparse or argparse as it does not + implement features that are implemented on a higher level (such as + types or defaults). + + :param ctx: optionally the :class:`~click.Context` where this parser + should go with. + """ + + def __init__(self, ctx=None): + #: The :class:`~click.Context` for this parser. This might be + #: `None` for some advanced use cases. + self.ctx = ctx + #: This controls how the parser deals with interspersed arguments. + #: If this is set to `False`, the parser will stop on the first + #: non-option. Click uses this to implement nested subcommands + #: safely. + self.allow_interspersed_args = True + #: This tells the parser how to deal with unknown options. By + #: default it will error out (which is sensible), but there is a + #: second mode where it will ignore it and continue processing + #: after shifting all the unknown options into the resulting args. + self.ignore_unknown_options = False + if ctx is not None: + self.allow_interspersed_args = ctx.allow_interspersed_args + self.ignore_unknown_options = ctx.ignore_unknown_options + self._short_opt = {} + self._long_opt = {} + self._opt_prefixes = set(['-', '--']) + self._args = [] + + def add_option(self, opts, dest, action=None, nargs=1, const=None, + obj=None): + """Adds a new option named `dest` to the parser. The destination + is not inferred (unlike with optparse) and needs to be explicitly + provided. Action can be any of ``store``, ``store_const``, + ``append``, ``appnd_const`` or ``count``. + + The `obj` can be used to identify the option in the order list + that is returned from the parser. + """ + if obj is None: + obj = dest + opts = [normalize_opt(opt, self.ctx) for opt in opts] + option = Option(opts, dest, action=action, nargs=nargs, + const=const, obj=obj) + self._opt_prefixes.update(option.prefixes) + for opt in option._short_opts: + self._short_opt[opt] = option + for opt in option._long_opts: + self._long_opt[opt] = option + + def add_argument(self, dest, nargs=1, obj=None): + """Adds a positional argument named `dest` to the parser. + + The `obj` can be used to identify the option in the order list + that is returned from the parser. + """ + if obj is None: + obj = dest + self._args.append(Argument(dest=dest, nargs=nargs, obj=obj)) + + def parse_args(self, args): + """Parses positional arguments and returns ``(values, args, order)`` + for the parsed options and arguments as well as the leftover + arguments if there are any. The order is a list of objects as they + appear on the command line. If arguments appear multiple times they + will be memorized multiple times as well. + """ + state = ParsingState(args) + try: + self._process_args_for_options(state) + self._process_args_for_args(state) + except UsageError: + if self.ctx is None or not self.ctx.resilient_parsing: + raise + return state.opts, state.largs, state.order + + def _process_args_for_args(self, state): + pargs, args = _unpack_args(state.largs + state.rargs, + [x.nargs for x in self._args]) + + for idx, arg in enumerate(self._args): + arg.process(pargs[idx], state) + + state.largs = args + state.rargs = [] + + def _process_args_for_options(self, state): + while state.rargs: + arg = state.rargs.pop(0) + arglen = len(arg) + # Double dashes always handled explicitly regardless of what + # prefixes are valid. + if arg == '--': + return + elif arg[:1] in self._opt_prefixes and arglen > 1: + self._process_opts(arg, state) + elif self.allow_interspersed_args: + state.largs.append(arg) + else: + state.rargs.insert(0, arg) + return + + # Say this is the original argument list: + # [arg0, arg1, ..., arg(i-1), arg(i), arg(i+1), ..., arg(N-1)] + # ^ + # (we are about to process arg(i)). + # + # Then rargs is [arg(i), ..., arg(N-1)] and largs is a *subset* of + # [arg0, ..., arg(i-1)] (any options and their arguments will have + # been removed from largs). + # + # The while loop will usually consume 1 or more arguments per pass. + # If it consumes 1 (eg. arg is an option that takes no arguments), + # then after _process_arg() is done the situation is: + # + # largs = subset of [arg0, ..., arg(i)] + # rargs = [arg(i+1), ..., arg(N-1)] + # + # If allow_interspersed_args is false, largs will always be + # *empty* -- still a subset of [arg0, ..., arg(i-1)], but + # not a very interesting subset! + + def _match_long_opt(self, opt, explicit_value, state): + if opt not in self._long_opt: + possibilities = [word for word in self._long_opt + if word.startswith(opt)] + raise NoSuchOption(opt, possibilities=possibilities) + + option = self._long_opt[opt] + if option.takes_value: + # At this point it's safe to modify rargs by injecting the + # explicit value, because no exception is raised in this + # branch. This means that the inserted value will be fully + # consumed. + if explicit_value is not None: + state.rargs.insert(0, explicit_value) + + nargs = option.nargs + if len(state.rargs) < nargs: + _error_opt_args(nargs, opt) + elif nargs == 1: + value = state.rargs.pop(0) + else: + value = tuple(state.rargs[:nargs]) + del state.rargs[:nargs] + + elif explicit_value is not None: + raise BadOptionUsage('%s option does not take a value' % opt) + + else: + value = None + + option.process(value, state) + + def _match_short_opt(self, arg, state): + stop = False + i = 1 + prefix = arg[0] + unknown_options = [] + + for ch in arg[1:]: + opt = normalize_opt(prefix + ch, self.ctx) + option = self._short_opt.get(opt) + i += 1 + + if not option: + if self.ignore_unknown_options: + unknown_options.append(ch) + continue + raise NoSuchOption(opt) + if option.takes_value: + # Any characters left in arg? Pretend they're the + # next arg, and stop consuming characters of arg. + if i < len(arg): + state.rargs.insert(0, arg[i:]) + stop = True + + nargs = option.nargs + if len(state.rargs) < nargs: + _error_opt_args(nargs, opt) + elif nargs == 1: + value = state.rargs.pop(0) + else: + value = tuple(state.rargs[:nargs]) + del state.rargs[:nargs] + + else: + value = None + + option.process(value, state) + + if stop: + break + + # If we got any unknown options we re-combinate the string of the + # remaining options and re-attach the prefix, then report that + # to the state as new larg. This way there is basic combinatorics + # that can be achieved while still ignoring unknown arguments. + if self.ignore_unknown_options and unknown_options: + state.largs.append(prefix + ''.join(unknown_options)) + + def _process_opts(self, arg, state): + explicit_value = None + # Long option handling happens in two parts. The first part is + # supporting explicitly attached values. In any case, we will try + # to long match the option first. + if '=' in arg: + long_opt, explicit_value = arg.split('=', 1) + else: + long_opt = arg + norm_long_opt = normalize_opt(long_opt, self.ctx) + + # At this point we will match the (assumed) long option through + # the long option matching code. Note that this allows options + # like "-foo" to be matched as long options. + try: + self._match_long_opt(norm_long_opt, explicit_value, state) + except NoSuchOption: + # At this point the long option matching failed, and we need + # to try with short options. However there is a special rule + # which says, that if we have a two character options prefix + # (applies to "--foo" for instance), we do not dispatch to the + # short option code and will instead raise the no option + # error. + if arg[:2] not in self._opt_prefixes: + return self._match_short_opt(arg, state) + if not self.ignore_unknown_options: + raise + state.largs.append(arg) diff --git a/pyextra/click/termui.py b/pyextra/click/termui.py new file mode 100644 index 00000000000000..d9fba52325f35b --- /dev/null +++ b/pyextra/click/termui.py @@ -0,0 +1,539 @@ +import os +import sys +import struct + +from ._compat import raw_input, text_type, string_types, \ + isatty, strip_ansi, get_winterm_size, DEFAULT_COLUMNS, WIN +from .utils import echo +from .exceptions import Abort, UsageError +from .types import convert_type +from .globals import resolve_color_default + + +# The prompt functions to use. The doc tools currently override these +# functions to customize how they work. +visible_prompt_func = raw_input + +_ansi_colors = ('black', 'red', 'green', 'yellow', 'blue', 'magenta', + 'cyan', 'white', 'reset') +_ansi_reset_all = '\033[0m' + + +def hidden_prompt_func(prompt): + import getpass + return getpass.getpass(prompt) + + +def _build_prompt(text, suffix, show_default=False, default=None): + prompt = text + if default is not None and show_default: + prompt = '%s [%s]' % (prompt, default) + return prompt + suffix + + +def prompt(text, default=None, hide_input=False, + confirmation_prompt=False, type=None, + value_proc=None, prompt_suffix=': ', + show_default=True, err=False): + """Prompts a user for input. This is a convenience function that can + be used to prompt a user for input later. + + If the user aborts the input by sending a interrupt signal, this + function will catch it and raise a :exc:`Abort` exception. + + .. versionadded:: 6.0 + Added unicode support for cmd.exe on Windows. + + .. versionadded:: 4.0 + Added the `err` parameter. + + :param text: the text to show for the prompt. + :param default: the default value to use if no input happens. If this + is not given it will prompt until it's aborted. + :param hide_input: if this is set to true then the input value will + be hidden. + :param confirmation_prompt: asks for confirmation for the value. + :param type: the type to use to check the value against. + :param value_proc: if this parameter is provided it's a function that + is invoked instead of the type conversion to + convert a value. + :param prompt_suffix: a suffix that should be added to the prompt. + :param show_default: shows or hides the default value in the prompt. + :param err: if set to true the file defaults to ``stderr`` instead of + ``stdout``, the same as with echo. + """ + result = None + + def prompt_func(text): + f = hide_input and hidden_prompt_func or visible_prompt_func + try: + # Write the prompt separately so that we get nice + # coloring through colorama on Windows + echo(text, nl=False, err=err) + return f('') + except (KeyboardInterrupt, EOFError): + # getpass doesn't print a newline if the user aborts input with ^C. + # Allegedly this behavior is inherited from getpass(3). + # A doc bug has been filed at https://bugs.python.org/issue24711 + if hide_input: + echo(None, err=err) + raise Abort() + + if value_proc is None: + value_proc = convert_type(type, default) + + prompt = _build_prompt(text, prompt_suffix, show_default, default) + + while 1: + while 1: + value = prompt_func(prompt) + if value: + break + # If a default is set and used, then the confirmation + # prompt is always skipped because that's the only thing + # that really makes sense. + elif default is not None: + return default + try: + result = value_proc(value) + except UsageError as e: + echo('Error: %s' % e.message, err=err) + continue + if not confirmation_prompt: + return result + while 1: + value2 = prompt_func('Repeat for confirmation: ') + if value2: + break + if value == value2: + return result + echo('Error: the two entered values do not match', err=err) + + +def confirm(text, default=False, abort=False, prompt_suffix=': ', + show_default=True, err=False): + """Prompts for confirmation (yes/no question). + + If the user aborts the input by sending a interrupt signal this + function will catch it and raise a :exc:`Abort` exception. + + .. versionadded:: 4.0 + Added the `err` parameter. + + :param text: the question to ask. + :param default: the default for the prompt. + :param abort: if this is set to `True` a negative answer aborts the + exception by raising :exc:`Abort`. + :param prompt_suffix: a suffix that should be added to the prompt. + :param show_default: shows or hides the default value in the prompt. + :param err: if set to true the file defaults to ``stderr`` instead of + ``stdout``, the same as with echo. + """ + prompt = _build_prompt(text, prompt_suffix, show_default, + default and 'Y/n' or 'y/N') + while 1: + try: + # Write the prompt separately so that we get nice + # coloring through colorama on Windows + echo(prompt, nl=False, err=err) + value = visible_prompt_func('').lower().strip() + except (KeyboardInterrupt, EOFError): + raise Abort() + if value in ('y', 'yes'): + rv = True + elif value in ('n', 'no'): + rv = False + elif value == '': + rv = default + else: + echo('Error: invalid input', err=err) + continue + break + if abort and not rv: + raise Abort() + return rv + + +def get_terminal_size(): + """Returns the current size of the terminal as tuple in the form + ``(width, height)`` in columns and rows. + """ + # If shutil has get_terminal_size() (Python 3.3 and later) use that + if sys.version_info >= (3, 3): + import shutil + shutil_get_terminal_size = getattr(shutil, 'get_terminal_size', None) + if shutil_get_terminal_size: + sz = shutil_get_terminal_size() + return sz.columns, sz.lines + + if get_winterm_size is not None: + return get_winterm_size() + + def ioctl_gwinsz(fd): + try: + import fcntl + import termios + cr = struct.unpack( + 'hh', fcntl.ioctl(fd, termios.TIOCGWINSZ, '1234')) + except Exception: + return + return cr + + cr = ioctl_gwinsz(0) or ioctl_gwinsz(1) or ioctl_gwinsz(2) + if not cr: + try: + fd = os.open(os.ctermid(), os.O_RDONLY) + try: + cr = ioctl_gwinsz(fd) + finally: + os.close(fd) + except Exception: + pass + if not cr or not cr[0] or not cr[1]: + cr = (os.environ.get('LINES', 25), + os.environ.get('COLUMNS', DEFAULT_COLUMNS)) + return int(cr[1]), int(cr[0]) + + +def echo_via_pager(text, color=None): + """This function takes a text and shows it via an environment specific + pager on stdout. + + .. versionchanged:: 3.0 + Added the `color` flag. + + :param text: the text to page. + :param color: controls if the pager supports ANSI colors or not. The + default is autodetection. + """ + color = resolve_color_default(color) + if not isinstance(text, string_types): + text = text_type(text) + from ._termui_impl import pager + return pager(text + '\n', color) + + +def progressbar(iterable=None, length=None, label=None, show_eta=True, + show_percent=None, show_pos=False, + item_show_func=None, fill_char='#', empty_char='-', + bar_template='%(label)s [%(bar)s] %(info)s', + info_sep=' ', width=36, file=None, color=None): + """This function creates an iterable context manager that can be used + to iterate over something while showing a progress bar. It will + either iterate over the `iterable` or `length` items (that are counted + up). While iteration happens, this function will print a rendered + progress bar to the given `file` (defaults to stdout) and will attempt + to calculate remaining time and more. By default, this progress bar + will not be rendered if the file is not a terminal. + + The context manager creates the progress bar. When the context + manager is entered the progress bar is already displayed. With every + iteration over the progress bar, the iterable passed to the bar is + advanced and the bar is updated. When the context manager exits, + a newline is printed and the progress bar is finalized on screen. + + No printing must happen or the progress bar will be unintentionally + destroyed. + + Example usage:: + + with progressbar(items) as bar: + for item in bar: + do_something_with(item) + + Alternatively, if no iterable is specified, one can manually update the + progress bar through the `update()` method instead of directly + iterating over the progress bar. The update method accepts the number + of steps to increment the bar with:: + + with progressbar(length=chunks.total_bytes) as bar: + for chunk in chunks: + process_chunk(chunk) + bar.update(chunks.bytes) + + .. versionadded:: 2.0 + + .. versionadded:: 4.0 + Added the `color` parameter. Added a `update` method to the + progressbar object. + + :param iterable: an iterable to iterate over. If not provided the length + is required. + :param length: the number of items to iterate over. By default the + progressbar will attempt to ask the iterator about its + length, which might or might not work. If an iterable is + also provided this parameter can be used to override the + length. If an iterable is not provided the progress bar + will iterate over a range of that length. + :param label: the label to show next to the progress bar. + :param show_eta: enables or disables the estimated time display. This is + automatically disabled if the length cannot be + determined. + :param show_percent: enables or disables the percentage display. The + default is `True` if the iterable has a length or + `False` if not. + :param show_pos: enables or disables the absolute position display. The + default is `False`. + :param item_show_func: a function called with the current item which + can return a string to show the current item + next to the progress bar. Note that the current + item can be `None`! + :param fill_char: the character to use to show the filled part of the + progress bar. + :param empty_char: the character to use to show the non-filled part of + the progress bar. + :param bar_template: the format string to use as template for the bar. + The parameters in it are ``label`` for the label, + ``bar`` for the progress bar and ``info`` for the + info section. + :param info_sep: the separator between multiple info items (eta etc.) + :param width: the width of the progress bar in characters, 0 means full + terminal width + :param file: the file to write to. If this is not a terminal then + only the label is printed. + :param color: controls if the terminal supports ANSI colors or not. The + default is autodetection. This is only needed if ANSI + codes are included anywhere in the progress bar output + which is not the case by default. + """ + from ._termui_impl import ProgressBar + color = resolve_color_default(color) + return ProgressBar(iterable=iterable, length=length, show_eta=show_eta, + show_percent=show_percent, show_pos=show_pos, + item_show_func=item_show_func, fill_char=fill_char, + empty_char=empty_char, bar_template=bar_template, + info_sep=info_sep, file=file, label=label, + width=width, color=color) + + +def clear(): + """Clears the terminal screen. This will have the effect of clearing + the whole visible space of the terminal and moving the cursor to the + top left. This does not do anything if not connected to a terminal. + + .. versionadded:: 2.0 + """ + if not isatty(sys.stdout): + return + # If we're on Windows and we don't have colorama available, then we + # clear the screen by shelling out. Otherwise we can use an escape + # sequence. + if WIN: + os.system('cls') + else: + sys.stdout.write('\033[2J\033[1;1H') + + +def style(text, fg=None, bg=None, bold=None, dim=None, underline=None, + blink=None, reverse=None, reset=True): + """Styles a text with ANSI styles and returns the new string. By + default the styling is self contained which means that at the end + of the string a reset code is issued. This can be prevented by + passing ``reset=False``. + + Examples:: + + click.echo(click.style('Hello World!', fg='green')) + click.echo(click.style('ATTENTION!', blink=True)) + click.echo(click.style('Some things', reverse=True, fg='cyan')) + + Supported color names: + + * ``black`` (might be a gray) + * ``red`` + * ``green`` + * ``yellow`` (might be an orange) + * ``blue`` + * ``magenta`` + * ``cyan`` + * ``white`` (might be light gray) + * ``reset`` (reset the color code only) + + .. versionadded:: 2.0 + + :param text: the string to style with ansi codes. + :param fg: if provided this will become the foreground color. + :param bg: if provided this will become the background color. + :param bold: if provided this will enable or disable bold mode. + :param dim: if provided this will enable or disable dim mode. This is + badly supported. + :param underline: if provided this will enable or disable underline. + :param blink: if provided this will enable or disable blinking. + :param reverse: if provided this will enable or disable inverse + rendering (foreground becomes background and the + other way round). + :param reset: by default a reset-all code is added at the end of the + string which means that styles do not carry over. This + can be disabled to compose styles. + """ + bits = [] + if fg: + try: + bits.append('\033[%dm' % (_ansi_colors.index(fg) + 30)) + except ValueError: + raise TypeError('Unknown color %r' % fg) + if bg: + try: + bits.append('\033[%dm' % (_ansi_colors.index(bg) + 40)) + except ValueError: + raise TypeError('Unknown color %r' % bg) + if bold is not None: + bits.append('\033[%dm' % (1 if bold else 22)) + if dim is not None: + bits.append('\033[%dm' % (2 if dim else 22)) + if underline is not None: + bits.append('\033[%dm' % (4 if underline else 24)) + if blink is not None: + bits.append('\033[%dm' % (5 if blink else 25)) + if reverse is not None: + bits.append('\033[%dm' % (7 if reverse else 27)) + bits.append(text) + if reset: + bits.append(_ansi_reset_all) + return ''.join(bits) + + +def unstyle(text): + """Removes ANSI styling information from a string. Usually it's not + necessary to use this function as Click's echo function will + automatically remove styling if necessary. + + .. versionadded:: 2.0 + + :param text: the text to remove style information from. + """ + return strip_ansi(text) + + +def secho(text, file=None, nl=True, err=False, color=None, **styles): + """This function combines :func:`echo` and :func:`style` into one + call. As such the following two calls are the same:: + + click.secho('Hello World!', fg='green') + click.echo(click.style('Hello World!', fg='green')) + + All keyword arguments are forwarded to the underlying functions + depending on which one they go with. + + .. versionadded:: 2.0 + """ + return echo(style(text, **styles), file=file, nl=nl, err=err, color=color) + + +def edit(text=None, editor=None, env=None, require_save=True, + extension='.txt', filename=None): + r"""Edits the given text in the defined editor. If an editor is given + (should be the full path to the executable but the regular operating + system search path is used for finding the executable) it overrides + the detected editor. Optionally, some environment variables can be + used. If the editor is closed without changes, `None` is returned. In + case a file is edited directly the return value is always `None` and + `require_save` and `extension` are ignored. + + If the editor cannot be opened a :exc:`UsageError` is raised. + + Note for Windows: to simplify cross-platform usage, the newlines are + automatically converted from POSIX to Windows and vice versa. As such, + the message here will have ``\n`` as newline markers. + + :param text: the text to edit. + :param editor: optionally the editor to use. Defaults to automatic + detection. + :param env: environment variables to forward to the editor. + :param require_save: if this is true, then not saving in the editor + will make the return value become `None`. + :param extension: the extension to tell the editor about. This defaults + to `.txt` but changing this might change syntax + highlighting. + :param filename: if provided it will edit this file instead of the + provided text contents. It will not use a temporary + file as an indirection in that case. + """ + from ._termui_impl import Editor + editor = Editor(editor=editor, env=env, require_save=require_save, + extension=extension) + if filename is None: + return editor.edit(text) + editor.edit_file(filename) + + +def launch(url, wait=False, locate=False): + """This function launches the given URL (or filename) in the default + viewer application for this file type. If this is an executable, it + might launch the executable in a new session. The return value is + the exit code of the launched application. Usually, ``0`` indicates + success. + + Examples:: + + click.launch('http://click.pocoo.org/') + click.launch('/my/downloaded/file', locate=True) + + .. versionadded:: 2.0 + + :param url: URL or filename of the thing to launch. + :param wait: waits for the program to stop. + :param locate: if this is set to `True` then instead of launching the + application associated with the URL it will attempt to + launch a file manager with the file located. This + might have weird effects if the URL does not point to + the filesystem. + """ + from ._termui_impl import open_url + return open_url(url, wait=wait, locate=locate) + + +# If this is provided, getchar() calls into this instead. This is used +# for unittesting purposes. +_getchar = None + + +def getchar(echo=False): + """Fetches a single character from the terminal and returns it. This + will always return a unicode character and under certain rare + circumstances this might return more than one character. The + situations which more than one character is returned is when for + whatever reason multiple characters end up in the terminal buffer or + standard input was not actually a terminal. + + Note that this will always read from the terminal, even if something + is piped into the standard input. + + .. versionadded:: 2.0 + + :param echo: if set to `True`, the character read will also show up on + the terminal. The default is to not show it. + """ + f = _getchar + if f is None: + from ._termui_impl import getchar as f + return f(echo) + + +def pause(info='Press any key to continue ...', err=False): + """This command stops execution and waits for the user to press any + key to continue. This is similar to the Windows batch "pause" + command. If the program is not run through a terminal, this command + will instead do nothing. + + .. versionadded:: 2.0 + + .. versionadded:: 4.0 + Added the `err` parameter. + + :param info: the info string to print before pausing. + :param err: if set to message goes to ``stderr`` instead of + ``stdout``, the same as with echo. + """ + if not isatty(sys.stdin) or not isatty(sys.stdout): + return + try: + if info: + echo(info, nl=False, err=err) + try: + getchar() + except (KeyboardInterrupt, EOFError): + pass + finally: + if info: + echo(err=err) diff --git a/pyextra/click/testing.py b/pyextra/click/testing.py new file mode 100644 index 00000000000000..4416c774136dc9 --- /dev/null +++ b/pyextra/click/testing.py @@ -0,0 +1,322 @@ +import os +import sys +import shutil +import tempfile +import contextlib + +from ._compat import iteritems, PY2 + + +# If someone wants to vendor click, we want to ensure the +# correct package is discovered. Ideally we could use a +# relative import here but unfortunately Python does not +# support that. +clickpkg = sys.modules[__name__.rsplit('.', 1)[0]] + + +if PY2: + from cStringIO import StringIO +else: + import io + from ._compat import _find_binary_reader + + +class EchoingStdin(object): + + def __init__(self, input, output): + self._input = input + self._output = output + + def __getattr__(self, x): + return getattr(self._input, x) + + def _echo(self, rv): + self._output.write(rv) + return rv + + def read(self, n=-1): + return self._echo(self._input.read(n)) + + def readline(self, n=-1): + return self._echo(self._input.readline(n)) + + def readlines(self): + return [self._echo(x) for x in self._input.readlines()] + + def __iter__(self): + return iter(self._echo(x) for x in self._input) + + def __repr__(self): + return repr(self._input) + + +def make_input_stream(input, charset): + # Is already an input stream. + if hasattr(input, 'read'): + if PY2: + return input + rv = _find_binary_reader(input) + if rv is not None: + return rv + raise TypeError('Could not find binary reader for input stream.') + + if input is None: + input = b'' + elif not isinstance(input, bytes): + input = input.encode(charset) + if PY2: + return StringIO(input) + return io.BytesIO(input) + + +class Result(object): + """Holds the captured result of an invoked CLI script.""" + + def __init__(self, runner, output_bytes, exit_code, exception, + exc_info=None): + #: The runner that created the result + self.runner = runner + #: The output as bytes. + self.output_bytes = output_bytes + #: The exit code as integer. + self.exit_code = exit_code + #: The exception that happend if one did. + self.exception = exception + #: The traceback + self.exc_info = exc_info + + @property + def output(self): + """The output as unicode string.""" + return self.output_bytes.decode(self.runner.charset, 'replace') \ + .replace('\r\n', '\n') + + def __repr__(self): + return '' % ( + self.exception and repr(self.exception) or 'okay', + ) + + +class CliRunner(object): + """The CLI runner provides functionality to invoke a Click command line + script for unittesting purposes in a isolated environment. This only + works in single-threaded systems without any concurrency as it changes the + global interpreter state. + + :param charset: the character set for the input and output data. This is + UTF-8 by default and should not be changed currently as + the reporting to Click only works in Python 2 properly. + :param env: a dictionary with environment variables for overriding. + :param echo_stdin: if this is set to `True`, then reading from stdin writes + to stdout. This is useful for showing examples in + some circumstances. Note that regular prompts + will automatically echo the input. + """ + + def __init__(self, charset=None, env=None, echo_stdin=False): + if charset is None: + charset = 'utf-8' + self.charset = charset + self.env = env or {} + self.echo_stdin = echo_stdin + + def get_default_prog_name(self, cli): + """Given a command object it will return the default program name + for it. The default is the `name` attribute or ``"root"`` if not + set. + """ + return cli.name or 'root' + + def make_env(self, overrides=None): + """Returns the environment overrides for invoking a script.""" + rv = dict(self.env) + if overrides: + rv.update(overrides) + return rv + + @contextlib.contextmanager + def isolation(self, input=None, env=None, color=False): + """A context manager that sets up the isolation for invoking of a + command line tool. This sets up stdin with the given input data + and `os.environ` with the overrides from the given dictionary. + This also rebinds some internals in Click to be mocked (like the + prompt functionality). + + This is automatically done in the :meth:`invoke` method. + + .. versionadded:: 4.0 + The ``color`` parameter was added. + + :param input: the input stream to put into sys.stdin. + :param env: the environment overrides as dictionary. + :param color: whether the output should contain color codes. The + application can still override this explicitly. + """ + input = make_input_stream(input, self.charset) + + old_stdin = sys.stdin + old_stdout = sys.stdout + old_stderr = sys.stderr + old_forced_width = clickpkg.formatting.FORCED_WIDTH + clickpkg.formatting.FORCED_WIDTH = 80 + + env = self.make_env(env) + + if PY2: + sys.stdout = sys.stderr = bytes_output = StringIO() + if self.echo_stdin: + input = EchoingStdin(input, bytes_output) + else: + bytes_output = io.BytesIO() + if self.echo_stdin: + input = EchoingStdin(input, bytes_output) + input = io.TextIOWrapper(input, encoding=self.charset) + sys.stdout = sys.stderr = io.TextIOWrapper( + bytes_output, encoding=self.charset) + + sys.stdin = input + + def visible_input(prompt=None): + sys.stdout.write(prompt or '') + val = input.readline().rstrip('\r\n') + sys.stdout.write(val + '\n') + sys.stdout.flush() + return val + + def hidden_input(prompt=None): + sys.stdout.write((prompt or '') + '\n') + sys.stdout.flush() + return input.readline().rstrip('\r\n') + + def _getchar(echo): + char = sys.stdin.read(1) + if echo: + sys.stdout.write(char) + sys.stdout.flush() + return char + + default_color = color + def should_strip_ansi(stream=None, color=None): + if color is None: + return not default_color + return not color + + old_visible_prompt_func = clickpkg.termui.visible_prompt_func + old_hidden_prompt_func = clickpkg.termui.hidden_prompt_func + old__getchar_func = clickpkg.termui._getchar + old_should_strip_ansi = clickpkg.utils.should_strip_ansi + clickpkg.termui.visible_prompt_func = visible_input + clickpkg.termui.hidden_prompt_func = hidden_input + clickpkg.termui._getchar = _getchar + clickpkg.utils.should_strip_ansi = should_strip_ansi + + old_env = {} + try: + for key, value in iteritems(env): + old_env[key] = os.environ.get(key) + if value is None: + try: + del os.environ[key] + except Exception: + pass + else: + os.environ[key] = value + yield bytes_output + finally: + for key, value in iteritems(old_env): + if value is None: + try: + del os.environ[key] + except Exception: + pass + else: + os.environ[key] = value + sys.stdout = old_stdout + sys.stderr = old_stderr + sys.stdin = old_stdin + clickpkg.termui.visible_prompt_func = old_visible_prompt_func + clickpkg.termui.hidden_prompt_func = old_hidden_prompt_func + clickpkg.termui._getchar = old__getchar_func + clickpkg.utils.should_strip_ansi = old_should_strip_ansi + clickpkg.formatting.FORCED_WIDTH = old_forced_width + + def invoke(self, cli, args=None, input=None, env=None, + catch_exceptions=True, color=False, **extra): + """Invokes a command in an isolated environment. The arguments are + forwarded directly to the command line script, the `extra` keyword + arguments are passed to the :meth:`~clickpkg.Command.main` function of + the command. + + This returns a :class:`Result` object. + + .. versionadded:: 3.0 + The ``catch_exceptions`` parameter was added. + + .. versionchanged:: 3.0 + The result object now has an `exc_info` attribute with the + traceback if available. + + .. versionadded:: 4.0 + The ``color`` parameter was added. + + :param cli: the command to invoke + :param args: the arguments to invoke + :param input: the input data for `sys.stdin`. + :param env: the environment overrides. + :param catch_exceptions: Whether to catch any other exceptions than + ``SystemExit``. + :param extra: the keyword arguments to pass to :meth:`main`. + :param color: whether the output should contain color codes. The + application can still override this explicitly. + """ + exc_info = None + with self.isolation(input=input, env=env, color=color) as out: + exception = None + exit_code = 0 + + try: + cli.main(args=args or (), + prog_name=self.get_default_prog_name(cli), **extra) + except SystemExit as e: + if e.code != 0: + exception = e + + exc_info = sys.exc_info() + + exit_code = e.code + if not isinstance(exit_code, int): + sys.stdout.write(str(exit_code)) + sys.stdout.write('\n') + exit_code = 1 + except Exception as e: + if not catch_exceptions: + raise + exception = e + exit_code = -1 + exc_info = sys.exc_info() + finally: + sys.stdout.flush() + output = out.getvalue() + + return Result(runner=self, + output_bytes=output, + exit_code=exit_code, + exception=exception, + exc_info=exc_info) + + @contextlib.contextmanager + def isolated_filesystem(self): + """A context manager that creates a temporary folder and changes + the current working directory to it for isolated filesystem tests. + """ + cwd = os.getcwd() + t = tempfile.mkdtemp() + os.chdir(t) + try: + yield t + finally: + os.chdir(cwd) + try: + shutil.rmtree(t) + except (OSError, IOError): + pass diff --git a/pyextra/click/types.py b/pyextra/click/types.py new file mode 100644 index 00000000000000..36390026dcd178 --- /dev/null +++ b/pyextra/click/types.py @@ -0,0 +1,550 @@ +import os +import stat + +from ._compat import open_stream, text_type, filename_to_ui, \ + get_filesystem_encoding, get_streerror, _get_argv_encoding, PY2 +from .exceptions import BadParameter +from .utils import safecall, LazyFile + + +class ParamType(object): + """Helper for converting values through types. The following is + necessary for a valid type: + + * it needs a name + * it needs to pass through None unchanged + * it needs to convert from a string + * it needs to convert its result type through unchanged + (eg: needs to be idempotent) + * it needs to be able to deal with param and context being `None`. + This can be the case when the object is used with prompt + inputs. + """ + is_composite = False + + #: the descriptive name of this type + name = None + + #: if a list of this type is expected and the value is pulled from a + #: string environment variable, this is what splits it up. `None` + #: means any whitespace. For all parameters the general rule is that + #: whitespace splits them up. The exception are paths and files which + #: are split by ``os.path.pathsep`` by default (":" on Unix and ";" on + #: Windows). + envvar_list_splitter = None + + def __call__(self, value, param=None, ctx=None): + if value is not None: + return self.convert(value, param, ctx) + + def get_metavar(self, param): + """Returns the metavar default for this param if it provides one.""" + + def get_missing_message(self, param): + """Optionally might return extra information about a missing + parameter. + + .. versionadded:: 2.0 + """ + + def convert(self, value, param, ctx): + """Converts the value. This is not invoked for values that are + `None` (the missing value). + """ + return value + + def split_envvar_value(self, rv): + """Given a value from an environment variable this splits it up + into small chunks depending on the defined envvar list splitter. + + If the splitter is set to `None`, which means that whitespace splits, + then leading and trailing whitespace is ignored. Otherwise, leading + and trailing splitters usually lead to empty items being included. + """ + return (rv or '').split(self.envvar_list_splitter) + + def fail(self, message, param=None, ctx=None): + """Helper method to fail with an invalid value message.""" + raise BadParameter(message, ctx=ctx, param=param) + + +class CompositeParamType(ParamType): + is_composite = True + + @property + def arity(self): + raise NotImplementedError() + + +class FuncParamType(ParamType): + + def __init__(self, func): + self.name = func.__name__ + self.func = func + + def convert(self, value, param, ctx): + try: + return self.func(value) + except ValueError: + try: + value = text_type(value) + except UnicodeError: + value = str(value).decode('utf-8', 'replace') + self.fail(value, param, ctx) + + +class UnprocessedParamType(ParamType): + name = 'text' + + def convert(self, value, param, ctx): + return value + + def __repr__(self): + return 'UNPROCESSED' + + +class StringParamType(ParamType): + name = 'text' + + def convert(self, value, param, ctx): + if isinstance(value, bytes): + enc = _get_argv_encoding() + try: + value = value.decode(enc) + except UnicodeError: + fs_enc = get_filesystem_encoding() + if fs_enc != enc: + try: + value = value.decode(fs_enc) + except UnicodeError: + value = value.decode('utf-8', 'replace') + return value + return value + + def __repr__(self): + return 'STRING' + + +class Choice(ParamType): + """The choice type allows a value to be checked against a fixed set of + supported values. All of these values have to be strings. + + See :ref:`choice-opts` for an example. + """ + name = 'choice' + + def __init__(self, choices): + self.choices = choices + + def get_metavar(self, param): + return '[%s]' % '|'.join(self.choices) + + def get_missing_message(self, param): + return 'Choose from %s.' % ', '.join(self.choices) + + def convert(self, value, param, ctx): + # Exact match + if value in self.choices: + return value + + # Match through normalization + if ctx is not None and \ + ctx.token_normalize_func is not None: + value = ctx.token_normalize_func(value) + for choice in self.choices: + if ctx.token_normalize_func(choice) == value: + return choice + + self.fail('invalid choice: %s. (choose from %s)' % + (value, ', '.join(self.choices)), param, ctx) + + def __repr__(self): + return 'Choice(%r)' % list(self.choices) + + +class IntParamType(ParamType): + name = 'integer' + + def convert(self, value, param, ctx): + try: + return int(value) + except (ValueError, UnicodeError): + self.fail('%s is not a valid integer' % value, param, ctx) + + def __repr__(self): + return 'INT' + + +class IntRange(IntParamType): + """A parameter that works similar to :data:`click.INT` but restricts + the value to fit into a range. The default behavior is to fail if the + value falls outside the range, but it can also be silently clamped + between the two edges. + + See :ref:`ranges` for an example. + """ + name = 'integer range' + + def __init__(self, min=None, max=None, clamp=False): + self.min = min + self.max = max + self.clamp = clamp + + def convert(self, value, param, ctx): + rv = IntParamType.convert(self, value, param, ctx) + if self.clamp: + if self.min is not None and rv < self.min: + return self.min + if self.max is not None and rv > self.max: + return self.max + if self.min is not None and rv < self.min or \ + self.max is not None and rv > self.max: + if self.min is None: + self.fail('%s is bigger than the maximum valid value ' + '%s.' % (rv, self.max), param, ctx) + elif self.max is None: + self.fail('%s is smaller than the minimum valid value ' + '%s.' % (rv, self.min), param, ctx) + else: + self.fail('%s is not in the valid range of %s to %s.' + % (rv, self.min, self.max), param, ctx) + return rv + + def __repr__(self): + return 'IntRange(%r, %r)' % (self.min, self.max) + + +class BoolParamType(ParamType): + name = 'boolean' + + def convert(self, value, param, ctx): + if isinstance(value, bool): + return bool(value) + value = value.lower() + if value in ('true', '1', 'yes', 'y'): + return True + elif value in ('false', '0', 'no', 'n'): + return False + self.fail('%s is not a valid boolean' % value, param, ctx) + + def __repr__(self): + return 'BOOL' + + +class FloatParamType(ParamType): + name = 'float' + + def convert(self, value, param, ctx): + try: + return float(value) + except (UnicodeError, ValueError): + self.fail('%s is not a valid floating point value' % + value, param, ctx) + + def __repr__(self): + return 'FLOAT' + + +class UUIDParameterType(ParamType): + name = 'uuid' + + def convert(self, value, param, ctx): + import uuid + try: + if PY2 and isinstance(value, text_type): + value = value.encode('ascii') + return uuid.UUID(value) + except (UnicodeError, ValueError): + self.fail('%s is not a valid UUID value' % value, param, ctx) + + def __repr__(self): + return 'UUID' + + +class File(ParamType): + """Declares a parameter to be a file for reading or writing. The file + is automatically closed once the context tears down (after the command + finished working). + + Files can be opened for reading or writing. The special value ``-`` + indicates stdin or stdout depending on the mode. + + By default, the file is opened for reading text data, but it can also be + opened in binary mode or for writing. The encoding parameter can be used + to force a specific encoding. + + The `lazy` flag controls if the file should be opened immediately or + upon first IO. The default is to be non lazy for standard input and + output streams as well as files opened for reading, lazy otherwise. + + Starting with Click 2.0, files can also be opened atomically in which + case all writes go into a separate file in the same folder and upon + completion the file will be moved over to the original location. This + is useful if a file regularly read by other users is modified. + + See :ref:`file-args` for more information. + """ + name = 'filename' + envvar_list_splitter = os.path.pathsep + + def __init__(self, mode='r', encoding=None, errors='strict', lazy=None, + atomic=False): + self.mode = mode + self.encoding = encoding + self.errors = errors + self.lazy = lazy + self.atomic = atomic + + def resolve_lazy_flag(self, value): + if self.lazy is not None: + return self.lazy + if value == '-': + return False + elif 'w' in self.mode: + return True + return False + + def convert(self, value, param, ctx): + try: + if hasattr(value, 'read') or hasattr(value, 'write'): + return value + + lazy = self.resolve_lazy_flag(value) + + if lazy: + f = LazyFile(value, self.mode, self.encoding, self.errors, + atomic=self.atomic) + if ctx is not None: + ctx.call_on_close(f.close_intelligently) + return f + + f, should_close = open_stream(value, self.mode, + self.encoding, self.errors, + atomic=self.atomic) + # If a context is provided, we automatically close the file + # at the end of the context execution (or flush out). If a + # context does not exist, it's the caller's responsibility to + # properly close the file. This for instance happens when the + # type is used with prompts. + if ctx is not None: + if should_close: + ctx.call_on_close(safecall(f.close)) + else: + ctx.call_on_close(safecall(f.flush)) + return f + except (IOError, OSError) as e: + self.fail('Could not open file: %s: %s' % ( + filename_to_ui(value), + get_streerror(e), + ), param, ctx) + + +class Path(ParamType): + """The path type is similar to the :class:`File` type but it performs + different checks. First of all, instead of returning an open file + handle it returns just the filename. Secondly, it can perform various + basic checks about what the file or directory should be. + + .. versionchanged:: 6.0 + `allow_dash` was added. + + :param exists: if set to true, the file or directory needs to exist for + this value to be valid. If this is not required and a + file does indeed not exist, then all further checks are + silently skipped. + :param file_okay: controls if a file is a possible value. + :param dir_okay: controls if a directory is a possible value. + :param writable: if true, a writable check is performed. + :param readable: if true, a readable check is performed. + :param resolve_path: if this is true, then the path is fully resolved + before the value is passed onwards. This means + that it's absolute and symlinks are resolved. + :param allow_dash: If this is set to `True`, a single dash to indicate + standard streams is permitted. + :param type: optionally a string type that should be used to + represent the path. The default is `None` which + means the return value will be either bytes or + unicode depending on what makes most sense given the + input data Click deals with. + """ + envvar_list_splitter = os.path.pathsep + + def __init__(self, exists=False, file_okay=True, dir_okay=True, + writable=False, readable=True, resolve_path=False, + allow_dash=False, path_type=None): + self.exists = exists + self.file_okay = file_okay + self.dir_okay = dir_okay + self.writable = writable + self.readable = readable + self.resolve_path = resolve_path + self.allow_dash = allow_dash + self.type = path_type + + if self.file_okay and not self.dir_okay: + self.name = 'file' + self.path_type = 'File' + if self.dir_okay and not self.file_okay: + self.name = 'directory' + self.path_type = 'Directory' + else: + self.name = 'path' + self.path_type = 'Path' + + def coerce_path_result(self, rv): + if self.type is not None and not isinstance(rv, self.type): + if self.type is text_type: + rv = rv.decode(get_filesystem_encoding()) + else: + rv = rv.encode(get_filesystem_encoding()) + return rv + + def convert(self, value, param, ctx): + rv = value + + is_dash = self.file_okay and self.allow_dash and rv in (b'-', '-') + + if not is_dash: + if self.resolve_path: + rv = os.path.realpath(rv) + + try: + st = os.stat(rv) + except OSError: + if not self.exists: + return self.coerce_path_result(rv) + self.fail('%s "%s" does not exist.' % ( + self.path_type, + filename_to_ui(value) + ), param, ctx) + + if not self.file_okay and stat.S_ISREG(st.st_mode): + self.fail('%s "%s" is a file.' % ( + self.path_type, + filename_to_ui(value) + ), param, ctx) + if not self.dir_okay and stat.S_ISDIR(st.st_mode): + self.fail('%s "%s" is a directory.' % ( + self.path_type, + filename_to_ui(value) + ), param, ctx) + if self.writable and not os.access(value, os.W_OK): + self.fail('%s "%s" is not writable.' % ( + self.path_type, + filename_to_ui(value) + ), param, ctx) + if self.readable and not os.access(value, os.R_OK): + self.fail('%s "%s" is not readable.' % ( + self.path_type, + filename_to_ui(value) + ), param, ctx) + + return self.coerce_path_result(rv) + + +class Tuple(CompositeParamType): + """The default behavior of Click is to apply a type on a value directly. + This works well in most cases, except for when `nargs` is set to a fixed + count and different types should be used for different items. In this + case the :class:`Tuple` type can be used. This type can only be used + if `nargs` is set to a fixed number. + + For more information see :ref:`tuple-type`. + + This can be selected by using a Python tuple literal as a type. + + :param types: a list of types that should be used for the tuple items. + """ + + def __init__(self, types): + self.types = [convert_type(ty) for ty in types] + + @property + def name(self): + return "<" + " ".join(ty.name for ty in self.types) + ">" + + @property + def arity(self): + return len(self.types) + + def convert(self, value, param, ctx): + if len(value) != len(self.types): + raise TypeError('It would appear that nargs is set to conflict ' + 'with the composite type arity.') + return tuple(ty(x, param, ctx) for ty, x in zip(self.types, value)) + + +def convert_type(ty, default=None): + """Converts a callable or python ty into the most appropriate param + ty. + """ + guessed_type = False + if ty is None and default is not None: + if isinstance(default, tuple): + ty = tuple(map(type, default)) + else: + ty = type(default) + guessed_type = True + + if isinstance(ty, tuple): + return Tuple(ty) + if isinstance(ty, ParamType): + return ty + if ty is text_type or ty is str or ty is None: + return STRING + if ty is int: + return INT + # Booleans are only okay if not guessed. This is done because for + # flags the default value is actually a bit of a lie in that it + # indicates which of the flags is the one we want. See get_default() + # for more information. + if ty is bool and not guessed_type: + return BOOL + if ty is float: + return FLOAT + if guessed_type: + return STRING + + # Catch a common mistake + if __debug__: + try: + if issubclass(ty, ParamType): + raise AssertionError('Attempted to use an uninstantiated ' + 'parameter type (%s).' % ty) + except TypeError: + pass + return FuncParamType(ty) + + +#: A dummy parameter type that just does nothing. From a user's +#: perspective this appears to just be the same as `STRING` but internally +#: no string conversion takes place. This is necessary to achieve the +#: same bytes/unicode behavior on Python 2/3 in situations where you want +#: to not convert argument types. This is usually useful when working +#: with file paths as they can appear in bytes and unicode. +#: +#: For path related uses the :class:`Path` type is a better choice but +#: there are situations where an unprocessed type is useful which is why +#: it is is provided. +#: +#: .. versionadded:: 4.0 +UNPROCESSED = UnprocessedParamType() + +#: A unicode string parameter type which is the implicit default. This +#: can also be selected by using ``str`` as type. +STRING = StringParamType() + +#: An integer parameter. This can also be selected by using ``int`` as +#: type. +INT = IntParamType() + +#: A floating point value parameter. This can also be selected by using +#: ``float`` as type. +FLOAT = FloatParamType() + +#: A boolean parameter. This is the default for boolean flags. This can +#: also be selected by using ``bool`` as a type. +BOOL = BoolParamType() + +#: A UUID parameter. +UUID = UUIDParameterType() diff --git a/pyextra/click/utils.py b/pyextra/click/utils.py new file mode 100644 index 00000000000000..eee626d3fd0153 --- /dev/null +++ b/pyextra/click/utils.py @@ -0,0 +1,415 @@ +import os +import sys + +from .globals import resolve_color_default + +from ._compat import text_type, open_stream, get_filesystem_encoding, \ + get_streerror, string_types, PY2, binary_streams, text_streams, \ + filename_to_ui, auto_wrap_for_ansi, strip_ansi, should_strip_ansi, \ + _default_text_stdout, _default_text_stderr, is_bytes, WIN + +if not PY2: + from ._compat import _find_binary_writer +elif WIN: + from ._winconsole import _get_windows_argv, \ + _hash_py_argv, _initial_argv_hash + + +echo_native_types = string_types + (bytes, bytearray) + + +def _posixify(name): + return '-'.join(name.split()).lower() + + +def safecall(func): + """Wraps a function so that it swallows exceptions.""" + def wrapper(*args, **kwargs): + try: + return func(*args, **kwargs) + except Exception: + pass + return wrapper + + +def make_str(value): + """Converts a value into a valid string.""" + if isinstance(value, bytes): + try: + return value.decode(get_filesystem_encoding()) + except UnicodeError: + return value.decode('utf-8', 'replace') + return text_type(value) + + +def make_default_short_help(help, max_length=45): + words = help.split() + total_length = 0 + result = [] + done = False + + for word in words: + if word[-1:] == '.': + done = True + new_length = result and 1 + len(word) or len(word) + if total_length + new_length > max_length: + result.append('...') + done = True + else: + if result: + result.append(' ') + result.append(word) + if done: + break + total_length += new_length + + return ''.join(result) + + +class LazyFile(object): + """A lazy file works like a regular file but it does not fully open + the file but it does perform some basic checks early to see if the + filename parameter does make sense. This is useful for safely opening + files for writing. + """ + + def __init__(self, filename, mode='r', encoding=None, errors='strict', + atomic=False): + self.name = filename + self.mode = mode + self.encoding = encoding + self.errors = errors + self.atomic = atomic + + if filename == '-': + self._f, self.should_close = open_stream(filename, mode, + encoding, errors) + else: + if 'r' in mode: + # Open and close the file in case we're opening it for + # reading so that we can catch at least some errors in + # some cases early. + open(filename, mode).close() + self._f = None + self.should_close = True + + def __getattr__(self, name): + return getattr(self.open(), name) + + def __repr__(self): + if self._f is not None: + return repr(self._f) + return '' % (self.name, self.mode) + + def open(self): + """Opens the file if it's not yet open. This call might fail with + a :exc:`FileError`. Not handling this error will produce an error + that Click shows. + """ + if self._f is not None: + return self._f + try: + rv, self.should_close = open_stream(self.name, self.mode, + self.encoding, + self.errors, + atomic=self.atomic) + except (IOError, OSError) as e: + from .exceptions import FileError + raise FileError(self.name, hint=get_streerror(e)) + self._f = rv + return rv + + def close(self): + """Closes the underlying file, no matter what.""" + if self._f is not None: + self._f.close() + + def close_intelligently(self): + """This function only closes the file if it was opened by the lazy + file wrapper. For instance this will never close stdin. + """ + if self.should_close: + self.close() + + def __enter__(self): + return self + + def __exit__(self, exc_type, exc_value, tb): + self.close_intelligently() + + def __iter__(self): + self.open() + return iter(self._f) + + +class KeepOpenFile(object): + + def __init__(self, file): + self._file = file + + def __getattr__(self, name): + return getattr(self._file, name) + + def __enter__(self): + return self + + def __exit__(self, exc_type, exc_value, tb): + pass + + def __repr__(self): + return repr(self._file) + + def __iter__(self): + return iter(self._file) + + +def echo(message=None, file=None, nl=True, err=False, color=None): + """Prints a message plus a newline to the given file or stdout. On + first sight, this looks like the print function, but it has improved + support for handling Unicode and binary data that does not fail no + matter how badly configured the system is. + + Primarily it means that you can print binary data as well as Unicode + data on both 2.x and 3.x to the given file in the most appropriate way + possible. This is a very carefree function as in that it will try its + best to not fail. As of Click 6.0 this includes support for unicode + output on the Windows console. + + In addition to that, if `colorama`_ is installed, the echo function will + also support clever handling of ANSI codes. Essentially it will then + do the following: + + - add transparent handling of ANSI color codes on Windows. + - hide ANSI codes automatically if the destination file is not a + terminal. + + .. _colorama: http://pypi.python.org/pypi/colorama + + .. versionchanged:: 6.0 + As of Click 6.0 the echo function will properly support unicode + output on the windows console. Not that click does not modify + the interpreter in any way which means that `sys.stdout` or the + print statement or function will still not provide unicode support. + + .. versionchanged:: 2.0 + Starting with version 2.0 of Click, the echo function will work + with colorama if it's installed. + + .. versionadded:: 3.0 + The `err` parameter was added. + + .. versionchanged:: 4.0 + Added the `color` flag. + + :param message: the message to print + :param file: the file to write to (defaults to ``stdout``) + :param err: if set to true the file defaults to ``stderr`` instead of + ``stdout``. This is faster and easier than calling + :func:`get_text_stderr` yourself. + :param nl: if set to `True` (the default) a newline is printed afterwards. + :param color: controls if the terminal supports ANSI colors or not. The + default is autodetection. + """ + if file is None: + if err: + file = _default_text_stderr() + else: + file = _default_text_stdout() + + # Convert non bytes/text into the native string type. + if message is not None and not isinstance(message, echo_native_types): + message = text_type(message) + + if nl: + message = message or u'' + if isinstance(message, text_type): + message += u'\n' + else: + message += b'\n' + + # If there is a message, and we're in Python 3, and the value looks + # like bytes, we manually need to find the binary stream and write the + # message in there. This is done separately so that most stream + # types will work as you would expect. Eg: you can write to StringIO + # for other cases. + if message and not PY2 and is_bytes(message): + binary_file = _find_binary_writer(file) + if binary_file is not None: + file.flush() + binary_file.write(message) + binary_file.flush() + return + + # ANSI-style support. If there is no message or we are dealing with + # bytes nothing is happening. If we are connected to a file we want + # to strip colors. If we are on windows we either wrap the stream + # to strip the color or we use the colorama support to translate the + # ansi codes to API calls. + if message and not is_bytes(message): + color = resolve_color_default(color) + if should_strip_ansi(file, color): + message = strip_ansi(message) + elif WIN: + if auto_wrap_for_ansi is not None: + file = auto_wrap_for_ansi(file) + elif not color: + message = strip_ansi(message) + + if message: + file.write(message) + file.flush() + + +def get_binary_stream(name): + """Returns a system stream for byte processing. This essentially + returns the stream from the sys module with the given name but it + solves some compatibility issues between different Python versions. + Primarily this function is necessary for getting binary streams on + Python 3. + + :param name: the name of the stream to open. Valid names are ``'stdin'``, + ``'stdout'`` and ``'stderr'`` + """ + opener = binary_streams.get(name) + if opener is None: + raise TypeError('Unknown standard stream %r' % name) + return opener() + + +def get_text_stream(name, encoding=None, errors='strict'): + """Returns a system stream for text processing. This usually returns + a wrapped stream around a binary stream returned from + :func:`get_binary_stream` but it also can take shortcuts on Python 3 + for already correctly configured streams. + + :param name: the name of the stream to open. Valid names are ``'stdin'``, + ``'stdout'`` and ``'stderr'`` + :param encoding: overrides the detected default encoding. + :param errors: overrides the default error mode. + """ + opener = text_streams.get(name) + if opener is None: + raise TypeError('Unknown standard stream %r' % name) + return opener(encoding, errors) + + +def open_file(filename, mode='r', encoding=None, errors='strict', + lazy=False, atomic=False): + """This is similar to how the :class:`File` works but for manual + usage. Files are opened non lazy by default. This can open regular + files as well as stdin/stdout if ``'-'`` is passed. + + If stdin/stdout is returned the stream is wrapped so that the context + manager will not close the stream accidentally. This makes it possible + to always use the function like this without having to worry to + accidentally close a standard stream:: + + with open_file(filename) as f: + ... + + .. versionadded:: 3.0 + + :param filename: the name of the file to open (or ``'-'`` for stdin/stdout). + :param mode: the mode in which to open the file. + :param encoding: the encoding to use. + :param errors: the error handling for this file. + :param lazy: can be flipped to true to open the file lazily. + :param atomic: in atomic mode writes go into a temporary file and it's + moved on close. + """ + if lazy: + return LazyFile(filename, mode, encoding, errors, atomic=atomic) + f, should_close = open_stream(filename, mode, encoding, errors, + atomic=atomic) + if not should_close: + f = KeepOpenFile(f) + return f + + +def get_os_args(): + """This returns the argument part of sys.argv in the most appropriate + form for processing. What this means is that this return value is in + a format that works for Click to process but does not necessarily + correspond well to what's actually standard for the interpreter. + + On most environments the return value is ``sys.argv[:1]`` unchanged. + However if you are on Windows and running Python 2 the return value + will actually be a list of unicode strings instead because the + default behavior on that platform otherwise will not be able to + carry all possible values that sys.argv can have. + + .. versionadded:: 6.0 + """ + # We can only extract the unicode argv if sys.argv has not been + # changed since the startup of the application. + if PY2 and WIN and _initial_argv_hash == _hash_py_argv(): + return _get_windows_argv() + return sys.argv[1:] + + +def format_filename(filename, shorten=False): + """Formats a filename for user display. The main purpose of this + function is to ensure that the filename can be displayed at all. This + will decode the filename to unicode if necessary in a way that it will + not fail. Optionally, it can shorten the filename to not include the + full path to the filename. + + :param filename: formats a filename for UI display. This will also convert + the filename into unicode without failing. + :param shorten: this optionally shortens the filename to strip of the + path that leads up to it. + """ + if shorten: + filename = os.path.basename(filename) + return filename_to_ui(filename) + + +def get_app_dir(app_name, roaming=True, force_posix=False): + r"""Returns the config folder for the application. The default behavior + is to return whatever is most appropriate for the operating system. + + To give you an idea, for an app called ``"Foo Bar"``, something like + the following folders could be returned: + + Mac OS X: + ``~/Library/Application Support/Foo Bar`` + Mac OS X (POSIX): + ``~/.foo-bar`` + Unix: + ``~/.config/foo-bar`` + Unix (POSIX): + ``~/.foo-bar`` + Win XP (roaming): + ``C:\Documents and Settings\\Local Settings\Application Data\Foo Bar`` + Win XP (not roaming): + ``C:\Documents and Settings\\Application Data\Foo Bar`` + Win 7 (roaming): + ``C:\Users\\AppData\Roaming\Foo Bar`` + Win 7 (not roaming): + ``C:\Users\\AppData\Local\Foo Bar`` + + .. versionadded:: 2.0 + + :param app_name: the application name. This should be properly capitalized + and can contain whitespace. + :param roaming: controls if the folder should be roaming or not on Windows. + Has no affect otherwise. + :param force_posix: if this is set to `True` then on any POSIX system the + folder will be stored in the home folder with a leading + dot instead of the XDG config home or darwin's + application support folder. + """ + if WIN: + key = roaming and 'APPDATA' or 'LOCALAPPDATA' + folder = os.environ.get(key) + if folder is None: + folder = os.path.expanduser('~') + return os.path.join(folder, app_name) + if force_posix: + return os.path.join(os.path.expanduser('~/.' + _posixify(app_name))) + if sys.platform == 'darwin': + return os.path.join(os.path.expanduser( + '~/Library/Application Support'), app_name) + return os.path.join( + os.environ.get('XDG_CONFIG_HOME', os.path.expanduser('~/.config')), + _posixify(app_name)) diff --git a/pyextra/flask/__init__.py b/pyextra/flask/__init__.py new file mode 100644 index 00000000000000..ded19822400ad7 --- /dev/null +++ b/pyextra/flask/__init__.py @@ -0,0 +1,49 @@ +# -*- coding: utf-8 -*- +""" + flask + ~~~~~ + + A microframework based on Werkzeug. It's extensively documented + and follows best practice patterns. + + :copyright: © 2010 by the Pallets team. + :license: BSD, see LICENSE for more details. +""" + +__version__ = '1.0.2' + +# utilities we import from Werkzeug and Jinja2 that are unused +# in the module but are exported as public interface. +from werkzeug.exceptions import abort +from werkzeug.utils import redirect +from jinja2 import Markup, escape + +from .app import Flask, Request, Response +from .config import Config +from .helpers import url_for, flash, send_file, send_from_directory, \ + get_flashed_messages, get_template_attribute, make_response, safe_join, \ + stream_with_context +from .globals import current_app, g, request, session, _request_ctx_stack, \ + _app_ctx_stack +from .ctx import has_request_context, has_app_context, \ + after_this_request, copy_current_request_context +from .blueprints import Blueprint +from .templating import render_template, render_template_string + +# the signals +from .signals import signals_available, template_rendered, request_started, \ + request_finished, got_request_exception, request_tearing_down, \ + appcontext_tearing_down, appcontext_pushed, \ + appcontext_popped, message_flashed, before_render_template + +# We're not exposing the actual json module but a convenient wrapper around +# it. +from . import json + +# This was the only thing that Flask used to export at one point and it had +# a more generic name. +jsonify = json.jsonify + +# backwards compat, goes away in 1.0 +from .sessions import SecureCookieSession as Session +json_available = True diff --git a/pyextra/flask/__main__.py b/pyextra/flask/__main__.py new file mode 100644 index 00000000000000..4aee654374633d --- /dev/null +++ b/pyextra/flask/__main__.py @@ -0,0 +1,14 @@ +# -*- coding: utf-8 -*- +""" + flask.__main__ + ~~~~~~~~~~~~~~ + + Alias for flask.run for the command line. + + :copyright: © 2010 by the Pallets team. + :license: BSD, see LICENSE for more details. +""" + +if __name__ == '__main__': + from .cli import main + main(as_module=True) diff --git a/pyextra/flask/_compat.py b/pyextra/flask/_compat.py new file mode 100644 index 00000000000000..a3b5b9c1c9ade6 --- /dev/null +++ b/pyextra/flask/_compat.py @@ -0,0 +1,99 @@ +# -*- coding: utf-8 -*- +""" + flask._compat + ~~~~~~~~~~~~~ + + Some py2/py3 compatibility support based on a stripped down + version of six so we don't have to depend on a specific version + of it. + + :copyright: © 2010 by the Pallets team. + :license: BSD, see LICENSE for more details. +""" + +import sys + +PY2 = sys.version_info[0] == 2 +_identity = lambda x: x + + +if not PY2: + text_type = str + string_types = (str,) + integer_types = (int,) + + iterkeys = lambda d: iter(d.keys()) + itervalues = lambda d: iter(d.values()) + iteritems = lambda d: iter(d.items()) + + from inspect import getfullargspec as getargspec + from io import StringIO + + def reraise(tp, value, tb=None): + if value.__traceback__ is not tb: + raise value.with_traceback(tb) + raise value + + implements_to_string = _identity + +else: + text_type = unicode + string_types = (str, unicode) + integer_types = (int, long) + + iterkeys = lambda d: d.iterkeys() + itervalues = lambda d: d.itervalues() + iteritems = lambda d: d.iteritems() + + from inspect import getargspec + from cStringIO import StringIO + + exec('def reraise(tp, value, tb=None):\n raise tp, value, tb') + + def implements_to_string(cls): + cls.__unicode__ = cls.__str__ + cls.__str__ = lambda x: x.__unicode__().encode('utf-8') + return cls + + +def with_metaclass(meta, *bases): + """Create a base class with a metaclass.""" + # This requires a bit of explanation: the basic idea is to make a + # dummy metaclass for one level of class instantiation that replaces + # itself with the actual metaclass. + class metaclass(type): + def __new__(cls, name, this_bases, d): + return meta(name, bases, d) + return type.__new__(metaclass, 'temporary_class', (), {}) + + +# Certain versions of pypy have a bug where clearing the exception stack +# breaks the __exit__ function in a very peculiar way. The second level of +# exception blocks is necessary because pypy seems to forget to check if an +# exception happened until the next bytecode instruction? +# +# Relevant PyPy bugfix commit: +# https://bitbucket.org/pypy/pypy/commits/77ecf91c635a287e88e60d8ddb0f4e9df4003301 +# According to ronan on #pypy IRC, it is released in PyPy2 2.3 and later +# versions. +# +# Ubuntu 14.04 has PyPy 2.2.1, which does exhibit this bug. +BROKEN_PYPY_CTXMGR_EXIT = False +if hasattr(sys, 'pypy_version_info'): + class _Mgr(object): + def __enter__(self): + return self + def __exit__(self, *args): + if hasattr(sys, 'exc_clear'): + # Python 3 (PyPy3) doesn't have exc_clear + sys.exc_clear() + try: + try: + with _Mgr(): + raise AssertionError() + except: + raise + except TypeError: + BROKEN_PYPY_CTXMGR_EXIT = True + except AssertionError: + pass diff --git a/pyextra/flask/app.py b/pyextra/flask/app.py new file mode 100644 index 00000000000000..87c5900348b5a2 --- /dev/null +++ b/pyextra/flask/app.py @@ -0,0 +1,2315 @@ +# -*- coding: utf-8 -*- +""" + flask.app + ~~~~~~~~~ + + This module implements the central WSGI application object. + + :copyright: © 2010 by the Pallets team. + :license: BSD, see LICENSE for more details. +""" + +import os +import sys +import warnings +from datetime import timedelta +from functools import update_wrapper +from itertools import chain +from threading import Lock + +from werkzeug.datastructures import Headers, ImmutableDict +from werkzeug.exceptions import BadRequest, BadRequestKeyError, HTTPException, \ + InternalServerError, MethodNotAllowed, default_exceptions +from werkzeug.routing import BuildError, Map, RequestRedirect, Rule + +from . import cli, json +from ._compat import integer_types, reraise, string_types, text_type +from .config import Config, ConfigAttribute +from .ctx import AppContext, RequestContext, _AppCtxGlobals +from .globals import _request_ctx_stack, g, request, session +from .helpers import ( + _PackageBoundObject, + _endpoint_from_view_func, find_package, get_env, get_debug_flag, + get_flashed_messages, locked_cached_property, url_for, get_load_dotenv +) +from .logging import create_logger +from .sessions import SecureCookieSessionInterface +from .signals import appcontext_tearing_down, got_request_exception, \ + request_finished, request_started, request_tearing_down +from .templating import DispatchingJinjaLoader, Environment, \ + _default_template_ctx_processor +from .wrappers import Request, Response + +# a singleton sentinel value for parameter defaults +_sentinel = object() + + +def _make_timedelta(value): + if not isinstance(value, timedelta): + return timedelta(seconds=value) + return value + + +def setupmethod(f): + """Wraps a method so that it performs a check in debug mode if the + first request was already handled. + """ + def wrapper_func(self, *args, **kwargs): + if self.debug and self._got_first_request: + raise AssertionError('A setup function was called after the ' + 'first request was handled. This usually indicates a bug ' + 'in the application where a module was not imported ' + 'and decorators or other functionality was called too late.\n' + 'To fix this make sure to import all your view modules, ' + 'database models and everything related at a central place ' + 'before the application starts serving requests.') + return f(self, *args, **kwargs) + return update_wrapper(wrapper_func, f) + + +class Flask(_PackageBoundObject): + """The flask object implements a WSGI application and acts as the central + object. It is passed the name of the module or package of the + application. Once it is created it will act as a central registry for + the view functions, the URL rules, template configuration and much more. + + The name of the package is used to resolve resources from inside the + package or the folder the module is contained in depending on if the + package parameter resolves to an actual python package (a folder with + an :file:`__init__.py` file inside) or a standard module (just a ``.py`` file). + + For more information about resource loading, see :func:`open_resource`. + + Usually you create a :class:`Flask` instance in your main module or + in the :file:`__init__.py` file of your package like this:: + + from flask import Flask + app = Flask(__name__) + + .. admonition:: About the First Parameter + + The idea of the first parameter is to give Flask an idea of what + belongs to your application. This name is used to find resources + on the filesystem, can be used by extensions to improve debugging + information and a lot more. + + So it's important what you provide there. If you are using a single + module, `__name__` is always the correct value. If you however are + using a package, it's usually recommended to hardcode the name of + your package there. + + For example if your application is defined in :file:`yourapplication/app.py` + you should create it with one of the two versions below:: + + app = Flask('yourapplication') + app = Flask(__name__.split('.')[0]) + + Why is that? The application will work even with `__name__`, thanks + to how resources are looked up. However it will make debugging more + painful. Certain extensions can make assumptions based on the + import name of your application. For example the Flask-SQLAlchemy + extension will look for the code in your application that triggered + an SQL query in debug mode. If the import name is not properly set + up, that debugging information is lost. (For example it would only + pick up SQL queries in `yourapplication.app` and not + `yourapplication.views.frontend`) + + .. versionadded:: 0.7 + The `static_url_path`, `static_folder`, and `template_folder` + parameters were added. + + .. versionadded:: 0.8 + The `instance_path` and `instance_relative_config` parameters were + added. + + .. versionadded:: 0.11 + The `root_path` parameter was added. + + .. versionadded:: 1.0 + The ``host_matching`` and ``static_host`` parameters were added. + + .. versionadded:: 1.0 + The ``subdomain_matching`` parameter was added. Subdomain + matching needs to be enabled manually now. Setting + :data:`SERVER_NAME` does not implicitly enable it. + + :param import_name: the name of the application package + :param static_url_path: can be used to specify a different path for the + static files on the web. Defaults to the name + of the `static_folder` folder. + :param static_folder: the folder with static files that should be served + at `static_url_path`. Defaults to the ``'static'`` + folder in the root path of the application. + :param static_host: the host to use when adding the static route. + Defaults to None. Required when using ``host_matching=True`` + with a ``static_folder`` configured. + :param host_matching: set ``url_map.host_matching`` attribute. + Defaults to False. + :param subdomain_matching: consider the subdomain relative to + :data:`SERVER_NAME` when matching routes. Defaults to False. + :param template_folder: the folder that contains the templates that should + be used by the application. Defaults to + ``'templates'`` folder in the root path of the + application. + :param instance_path: An alternative instance path for the application. + By default the folder ``'instance'`` next to the + package or module is assumed to be the instance + path. + :param instance_relative_config: if set to ``True`` relative filenames + for loading the config are assumed to + be relative to the instance path instead + of the application root. + :param root_path: Flask by default will automatically calculate the path + to the root of the application. In certain situations + this cannot be achieved (for instance if the package + is a Python 3 namespace package) and needs to be + manually defined. + """ + + #: The class that is used for request objects. See :class:`~flask.Request` + #: for more information. + request_class = Request + + #: The class that is used for response objects. See + #: :class:`~flask.Response` for more information. + response_class = Response + + #: The class that is used for the Jinja environment. + #: + #: .. versionadded:: 0.11 + jinja_environment = Environment + + #: The class that is used for the :data:`~flask.g` instance. + #: + #: Example use cases for a custom class: + #: + #: 1. Store arbitrary attributes on flask.g. + #: 2. Add a property for lazy per-request database connectors. + #: 3. Return None instead of AttributeError on unexpected attributes. + #: 4. Raise exception if an unexpected attr is set, a "controlled" flask.g. + #: + #: In Flask 0.9 this property was called `request_globals_class` but it + #: was changed in 0.10 to :attr:`app_ctx_globals_class` because the + #: flask.g object is now application context scoped. + #: + #: .. versionadded:: 0.10 + app_ctx_globals_class = _AppCtxGlobals + + #: The class that is used for the ``config`` attribute of this app. + #: Defaults to :class:`~flask.Config`. + #: + #: Example use cases for a custom class: + #: + #: 1. Default values for certain config options. + #: 2. Access to config values through attributes in addition to keys. + #: + #: .. versionadded:: 0.11 + config_class = Config + + #: The testing flag. Set this to ``True`` to enable the test mode of + #: Flask extensions (and in the future probably also Flask itself). + #: For example this might activate test helpers that have an + #: additional runtime cost which should not be enabled by default. + #: + #: If this is enabled and PROPAGATE_EXCEPTIONS is not changed from the + #: default it's implicitly enabled. + #: + #: This attribute can also be configured from the config with the + #: ``TESTING`` configuration key. Defaults to ``False``. + testing = ConfigAttribute('TESTING') + + #: If a secret key is set, cryptographic components can use this to + #: sign cookies and other things. Set this to a complex random value + #: when you want to use the secure cookie for instance. + #: + #: This attribute can also be configured from the config with the + #: :data:`SECRET_KEY` configuration key. Defaults to ``None``. + secret_key = ConfigAttribute('SECRET_KEY') + + #: The secure cookie uses this for the name of the session cookie. + #: + #: This attribute can also be configured from the config with the + #: ``SESSION_COOKIE_NAME`` configuration key. Defaults to ``'session'`` + session_cookie_name = ConfigAttribute('SESSION_COOKIE_NAME') + + #: A :class:`~datetime.timedelta` which is used to set the expiration + #: date of a permanent session. The default is 31 days which makes a + #: permanent session survive for roughly one month. + #: + #: This attribute can also be configured from the config with the + #: ``PERMANENT_SESSION_LIFETIME`` configuration key. Defaults to + #: ``timedelta(days=31)`` + permanent_session_lifetime = ConfigAttribute('PERMANENT_SESSION_LIFETIME', + get_converter=_make_timedelta) + + #: A :class:`~datetime.timedelta` which is used as default cache_timeout + #: for the :func:`send_file` functions. The default is 12 hours. + #: + #: This attribute can also be configured from the config with the + #: ``SEND_FILE_MAX_AGE_DEFAULT`` configuration key. This configuration + #: variable can also be set with an integer value used as seconds. + #: Defaults to ``timedelta(hours=12)`` + send_file_max_age_default = ConfigAttribute('SEND_FILE_MAX_AGE_DEFAULT', + get_converter=_make_timedelta) + + #: Enable this if you want to use the X-Sendfile feature. Keep in + #: mind that the server has to support this. This only affects files + #: sent with the :func:`send_file` method. + #: + #: .. versionadded:: 0.2 + #: + #: This attribute can also be configured from the config with the + #: ``USE_X_SENDFILE`` configuration key. Defaults to ``False``. + use_x_sendfile = ConfigAttribute('USE_X_SENDFILE') + + #: The JSON encoder class to use. Defaults to :class:`~flask.json.JSONEncoder`. + #: + #: .. versionadded:: 0.10 + json_encoder = json.JSONEncoder + + #: The JSON decoder class to use. Defaults to :class:`~flask.json.JSONDecoder`. + #: + #: .. versionadded:: 0.10 + json_decoder = json.JSONDecoder + + #: Options that are passed directly to the Jinja2 environment. + jinja_options = ImmutableDict( + extensions=['jinja2.ext.autoescape', 'jinja2.ext.with_'] + ) + + #: Default configuration parameters. + default_config = ImmutableDict({ + 'ENV': None, + 'DEBUG': None, + 'TESTING': False, + 'PROPAGATE_EXCEPTIONS': None, + 'PRESERVE_CONTEXT_ON_EXCEPTION': None, + 'SECRET_KEY': None, + 'PERMANENT_SESSION_LIFETIME': timedelta(days=31), + 'USE_X_SENDFILE': False, + 'SERVER_NAME': None, + 'APPLICATION_ROOT': '/', + 'SESSION_COOKIE_NAME': 'session', + 'SESSION_COOKIE_DOMAIN': None, + 'SESSION_COOKIE_PATH': None, + 'SESSION_COOKIE_HTTPONLY': True, + 'SESSION_COOKIE_SECURE': False, + 'SESSION_COOKIE_SAMESITE': None, + 'SESSION_REFRESH_EACH_REQUEST': True, + 'MAX_CONTENT_LENGTH': None, + 'SEND_FILE_MAX_AGE_DEFAULT': timedelta(hours=12), + 'TRAP_BAD_REQUEST_ERRORS': None, + 'TRAP_HTTP_EXCEPTIONS': False, + 'EXPLAIN_TEMPLATE_LOADING': False, + 'PREFERRED_URL_SCHEME': 'http', + 'JSON_AS_ASCII': True, + 'JSON_SORT_KEYS': True, + 'JSONIFY_PRETTYPRINT_REGULAR': False, + 'JSONIFY_MIMETYPE': 'application/json', + 'TEMPLATES_AUTO_RELOAD': None, + 'MAX_COOKIE_SIZE': 4093, + }) + + #: The rule object to use for URL rules created. This is used by + #: :meth:`add_url_rule`. Defaults to :class:`werkzeug.routing.Rule`. + #: + #: .. versionadded:: 0.7 + url_rule_class = Rule + + #: the test client that is used with when `test_client` is used. + #: + #: .. versionadded:: 0.7 + test_client_class = None + + #: The :class:`~click.testing.CliRunner` subclass, by default + #: :class:`~flask.testing.FlaskCliRunner` that is used by + #: :meth:`test_cli_runner`. Its ``__init__`` method should take a + #: Flask app object as the first argument. + #: + #: .. versionadded:: 1.0 + test_cli_runner_class = None + + #: the session interface to use. By default an instance of + #: :class:`~flask.sessions.SecureCookieSessionInterface` is used here. + #: + #: .. versionadded:: 0.8 + session_interface = SecureCookieSessionInterface() + + # TODO remove the next three attrs when Sphinx :inherited-members: works + # https://github.com/sphinx-doc/sphinx/issues/741 + + #: The name of the package or module that this app belongs to. Do not + #: change this once it is set by the constructor. + import_name = None + + #: Location of the template files to be added to the template lookup. + #: ``None`` if templates should not be added. + template_folder = None + + #: Absolute path to the package on the filesystem. Used to look up + #: resources contained in the package. + root_path = None + + def __init__( + self, + import_name, + static_url_path=None, + static_folder='static', + static_host=None, + host_matching=False, + subdomain_matching=False, + template_folder='templates', + instance_path=None, + instance_relative_config=False, + root_path=None + ): + _PackageBoundObject.__init__( + self, + import_name, + template_folder=template_folder, + root_path=root_path + ) + + if static_url_path is not None: + self.static_url_path = static_url_path + + if static_folder is not None: + self.static_folder = static_folder + + if instance_path is None: + instance_path = self.auto_find_instance_path() + elif not os.path.isabs(instance_path): + raise ValueError( + 'If an instance path is provided it must be absolute.' + ' A relative path was given instead.' + ) + + #: Holds the path to the instance folder. + #: + #: .. versionadded:: 0.8 + self.instance_path = instance_path + + #: The configuration dictionary as :class:`Config`. This behaves + #: exactly like a regular dictionary but supports additional methods + #: to load a config from files. + self.config = self.make_config(instance_relative_config) + + #: A dictionary of all view functions registered. The keys will + #: be function names which are also used to generate URLs and + #: the values are the function objects themselves. + #: To register a view function, use the :meth:`route` decorator. + self.view_functions = {} + + #: A dictionary of all registered error handlers. The key is ``None`` + #: for error handlers active on the application, otherwise the key is + #: the name of the blueprint. Each key points to another dictionary + #: where the key is the status code of the http exception. The + #: special key ``None`` points to a list of tuples where the first item + #: is the class for the instance check and the second the error handler + #: function. + #: + #: To register an error handler, use the :meth:`errorhandler` + #: decorator. + self.error_handler_spec = {} + + #: A list of functions that are called when :meth:`url_for` raises a + #: :exc:`~werkzeug.routing.BuildError`. Each function registered here + #: is called with `error`, `endpoint` and `values`. If a function + #: returns ``None`` or raises a :exc:`BuildError` the next function is + #: tried. + #: + #: .. versionadded:: 0.9 + self.url_build_error_handlers = [] + + #: A dictionary with lists of functions that will be called at the + #: beginning of each request. The key of the dictionary is the name of + #: the blueprint this function is active for, or ``None`` for all + #: requests. To register a function, use the :meth:`before_request` + #: decorator. + self.before_request_funcs = {} + + #: A list of functions that will be called at the beginning of the + #: first request to this instance. To register a function, use the + #: :meth:`before_first_request` decorator. + #: + #: .. versionadded:: 0.8 + self.before_first_request_funcs = [] + + #: A dictionary with lists of functions that should be called after + #: each request. The key of the dictionary is the name of the blueprint + #: this function is active for, ``None`` for all requests. This can for + #: example be used to close database connections. To register a function + #: here, use the :meth:`after_request` decorator. + self.after_request_funcs = {} + + #: A dictionary with lists of functions that are called after + #: each request, even if an exception has occurred. The key of the + #: dictionary is the name of the blueprint this function is active for, + #: ``None`` for all requests. These functions are not allowed to modify + #: the request, and their return values are ignored. If an exception + #: occurred while processing the request, it gets passed to each + #: teardown_request function. To register a function here, use the + #: :meth:`teardown_request` decorator. + #: + #: .. versionadded:: 0.7 + self.teardown_request_funcs = {} + + #: A list of functions that are called when the application context + #: is destroyed. Since the application context is also torn down + #: if the request ends this is the place to store code that disconnects + #: from databases. + #: + #: .. versionadded:: 0.9 + self.teardown_appcontext_funcs = [] + + #: A dictionary with lists of functions that are called before the + #: :attr:`before_request_funcs` functions. The key of the dictionary is + #: the name of the blueprint this function is active for, or ``None`` + #: for all requests. To register a function, use + #: :meth:`url_value_preprocessor`. + #: + #: .. versionadded:: 0.7 + self.url_value_preprocessors = {} + + #: A dictionary with lists of functions that can be used as URL value + #: preprocessors. The key ``None`` here is used for application wide + #: callbacks, otherwise the key is the name of the blueprint. + #: Each of these functions has the chance to modify the dictionary + #: of URL values before they are used as the keyword arguments of the + #: view function. For each function registered this one should also + #: provide a :meth:`url_defaults` function that adds the parameters + #: automatically again that were removed that way. + #: + #: .. versionadded:: 0.7 + self.url_default_functions = {} + + #: A dictionary with list of functions that are called without argument + #: to populate the template context. The key of the dictionary is the + #: name of the blueprint this function is active for, ``None`` for all + #: requests. Each returns a dictionary that the template context is + #: updated with. To register a function here, use the + #: :meth:`context_processor` decorator. + self.template_context_processors = { + None: [_default_template_ctx_processor] + } + + #: A list of shell context processor functions that should be run + #: when a shell context is created. + #: + #: .. versionadded:: 0.11 + self.shell_context_processors = [] + + #: all the attached blueprints in a dictionary by name. Blueprints + #: can be attached multiple times so this dictionary does not tell + #: you how often they got attached. + #: + #: .. versionadded:: 0.7 + self.blueprints = {} + self._blueprint_order = [] + + #: a place where extensions can store application specific state. For + #: example this is where an extension could store database engines and + #: similar things. For backwards compatibility extensions should register + #: themselves like this:: + #: + #: if not hasattr(app, 'extensions'): + #: app.extensions = {} + #: app.extensions['extensionname'] = SomeObject() + #: + #: The key must match the name of the extension module. For example in + #: case of a "Flask-Foo" extension in `flask_foo`, the key would be + #: ``'foo'``. + #: + #: .. versionadded:: 0.7 + self.extensions = {} + + #: The :class:`~werkzeug.routing.Map` for this instance. You can use + #: this to change the routing converters after the class was created + #: but before any routes are connected. Example:: + #: + #: from werkzeug.routing import BaseConverter + #: + #: class ListConverter(BaseConverter): + #: def to_python(self, value): + #: return value.split(',') + #: def to_url(self, values): + #: return ','.join(super(ListConverter, self).to_url(value) + #: for value in values) + #: + #: app = Flask(__name__) + #: app.url_map.converters['list'] = ListConverter + self.url_map = Map() + + self.url_map.host_matching = host_matching + self.subdomain_matching = subdomain_matching + + # tracks internally if the application already handled at least one + # request. + self._got_first_request = False + self._before_request_lock = Lock() + + # Add a static route using the provided static_url_path, static_host, + # and static_folder if there is a configured static_folder. + # Note we do this without checking if static_folder exists. + # For one, it might be created while the server is running (e.g. during + # development). Also, Google App Engine stores static files somewhere + if self.has_static_folder: + assert bool(static_host) == host_matching, 'Invalid static_host/host_matching combination' + self.add_url_rule( + self.static_url_path + '/', + endpoint='static', + host=static_host, + view_func=self.send_static_file + ) + + #: The click command line context for this application. Commands + #: registered here show up in the :command:`flask` command once the + #: application has been discovered. The default commands are + #: provided by Flask itself and can be overridden. + #: + #: This is an instance of a :class:`click.Group` object. + self.cli = cli.AppGroup(self.name) + + @locked_cached_property + def name(self): + """The name of the application. This is usually the import name + with the difference that it's guessed from the run file if the + import name is main. This name is used as a display name when + Flask needs the name of the application. It can be set and overridden + to change the value. + + .. versionadded:: 0.8 + """ + if self.import_name == '__main__': + fn = getattr(sys.modules['__main__'], '__file__', None) + if fn is None: + return '__main__' + return os.path.splitext(os.path.basename(fn))[0] + return self.import_name + + @property + def propagate_exceptions(self): + """Returns the value of the ``PROPAGATE_EXCEPTIONS`` configuration + value in case it's set, otherwise a sensible default is returned. + + .. versionadded:: 0.7 + """ + rv = self.config['PROPAGATE_EXCEPTIONS'] + if rv is not None: + return rv + return self.testing or self.debug + + @property + def preserve_context_on_exception(self): + """Returns the value of the ``PRESERVE_CONTEXT_ON_EXCEPTION`` + configuration value in case it's set, otherwise a sensible default + is returned. + + .. versionadded:: 0.7 + """ + rv = self.config['PRESERVE_CONTEXT_ON_EXCEPTION'] + if rv is not None: + return rv + return self.debug + + @locked_cached_property + def logger(self): + """The ``'flask.app'`` logger, a standard Python + :class:`~logging.Logger`. + + In debug mode, the logger's :attr:`~logging.Logger.level` will be set + to :data:`~logging.DEBUG`. + + If there are no handlers configured, a default handler will be added. + See :ref:`logging` for more information. + + .. versionchanged:: 1.0 + Behavior was simplified. The logger is always named + ``flask.app``. The level is only set during configuration, it + doesn't check ``app.debug`` each time. Only one format is used, + not different ones depending on ``app.debug``. No handlers are + removed, and a handler is only added if no handlers are already + configured. + + .. versionadded:: 0.3 + """ + return create_logger(self) + + @locked_cached_property + def jinja_env(self): + """The Jinja2 environment used to load templates.""" + return self.create_jinja_environment() + + @property + def got_first_request(self): + """This attribute is set to ``True`` if the application started + handling the first request. + + .. versionadded:: 0.8 + """ + return self._got_first_request + + def make_config(self, instance_relative=False): + """Used to create the config attribute by the Flask constructor. + The `instance_relative` parameter is passed in from the constructor + of Flask (there named `instance_relative_config`) and indicates if + the config should be relative to the instance path or the root path + of the application. + + .. versionadded:: 0.8 + """ + root_path = self.root_path + if instance_relative: + root_path = self.instance_path + defaults = dict(self.default_config) + defaults['ENV'] = get_env() + defaults['DEBUG'] = get_debug_flag() + return self.config_class(root_path, defaults) + + def auto_find_instance_path(self): + """Tries to locate the instance path if it was not provided to the + constructor of the application class. It will basically calculate + the path to a folder named ``instance`` next to your main file or + the package. + + .. versionadded:: 0.8 + """ + prefix, package_path = find_package(self.import_name) + if prefix is None: + return os.path.join(package_path, 'instance') + return os.path.join(prefix, 'var', self.name + '-instance') + + def open_instance_resource(self, resource, mode='rb'): + """Opens a resource from the application's instance folder + (:attr:`instance_path`). Otherwise works like + :meth:`open_resource`. Instance resources can also be opened for + writing. + + :param resource: the name of the resource. To access resources within + subfolders use forward slashes as separator. + :param mode: resource file opening mode, default is 'rb'. + """ + return open(os.path.join(self.instance_path, resource), mode) + + def _get_templates_auto_reload(self): + """Reload templates when they are changed. Used by + :meth:`create_jinja_environment`. + + This attribute can be configured with :data:`TEMPLATES_AUTO_RELOAD`. If + not set, it will be enabled in debug mode. + + .. versionadded:: 1.0 + This property was added but the underlying config and behavior + already existed. + """ + rv = self.config['TEMPLATES_AUTO_RELOAD'] + return rv if rv is not None else self.debug + + def _set_templates_auto_reload(self, value): + self.config['TEMPLATES_AUTO_RELOAD'] = value + + templates_auto_reload = property( + _get_templates_auto_reload, _set_templates_auto_reload + ) + del _get_templates_auto_reload, _set_templates_auto_reload + + def create_jinja_environment(self): + """Creates the Jinja2 environment based on :attr:`jinja_options` + and :meth:`select_jinja_autoescape`. Since 0.7 this also adds + the Jinja2 globals and filters after initialization. Override + this function to customize the behavior. + + .. versionadded:: 0.5 + .. versionchanged:: 0.11 + ``Environment.auto_reload`` set in accordance with + ``TEMPLATES_AUTO_RELOAD`` configuration option. + """ + options = dict(self.jinja_options) + + if 'autoescape' not in options: + options['autoescape'] = self.select_jinja_autoescape + + if 'auto_reload' not in options: + options['auto_reload'] = self.templates_auto_reload + + rv = self.jinja_environment(self, **options) + rv.globals.update( + url_for=url_for, + get_flashed_messages=get_flashed_messages, + config=self.config, + # request, session and g are normally added with the + # context processor for efficiency reasons but for imported + # templates we also want the proxies in there. + request=request, + session=session, + g=g + ) + rv.filters['tojson'] = json.tojson_filter + return rv + + def create_global_jinja_loader(self): + """Creates the loader for the Jinja2 environment. Can be used to + override just the loader and keeping the rest unchanged. It's + discouraged to override this function. Instead one should override + the :meth:`jinja_loader` function instead. + + The global loader dispatches between the loaders of the application + and the individual blueprints. + + .. versionadded:: 0.7 + """ + return DispatchingJinjaLoader(self) + + def select_jinja_autoescape(self, filename): + """Returns ``True`` if autoescaping should be active for the given + template name. If no template name is given, returns `True`. + + .. versionadded:: 0.5 + """ + if filename is None: + return True + return filename.endswith(('.html', '.htm', '.xml', '.xhtml')) + + def update_template_context(self, context): + """Update the template context with some commonly used variables. + This injects request, session, config and g into the template + context as well as everything template context processors want + to inject. Note that the as of Flask 0.6, the original values + in the context will not be overridden if a context processor + decides to return a value with the same key. + + :param context: the context as a dictionary that is updated in place + to add extra variables. + """ + funcs = self.template_context_processors[None] + reqctx = _request_ctx_stack.top + if reqctx is not None: + bp = reqctx.request.blueprint + if bp is not None and bp in self.template_context_processors: + funcs = chain(funcs, self.template_context_processors[bp]) + orig_ctx = context.copy() + for func in funcs: + context.update(func()) + # make sure the original values win. This makes it possible to + # easier add new variables in context processors without breaking + # existing views. + context.update(orig_ctx) + + def make_shell_context(self): + """Returns the shell context for an interactive shell for this + application. This runs all the registered shell context + processors. + + .. versionadded:: 0.11 + """ + rv = {'app': self, 'g': g} + for processor in self.shell_context_processors: + rv.update(processor()) + return rv + + #: What environment the app is running in. Flask and extensions may + #: enable behaviors based on the environment, such as enabling debug + #: mode. This maps to the :data:`ENV` config key. This is set by the + #: :envvar:`FLASK_ENV` environment variable and may not behave as + #: expected if set in code. + #: + #: **Do not enable development when deploying in production.** + #: + #: Default: ``'production'`` + env = ConfigAttribute('ENV') + + def _get_debug(self): + return self.config['DEBUG'] + + def _set_debug(self, value): + self.config['DEBUG'] = value + self.jinja_env.auto_reload = self.templates_auto_reload + + #: Whether debug mode is enabled. When using ``flask run`` to start + #: the development server, an interactive debugger will be shown for + #: unhandled exceptions, and the server will be reloaded when code + #: changes. This maps to the :data:`DEBUG` config key. This is + #: enabled when :attr:`env` is ``'development'`` and is overridden + #: by the ``FLASK_DEBUG`` environment variable. It may not behave as + #: expected if set in code. + #: + #: **Do not enable debug mode when deploying in production.** + #: + #: Default: ``True`` if :attr:`env` is ``'development'``, or + #: ``False`` otherwise. + debug = property(_get_debug, _set_debug) + del _get_debug, _set_debug + + def run(self, host=None, port=None, debug=None, + load_dotenv=True, **options): + """Runs the application on a local development server. + + Do not use ``run()`` in a production setting. It is not intended to + meet security and performance requirements for a production server. + Instead, see :ref:`deployment` for WSGI server recommendations. + + If the :attr:`debug` flag is set the server will automatically reload + for code changes and show a debugger in case an exception happened. + + If you want to run the application in debug mode, but disable the + code execution on the interactive debugger, you can pass + ``use_evalex=False`` as parameter. This will keep the debugger's + traceback screen active, but disable code execution. + + It is not recommended to use this function for development with + automatic reloading as this is badly supported. Instead you should + be using the :command:`flask` command line script's ``run`` support. + + .. admonition:: Keep in Mind + + Flask will suppress any server error with a generic error page + unless it is in debug mode. As such to enable just the + interactive debugger without the code reloading, you have to + invoke :meth:`run` with ``debug=True`` and ``use_reloader=False``. + Setting ``use_debugger`` to ``True`` without being in debug mode + won't catch any exceptions because there won't be any to + catch. + + :param host: the hostname to listen on. Set this to ``'0.0.0.0'`` to + have the server available externally as well. Defaults to + ``'127.0.0.1'`` or the host in the ``SERVER_NAME`` config variable + if present. + :param port: the port of the webserver. Defaults to ``5000`` or the + port defined in the ``SERVER_NAME`` config variable if present. + :param debug: if given, enable or disable debug mode. See + :attr:`debug`. + :param load_dotenv: Load the nearest :file:`.env` and :file:`.flaskenv` + files to set environment variables. Will also change the working + directory to the directory containing the first file found. + :param options: the options to be forwarded to the underlying Werkzeug + server. See :func:`werkzeug.serving.run_simple` for more + information. + + .. versionchanged:: 1.0 + If installed, python-dotenv will be used to load environment + variables from :file:`.env` and :file:`.flaskenv` files. + + If set, the :envvar:`FLASK_ENV` and :envvar:`FLASK_DEBUG` + environment variables will override :attr:`env` and + :attr:`debug`. + + Threaded mode is enabled by default. + + .. versionchanged:: 0.10 + The default port is now picked from the ``SERVER_NAME`` + variable. + """ + # Change this into a no-op if the server is invoked from the + # command line. Have a look at cli.py for more information. + if os.environ.get('FLASK_RUN_FROM_CLI') == 'true': + from .debughelpers import explain_ignored_app_run + explain_ignored_app_run() + return + + if get_load_dotenv(load_dotenv): + cli.load_dotenv() + + # if set, let env vars override previous values + if 'FLASK_ENV' in os.environ: + self.env = get_env() + self.debug = get_debug_flag() + elif 'FLASK_DEBUG' in os.environ: + self.debug = get_debug_flag() + + # debug passed to method overrides all other sources + if debug is not None: + self.debug = bool(debug) + + _host = '127.0.0.1' + _port = 5000 + server_name = self.config.get('SERVER_NAME') + sn_host, sn_port = None, None + + if server_name: + sn_host, _, sn_port = server_name.partition(':') + + host = host or sn_host or _host + port = int(port or sn_port or _port) + + options.setdefault('use_reloader', self.debug) + options.setdefault('use_debugger', self.debug) + options.setdefault('threaded', True) + + cli.show_server_banner(self.env, self.debug, self.name, False) + + from werkzeug.serving import run_simple + + try: + run_simple(host, port, self, **options) + finally: + # reset the first request information if the development server + # reset normally. This makes it possible to restart the server + # without reloader and that stuff from an interactive shell. + self._got_first_request = False + + def test_client(self, use_cookies=True, **kwargs): + """Creates a test client for this application. For information + about unit testing head over to :ref:`testing`. + + Note that if you are testing for assertions or exceptions in your + application code, you must set ``app.testing = True`` in order for the + exceptions to propagate to the test client. Otherwise, the exception + will be handled by the application (not visible to the test client) and + the only indication of an AssertionError or other exception will be a + 500 status code response to the test client. See the :attr:`testing` + attribute. For example:: + + app.testing = True + client = app.test_client() + + The test client can be used in a ``with`` block to defer the closing down + of the context until the end of the ``with`` block. This is useful if + you want to access the context locals for testing:: + + with app.test_client() as c: + rv = c.get('/?vodka=42') + assert request.args['vodka'] == '42' + + Additionally, you may pass optional keyword arguments that will then + be passed to the application's :attr:`test_client_class` constructor. + For example:: + + from flask.testing import FlaskClient + + class CustomClient(FlaskClient): + def __init__(self, *args, **kwargs): + self._authentication = kwargs.pop("authentication") + super(CustomClient,self).__init__( *args, **kwargs) + + app.test_client_class = CustomClient + client = app.test_client(authentication='Basic ....') + + See :class:`~flask.testing.FlaskClient` for more information. + + .. versionchanged:: 0.4 + added support for ``with`` block usage for the client. + + .. versionadded:: 0.7 + The `use_cookies` parameter was added as well as the ability + to override the client to be used by setting the + :attr:`test_client_class` attribute. + + .. versionchanged:: 0.11 + Added `**kwargs` to support passing additional keyword arguments to + the constructor of :attr:`test_client_class`. + """ + cls = self.test_client_class + if cls is None: + from flask.testing import FlaskClient as cls + return cls(self, self.response_class, use_cookies=use_cookies, **kwargs) + + def test_cli_runner(self, **kwargs): + """Create a CLI runner for testing CLI commands. + See :ref:`testing-cli`. + + Returns an instance of :attr:`test_cli_runner_class`, by default + :class:`~flask.testing.FlaskCliRunner`. The Flask app object is + passed as the first argument. + + .. versionadded:: 1.0 + """ + cls = self.test_cli_runner_class + + if cls is None: + from flask.testing import FlaskCliRunner as cls + + return cls(self, **kwargs) + + def open_session(self, request): + """Creates or opens a new session. Default implementation stores all + session data in a signed cookie. This requires that the + :attr:`secret_key` is set. Instead of overriding this method + we recommend replacing the :class:`session_interface`. + + .. deprecated: 1.0 + Will be removed in 1.1. Use ``session_interface.open_session`` + instead. + + :param request: an instance of :attr:`request_class`. + """ + + warnings.warn(DeprecationWarning( + '"open_session" is deprecated and will be removed in 1.1. Use' + ' "session_interface.open_session" instead.' + )) + return self.session_interface.open_session(self, request) + + def save_session(self, session, response): + """Saves the session if it needs updates. For the default + implementation, check :meth:`open_session`. Instead of overriding this + method we recommend replacing the :class:`session_interface`. + + .. deprecated: 1.0 + Will be removed in 1.1. Use ``session_interface.save_session`` + instead. + + :param session: the session to be saved (a + :class:`~werkzeug.contrib.securecookie.SecureCookie` + object) + :param response: an instance of :attr:`response_class` + """ + + warnings.warn(DeprecationWarning( + '"save_session" is deprecated and will be removed in 1.1. Use' + ' "session_interface.save_session" instead.' + )) + return self.session_interface.save_session(self, session, response) + + def make_null_session(self): + """Creates a new instance of a missing session. Instead of overriding + this method we recommend replacing the :class:`session_interface`. + + .. deprecated: 1.0 + Will be removed in 1.1. Use ``session_interface.make_null_session`` + instead. + + .. versionadded:: 0.7 + """ + + warnings.warn(DeprecationWarning( + '"make_null_session" is deprecated and will be removed in 1.1. Use' + ' "session_interface.make_null_session" instead.' + )) + return self.session_interface.make_null_session(self) + + @setupmethod + def register_blueprint(self, blueprint, **options): + """Register a :class:`~flask.Blueprint` on the application. Keyword + arguments passed to this method will override the defaults set on the + blueprint. + + Calls the blueprint's :meth:`~flask.Blueprint.register` method after + recording the blueprint in the application's :attr:`blueprints`. + + :param blueprint: The blueprint to register. + :param url_prefix: Blueprint routes will be prefixed with this. + :param subdomain: Blueprint routes will match on this subdomain. + :param url_defaults: Blueprint routes will use these default values for + view arguments. + :param options: Additional keyword arguments are passed to + :class:`~flask.blueprints.BlueprintSetupState`. They can be + accessed in :meth:`~flask.Blueprint.record` callbacks. + + .. versionadded:: 0.7 + """ + first_registration = False + + if blueprint.name in self.blueprints: + assert self.blueprints[blueprint.name] is blueprint, ( + 'A name collision occurred between blueprints %r and %r. Both' + ' share the same name "%s". Blueprints that are created on the' + ' fly need unique names.' % ( + blueprint, self.blueprints[blueprint.name], blueprint.name + ) + ) + else: + self.blueprints[blueprint.name] = blueprint + self._blueprint_order.append(blueprint) + first_registration = True + + blueprint.register(self, options, first_registration) + + def iter_blueprints(self): + """Iterates over all blueprints by the order they were registered. + + .. versionadded:: 0.11 + """ + return iter(self._blueprint_order) + + @setupmethod + def add_url_rule(self, rule, endpoint=None, view_func=None, + provide_automatic_options=None, **options): + """Connects a URL rule. Works exactly like the :meth:`route` + decorator. If a view_func is provided it will be registered with the + endpoint. + + Basically this example:: + + @app.route('/') + def index(): + pass + + Is equivalent to the following:: + + def index(): + pass + app.add_url_rule('/', 'index', index) + + If the view_func is not provided you will need to connect the endpoint + to a view function like so:: + + app.view_functions['index'] = index + + Internally :meth:`route` invokes :meth:`add_url_rule` so if you want + to customize the behavior via subclassing you only need to change + this method. + + For more information refer to :ref:`url-route-registrations`. + + .. versionchanged:: 0.2 + `view_func` parameter added. + + .. versionchanged:: 0.6 + ``OPTIONS`` is added automatically as method. + + :param rule: the URL rule as string + :param endpoint: the endpoint for the registered URL rule. Flask + itself assumes the name of the view function as + endpoint + :param view_func: the function to call when serving a request to the + provided endpoint + :param provide_automatic_options: controls whether the ``OPTIONS`` + method should be added automatically. This can also be controlled + by setting the ``view_func.provide_automatic_options = False`` + before adding the rule. + :param options: the options to be forwarded to the underlying + :class:`~werkzeug.routing.Rule` object. A change + to Werkzeug is handling of method options. methods + is a list of methods this rule should be limited + to (``GET``, ``POST`` etc.). By default a rule + just listens for ``GET`` (and implicitly ``HEAD``). + Starting with Flask 0.6, ``OPTIONS`` is implicitly + added and handled by the standard request handling. + """ + if endpoint is None: + endpoint = _endpoint_from_view_func(view_func) + options['endpoint'] = endpoint + methods = options.pop('methods', None) + + # if the methods are not given and the view_func object knows its + # methods we can use that instead. If neither exists, we go with + # a tuple of only ``GET`` as default. + if methods is None: + methods = getattr(view_func, 'methods', None) or ('GET',) + if isinstance(methods, string_types): + raise TypeError('Allowed methods have to be iterables of strings, ' + 'for example: @app.route(..., methods=["POST"])') + methods = set(item.upper() for item in methods) + + # Methods that should always be added + required_methods = set(getattr(view_func, 'required_methods', ())) + + # starting with Flask 0.8 the view_func object can disable and + # force-enable the automatic options handling. + if provide_automatic_options is None: + provide_automatic_options = getattr(view_func, + 'provide_automatic_options', None) + + if provide_automatic_options is None: + if 'OPTIONS' not in methods: + provide_automatic_options = True + required_methods.add('OPTIONS') + else: + provide_automatic_options = False + + # Add the required methods now. + methods |= required_methods + + rule = self.url_rule_class(rule, methods=methods, **options) + rule.provide_automatic_options = provide_automatic_options + + self.url_map.add(rule) + if view_func is not None: + old_func = self.view_functions.get(endpoint) + if old_func is not None and old_func != view_func: + raise AssertionError('View function mapping is overwriting an ' + 'existing endpoint function: %s' % endpoint) + self.view_functions[endpoint] = view_func + + def route(self, rule, **options): + """A decorator that is used to register a view function for a + given URL rule. This does the same thing as :meth:`add_url_rule` + but is intended for decorator usage:: + + @app.route('/') + def index(): + return 'Hello World' + + For more information refer to :ref:`url-route-registrations`. + + :param rule: the URL rule as string + :param endpoint: the endpoint for the registered URL rule. Flask + itself assumes the name of the view function as + endpoint + :param options: the options to be forwarded to the underlying + :class:`~werkzeug.routing.Rule` object. A change + to Werkzeug is handling of method options. methods + is a list of methods this rule should be limited + to (``GET``, ``POST`` etc.). By default a rule + just listens for ``GET`` (and implicitly ``HEAD``). + Starting with Flask 0.6, ``OPTIONS`` is implicitly + added and handled by the standard request handling. + """ + def decorator(f): + endpoint = options.pop('endpoint', None) + self.add_url_rule(rule, endpoint, f, **options) + return f + return decorator + + @setupmethod + def endpoint(self, endpoint): + """A decorator to register a function as an endpoint. + Example:: + + @app.endpoint('example.endpoint') + def example(): + return "example" + + :param endpoint: the name of the endpoint + """ + def decorator(f): + self.view_functions[endpoint] = f + return f + return decorator + + @staticmethod + def _get_exc_class_and_code(exc_class_or_code): + """Ensure that we register only exceptions as handler keys""" + if isinstance(exc_class_or_code, integer_types): + exc_class = default_exceptions[exc_class_or_code] + else: + exc_class = exc_class_or_code + + assert issubclass(exc_class, Exception) + + if issubclass(exc_class, HTTPException): + return exc_class, exc_class.code + else: + return exc_class, None + + @setupmethod + def errorhandler(self, code_or_exception): + """Register a function to handle errors by code or exception class. + + A decorator that is used to register a function given an + error code. Example:: + + @app.errorhandler(404) + def page_not_found(error): + return 'This page does not exist', 404 + + You can also register handlers for arbitrary exceptions:: + + @app.errorhandler(DatabaseError) + def special_exception_handler(error): + return 'Database connection failed', 500 + + .. versionadded:: 0.7 + Use :meth:`register_error_handler` instead of modifying + :attr:`error_handler_spec` directly, for application wide error + handlers. + + .. versionadded:: 0.7 + One can now additionally also register custom exception types + that do not necessarily have to be a subclass of the + :class:`~werkzeug.exceptions.HTTPException` class. + + :param code_or_exception: the code as integer for the handler, or + an arbitrary exception + """ + def decorator(f): + self._register_error_handler(None, code_or_exception, f) + return f + return decorator + + @setupmethod + def register_error_handler(self, code_or_exception, f): + """Alternative error attach function to the :meth:`errorhandler` + decorator that is more straightforward to use for non decorator + usage. + + .. versionadded:: 0.7 + """ + self._register_error_handler(None, code_or_exception, f) + + @setupmethod + def _register_error_handler(self, key, code_or_exception, f): + """ + :type key: None|str + :type code_or_exception: int|T<=Exception + :type f: callable + """ + if isinstance(code_or_exception, HTTPException): # old broken behavior + raise ValueError( + 'Tried to register a handler for an exception instance {0!r}.' + ' Handlers can only be registered for exception classes or' + ' HTTP error codes.'.format(code_or_exception) + ) + + try: + exc_class, code = self._get_exc_class_and_code(code_or_exception) + except KeyError: + raise KeyError( + "'{0}' is not a recognized HTTP error code. Use a subclass of" + " HTTPException with that code instead.".format(code_or_exception) + ) + + handlers = self.error_handler_spec.setdefault(key, {}).setdefault(code, {}) + handlers[exc_class] = f + + @setupmethod + def template_filter(self, name=None): + """A decorator that is used to register custom template filter. + You can specify a name for the filter, otherwise the function + name will be used. Example:: + + @app.template_filter() + def reverse(s): + return s[::-1] + + :param name: the optional name of the filter, otherwise the + function name will be used. + """ + def decorator(f): + self.add_template_filter(f, name=name) + return f + return decorator + + @setupmethod + def add_template_filter(self, f, name=None): + """Register a custom template filter. Works exactly like the + :meth:`template_filter` decorator. + + :param name: the optional name of the filter, otherwise the + function name will be used. + """ + self.jinja_env.filters[name or f.__name__] = f + + @setupmethod + def template_test(self, name=None): + """A decorator that is used to register custom template test. + You can specify a name for the test, otherwise the function + name will be used. Example:: + + @app.template_test() + def is_prime(n): + if n == 2: + return True + for i in range(2, int(math.ceil(math.sqrt(n))) + 1): + if n % i == 0: + return False + return True + + .. versionadded:: 0.10 + + :param name: the optional name of the test, otherwise the + function name will be used. + """ + def decorator(f): + self.add_template_test(f, name=name) + return f + return decorator + + @setupmethod + def add_template_test(self, f, name=None): + """Register a custom template test. Works exactly like the + :meth:`template_test` decorator. + + .. versionadded:: 0.10 + + :param name: the optional name of the test, otherwise the + function name will be used. + """ + self.jinja_env.tests[name or f.__name__] = f + + @setupmethod + def template_global(self, name=None): + """A decorator that is used to register a custom template global function. + You can specify a name for the global function, otherwise the function + name will be used. Example:: + + @app.template_global() + def double(n): + return 2 * n + + .. versionadded:: 0.10 + + :param name: the optional name of the global function, otherwise the + function name will be used. + """ + def decorator(f): + self.add_template_global(f, name=name) + return f + return decorator + + @setupmethod + def add_template_global(self, f, name=None): + """Register a custom template global function. Works exactly like the + :meth:`template_global` decorator. + + .. versionadded:: 0.10 + + :param name: the optional name of the global function, otherwise the + function name will be used. + """ + self.jinja_env.globals[name or f.__name__] = f + + @setupmethod + def before_request(self, f): + """Registers a function to run before each request. + + For example, this can be used to open a database connection, or to load + the logged in user from the session. + + The function will be called without any arguments. If it returns a + non-None value, the value is handled as if it was the return value from + the view, and further request handling is stopped. + """ + self.before_request_funcs.setdefault(None, []).append(f) + return f + + @setupmethod + def before_first_request(self, f): + """Registers a function to be run before the first request to this + instance of the application. + + The function will be called without any arguments and its return + value is ignored. + + .. versionadded:: 0.8 + """ + self.before_first_request_funcs.append(f) + return f + + @setupmethod + def after_request(self, f): + """Register a function to be run after each request. + + Your function must take one parameter, an instance of + :attr:`response_class` and return a new response object or the + same (see :meth:`process_response`). + + As of Flask 0.7 this function might not be executed at the end of the + request in case an unhandled exception occurred. + """ + self.after_request_funcs.setdefault(None, []).append(f) + return f + + @setupmethod + def teardown_request(self, f): + """Register a function to be run at the end of each request, + regardless of whether there was an exception or not. These functions + are executed when the request context is popped, even if not an + actual request was performed. + + Example:: + + ctx = app.test_request_context() + ctx.push() + ... + ctx.pop() + + When ``ctx.pop()`` is executed in the above example, the teardown + functions are called just before the request context moves from the + stack of active contexts. This becomes relevant if you are using + such constructs in tests. + + Generally teardown functions must take every necessary step to avoid + that they will fail. If they do execute code that might fail they + will have to surround the execution of these code by try/except + statements and log occurring errors. + + When a teardown function was called because of an exception it will + be passed an error object. + + The return values of teardown functions are ignored. + + .. admonition:: Debug Note + + In debug mode Flask will not tear down a request on an exception + immediately. Instead it will keep it alive so that the interactive + debugger can still access it. This behavior can be controlled + by the ``PRESERVE_CONTEXT_ON_EXCEPTION`` configuration variable. + """ + self.teardown_request_funcs.setdefault(None, []).append(f) + return f + + @setupmethod + def teardown_appcontext(self, f): + """Registers a function to be called when the application context + ends. These functions are typically also called when the request + context is popped. + + Example:: + + ctx = app.app_context() + ctx.push() + ... + ctx.pop() + + When ``ctx.pop()`` is executed in the above example, the teardown + functions are called just before the app context moves from the + stack of active contexts. This becomes relevant if you are using + such constructs in tests. + + Since a request context typically also manages an application + context it would also be called when you pop a request context. + + When a teardown function was called because of an unhandled exception + it will be passed an error object. If an :meth:`errorhandler` is + registered, it will handle the exception and the teardown will not + receive it. + + The return values of teardown functions are ignored. + + .. versionadded:: 0.9 + """ + self.teardown_appcontext_funcs.append(f) + return f + + @setupmethod + def context_processor(self, f): + """Registers a template context processor function.""" + self.template_context_processors[None].append(f) + return f + + @setupmethod + def shell_context_processor(self, f): + """Registers a shell context processor function. + + .. versionadded:: 0.11 + """ + self.shell_context_processors.append(f) + return f + + @setupmethod + def url_value_preprocessor(self, f): + """Register a URL value preprocessor function for all view + functions in the application. These functions will be called before the + :meth:`before_request` functions. + + The function can modify the values captured from the matched url before + they are passed to the view. For example, this can be used to pop a + common language code value and place it in ``g`` rather than pass it to + every view. + + The function is passed the endpoint name and values dict. The return + value is ignored. + """ + self.url_value_preprocessors.setdefault(None, []).append(f) + return f + + @setupmethod + def url_defaults(self, f): + """Callback function for URL defaults for all view functions of the + application. It's called with the endpoint and values and should + update the values passed in place. + """ + self.url_default_functions.setdefault(None, []).append(f) + return f + + def _find_error_handler(self, e): + """Return a registered error handler for an exception in this order: + blueprint handler for a specific code, app handler for a specific code, + blueprint handler for an exception class, app handler for an exception + class, or ``None`` if a suitable handler is not found. + """ + exc_class, code = self._get_exc_class_and_code(type(e)) + + for name, c in ( + (request.blueprint, code), (None, code), + (request.blueprint, None), (None, None) + ): + handler_map = self.error_handler_spec.setdefault(name, {}).get(c) + + if not handler_map: + continue + + for cls in exc_class.__mro__: + handler = handler_map.get(cls) + + if handler is not None: + return handler + + def handle_http_exception(self, e): + """Handles an HTTP exception. By default this will invoke the + registered error handlers and fall back to returning the + exception as response. + + .. versionadded:: 0.3 + """ + # Proxy exceptions don't have error codes. We want to always return + # those unchanged as errors + if e.code is None: + return e + + handler = self._find_error_handler(e) + if handler is None: + return e + return handler(e) + + def trap_http_exception(self, e): + """Checks if an HTTP exception should be trapped or not. By default + this will return ``False`` for all exceptions except for a bad request + key error if ``TRAP_BAD_REQUEST_ERRORS`` is set to ``True``. It + also returns ``True`` if ``TRAP_HTTP_EXCEPTIONS`` is set to ``True``. + + This is called for all HTTP exceptions raised by a view function. + If it returns ``True`` for any exception the error handler for this + exception is not called and it shows up as regular exception in the + traceback. This is helpful for debugging implicitly raised HTTP + exceptions. + + .. versionchanged:: 1.0 + Bad request errors are not trapped by default in debug mode. + + .. versionadded:: 0.8 + """ + if self.config['TRAP_HTTP_EXCEPTIONS']: + return True + + trap_bad_request = self.config['TRAP_BAD_REQUEST_ERRORS'] + + # if unset, trap key errors in debug mode + if ( + trap_bad_request is None and self.debug + and isinstance(e, BadRequestKeyError) + ): + return True + + if trap_bad_request: + return isinstance(e, BadRequest) + + return False + + def handle_user_exception(self, e): + """This method is called whenever an exception occurs that should be + handled. A special case are + :class:`~werkzeug.exception.HTTPException`\s which are forwarded by + this function to the :meth:`handle_http_exception` method. This + function will either return a response value or reraise the + exception with the same traceback. + + .. versionchanged:: 1.0 + Key errors raised from request data like ``form`` show the the bad + key in debug mode rather than a generic bad request message. + + .. versionadded:: 0.7 + """ + exc_type, exc_value, tb = sys.exc_info() + assert exc_value is e + # ensure not to trash sys.exc_info() at that point in case someone + # wants the traceback preserved in handle_http_exception. Of course + # we cannot prevent users from trashing it themselves in a custom + # trap_http_exception method so that's their fault then. + + # MultiDict passes the key to the exception, but that's ignored + # when generating the response message. Set an informative + # description for key errors in debug mode or when trapping errors. + if ( + (self.debug or self.config['TRAP_BAD_REQUEST_ERRORS']) + and isinstance(e, BadRequestKeyError) + # only set it if it's still the default description + and e.description is BadRequestKeyError.description + ): + e.description = "KeyError: '{0}'".format(*e.args) + + if isinstance(e, HTTPException) and not self.trap_http_exception(e): + return self.handle_http_exception(e) + + handler = self._find_error_handler(e) + + if handler is None: + reraise(exc_type, exc_value, tb) + return handler(e) + + def handle_exception(self, e): + """Default exception handling that kicks in when an exception + occurs that is not caught. In debug mode the exception will + be re-raised immediately, otherwise it is logged and the handler + for a 500 internal server error is used. If no such handler + exists, a default 500 internal server error message is displayed. + + .. versionadded:: 0.3 + """ + exc_type, exc_value, tb = sys.exc_info() + + got_request_exception.send(self, exception=e) + handler = self._find_error_handler(InternalServerError()) + + if self.propagate_exceptions: + # if we want to repropagate the exception, we can attempt to + # raise it with the whole traceback in case we can do that + # (the function was actually called from the except part) + # otherwise, we just raise the error again + if exc_value is e: + reraise(exc_type, exc_value, tb) + else: + raise e + + self.log_exception((exc_type, exc_value, tb)) + if handler is None: + return InternalServerError() + return self.finalize_request(handler(e), from_error_handler=True) + + def log_exception(self, exc_info): + """Logs an exception. This is called by :meth:`handle_exception` + if debugging is disabled and right before the handler is called. + The default implementation logs the exception as error on the + :attr:`logger`. + + .. versionadded:: 0.8 + """ + self.logger.error('Exception on %s [%s]' % ( + request.path, + request.method + ), exc_info=exc_info) + + def raise_routing_exception(self, request): + """Exceptions that are recording during routing are reraised with + this method. During debug we are not reraising redirect requests + for non ``GET``, ``HEAD``, or ``OPTIONS`` requests and we're raising + a different error instead to help debug situations. + + :internal: + """ + if not self.debug \ + or not isinstance(request.routing_exception, RequestRedirect) \ + or request.method in ('GET', 'HEAD', 'OPTIONS'): + raise request.routing_exception + + from .debughelpers import FormDataRoutingRedirect + raise FormDataRoutingRedirect(request) + + def dispatch_request(self): + """Does the request dispatching. Matches the URL and returns the + return value of the view or error handler. This does not have to + be a response object. In order to convert the return value to a + proper response object, call :func:`make_response`. + + .. versionchanged:: 0.7 + This no longer does the exception handling, this code was + moved to the new :meth:`full_dispatch_request`. + """ + req = _request_ctx_stack.top.request + if req.routing_exception is not None: + self.raise_routing_exception(req) + rule = req.url_rule + # if we provide automatic options for this URL and the + # request came with the OPTIONS method, reply automatically + if getattr(rule, 'provide_automatic_options', False) \ + and req.method == 'OPTIONS': + return self.make_default_options_response() + # otherwise dispatch to the handler for that endpoint + return self.view_functions[rule.endpoint](**req.view_args) + + def full_dispatch_request(self): + """Dispatches the request and on top of that performs request + pre and postprocessing as well as HTTP exception catching and + error handling. + + .. versionadded:: 0.7 + """ + self.try_trigger_before_first_request_functions() + try: + request_started.send(self) + rv = self.preprocess_request() + if rv is None: + rv = self.dispatch_request() + except Exception as e: + rv = self.handle_user_exception(e) + return self.finalize_request(rv) + + def finalize_request(self, rv, from_error_handler=False): + """Given the return value from a view function this finalizes + the request by converting it into a response and invoking the + postprocessing functions. This is invoked for both normal + request dispatching as well as error handlers. + + Because this means that it might be called as a result of a + failure a special safe mode is available which can be enabled + with the `from_error_handler` flag. If enabled, failures in + response processing will be logged and otherwise ignored. + + :internal: + """ + response = self.make_response(rv) + try: + response = self.process_response(response) + request_finished.send(self, response=response) + except Exception: + if not from_error_handler: + raise + self.logger.exception('Request finalizing failed with an ' + 'error while handling an error') + return response + + def try_trigger_before_first_request_functions(self): + """Called before each request and will ensure that it triggers + the :attr:`before_first_request_funcs` and only exactly once per + application instance (which means process usually). + + :internal: + """ + if self._got_first_request: + return + with self._before_request_lock: + if self._got_first_request: + return + for func in self.before_first_request_funcs: + func() + self._got_first_request = True + + def make_default_options_response(self): + """This method is called to create the default ``OPTIONS`` response. + This can be changed through subclassing to change the default + behavior of ``OPTIONS`` responses. + + .. versionadded:: 0.7 + """ + adapter = _request_ctx_stack.top.url_adapter + if hasattr(adapter, 'allowed_methods'): + methods = adapter.allowed_methods() + else: + # fallback for Werkzeug < 0.7 + methods = [] + try: + adapter.match(method='--') + except MethodNotAllowed as e: + methods = e.valid_methods + except HTTPException as e: + pass + rv = self.response_class() + rv.allow.update(methods) + return rv + + def should_ignore_error(self, error): + """This is called to figure out if an error should be ignored + or not as far as the teardown system is concerned. If this + function returns ``True`` then the teardown handlers will not be + passed the error. + + .. versionadded:: 0.10 + """ + return False + + def make_response(self, rv): + """Convert the return value from a view function to an instance of + :attr:`response_class`. + + :param rv: the return value from the view function. The view function + must return a response. Returning ``None``, or the view ending + without returning, is not allowed. The following types are allowed + for ``view_rv``: + + ``str`` (``unicode`` in Python 2) + A response object is created with the string encoded to UTF-8 + as the body. + + ``bytes`` (``str`` in Python 2) + A response object is created with the bytes as the body. + + ``tuple`` + Either ``(body, status, headers)``, ``(body, status)``, or + ``(body, headers)``, where ``body`` is any of the other types + allowed here, ``status`` is a string or an integer, and + ``headers`` is a dictionary or a list of ``(key, value)`` + tuples. If ``body`` is a :attr:`response_class` instance, + ``status`` overwrites the exiting value and ``headers`` are + extended. + + :attr:`response_class` + The object is returned unchanged. + + other :class:`~werkzeug.wrappers.Response` class + The object is coerced to :attr:`response_class`. + + :func:`callable` + The function is called as a WSGI application. The result is + used to create a response object. + + .. versionchanged:: 0.9 + Previously a tuple was interpreted as the arguments for the + response object. + """ + + status = headers = None + + # unpack tuple returns + if isinstance(rv, tuple): + len_rv = len(rv) + + # a 3-tuple is unpacked directly + if len_rv == 3: + rv, status, headers = rv + # decide if a 2-tuple has status or headers + elif len_rv == 2: + if isinstance(rv[1], (Headers, dict, tuple, list)): + rv, headers = rv + else: + rv, status = rv + # other sized tuples are not allowed + else: + raise TypeError( + 'The view function did not return a valid response tuple.' + ' The tuple must have the form (body, status, headers),' + ' (body, status), or (body, headers).' + ) + + # the body must not be None + if rv is None: + raise TypeError( + 'The view function did not return a valid response. The' + ' function either returned None or ended without a return' + ' statement.' + ) + + # make sure the body is an instance of the response class + if not isinstance(rv, self.response_class): + if isinstance(rv, (text_type, bytes, bytearray)): + # let the response class set the status and headers instead of + # waiting to do it manually, so that the class can handle any + # special logic + rv = self.response_class(rv, status=status, headers=headers) + status = headers = None + else: + # evaluate a WSGI callable, or coerce a different response + # class to the correct type + try: + rv = self.response_class.force_type(rv, request.environ) + except TypeError as e: + new_error = TypeError( + '{e}\nThe view function did not return a valid' + ' response. The return type must be a string, tuple,' + ' Response instance, or WSGI callable, but it was a' + ' {rv.__class__.__name__}.'.format(e=e, rv=rv) + ) + reraise(TypeError, new_error, sys.exc_info()[2]) + + # prefer the status if it was provided + if status is not None: + if isinstance(status, (text_type, bytes, bytearray)): + rv.status = status + else: + rv.status_code = status + + # extend existing headers with provided headers + if headers: + rv.headers.extend(headers) + + return rv + + def create_url_adapter(self, request): + """Creates a URL adapter for the given request. The URL adapter + is created at a point where the request context is not yet set + up so the request is passed explicitly. + + .. versionadded:: 0.6 + + .. versionchanged:: 0.9 + This can now also be called without a request object when the + URL adapter is created for the application context. + + .. versionchanged:: 1.0 + :data:`SERVER_NAME` no longer implicitly enables subdomain + matching. Use :attr:`subdomain_matching` instead. + """ + if request is not None: + # If subdomain matching is disabled (the default), use the + # default subdomain in all cases. This should be the default + # in Werkzeug but it currently does not have that feature. + subdomain = ((self.url_map.default_subdomain or None) + if not self.subdomain_matching else None) + return self.url_map.bind_to_environ( + request.environ, + server_name=self.config['SERVER_NAME'], + subdomain=subdomain) + # We need at the very least the server name to be set for this + # to work. + if self.config['SERVER_NAME'] is not None: + return self.url_map.bind( + self.config['SERVER_NAME'], + script_name=self.config['APPLICATION_ROOT'], + url_scheme=self.config['PREFERRED_URL_SCHEME']) + + def inject_url_defaults(self, endpoint, values): + """Injects the URL defaults for the given endpoint directly into + the values dictionary passed. This is used internally and + automatically called on URL building. + + .. versionadded:: 0.7 + """ + funcs = self.url_default_functions.get(None, ()) + if '.' in endpoint: + bp = endpoint.rsplit('.', 1)[0] + funcs = chain(funcs, self.url_default_functions.get(bp, ())) + for func in funcs: + func(endpoint, values) + + def handle_url_build_error(self, error, endpoint, values): + """Handle :class:`~werkzeug.routing.BuildError` on :meth:`url_for`. + """ + exc_type, exc_value, tb = sys.exc_info() + for handler in self.url_build_error_handlers: + try: + rv = handler(error, endpoint, values) + if rv is not None: + return rv + except BuildError as e: + # make error available outside except block (py3) + error = e + + # At this point we want to reraise the exception. If the error is + # still the same one we can reraise it with the original traceback, + # otherwise we raise it from here. + if error is exc_value: + reraise(exc_type, exc_value, tb) + raise error + + def preprocess_request(self): + """Called before the request is dispatched. Calls + :attr:`url_value_preprocessors` registered with the app and the + current blueprint (if any). Then calls :attr:`before_request_funcs` + registered with the app and the blueprint. + + If any :meth:`before_request` handler returns a non-None value, the + value is handled as if it was the return value from the view, and + further request handling is stopped. + """ + + bp = _request_ctx_stack.top.request.blueprint + + funcs = self.url_value_preprocessors.get(None, ()) + if bp is not None and bp in self.url_value_preprocessors: + funcs = chain(funcs, self.url_value_preprocessors[bp]) + for func in funcs: + func(request.endpoint, request.view_args) + + funcs = self.before_request_funcs.get(None, ()) + if bp is not None and bp in self.before_request_funcs: + funcs = chain(funcs, self.before_request_funcs[bp]) + for func in funcs: + rv = func() + if rv is not None: + return rv + + def process_response(self, response): + """Can be overridden in order to modify the response object + before it's sent to the WSGI server. By default this will + call all the :meth:`after_request` decorated functions. + + .. versionchanged:: 0.5 + As of Flask 0.5 the functions registered for after request + execution are called in reverse order of registration. + + :param response: a :attr:`response_class` object. + :return: a new response object or the same, has to be an + instance of :attr:`response_class`. + """ + ctx = _request_ctx_stack.top + bp = ctx.request.blueprint + funcs = ctx._after_request_functions + if bp is not None and bp in self.after_request_funcs: + funcs = chain(funcs, reversed(self.after_request_funcs[bp])) + if None in self.after_request_funcs: + funcs = chain(funcs, reversed(self.after_request_funcs[None])) + for handler in funcs: + response = handler(response) + if not self.session_interface.is_null_session(ctx.session): + self.session_interface.save_session(self, ctx.session, response) + return response + + def do_teardown_request(self, exc=_sentinel): + """Called after the request is dispatched and the response is + returned, right before the request context is popped. + + This calls all functions decorated with + :meth:`teardown_request`, and :meth:`Blueprint.teardown_request` + if a blueprint handled the request. Finally, the + :data:`request_tearing_down` signal is sent. + + This is called by + :meth:`RequestContext.pop() `, + which may be delayed during testing to maintain access to + resources. + + :param exc: An unhandled exception raised while dispatching the + request. Detected from the current exception information if + not passed. Passed to each teardown function. + + .. versionchanged:: 0.9 + Added the ``exc`` argument. + """ + if exc is _sentinel: + exc = sys.exc_info()[1] + funcs = reversed(self.teardown_request_funcs.get(None, ())) + bp = _request_ctx_stack.top.request.blueprint + if bp is not None and bp in self.teardown_request_funcs: + funcs = chain(funcs, reversed(self.teardown_request_funcs[bp])) + for func in funcs: + func(exc) + request_tearing_down.send(self, exc=exc) + + def do_teardown_appcontext(self, exc=_sentinel): + """Called right before the application context is popped. + + When handling a request, the application context is popped + after the request context. See :meth:`do_teardown_request`. + + This calls all functions decorated with + :meth:`teardown_appcontext`. Then the + :data:`appcontext_tearing_down` signal is sent. + + This is called by + :meth:`AppContext.pop() `. + + .. versionadded:: 0.9 + """ + if exc is _sentinel: + exc = sys.exc_info()[1] + for func in reversed(self.teardown_appcontext_funcs): + func(exc) + appcontext_tearing_down.send(self, exc=exc) + + def app_context(self): + """Create an :class:`~flask.ctx.AppContext`. Use as a ``with`` + block to push the context, which will make :data:`current_app` + point at this application. + + An application context is automatically pushed by + :meth:`RequestContext.push() ` + when handling a request, and when running a CLI command. Use + this to manually create a context outside of these situations. + + :: + + with app.app_context(): + init_db() + + See :doc:`/appcontext`. + + .. versionadded:: 0.9 + """ + return AppContext(self) + + def request_context(self, environ): + """Create a :class:`~flask.ctx.RequestContext` representing a + WSGI environment. Use a ``with`` block to push the context, + which will make :data:`request` point at this request. + + See :doc:`/reqcontext`. + + Typically you should not call this from your own code. A request + context is automatically pushed by the :meth:`wsgi_app` when + handling a request. Use :meth:`test_request_context` to create + an environment and context instead of this method. + + :param environ: a WSGI environment + """ + return RequestContext(self, environ) + + def test_request_context(self, *args, **kwargs): + """Create a :class:`~flask.ctx.RequestContext` for a WSGI + environment created from the given values. This is mostly useful + during testing, where you may want to run a function that uses + request data without dispatching a full request. + + See :doc:`/reqcontext`. + + Use a ``with`` block to push the context, which will make + :data:`request` point at the request for the created + environment. :: + + with test_request_context(...): + generate_report() + + When using the shell, it may be easier to push and pop the + context manually to avoid indentation. :: + + ctx = app.test_request_context(...) + ctx.push() + ... + ctx.pop() + + Takes the same arguments as Werkzeug's + :class:`~werkzeug.test.EnvironBuilder`, with some defaults from + the application. See the linked Werkzeug docs for most of the + available arguments. Flask-specific behavior is listed here. + + :param path: URL path being requested. + :param base_url: Base URL where the app is being served, which + ``path`` is relative to. If not given, built from + :data:`PREFERRED_URL_SCHEME`, ``subdomain``, + :data:`SERVER_NAME`, and :data:`APPLICATION_ROOT`. + :param subdomain: Subdomain name to append to + :data:`SERVER_NAME`. + :param url_scheme: Scheme to use instead of + :data:`PREFERRED_URL_SCHEME`. + :param data: The request body, either as a string or a dict of + form keys and values. + :param json: If given, this is serialized as JSON and passed as + ``data``. Also defaults ``content_type`` to + ``application/json``. + :param args: other positional arguments passed to + :class:`~werkzeug.test.EnvironBuilder`. + :param kwargs: other keyword arguments passed to + :class:`~werkzeug.test.EnvironBuilder`. + """ + from flask.testing import make_test_environ_builder + + builder = make_test_environ_builder(self, *args, **kwargs) + + try: + return self.request_context(builder.get_environ()) + finally: + builder.close() + + def wsgi_app(self, environ, start_response): + """The actual WSGI application. This is not implemented in + :meth:`__call__` so that middlewares can be applied without + losing a reference to the app object. Instead of doing this:: + + app = MyMiddleware(app) + + It's a better idea to do this instead:: + + app.wsgi_app = MyMiddleware(app.wsgi_app) + + Then you still have the original application object around and + can continue to call methods on it. + + .. versionchanged:: 0.7 + Teardown events for the request and app contexts are called + even if an unhandled error occurs. Other events may not be + called depending on when an error occurs during dispatch. + See :ref:`callbacks-and-errors`. + + :param environ: A WSGI environment. + :param start_response: A callable accepting a status code, + a list of headers, and an optional exception context to + start the response. + """ + ctx = self.request_context(environ) + error = None + try: + try: + ctx.push() + response = self.full_dispatch_request() + except Exception as e: + error = e + response = self.handle_exception(e) + except: + error = sys.exc_info()[1] + raise + return response(environ, start_response) + finally: + if self.should_ignore_error(error): + error = None + ctx.auto_pop(error) + + def __call__(self, environ, start_response): + """The WSGI server calls the Flask application object as the + WSGI application. This calls :meth:`wsgi_app` which can be + wrapped to applying middleware.""" + return self.wsgi_app(environ, start_response) + + def __repr__(self): + return '<%s %r>' % ( + self.__class__.__name__, + self.name, + ) diff --git a/pyextra/flask/blueprints.py b/pyextra/flask/blueprints.py new file mode 100644 index 00000000000000..5ce5561e4e1950 --- /dev/null +++ b/pyextra/flask/blueprints.py @@ -0,0 +1,448 @@ +# -*- coding: utf-8 -*- +""" + flask.blueprints + ~~~~~~~~~~~~~~~~ + + Blueprints are the recommended way to implement larger or more + pluggable applications in Flask 0.7 and later. + + :copyright: © 2010 by the Pallets team. + :license: BSD, see LICENSE for more details. +""" +from functools import update_wrapper +from werkzeug.urls import url_join + +from .helpers import _PackageBoundObject, _endpoint_from_view_func + + +class BlueprintSetupState(object): + """Temporary holder object for registering a blueprint with the + application. An instance of this class is created by the + :meth:`~flask.Blueprint.make_setup_state` method and later passed + to all register callback functions. + """ + + def __init__(self, blueprint, app, options, first_registration): + #: a reference to the current application + self.app = app + + #: a reference to the blueprint that created this setup state. + self.blueprint = blueprint + + #: a dictionary with all options that were passed to the + #: :meth:`~flask.Flask.register_blueprint` method. + self.options = options + + #: as blueprints can be registered multiple times with the + #: application and not everything wants to be registered + #: multiple times on it, this attribute can be used to figure + #: out if the blueprint was registered in the past already. + self.first_registration = first_registration + + subdomain = self.options.get('subdomain') + if subdomain is None: + subdomain = self.blueprint.subdomain + + #: The subdomain that the blueprint should be active for, ``None`` + #: otherwise. + self.subdomain = subdomain + + url_prefix = self.options.get('url_prefix') + if url_prefix is None: + url_prefix = self.blueprint.url_prefix + #: The prefix that should be used for all URLs defined on the + #: blueprint. + self.url_prefix = url_prefix + + #: A dictionary with URL defaults that is added to each and every + #: URL that was defined with the blueprint. + self.url_defaults = dict(self.blueprint.url_values_defaults) + self.url_defaults.update(self.options.get('url_defaults', ())) + + def add_url_rule(self, rule, endpoint=None, view_func=None, **options): + """A helper method to register a rule (and optionally a view function) + to the application. The endpoint is automatically prefixed with the + blueprint's name. + """ + if self.url_prefix is not None: + if rule: + rule = '/'.join(( + self.url_prefix.rstrip('/'), rule.lstrip('/'))) + else: + rule = self.url_prefix + options.setdefault('subdomain', self.subdomain) + if endpoint is None: + endpoint = _endpoint_from_view_func(view_func) + defaults = self.url_defaults + if 'defaults' in options: + defaults = dict(defaults, **options.pop('defaults')) + self.app.add_url_rule(rule, '%s.%s' % (self.blueprint.name, endpoint), + view_func, defaults=defaults, **options) + + +class Blueprint(_PackageBoundObject): + """Represents a blueprint. A blueprint is an object that records + functions that will be called with the + :class:`~flask.blueprints.BlueprintSetupState` later to register functions + or other things on the main application. See :ref:`blueprints` for more + information. + + .. versionadded:: 0.7 + """ + + warn_on_modifications = False + _got_registered_once = False + + #: Blueprint local JSON decoder class to use. + #: Set to ``None`` to use the app's :class:`~flask.app.Flask.json_encoder`. + json_encoder = None + #: Blueprint local JSON decoder class to use. + #: Set to ``None`` to use the app's :class:`~flask.app.Flask.json_decoder`. + json_decoder = None + + # TODO remove the next three attrs when Sphinx :inherited-members: works + # https://github.com/sphinx-doc/sphinx/issues/741 + + #: The name of the package or module that this app belongs to. Do not + #: change this once it is set by the constructor. + import_name = None + + #: Location of the template files to be added to the template lookup. + #: ``None`` if templates should not be added. + template_folder = None + + #: Absolute path to the package on the filesystem. Used to look up + #: resources contained in the package. + root_path = None + + def __init__(self, name, import_name, static_folder=None, + static_url_path=None, template_folder=None, + url_prefix=None, subdomain=None, url_defaults=None, + root_path=None): + _PackageBoundObject.__init__(self, import_name, template_folder, + root_path=root_path) + self.name = name + self.url_prefix = url_prefix + self.subdomain = subdomain + self.static_folder = static_folder + self.static_url_path = static_url_path + self.deferred_functions = [] + if url_defaults is None: + url_defaults = {} + self.url_values_defaults = url_defaults + + def record(self, func): + """Registers a function that is called when the blueprint is + registered on the application. This function is called with the + state as argument as returned by the :meth:`make_setup_state` + method. + """ + if self._got_registered_once and self.warn_on_modifications: + from warnings import warn + warn(Warning('The blueprint was already registered once ' + 'but is getting modified now. These changes ' + 'will not show up.')) + self.deferred_functions.append(func) + + def record_once(self, func): + """Works like :meth:`record` but wraps the function in another + function that will ensure the function is only called once. If the + blueprint is registered a second time on the application, the + function passed is not called. + """ + def wrapper(state): + if state.first_registration: + func(state) + return self.record(update_wrapper(wrapper, func)) + + def make_setup_state(self, app, options, first_registration=False): + """Creates an instance of :meth:`~flask.blueprints.BlueprintSetupState` + object that is later passed to the register callback functions. + Subclasses can override this to return a subclass of the setup state. + """ + return BlueprintSetupState(self, app, options, first_registration) + + def register(self, app, options, first_registration=False): + """Called by :meth:`Flask.register_blueprint` to register all views + and callbacks registered on the blueprint with the application. Creates + a :class:`.BlueprintSetupState` and calls each :meth:`record` callback + with it. + + :param app: The application this blueprint is being registered with. + :param options: Keyword arguments forwarded from + :meth:`~Flask.register_blueprint`. + :param first_registration: Whether this is the first time this + blueprint has been registered on the application. + """ + self._got_registered_once = True + state = self.make_setup_state(app, options, first_registration) + + if self.has_static_folder: + state.add_url_rule( + self.static_url_path + '/', + view_func=self.send_static_file, endpoint='static' + ) + + for deferred in self.deferred_functions: + deferred(state) + + def route(self, rule, **options): + """Like :meth:`Flask.route` but for a blueprint. The endpoint for the + :func:`url_for` function is prefixed with the name of the blueprint. + """ + def decorator(f): + endpoint = options.pop("endpoint", f.__name__) + self.add_url_rule(rule, endpoint, f, **options) + return f + return decorator + + def add_url_rule(self, rule, endpoint=None, view_func=None, **options): + """Like :meth:`Flask.add_url_rule` but for a blueprint. The endpoint for + the :func:`url_for` function is prefixed with the name of the blueprint. + """ + if endpoint: + assert '.' not in endpoint, "Blueprint endpoints should not contain dots" + if view_func and hasattr(view_func, '__name__'): + assert '.' not in view_func.__name__, "Blueprint view function name should not contain dots" + self.record(lambda s: + s.add_url_rule(rule, endpoint, view_func, **options)) + + def endpoint(self, endpoint): + """Like :meth:`Flask.endpoint` but for a blueprint. This does not + prefix the endpoint with the blueprint name, this has to be done + explicitly by the user of this method. If the endpoint is prefixed + with a `.` it will be registered to the current blueprint, otherwise + it's an application independent endpoint. + """ + def decorator(f): + def register_endpoint(state): + state.app.view_functions[endpoint] = f + self.record_once(register_endpoint) + return f + return decorator + + def app_template_filter(self, name=None): + """Register a custom template filter, available application wide. Like + :meth:`Flask.template_filter` but for a blueprint. + + :param name: the optional name of the filter, otherwise the + function name will be used. + """ + def decorator(f): + self.add_app_template_filter(f, name=name) + return f + return decorator + + def add_app_template_filter(self, f, name=None): + """Register a custom template filter, available application wide. Like + :meth:`Flask.add_template_filter` but for a blueprint. Works exactly + like the :meth:`app_template_filter` decorator. + + :param name: the optional name of the filter, otherwise the + function name will be used. + """ + def register_template(state): + state.app.jinja_env.filters[name or f.__name__] = f + self.record_once(register_template) + + def app_template_test(self, name=None): + """Register a custom template test, available application wide. Like + :meth:`Flask.template_test` but for a blueprint. + + .. versionadded:: 0.10 + + :param name: the optional name of the test, otherwise the + function name will be used. + """ + def decorator(f): + self.add_app_template_test(f, name=name) + return f + return decorator + + def add_app_template_test(self, f, name=None): + """Register a custom template test, available application wide. Like + :meth:`Flask.add_template_test` but for a blueprint. Works exactly + like the :meth:`app_template_test` decorator. + + .. versionadded:: 0.10 + + :param name: the optional name of the test, otherwise the + function name will be used. + """ + def register_template(state): + state.app.jinja_env.tests[name or f.__name__] = f + self.record_once(register_template) + + def app_template_global(self, name=None): + """Register a custom template global, available application wide. Like + :meth:`Flask.template_global` but for a blueprint. + + .. versionadded:: 0.10 + + :param name: the optional name of the global, otherwise the + function name will be used. + """ + def decorator(f): + self.add_app_template_global(f, name=name) + return f + return decorator + + def add_app_template_global(self, f, name=None): + """Register a custom template global, available application wide. Like + :meth:`Flask.add_template_global` but for a blueprint. Works exactly + like the :meth:`app_template_global` decorator. + + .. versionadded:: 0.10 + + :param name: the optional name of the global, otherwise the + function name will be used. + """ + def register_template(state): + state.app.jinja_env.globals[name or f.__name__] = f + self.record_once(register_template) + + def before_request(self, f): + """Like :meth:`Flask.before_request` but for a blueprint. This function + is only executed before each request that is handled by a function of + that blueprint. + """ + self.record_once(lambda s: s.app.before_request_funcs + .setdefault(self.name, []).append(f)) + return f + + def before_app_request(self, f): + """Like :meth:`Flask.before_request`. Such a function is executed + before each request, even if outside of a blueprint. + """ + self.record_once(lambda s: s.app.before_request_funcs + .setdefault(None, []).append(f)) + return f + + def before_app_first_request(self, f): + """Like :meth:`Flask.before_first_request`. Such a function is + executed before the first request to the application. + """ + self.record_once(lambda s: s.app.before_first_request_funcs.append(f)) + return f + + def after_request(self, f): + """Like :meth:`Flask.after_request` but for a blueprint. This function + is only executed after each request that is handled by a function of + that blueprint. + """ + self.record_once(lambda s: s.app.after_request_funcs + .setdefault(self.name, []).append(f)) + return f + + def after_app_request(self, f): + """Like :meth:`Flask.after_request` but for a blueprint. Such a function + is executed after each request, even if outside of the blueprint. + """ + self.record_once(lambda s: s.app.after_request_funcs + .setdefault(None, []).append(f)) + return f + + def teardown_request(self, f): + """Like :meth:`Flask.teardown_request` but for a blueprint. This + function is only executed when tearing down requests handled by a + function of that blueprint. Teardown request functions are executed + when the request context is popped, even when no actual request was + performed. + """ + self.record_once(lambda s: s.app.teardown_request_funcs + .setdefault(self.name, []).append(f)) + return f + + def teardown_app_request(self, f): + """Like :meth:`Flask.teardown_request` but for a blueprint. Such a + function is executed when tearing down each request, even if outside of + the blueprint. + """ + self.record_once(lambda s: s.app.teardown_request_funcs + .setdefault(None, []).append(f)) + return f + + def context_processor(self, f): + """Like :meth:`Flask.context_processor` but for a blueprint. This + function is only executed for requests handled by a blueprint. + """ + self.record_once(lambda s: s.app.template_context_processors + .setdefault(self.name, []).append(f)) + return f + + def app_context_processor(self, f): + """Like :meth:`Flask.context_processor` but for a blueprint. Such a + function is executed each request, even if outside of the blueprint. + """ + self.record_once(lambda s: s.app.template_context_processors + .setdefault(None, []).append(f)) + return f + + def app_errorhandler(self, code): + """Like :meth:`Flask.errorhandler` but for a blueprint. This + handler is used for all requests, even if outside of the blueprint. + """ + def decorator(f): + self.record_once(lambda s: s.app.errorhandler(code)(f)) + return f + return decorator + + def url_value_preprocessor(self, f): + """Registers a function as URL value preprocessor for this + blueprint. It's called before the view functions are called and + can modify the url values provided. + """ + self.record_once(lambda s: s.app.url_value_preprocessors + .setdefault(self.name, []).append(f)) + return f + + def url_defaults(self, f): + """Callback function for URL defaults for this blueprint. It's called + with the endpoint and values and should update the values passed + in place. + """ + self.record_once(lambda s: s.app.url_default_functions + .setdefault(self.name, []).append(f)) + return f + + def app_url_value_preprocessor(self, f): + """Same as :meth:`url_value_preprocessor` but application wide. + """ + self.record_once(lambda s: s.app.url_value_preprocessors + .setdefault(None, []).append(f)) + return f + + def app_url_defaults(self, f): + """Same as :meth:`url_defaults` but application wide. + """ + self.record_once(lambda s: s.app.url_default_functions + .setdefault(None, []).append(f)) + return f + + def errorhandler(self, code_or_exception): + """Registers an error handler that becomes active for this blueprint + only. Please be aware that routing does not happen local to a + blueprint so an error handler for 404 usually is not handled by + a blueprint unless it is caused inside a view function. Another + special case is the 500 internal server error which is always looked + up from the application. + + Otherwise works as the :meth:`~flask.Flask.errorhandler` decorator + of the :class:`~flask.Flask` object. + """ + def decorator(f): + self.record_once(lambda s: s.app._register_error_handler( + self.name, code_or_exception, f)) + return f + return decorator + + def register_error_handler(self, code_or_exception, f): + """Non-decorator version of the :meth:`errorhandler` error attach + function, akin to the :meth:`~flask.Flask.register_error_handler` + application-wide function of the :class:`~flask.Flask` object but + for error handlers limited to this blueprint. + + .. versionadded:: 0.11 + """ + self.record_once(lambda s: s.app._register_error_handler( + self.name, code_or_exception, f)) diff --git a/pyextra/flask/cli.py b/pyextra/flask/cli.py new file mode 100644 index 00000000000000..efc1733e29cb86 --- /dev/null +++ b/pyextra/flask/cli.py @@ -0,0 +1,898 @@ +# -*- coding: utf-8 -*- +""" + flask.cli + ~~~~~~~~~ + + A simple command line application to run flask apps. + + :copyright: © 2010 by the Pallets team. + :license: BSD, see LICENSE for more details. +""" + +from __future__ import print_function + +import ast +import inspect +import os +import re +import ssl +import sys +import traceback +from functools import update_wrapper +from operator import attrgetter +from threading import Lock, Thread + +import click +from werkzeug.utils import import_string + +from . import __version__ +from ._compat import getargspec, iteritems, reraise, text_type +from .globals import current_app +from .helpers import get_debug_flag, get_env, get_load_dotenv + +try: + import dotenv +except ImportError: + dotenv = None + + +class NoAppException(click.UsageError): + """Raised if an application cannot be found or loaded.""" + + +def find_best_app(script_info, module): + """Given a module instance this tries to find the best possible + application in the module or raises an exception. + """ + from . import Flask + + # Search for the most common names first. + for attr_name in ('app', 'application'): + app = getattr(module, attr_name, None) + + if isinstance(app, Flask): + return app + + # Otherwise find the only object that is a Flask instance. + matches = [ + v for k, v in iteritems(module.__dict__) if isinstance(v, Flask) + ] + + if len(matches) == 1: + return matches[0] + elif len(matches) > 1: + raise NoAppException( + 'Detected multiple Flask applications in module "{module}". Use ' + '"FLASK_APP={module}:name" to specify the correct ' + 'one.'.format(module=module.__name__) + ) + + # Search for app factory functions. + for attr_name in ('create_app', 'make_app'): + app_factory = getattr(module, attr_name, None) + + if inspect.isfunction(app_factory): + try: + app = call_factory(script_info, app_factory) + + if isinstance(app, Flask): + return app + except TypeError: + if not _called_with_wrong_args(app_factory): + raise + raise NoAppException( + 'Detected factory "{factory}" in module "{module}", but ' + 'could not call it without arguments. Use ' + '"FLASK_APP=\'{module}:{factory}(args)\'" to specify ' + 'arguments.'.format( + factory=attr_name, module=module.__name__ + ) + ) + + raise NoAppException( + 'Failed to find Flask application or factory in module "{module}". ' + 'Use "FLASK_APP={module}:name to specify one.'.format( + module=module.__name__ + ) + ) + + +def call_factory(script_info, app_factory, arguments=()): + """Takes an app factory, a ``script_info` object and optionally a tuple + of arguments. Checks for the existence of a script_info argument and calls + the app_factory depending on that and the arguments provided. + """ + args_spec = getargspec(app_factory) + arg_names = args_spec.args + arg_defaults = args_spec.defaults + + if 'script_info' in arg_names: + return app_factory(*arguments, script_info=script_info) + elif arguments: + return app_factory(*arguments) + elif not arguments and len(arg_names) == 1 and arg_defaults is None: + return app_factory(script_info) + + return app_factory() + + +def _called_with_wrong_args(factory): + """Check whether calling a function raised a ``TypeError`` because + the call failed or because something in the factory raised the + error. + + :param factory: the factory function that was called + :return: true if the call failed + """ + tb = sys.exc_info()[2] + + try: + while tb is not None: + if tb.tb_frame.f_code is factory.__code__: + # in the factory, it was called successfully + return False + + tb = tb.tb_next + + # didn't reach the factory + return True + finally: + del tb + + +def find_app_by_string(script_info, module, app_name): + """Checks if the given string is a variable name or a function. If it is a + function, it checks for specified arguments and whether it takes a + ``script_info`` argument and calls the function with the appropriate + arguments. + """ + from flask import Flask + match = re.match(r'^ *([^ ()]+) *(?:\((.*?) *,? *\))? *$', app_name) + + if not match: + raise NoAppException( + '"{name}" is not a valid variable name or function ' + 'expression.'.format(name=app_name) + ) + + name, args = match.groups() + + try: + attr = getattr(module, name) + except AttributeError as e: + raise NoAppException(e.args[0]) + + if inspect.isfunction(attr): + if args: + try: + args = ast.literal_eval('({args},)'.format(args=args)) + except (ValueError, SyntaxError)as e: + raise NoAppException( + 'Could not parse the arguments in ' + '"{app_name}".'.format(e=e, app_name=app_name) + ) + else: + args = () + + try: + app = call_factory(script_info, attr, args) + except TypeError as e: + if not _called_with_wrong_args(attr): + raise + + raise NoAppException( + '{e}\nThe factory "{app_name}" in module "{module}" could not ' + 'be called with the specified arguments.'.format( + e=e, app_name=app_name, module=module.__name__ + ) + ) + else: + app = attr + + if isinstance(app, Flask): + return app + + raise NoAppException( + 'A valid Flask application was not obtained from ' + '"{module}:{app_name}".'.format( + module=module.__name__, app_name=app_name + ) + ) + + +def prepare_import(path): + """Given a filename this will try to calculate the python path, add it + to the search path and return the actual module name that is expected. + """ + path = os.path.realpath(path) + + if os.path.splitext(path)[1] == '.py': + path = os.path.splitext(path)[0] + + if os.path.basename(path) == '__init__': + path = os.path.dirname(path) + + module_name = [] + + # move up until outside package structure (no __init__.py) + while True: + path, name = os.path.split(path) + module_name.append(name) + + if not os.path.exists(os.path.join(path, '__init__.py')): + break + + if sys.path[0] != path: + sys.path.insert(0, path) + + return '.'.join(module_name[::-1]) + + +def locate_app(script_info, module_name, app_name, raise_if_not_found=True): + __traceback_hide__ = True + + try: + __import__(module_name) + except ImportError: + # Reraise the ImportError if it occurred within the imported module. + # Determine this by checking whether the trace has a depth > 1. + if sys.exc_info()[-1].tb_next: + raise NoAppException( + 'While importing "{name}", an ImportError was raised:' + '\n\n{tb}'.format(name=module_name, tb=traceback.format_exc()) + ) + elif raise_if_not_found: + raise NoAppException( + 'Could not import "{name}".'.format(name=module_name) + ) + else: + return + + module = sys.modules[module_name] + + if app_name is None: + return find_best_app(script_info, module) + else: + return find_app_by_string(script_info, module, app_name) + + +def get_version(ctx, param, value): + if not value or ctx.resilient_parsing: + return + message = 'Flask %(version)s\nPython %(python_version)s' + click.echo(message % { + 'version': __version__, + 'python_version': sys.version, + }, color=ctx.color) + ctx.exit() + + +version_option = click.Option( + ['--version'], + help='Show the flask version', + expose_value=False, + callback=get_version, + is_flag=True, + is_eager=True +) + + +class DispatchingApp(object): + """Special application that dispatches to a Flask application which + is imported by name in a background thread. If an error happens + it is recorded and shown as part of the WSGI handling which in case + of the Werkzeug debugger means that it shows up in the browser. + """ + + def __init__(self, loader, use_eager_loading=False): + self.loader = loader + self._app = None + self._lock = Lock() + self._bg_loading_exc_info = None + if use_eager_loading: + self._load_unlocked() + else: + self._load_in_background() + + def _load_in_background(self): + def _load_app(): + __traceback_hide__ = True + with self._lock: + try: + self._load_unlocked() + except Exception: + self._bg_loading_exc_info = sys.exc_info() + t = Thread(target=_load_app, args=()) + t.start() + + def _flush_bg_loading_exception(self): + __traceback_hide__ = True + exc_info = self._bg_loading_exc_info + if exc_info is not None: + self._bg_loading_exc_info = None + reraise(*exc_info) + + def _load_unlocked(self): + __traceback_hide__ = True + self._app = rv = self.loader() + self._bg_loading_exc_info = None + return rv + + def __call__(self, environ, start_response): + __traceback_hide__ = True + if self._app is not None: + return self._app(environ, start_response) + self._flush_bg_loading_exception() + with self._lock: + if self._app is not None: + rv = self._app + else: + rv = self._load_unlocked() + return rv(environ, start_response) + + +class ScriptInfo(object): + """Help object to deal with Flask applications. This is usually not + necessary to interface with as it's used internally in the dispatching + to click. In future versions of Flask this object will most likely play + a bigger role. Typically it's created automatically by the + :class:`FlaskGroup` but you can also manually create it and pass it + onwards as click object. + """ + + def __init__(self, app_import_path=None, create_app=None): + #: Optionally the import path for the Flask application. + self.app_import_path = app_import_path or os.environ.get('FLASK_APP') + #: Optionally a function that is passed the script info to create + #: the instance of the application. + self.create_app = create_app + #: A dictionary with arbitrary data that can be associated with + #: this script info. + self.data = {} + self._loaded_app = None + + def load_app(self): + """Loads the Flask app (if not yet loaded) and returns it. Calling + this multiple times will just result in the already loaded app to + be returned. + """ + __traceback_hide__ = True + + if self._loaded_app is not None: + return self._loaded_app + + app = None + + if self.create_app is not None: + app = call_factory(self, self.create_app) + else: + if self.app_import_path: + path, name = (self.app_import_path.split(':', 1) + [None])[:2] + import_name = prepare_import(path) + app = locate_app(self, import_name, name) + else: + for path in ('wsgi.py', 'app.py'): + import_name = prepare_import(path) + app = locate_app(self, import_name, None, + raise_if_not_found=False) + + if app: + break + + if not app: + raise NoAppException( + 'Could not locate a Flask application. You did not provide ' + 'the "FLASK_APP" environment variable, and a "wsgi.py" or ' + '"app.py" module was not found in the current directory.' + ) + + debug = get_debug_flag() + + # Update the app's debug flag through the descriptor so that other + # values repopulate as well. + if debug is not None: + app.debug = debug + + self._loaded_app = app + return app + + +pass_script_info = click.make_pass_decorator(ScriptInfo, ensure=True) + + +def with_appcontext(f): + """Wraps a callback so that it's guaranteed to be executed with the + script's application context. If callbacks are registered directly + to the ``app.cli`` object then they are wrapped with this function + by default unless it's disabled. + """ + @click.pass_context + def decorator(__ctx, *args, **kwargs): + with __ctx.ensure_object(ScriptInfo).load_app().app_context(): + return __ctx.invoke(f, *args, **kwargs) + return update_wrapper(decorator, f) + + +class AppGroup(click.Group): + """This works similar to a regular click :class:`~click.Group` but it + changes the behavior of the :meth:`command` decorator so that it + automatically wraps the functions in :func:`with_appcontext`. + + Not to be confused with :class:`FlaskGroup`. + """ + + def command(self, *args, **kwargs): + """This works exactly like the method of the same name on a regular + :class:`click.Group` but it wraps callbacks in :func:`with_appcontext` + unless it's disabled by passing ``with_appcontext=False``. + """ + wrap_for_ctx = kwargs.pop('with_appcontext', True) + def decorator(f): + if wrap_for_ctx: + f = with_appcontext(f) + return click.Group.command(self, *args, **kwargs)(f) + return decorator + + def group(self, *args, **kwargs): + """This works exactly like the method of the same name on a regular + :class:`click.Group` but it defaults the group class to + :class:`AppGroup`. + """ + kwargs.setdefault('cls', AppGroup) + return click.Group.group(self, *args, **kwargs) + + +class FlaskGroup(AppGroup): + """Special subclass of the :class:`AppGroup` group that supports + loading more commands from the configured Flask app. Normally a + developer does not have to interface with this class but there are + some very advanced use cases for which it makes sense to create an + instance of this. + + For information as of why this is useful see :ref:`custom-scripts`. + + :param add_default_commands: if this is True then the default run and + shell commands wil be added. + :param add_version_option: adds the ``--version`` option. + :param create_app: an optional callback that is passed the script info and + returns the loaded app. + :param load_dotenv: Load the nearest :file:`.env` and :file:`.flaskenv` + files to set environment variables. Will also change the working + directory to the directory containing the first file found. + + .. versionchanged:: 1.0 + If installed, python-dotenv will be used to load environment variables + from :file:`.env` and :file:`.flaskenv` files. + """ + + def __init__(self, add_default_commands=True, create_app=None, + add_version_option=True, load_dotenv=True, **extra): + params = list(extra.pop('params', None) or ()) + + if add_version_option: + params.append(version_option) + + AppGroup.__init__(self, params=params, **extra) + self.create_app = create_app + self.load_dotenv = load_dotenv + + if add_default_commands: + self.add_command(run_command) + self.add_command(shell_command) + self.add_command(routes_command) + + self._loaded_plugin_commands = False + + def _load_plugin_commands(self): + if self._loaded_plugin_commands: + return + try: + import pkg_resources + except ImportError: + self._loaded_plugin_commands = True + return + + for ep in pkg_resources.iter_entry_points('flask.commands'): + self.add_command(ep.load(), ep.name) + self._loaded_plugin_commands = True + + def get_command(self, ctx, name): + self._load_plugin_commands() + + # We load built-in commands first as these should always be the + # same no matter what the app does. If the app does want to + # override this it needs to make a custom instance of this group + # and not attach the default commands. + # + # This also means that the script stays functional in case the + # application completely fails. + rv = AppGroup.get_command(self, ctx, name) + if rv is not None: + return rv + + info = ctx.ensure_object(ScriptInfo) + try: + rv = info.load_app().cli.get_command(ctx, name) + if rv is not None: + return rv + except NoAppException: + pass + + def list_commands(self, ctx): + self._load_plugin_commands() + + # The commands available is the list of both the application (if + # available) plus the builtin commands. + rv = set(click.Group.list_commands(self, ctx)) + info = ctx.ensure_object(ScriptInfo) + try: + rv.update(info.load_app().cli.list_commands(ctx)) + except Exception: + # Here we intentionally swallow all exceptions as we don't + # want the help page to break if the app does not exist. + # If someone attempts to use the command we try to create + # the app again and this will give us the error. + # However, we will not do so silently because that would confuse + # users. + traceback.print_exc() + return sorted(rv) + + def main(self, *args, **kwargs): + # Set a global flag that indicates that we were invoked from the + # command line interface. This is detected by Flask.run to make the + # call into a no-op. This is necessary to avoid ugly errors when the + # script that is loaded here also attempts to start a server. + os.environ['FLASK_RUN_FROM_CLI'] = 'true' + + if get_load_dotenv(self.load_dotenv): + load_dotenv() + + obj = kwargs.get('obj') + + if obj is None: + obj = ScriptInfo(create_app=self.create_app) + + kwargs['obj'] = obj + kwargs.setdefault('auto_envvar_prefix', 'FLASK') + return super(FlaskGroup, self).main(*args, **kwargs) + + +def _path_is_ancestor(path, other): + """Take ``other`` and remove the length of ``path`` from it. Then join it + to ``path``. If it is the original value, ``path`` is an ancestor of + ``other``.""" + return os.path.join(path, other[len(path):].lstrip(os.sep)) == other + + +def load_dotenv(path=None): + """Load "dotenv" files in order of precedence to set environment variables. + + If an env var is already set it is not overwritten, so earlier files in the + list are preferred over later files. + + Changes the current working directory to the location of the first file + found, with the assumption that it is in the top level project directory + and will be where the Python path should import local packages from. + + This is a no-op if `python-dotenv`_ is not installed. + + .. _python-dotenv: https://github.com/theskumar/python-dotenv#readme + + :param path: Load the file at this location instead of searching. + :return: ``True`` if a file was loaded. + + .. versionadded:: 1.0 + """ + if dotenv is None: + if path or os.path.exists('.env') or os.path.exists('.flaskenv'): + click.secho( + ' * Tip: There are .env files present.' + ' Do "pip install python-dotenv" to use them.', + fg='yellow') + return + + if path is not None: + return dotenv.load_dotenv(path) + + new_dir = None + + for name in ('.env', '.flaskenv'): + path = dotenv.find_dotenv(name, usecwd=True) + + if not path: + continue + + if new_dir is None: + new_dir = os.path.dirname(path) + + dotenv.load_dotenv(path) + + if new_dir and os.getcwd() != new_dir: + os.chdir(new_dir) + + return new_dir is not None # at least one file was located and loaded + + +def show_server_banner(env, debug, app_import_path, eager_loading): + """Show extra startup messages the first time the server is run, + ignoring the reloader. + """ + if os.environ.get('WERKZEUG_RUN_MAIN') == 'true': + return + + if app_import_path is not None: + message = ' * Serving Flask app "{0}"'.format(app_import_path) + + if not eager_loading: + message += ' (lazy loading)' + + click.echo(message) + + click.echo(' * Environment: {0}'.format(env)) + + if env == 'production': + click.secho( + ' WARNING: Do not use the development server in a production' + ' environment.', fg='red') + click.secho(' Use a production WSGI server instead.', dim=True) + + if debug is not None: + click.echo(' * Debug mode: {0}'.format('on' if debug else 'off')) + + +class CertParamType(click.ParamType): + """Click option type for the ``--cert`` option. Allows either an + existing file, the string ``'adhoc'``, or an import for a + :class:`~ssl.SSLContext` object. + """ + + name = 'path' + + def __init__(self): + self.path_type = click.Path( + exists=True, dir_okay=False, resolve_path=True) + + def convert(self, value, param, ctx): + try: + return self.path_type(value, param, ctx) + except click.BadParameter: + value = click.STRING(value, param, ctx).lower() + + if value == 'adhoc': + try: + import OpenSSL + except ImportError: + raise click.BadParameter( + 'Using ad-hoc certificates requires pyOpenSSL.', + ctx, param) + + return value + + obj = import_string(value, silent=True) + + if sys.version_info < (2, 7): + if obj: + return obj + else: + if isinstance(obj, ssl.SSLContext): + return obj + + raise + + +def _validate_key(ctx, param, value): + """The ``--key`` option must be specified when ``--cert`` is a file. + Modifies the ``cert`` param to be a ``(cert, key)`` pair if needed. + """ + cert = ctx.params.get('cert') + is_adhoc = cert == 'adhoc' + + if sys.version_info < (2, 7): + is_context = cert and not isinstance(cert, (text_type, bytes)) + else: + is_context = isinstance(cert, ssl.SSLContext) + + if value is not None: + if is_adhoc: + raise click.BadParameter( + 'When "--cert" is "adhoc", "--key" is not used.', + ctx, param) + + if is_context: + raise click.BadParameter( + 'When "--cert" is an SSLContext object, "--key is not used.', + ctx, param) + + if not cert: + raise click.BadParameter( + '"--cert" must also be specified.', + ctx, param) + + ctx.params['cert'] = cert, value + + else: + if cert and not (is_adhoc or is_context): + raise click.BadParameter( + 'Required when using "--cert".', + ctx, param) + + return value + + +@click.command('run', short_help='Runs a development server.') +@click.option('--host', '-h', default='127.0.0.1', + help='The interface to bind to.') +@click.option('--port', '-p', default=5000, + help='The port to bind to.') +@click.option('--cert', type=CertParamType(), + help='Specify a certificate file to use HTTPS.') +@click.option('--key', + type=click.Path(exists=True, dir_okay=False, resolve_path=True), + callback=_validate_key, expose_value=False, + help='The key file to use when specifying a certificate.') +@click.option('--reload/--no-reload', default=None, + help='Enable or disable the reloader. By default the reloader ' + 'is active if debug is enabled.') +@click.option('--debugger/--no-debugger', default=None, + help='Enable or disable the debugger. By default the debugger ' + 'is active if debug is enabled.') +@click.option('--eager-loading/--lazy-loader', default=None, + help='Enable or disable eager loading. By default eager ' + 'loading is enabled if the reloader is disabled.') +@click.option('--with-threads/--without-threads', default=True, + help='Enable or disable multithreading.') +@pass_script_info +def run_command(info, host, port, reload, debugger, eager_loading, + with_threads, cert): + """Run a local development server. + + This server is for development purposes only. It does not provide + the stability, security, or performance of production WSGI servers. + + The reloader and debugger are enabled by default if + FLASK_ENV=development or FLASK_DEBUG=1. + """ + debug = get_debug_flag() + + if reload is None: + reload = debug + + if debugger is None: + debugger = debug + + if eager_loading is None: + eager_loading = not reload + + show_server_banner(get_env(), debug, info.app_import_path, eager_loading) + app = DispatchingApp(info.load_app, use_eager_loading=eager_loading) + + from werkzeug.serving import run_simple + run_simple(host, port, app, use_reloader=reload, use_debugger=debugger, + threaded=with_threads, ssl_context=cert) + + +@click.command('shell', short_help='Runs a shell in the app context.') +@with_appcontext +def shell_command(): + """Runs an interactive Python shell in the context of a given + Flask application. The application will populate the default + namespace of this shell according to it's configuration. + + This is useful for executing small snippets of management code + without having to manually configure the application. + """ + import code + from flask.globals import _app_ctx_stack + app = _app_ctx_stack.top.app + banner = 'Python %s on %s\nApp: %s [%s]\nInstance: %s' % ( + sys.version, + sys.platform, + app.import_name, + app.env, + app.instance_path, + ) + ctx = {} + + # Support the regular Python interpreter startup script if someone + # is using it. + startup = os.environ.get('PYTHONSTARTUP') + if startup and os.path.isfile(startup): + with open(startup, 'r') as f: + eval(compile(f.read(), startup, 'exec'), ctx) + + ctx.update(app.make_shell_context()) + + code.interact(banner=banner, local=ctx) + + +@click.command('routes', short_help='Show the routes for the app.') +@click.option( + '--sort', '-s', + type=click.Choice(('endpoint', 'methods', 'rule', 'match')), + default='endpoint', + help=( + 'Method to sort routes by. "match" is the order that Flask will match ' + 'routes when dispatching a request.' + ) +) +@click.option( + '--all-methods', + is_flag=True, + help="Show HEAD and OPTIONS methods." +) +@with_appcontext +def routes_command(sort, all_methods): + """Show all registered routes with endpoints and methods.""" + + rules = list(current_app.url_map.iter_rules()) + if not rules: + click.echo('No routes were registered.') + return + + ignored_methods = set(() if all_methods else ('HEAD', 'OPTIONS')) + + if sort in ('endpoint', 'rule'): + rules = sorted(rules, key=attrgetter(sort)) + elif sort == 'methods': + rules = sorted(rules, key=lambda rule: sorted(rule.methods)) + + rule_methods = [ + ', '.join(sorted(rule.methods - ignored_methods)) for rule in rules + ] + + headers = ('Endpoint', 'Methods', 'Rule') + widths = ( + max(len(rule.endpoint) for rule in rules), + max(len(methods) for methods in rule_methods), + max(len(rule.rule) for rule in rules), + ) + widths = [max(len(h), w) for h, w in zip(headers, widths)] + row = '{{0:<{0}}} {{1:<{1}}} {{2:<{2}}}'.format(*widths) + + click.echo(row.format(*headers).strip()) + click.echo(row.format(*('-' * width for width in widths))) + + for rule, methods in zip(rules, rule_methods): + click.echo(row.format(rule.endpoint, methods, rule.rule).rstrip()) + + +cli = FlaskGroup(help="""\ +A general utility script for Flask applications. + +Provides commands from Flask, extensions, and the application. Loads the +application defined in the FLASK_APP environment variable, or from a wsgi.py +file. Setting the FLASK_ENV environment variable to 'development' will enable +debug mode. + +\b + {prefix}{cmd} FLASK_APP=hello.py + {prefix}{cmd} FLASK_ENV=development + {prefix}flask run +""".format( + cmd='export' if os.name == 'posix' else 'set', + prefix='$ ' if os.name == 'posix' else '> ' +)) + + +def main(as_module=False): + args = sys.argv[1:] + + if as_module: + this_module = 'flask' + + if sys.version_info < (2, 7): + this_module += '.cli' + + name = 'python -m ' + this_module + + # Python rewrites "python -m flask" to the path to the file in argv. + # Restore the original command so that the reloader works. + sys.argv = ['-m', this_module] + args + else: + name = None + + cli.main(args=args, prog_name=name) + + +if __name__ == '__main__': + main(as_module=True) diff --git a/pyextra/flask/config.py b/pyextra/flask/config.py new file mode 100644 index 00000000000000..d6074baa8565e4 --- /dev/null +++ b/pyextra/flask/config.py @@ -0,0 +1,265 @@ +# -*- coding: utf-8 -*- +""" + flask.config + ~~~~~~~~~~~~ + + Implements the configuration related objects. + + :copyright: © 2010 by the Pallets team. + :license: BSD, see LICENSE for more details. +""" + +import os +import types +import errno + +from werkzeug.utils import import_string +from ._compat import string_types, iteritems +from . import json + + +class ConfigAttribute(object): + """Makes an attribute forward to the config""" + + def __init__(self, name, get_converter=None): + self.__name__ = name + self.get_converter = get_converter + + def __get__(self, obj, type=None): + if obj is None: + return self + rv = obj.config[self.__name__] + if self.get_converter is not None: + rv = self.get_converter(rv) + return rv + + def __set__(self, obj, value): + obj.config[self.__name__] = value + + +class Config(dict): + """Works exactly like a dict but provides ways to fill it from files + or special dictionaries. There are two common patterns to populate the + config. + + Either you can fill the config from a config file:: + + app.config.from_pyfile('yourconfig.cfg') + + Or alternatively you can define the configuration options in the + module that calls :meth:`from_object` or provide an import path to + a module that should be loaded. It is also possible to tell it to + use the same module and with that provide the configuration values + just before the call:: + + DEBUG = True + SECRET_KEY = 'development key' + app.config.from_object(__name__) + + In both cases (loading from any Python file or loading from modules), + only uppercase keys are added to the config. This makes it possible to use + lowercase values in the config file for temporary values that are not added + to the config or to define the config keys in the same file that implements + the application. + + Probably the most interesting way to load configurations is from an + environment variable pointing to a file:: + + app.config.from_envvar('YOURAPPLICATION_SETTINGS') + + In this case before launching the application you have to set this + environment variable to the file you want to use. On Linux and OS X + use the export statement:: + + export YOURAPPLICATION_SETTINGS='/path/to/config/file' + + On windows use `set` instead. + + :param root_path: path to which files are read relative from. When the + config object is created by the application, this is + the application's :attr:`~flask.Flask.root_path`. + :param defaults: an optional dictionary of default values + """ + + def __init__(self, root_path, defaults=None): + dict.__init__(self, defaults or {}) + self.root_path = root_path + + def from_envvar(self, variable_name, silent=False): + """Loads a configuration from an environment variable pointing to + a configuration file. This is basically just a shortcut with nicer + error messages for this line of code:: + + app.config.from_pyfile(os.environ['YOURAPPLICATION_SETTINGS']) + + :param variable_name: name of the environment variable + :param silent: set to ``True`` if you want silent failure for missing + files. + :return: bool. ``True`` if able to load config, ``False`` otherwise. + """ + rv = os.environ.get(variable_name) + if not rv: + if silent: + return False + raise RuntimeError('The environment variable %r is not set ' + 'and as such configuration could not be ' + 'loaded. Set this variable and make it ' + 'point to a configuration file' % + variable_name) + return self.from_pyfile(rv, silent=silent) + + def from_pyfile(self, filename, silent=False): + """Updates the values in the config from a Python file. This function + behaves as if the file was imported as module with the + :meth:`from_object` function. + + :param filename: the filename of the config. This can either be an + absolute filename or a filename relative to the + root path. + :param silent: set to ``True`` if you want silent failure for missing + files. + + .. versionadded:: 0.7 + `silent` parameter. + """ + filename = os.path.join(self.root_path, filename) + d = types.ModuleType('config') + d.__file__ = filename + try: + with open(filename, mode='rb') as config_file: + exec(compile(config_file.read(), filename, 'exec'), d.__dict__) + except IOError as e: + if silent and e.errno in ( + errno.ENOENT, errno.EISDIR, errno.ENOTDIR + ): + return False + e.strerror = 'Unable to load configuration file (%s)' % e.strerror + raise + self.from_object(d) + return True + + def from_object(self, obj): + """Updates the values from the given object. An object can be of one + of the following two types: + + - a string: in this case the object with that name will be imported + - an actual object reference: that object is used directly + + Objects are usually either modules or classes. :meth:`from_object` + loads only the uppercase attributes of the module/class. A ``dict`` + object will not work with :meth:`from_object` because the keys of a + ``dict`` are not attributes of the ``dict`` class. + + Example of module-based configuration:: + + app.config.from_object('yourapplication.default_config') + from yourapplication import default_config + app.config.from_object(default_config) + + You should not use this function to load the actual configuration but + rather configuration defaults. The actual config should be loaded + with :meth:`from_pyfile` and ideally from a location not within the + package because the package might be installed system wide. + + See :ref:`config-dev-prod` for an example of class-based configuration + using :meth:`from_object`. + + :param obj: an import name or object + """ + if isinstance(obj, string_types): + obj = import_string(obj) + for key in dir(obj): + if key.isupper(): + self[key] = getattr(obj, key) + + def from_json(self, filename, silent=False): + """Updates the values in the config from a JSON file. This function + behaves as if the JSON object was a dictionary and passed to the + :meth:`from_mapping` function. + + :param filename: the filename of the JSON file. This can either be an + absolute filename or a filename relative to the + root path. + :param silent: set to ``True`` if you want silent failure for missing + files. + + .. versionadded:: 0.11 + """ + filename = os.path.join(self.root_path, filename) + + try: + with open(filename) as json_file: + obj = json.loads(json_file.read()) + except IOError as e: + if silent and e.errno in (errno.ENOENT, errno.EISDIR): + return False + e.strerror = 'Unable to load configuration file (%s)' % e.strerror + raise + return self.from_mapping(obj) + + def from_mapping(self, *mapping, **kwargs): + """Updates the config like :meth:`update` ignoring items with non-upper + keys. + + .. versionadded:: 0.11 + """ + mappings = [] + if len(mapping) == 1: + if hasattr(mapping[0], 'items'): + mappings.append(mapping[0].items()) + else: + mappings.append(mapping[0]) + elif len(mapping) > 1: + raise TypeError( + 'expected at most 1 positional argument, got %d' % len(mapping) + ) + mappings.append(kwargs.items()) + for mapping in mappings: + for (key, value) in mapping: + if key.isupper(): + self[key] = value + return True + + def get_namespace(self, namespace, lowercase=True, trim_namespace=True): + """Returns a dictionary containing a subset of configuration options + that match the specified namespace/prefix. Example usage:: + + app.config['IMAGE_STORE_TYPE'] = 'fs' + app.config['IMAGE_STORE_PATH'] = '/var/app/images' + app.config['IMAGE_STORE_BASE_URL'] = 'http://img.website.com' + image_store_config = app.config.get_namespace('IMAGE_STORE_') + + The resulting dictionary `image_store_config` would look like:: + + { + 'type': 'fs', + 'path': '/var/app/images', + 'base_url': 'http://img.website.com' + } + + This is often useful when configuration options map directly to + keyword arguments in functions or class constructors. + + :param namespace: a configuration namespace + :param lowercase: a flag indicating if the keys of the resulting + dictionary should be lowercase + :param trim_namespace: a flag indicating if the keys of the resulting + dictionary should not include the namespace + + .. versionadded:: 0.11 + """ + rv = {} + for k, v in iteritems(self): + if not k.startswith(namespace): + continue + if trim_namespace: + key = k[len(namespace):] + else: + key = k + if lowercase: + key = key.lower() + rv[key] = v + return rv + + def __repr__(self): + return '<%s %s>' % (self.__class__.__name__, dict.__repr__(self)) diff --git a/pyextra/flask/ctx.py b/pyextra/flask/ctx.py new file mode 100644 index 00000000000000..8472c920c2d6ef --- /dev/null +++ b/pyextra/flask/ctx.py @@ -0,0 +1,457 @@ +# -*- coding: utf-8 -*- +""" + flask.ctx + ~~~~~~~~~ + + Implements the objects required to keep the context. + + :copyright: © 2010 by the Pallets team. + :license: BSD, see LICENSE for more details. +""" + +import sys +from functools import update_wrapper + +from werkzeug.exceptions import HTTPException + +from .globals import _request_ctx_stack, _app_ctx_stack +from .signals import appcontext_pushed, appcontext_popped +from ._compat import BROKEN_PYPY_CTXMGR_EXIT, reraise + + +# a singleton sentinel value for parameter defaults +_sentinel = object() + + +class _AppCtxGlobals(object): + """A plain object. Used as a namespace for storing data during an + application context. + + Creating an app context automatically creates this object, which is + made available as the :data:`g` proxy. + + .. describe:: 'key' in g + + Check whether an attribute is present. + + .. versionadded:: 0.10 + + .. describe:: iter(g) + + Return an iterator over the attribute names. + + .. versionadded:: 0.10 + """ + + def get(self, name, default=None): + """Get an attribute by name, or a default value. Like + :meth:`dict.get`. + + :param name: Name of attribute to get. + :param default: Value to return if the attribute is not present. + + .. versionadded:: 0.10 + """ + return self.__dict__.get(name, default) + + def pop(self, name, default=_sentinel): + """Get and remove an attribute by name. Like :meth:`dict.pop`. + + :param name: Name of attribute to pop. + :param default: Value to return if the attribute is not present, + instead of raise a ``KeyError``. + + .. versionadded:: 0.11 + """ + if default is _sentinel: + return self.__dict__.pop(name) + else: + return self.__dict__.pop(name, default) + + def setdefault(self, name, default=None): + """Get the value of an attribute if it is present, otherwise + set and return a default value. Like :meth:`dict.setdefault`. + + :param name: Name of attribute to get. + :param: default: Value to set and return if the attribute is not + present. + + .. versionadded:: 0.11 + """ + return self.__dict__.setdefault(name, default) + + def __contains__(self, item): + return item in self.__dict__ + + def __iter__(self): + return iter(self.__dict__) + + def __repr__(self): + top = _app_ctx_stack.top + if top is not None: + return '' % top.app.name + return object.__repr__(self) + + +def after_this_request(f): + """Executes a function after this request. This is useful to modify + response objects. The function is passed the response object and has + to return the same or a new one. + + Example:: + + @app.route('/') + def index(): + @after_this_request + def add_header(response): + response.headers['X-Foo'] = 'Parachute' + return response + return 'Hello World!' + + This is more useful if a function other than the view function wants to + modify a response. For instance think of a decorator that wants to add + some headers without converting the return value into a response object. + + .. versionadded:: 0.9 + """ + _request_ctx_stack.top._after_request_functions.append(f) + return f + + +def copy_current_request_context(f): + """A helper function that decorates a function to retain the current + request context. This is useful when working with greenlets. The moment + the function is decorated a copy of the request context is created and + then pushed when the function is called. + + Example:: + + import gevent + from flask import copy_current_request_context + + @app.route('/') + def index(): + @copy_current_request_context + def do_some_work(): + # do some work here, it can access flask.request like you + # would otherwise in the view function. + ... + gevent.spawn(do_some_work) + return 'Regular response' + + .. versionadded:: 0.10 + """ + top = _request_ctx_stack.top + if top is None: + raise RuntimeError('This decorator can only be used at local scopes ' + 'when a request context is on the stack. For instance within ' + 'view functions.') + reqctx = top.copy() + def wrapper(*args, **kwargs): + with reqctx: + return f(*args, **kwargs) + return update_wrapper(wrapper, f) + + +def has_request_context(): + """If you have code that wants to test if a request context is there or + not this function can be used. For instance, you may want to take advantage + of request information if the request object is available, but fail + silently if it is unavailable. + + :: + + class User(db.Model): + + def __init__(self, username, remote_addr=None): + self.username = username + if remote_addr is None and has_request_context(): + remote_addr = request.remote_addr + self.remote_addr = remote_addr + + Alternatively you can also just test any of the context bound objects + (such as :class:`request` or :class:`g` for truthness):: + + class User(db.Model): + + def __init__(self, username, remote_addr=None): + self.username = username + if remote_addr is None and request: + remote_addr = request.remote_addr + self.remote_addr = remote_addr + + .. versionadded:: 0.7 + """ + return _request_ctx_stack.top is not None + + +def has_app_context(): + """Works like :func:`has_request_context` but for the application + context. You can also just do a boolean check on the + :data:`current_app` object instead. + + .. versionadded:: 0.9 + """ + return _app_ctx_stack.top is not None + + +class AppContext(object): + """The application context binds an application object implicitly + to the current thread or greenlet, similar to how the + :class:`RequestContext` binds request information. The application + context is also implicitly created if a request context is created + but the application is not on top of the individual application + context. + """ + + def __init__(self, app): + self.app = app + self.url_adapter = app.create_url_adapter(None) + self.g = app.app_ctx_globals_class() + + # Like request context, app contexts can be pushed multiple times + # but there a basic "refcount" is enough to track them. + self._refcnt = 0 + + def push(self): + """Binds the app context to the current context.""" + self._refcnt += 1 + if hasattr(sys, 'exc_clear'): + sys.exc_clear() + _app_ctx_stack.push(self) + appcontext_pushed.send(self.app) + + def pop(self, exc=_sentinel): + """Pops the app context.""" + try: + self._refcnt -= 1 + if self._refcnt <= 0: + if exc is _sentinel: + exc = sys.exc_info()[1] + self.app.do_teardown_appcontext(exc) + finally: + rv = _app_ctx_stack.pop() + assert rv is self, 'Popped wrong app context. (%r instead of %r)' \ + % (rv, self) + appcontext_popped.send(self.app) + + def __enter__(self): + self.push() + return self + + def __exit__(self, exc_type, exc_value, tb): + self.pop(exc_value) + + if BROKEN_PYPY_CTXMGR_EXIT and exc_type is not None: + reraise(exc_type, exc_value, tb) + + +class RequestContext(object): + """The request context contains all request relevant information. It is + created at the beginning of the request and pushed to the + `_request_ctx_stack` and removed at the end of it. It will create the + URL adapter and request object for the WSGI environment provided. + + Do not attempt to use this class directly, instead use + :meth:`~flask.Flask.test_request_context` and + :meth:`~flask.Flask.request_context` to create this object. + + When the request context is popped, it will evaluate all the + functions registered on the application for teardown execution + (:meth:`~flask.Flask.teardown_request`). + + The request context is automatically popped at the end of the request + for you. In debug mode the request context is kept around if + exceptions happen so that interactive debuggers have a chance to + introspect the data. With 0.4 this can also be forced for requests + that did not fail and outside of ``DEBUG`` mode. By setting + ``'flask._preserve_context'`` to ``True`` on the WSGI environment the + context will not pop itself at the end of the request. This is used by + the :meth:`~flask.Flask.test_client` for example to implement the + deferred cleanup functionality. + + You might find this helpful for unittests where you need the + information from the context local around for a little longer. Make + sure to properly :meth:`~werkzeug.LocalStack.pop` the stack yourself in + that situation, otherwise your unittests will leak memory. + """ + + def __init__(self, app, environ, request=None): + self.app = app + if request is None: + request = app.request_class(environ) + self.request = request + self.url_adapter = app.create_url_adapter(self.request) + self.flashes = None + self.session = None + + # Request contexts can be pushed multiple times and interleaved with + # other request contexts. Now only if the last level is popped we + # get rid of them. Additionally if an application context is missing + # one is created implicitly so for each level we add this information + self._implicit_app_ctx_stack = [] + + # indicator if the context was preserved. Next time another context + # is pushed the preserved context is popped. + self.preserved = False + + # remembers the exception for pop if there is one in case the context + # preservation kicks in. + self._preserved_exc = None + + # Functions that should be executed after the request on the response + # object. These will be called before the regular "after_request" + # functions. + self._after_request_functions = [] + + self.match_request() + + def _get_g(self): + return _app_ctx_stack.top.g + def _set_g(self, value): + _app_ctx_stack.top.g = value + g = property(_get_g, _set_g) + del _get_g, _set_g + + def copy(self): + """Creates a copy of this request context with the same request object. + This can be used to move a request context to a different greenlet. + Because the actual request object is the same this cannot be used to + move a request context to a different thread unless access to the + request object is locked. + + .. versionadded:: 0.10 + """ + return self.__class__(self.app, + environ=self.request.environ, + request=self.request + ) + + def match_request(self): + """Can be overridden by a subclass to hook into the matching + of the request. + """ + try: + url_rule, self.request.view_args = \ + self.url_adapter.match(return_rule=True) + self.request.url_rule = url_rule + except HTTPException as e: + self.request.routing_exception = e + + def push(self): + """Binds the request context to the current context.""" + # If an exception occurs in debug mode or if context preservation is + # activated under exception situations exactly one context stays + # on the stack. The rationale is that you want to access that + # information under debug situations. However if someone forgets to + # pop that context again we want to make sure that on the next push + # it's invalidated, otherwise we run at risk that something leaks + # memory. This is usually only a problem in test suite since this + # functionality is not active in production environments. + top = _request_ctx_stack.top + if top is not None and top.preserved: + top.pop(top._preserved_exc) + + # Before we push the request context we have to ensure that there + # is an application context. + app_ctx = _app_ctx_stack.top + if app_ctx is None or app_ctx.app != self.app: + app_ctx = self.app.app_context() + app_ctx.push() + self._implicit_app_ctx_stack.append(app_ctx) + else: + self._implicit_app_ctx_stack.append(None) + + if hasattr(sys, 'exc_clear'): + sys.exc_clear() + + _request_ctx_stack.push(self) + + # Open the session at the moment that the request context is available. + # This allows a custom open_session method to use the request context. + # Only open a new session if this is the first time the request was + # pushed, otherwise stream_with_context loses the session. + if self.session is None: + session_interface = self.app.session_interface + self.session = session_interface.open_session( + self.app, self.request + ) + + if self.session is None: + self.session = session_interface.make_null_session(self.app) + + def pop(self, exc=_sentinel): + """Pops the request context and unbinds it by doing that. This will + also trigger the execution of functions registered by the + :meth:`~flask.Flask.teardown_request` decorator. + + .. versionchanged:: 0.9 + Added the `exc` argument. + """ + app_ctx = self._implicit_app_ctx_stack.pop() + + try: + clear_request = False + if not self._implicit_app_ctx_stack: + self.preserved = False + self._preserved_exc = None + if exc is _sentinel: + exc = sys.exc_info()[1] + self.app.do_teardown_request(exc) + + # If this interpreter supports clearing the exception information + # we do that now. This will only go into effect on Python 2.x, + # on 3.x it disappears automatically at the end of the exception + # stack. + if hasattr(sys, 'exc_clear'): + sys.exc_clear() + + request_close = getattr(self.request, 'close', None) + if request_close is not None: + request_close() + clear_request = True + finally: + rv = _request_ctx_stack.pop() + + # get rid of circular dependencies at the end of the request + # so that we don't require the GC to be active. + if clear_request: + rv.request.environ['werkzeug.request'] = None + + # Get rid of the app as well if necessary. + if app_ctx is not None: + app_ctx.pop(exc) + + assert rv is self, 'Popped wrong request context. ' \ + '(%r instead of %r)' % (rv, self) + + def auto_pop(self, exc): + if self.request.environ.get('flask._preserve_context') or \ + (exc is not None and self.app.preserve_context_on_exception): + self.preserved = True + self._preserved_exc = exc + else: + self.pop(exc) + + def __enter__(self): + self.push() + return self + + def __exit__(self, exc_type, exc_value, tb): + # do not pop the request stack if we are in debug mode and an + # exception happened. This will allow the debugger to still + # access the request object in the interactive shell. Furthermore + # the context can be force kept alive for the test client. + # See flask.testing for how this works. + self.auto_pop(exc_value) + + if BROKEN_PYPY_CTXMGR_EXIT and exc_type is not None: + reraise(exc_type, exc_value, tb) + + def __repr__(self): + return '<%s \'%s\' [%s] of %s>' % ( + self.__class__.__name__, + self.request.url, + self.request.method, + self.app.name, + ) diff --git a/pyextra/flask/debughelpers.py b/pyextra/flask/debughelpers.py new file mode 100644 index 00000000000000..e9765f20d0a2e4 --- /dev/null +++ b/pyextra/flask/debughelpers.py @@ -0,0 +1,168 @@ +# -*- coding: utf-8 -*- +""" + flask.debughelpers + ~~~~~~~~~~~~~~~~~~ + + Various helpers to make the development experience better. + + :copyright: © 2010 by the Pallets team. + :license: BSD, see LICENSE for more details. +""" + +import os +from warnings import warn + +from ._compat import implements_to_string, text_type +from .app import Flask +from .blueprints import Blueprint +from .globals import _request_ctx_stack + + +class UnexpectedUnicodeError(AssertionError, UnicodeError): + """Raised in places where we want some better error reporting for + unexpected unicode or binary data. + """ + + +@implements_to_string +class DebugFilesKeyError(KeyError, AssertionError): + """Raised from request.files during debugging. The idea is that it can + provide a better error message than just a generic KeyError/BadRequest. + """ + + def __init__(self, request, key): + form_matches = request.form.getlist(key) + buf = ['You tried to access the file "%s" in the request.files ' + 'dictionary but it does not exist. The mimetype for the request ' + 'is "%s" instead of "multipart/form-data" which means that no ' + 'file contents were transmitted. To fix this error you should ' + 'provide enctype="multipart/form-data" in your form.' % + (key, request.mimetype)] + if form_matches: + buf.append('\n\nThe browser instead transmitted some file names. ' + 'This was submitted: %s' % ', '.join('"%s"' % x + for x in form_matches)) + self.msg = ''.join(buf) + + def __str__(self): + return self.msg + + +class FormDataRoutingRedirect(AssertionError): + """This exception is raised by Flask in debug mode if it detects a + redirect caused by the routing system when the request method is not + GET, HEAD or OPTIONS. Reasoning: form data will be dropped. + """ + + def __init__(self, request): + exc = request.routing_exception + buf = ['A request was sent to this URL (%s) but a redirect was ' + 'issued automatically by the routing system to "%s".' + % (request.url, exc.new_url)] + + # In case just a slash was appended we can be extra helpful + if request.base_url + '/' == exc.new_url.split('?')[0]: + buf.append(' The URL was defined with a trailing slash so ' + 'Flask will automatically redirect to the URL ' + 'with the trailing slash if it was accessed ' + 'without one.') + + buf.append(' Make sure to directly send your %s-request to this URL ' + 'since we can\'t make browsers or HTTP clients redirect ' + 'with form data reliably or without user interaction.' % + request.method) + buf.append('\n\nNote: this exception is only raised in debug mode') + AssertionError.__init__(self, ''.join(buf).encode('utf-8')) + + +def attach_enctype_error_multidict(request): + """Since Flask 0.8 we're monkeypatching the files object in case a + request is detected that does not use multipart form data but the files + object is accessed. + """ + oldcls = request.files.__class__ + class newcls(oldcls): + def __getitem__(self, key): + try: + return oldcls.__getitem__(self, key) + except KeyError: + if key not in request.form: + raise + raise DebugFilesKeyError(request, key) + newcls.__name__ = oldcls.__name__ + newcls.__module__ = oldcls.__module__ + request.files.__class__ = newcls + + +def _dump_loader_info(loader): + yield 'class: %s.%s' % (type(loader).__module__, type(loader).__name__) + for key, value in sorted(loader.__dict__.items()): + if key.startswith('_'): + continue + if isinstance(value, (tuple, list)): + if not all(isinstance(x, (str, text_type)) for x in value): + continue + yield '%s:' % key + for item in value: + yield ' - %s' % item + continue + elif not isinstance(value, (str, text_type, int, float, bool)): + continue + yield '%s: %r' % (key, value) + + +def explain_template_loading_attempts(app, template, attempts): + """This should help developers understand what failed""" + info = ['Locating template "%s":' % template] + total_found = 0 + blueprint = None + reqctx = _request_ctx_stack.top + if reqctx is not None and reqctx.request.blueprint is not None: + blueprint = reqctx.request.blueprint + + for idx, (loader, srcobj, triple) in enumerate(attempts): + if isinstance(srcobj, Flask): + src_info = 'application "%s"' % srcobj.import_name + elif isinstance(srcobj, Blueprint): + src_info = 'blueprint "%s" (%s)' % (srcobj.name, + srcobj.import_name) + else: + src_info = repr(srcobj) + + info.append('% 5d: trying loader of %s' % ( + idx + 1, src_info)) + + for line in _dump_loader_info(loader): + info.append(' %s' % line) + + if triple is None: + detail = 'no match' + else: + detail = 'found (%r)' % (triple[1] or '') + total_found += 1 + info.append(' -> %s' % detail) + + seems_fishy = False + if total_found == 0: + info.append('Error: the template could not be found.') + seems_fishy = True + elif total_found > 1: + info.append('Warning: multiple loaders returned a match for the template.') + seems_fishy = True + + if blueprint is not None and seems_fishy: + info.append(' The template was looked up from an endpoint that ' + 'belongs to the blueprint "%s".' % blueprint) + info.append(' Maybe you did not place a template in the right folder?') + info.append(' See http://flask.pocoo.org/docs/blueprints/#templates') + + app.logger.info('\n'.join(info)) + + +def explain_ignored_app_run(): + if os.environ.get('WERKZEUG_RUN_MAIN') != 'true': + warn(Warning('Silently ignoring app.run() because the ' + 'application is run from the flask command line ' + 'executable. Consider putting app.run() behind an ' + 'if __name__ == "__main__" guard to silence this ' + 'warning.'), stacklevel=3) diff --git a/pyextra/flask/globals.py b/pyextra/flask/globals.py new file mode 100644 index 00000000000000..7d50a6f6d4052f --- /dev/null +++ b/pyextra/flask/globals.py @@ -0,0 +1,61 @@ +# -*- coding: utf-8 -*- +""" + flask.globals + ~~~~~~~~~~~~~ + + Defines all the global objects that are proxies to the current + active context. + + :copyright: © 2010 by the Pallets team. + :license: BSD, see LICENSE for more details. +""" + +from functools import partial +from werkzeug.local import LocalStack, LocalProxy + + +_request_ctx_err_msg = '''\ +Working outside of request context. + +This typically means that you attempted to use functionality that needed +an active HTTP request. Consult the documentation on testing for +information about how to avoid this problem.\ +''' +_app_ctx_err_msg = '''\ +Working outside of application context. + +This typically means that you attempted to use functionality that needed +to interface with the current application object in some way. To solve +this, set up an application context with app.app_context(). See the +documentation for more information.\ +''' + + +def _lookup_req_object(name): + top = _request_ctx_stack.top + if top is None: + raise RuntimeError(_request_ctx_err_msg) + return getattr(top, name) + + +def _lookup_app_object(name): + top = _app_ctx_stack.top + if top is None: + raise RuntimeError(_app_ctx_err_msg) + return getattr(top, name) + + +def _find_app(): + top = _app_ctx_stack.top + if top is None: + raise RuntimeError(_app_ctx_err_msg) + return top.app + + +# context locals +_request_ctx_stack = LocalStack() +_app_ctx_stack = LocalStack() +current_app = LocalProxy(_find_app) +request = LocalProxy(partial(_lookup_req_object, 'request')) +session = LocalProxy(partial(_lookup_req_object, 'session')) +g = LocalProxy(partial(_lookup_app_object, 'g')) diff --git a/pyextra/flask/helpers.py b/pyextra/flask/helpers.py new file mode 100644 index 00000000000000..df0b91fc55ee0e --- /dev/null +++ b/pyextra/flask/helpers.py @@ -0,0 +1,1044 @@ +# -*- coding: utf-8 -*- +""" + flask.helpers + ~~~~~~~~~~~~~ + + Implements various helpers. + + :copyright: © 2010 by the Pallets team. + :license: BSD, see LICENSE for more details. +""" + +import os +import socket +import sys +import pkgutil +import posixpath +import mimetypes +from time import time +from zlib import adler32 +from threading import RLock +import unicodedata +from werkzeug.routing import BuildError +from functools import update_wrapper + +from werkzeug.urls import url_quote +from werkzeug.datastructures import Headers, Range +from werkzeug.exceptions import BadRequest, NotFound, \ + RequestedRangeNotSatisfiable + +from werkzeug.wsgi import wrap_file +from jinja2 import FileSystemLoader + +from .signals import message_flashed +from .globals import session, _request_ctx_stack, _app_ctx_stack, \ + current_app, request +from ._compat import string_types, text_type, PY2 + +# sentinel +_missing = object() + + +# what separators does this operating system provide that are not a slash? +# this is used by the send_from_directory function to ensure that nobody is +# able to access files from outside the filesystem. +_os_alt_seps = list(sep for sep in [os.path.sep, os.path.altsep] + if sep not in (None, '/')) + + +def get_env(): + """Get the environment the app is running in, indicated by the + :envvar:`FLASK_ENV` environment variable. The default is + ``'production'``. + """ + return os.environ.get('FLASK_ENV') or 'production' + + +def get_debug_flag(): + """Get whether debug mode should be enabled for the app, indicated + by the :envvar:`FLASK_DEBUG` environment variable. The default is + ``True`` if :func:`.get_env` returns ``'development'``, or ``False`` + otherwise. + """ + val = os.environ.get('FLASK_DEBUG') + + if not val: + return get_env() == 'development' + + return val.lower() not in ('0', 'false', 'no') + + +def get_load_dotenv(default=True): + """Get whether the user has disabled loading dotenv files by setting + :envvar:`FLASK_SKIP_DOTENV`. The default is ``True``, load the + files. + + :param default: What to return if the env var isn't set. + """ + val = os.environ.get('FLASK_SKIP_DOTENV') + + if not val: + return default + + return val.lower() in ('0', 'false', 'no') + + +def _endpoint_from_view_func(view_func): + """Internal helper that returns the default endpoint for a given + function. This always is the function name. + """ + assert view_func is not None, 'expected view func if endpoint ' \ + 'is not provided.' + return view_func.__name__ + + +def stream_with_context(generator_or_function): + """Request contexts disappear when the response is started on the server. + This is done for efficiency reasons and to make it less likely to encounter + memory leaks with badly written WSGI middlewares. The downside is that if + you are using streamed responses, the generator cannot access request bound + information any more. + + This function however can help you keep the context around for longer:: + + from flask import stream_with_context, request, Response + + @app.route('/stream') + def streamed_response(): + @stream_with_context + def generate(): + yield 'Hello ' + yield request.args['name'] + yield '!' + return Response(generate()) + + Alternatively it can also be used around a specific generator:: + + from flask import stream_with_context, request, Response + + @app.route('/stream') + def streamed_response(): + def generate(): + yield 'Hello ' + yield request.args['name'] + yield '!' + return Response(stream_with_context(generate())) + + .. versionadded:: 0.9 + """ + try: + gen = iter(generator_or_function) + except TypeError: + def decorator(*args, **kwargs): + gen = generator_or_function(*args, **kwargs) + return stream_with_context(gen) + return update_wrapper(decorator, generator_or_function) + + def generator(): + ctx = _request_ctx_stack.top + if ctx is None: + raise RuntimeError('Attempted to stream with context but ' + 'there was no context in the first place to keep around.') + with ctx: + # Dummy sentinel. Has to be inside the context block or we're + # not actually keeping the context around. + yield None + + # The try/finally is here so that if someone passes a WSGI level + # iterator in we're still running the cleanup logic. Generators + # don't need that because they are closed on their destruction + # automatically. + try: + for item in gen: + yield item + finally: + if hasattr(gen, 'close'): + gen.close() + + # The trick is to start the generator. Then the code execution runs until + # the first dummy None is yielded at which point the context was already + # pushed. This item is discarded. Then when the iteration continues the + # real generator is executed. + wrapped_g = generator() + next(wrapped_g) + return wrapped_g + + +def make_response(*args): + """Sometimes it is necessary to set additional headers in a view. Because + views do not have to return response objects but can return a value that + is converted into a response object by Flask itself, it becomes tricky to + add headers to it. This function can be called instead of using a return + and you will get a response object which you can use to attach headers. + + If view looked like this and you want to add a new header:: + + def index(): + return render_template('index.html', foo=42) + + You can now do something like this:: + + def index(): + response = make_response(render_template('index.html', foo=42)) + response.headers['X-Parachutes'] = 'parachutes are cool' + return response + + This function accepts the very same arguments you can return from a + view function. This for example creates a response with a 404 error + code:: + + response = make_response(render_template('not_found.html'), 404) + + The other use case of this function is to force the return value of a + view function into a response which is helpful with view + decorators:: + + response = make_response(view_function()) + response.headers['X-Parachutes'] = 'parachutes are cool' + + Internally this function does the following things: + + - if no arguments are passed, it creates a new response argument + - if one argument is passed, :meth:`flask.Flask.make_response` + is invoked with it. + - if more than one argument is passed, the arguments are passed + to the :meth:`flask.Flask.make_response` function as tuple. + + .. versionadded:: 0.6 + """ + if not args: + return current_app.response_class() + if len(args) == 1: + args = args[0] + return current_app.make_response(args) + + +def url_for(endpoint, **values): + """Generates a URL to the given endpoint with the method provided. + + Variable arguments that are unknown to the target endpoint are appended + to the generated URL as query arguments. If the value of a query argument + is ``None``, the whole pair is skipped. In case blueprints are active + you can shortcut references to the same blueprint by prefixing the + local endpoint with a dot (``.``). + + This will reference the index function local to the current blueprint:: + + url_for('.index') + + For more information, head over to the :ref:`Quickstart `. + + To integrate applications, :class:`Flask` has a hook to intercept URL build + errors through :attr:`Flask.url_build_error_handlers`. The `url_for` + function results in a :exc:`~werkzeug.routing.BuildError` when the current + app does not have a URL for the given endpoint and values. When it does, the + :data:`~flask.current_app` calls its :attr:`~Flask.url_build_error_handlers` if + it is not ``None``, which can return a string to use as the result of + `url_for` (instead of `url_for`'s default to raise the + :exc:`~werkzeug.routing.BuildError` exception) or re-raise the exception. + An example:: + + def external_url_handler(error, endpoint, values): + "Looks up an external URL when `url_for` cannot build a URL." + # This is an example of hooking the build_error_handler. + # Here, lookup_url is some utility function you've built + # which looks up the endpoint in some external URL registry. + url = lookup_url(endpoint, **values) + if url is None: + # External lookup did not have a URL. + # Re-raise the BuildError, in context of original traceback. + exc_type, exc_value, tb = sys.exc_info() + if exc_value is error: + raise exc_type, exc_value, tb + else: + raise error + # url_for will use this result, instead of raising BuildError. + return url + + app.url_build_error_handlers.append(external_url_handler) + + Here, `error` is the instance of :exc:`~werkzeug.routing.BuildError`, and + `endpoint` and `values` are the arguments passed into `url_for`. Note + that this is for building URLs outside the current application, and not for + handling 404 NotFound errors. + + .. versionadded:: 0.10 + The `_scheme` parameter was added. + + .. versionadded:: 0.9 + The `_anchor` and `_method` parameters were added. + + .. versionadded:: 0.9 + Calls :meth:`Flask.handle_build_error` on + :exc:`~werkzeug.routing.BuildError`. + + :param endpoint: the endpoint of the URL (name of the function) + :param values: the variable arguments of the URL rule + :param _external: if set to ``True``, an absolute URL is generated. Server + address can be changed via ``SERVER_NAME`` configuration variable which + defaults to `localhost`. + :param _scheme: a string specifying the desired URL scheme. The `_external` + parameter must be set to ``True`` or a :exc:`ValueError` is raised. The default + behavior uses the same scheme as the current request, or + ``PREFERRED_URL_SCHEME`` from the :ref:`app configuration ` if no + request context is available. As of Werkzeug 0.10, this also can be set + to an empty string to build protocol-relative URLs. + :param _anchor: if provided this is added as anchor to the URL. + :param _method: if provided this explicitly specifies an HTTP method. + """ + appctx = _app_ctx_stack.top + reqctx = _request_ctx_stack.top + + if appctx is None: + raise RuntimeError( + 'Attempted to generate a URL without the application context being' + ' pushed. This has to be executed when application context is' + ' available.' + ) + + # If request specific information is available we have some extra + # features that support "relative" URLs. + if reqctx is not None: + url_adapter = reqctx.url_adapter + blueprint_name = request.blueprint + + if endpoint[:1] == '.': + if blueprint_name is not None: + endpoint = blueprint_name + endpoint + else: + endpoint = endpoint[1:] + + external = values.pop('_external', False) + + # Otherwise go with the url adapter from the appctx and make + # the URLs external by default. + else: + url_adapter = appctx.url_adapter + + if url_adapter is None: + raise RuntimeError( + 'Application was not able to create a URL adapter for request' + ' independent URL generation. You might be able to fix this by' + ' setting the SERVER_NAME config variable.' + ) + + external = values.pop('_external', True) + + anchor = values.pop('_anchor', None) + method = values.pop('_method', None) + scheme = values.pop('_scheme', None) + appctx.app.inject_url_defaults(endpoint, values) + + # This is not the best way to deal with this but currently the + # underlying Werkzeug router does not support overriding the scheme on + # a per build call basis. + old_scheme = None + if scheme is not None: + if not external: + raise ValueError('When specifying _scheme, _external must be True') + old_scheme = url_adapter.url_scheme + url_adapter.url_scheme = scheme + + try: + try: + rv = url_adapter.build(endpoint, values, method=method, + force_external=external) + finally: + if old_scheme is not None: + url_adapter.url_scheme = old_scheme + except BuildError as error: + # We need to inject the values again so that the app callback can + # deal with that sort of stuff. + values['_external'] = external + values['_anchor'] = anchor + values['_method'] = method + values['_scheme'] = scheme + return appctx.app.handle_url_build_error(error, endpoint, values) + + if anchor is not None: + rv += '#' + url_quote(anchor) + return rv + + +def get_template_attribute(template_name, attribute): + """Loads a macro (or variable) a template exports. This can be used to + invoke a macro from within Python code. If you for example have a + template named :file:`_cider.html` with the following contents: + + .. sourcecode:: html+jinja + + {% macro hello(name) %}Hello {{ name }}!{% endmacro %} + + You can access this from Python code like this:: + + hello = get_template_attribute('_cider.html', 'hello') + return hello('World') + + .. versionadded:: 0.2 + + :param template_name: the name of the template + :param attribute: the name of the variable of macro to access + """ + return getattr(current_app.jinja_env.get_template(template_name).module, + attribute) + + +def flash(message, category='message'): + """Flashes a message to the next request. In order to remove the + flashed message from the session and to display it to the user, + the template has to call :func:`get_flashed_messages`. + + .. versionchanged:: 0.3 + `category` parameter added. + + :param message: the message to be flashed. + :param category: the category for the message. The following values + are recommended: ``'message'`` for any kind of message, + ``'error'`` for errors, ``'info'`` for information + messages and ``'warning'`` for warnings. However any + kind of string can be used as category. + """ + # Original implementation: + # + # session.setdefault('_flashes', []).append((category, message)) + # + # This assumed that changes made to mutable structures in the session are + # always in sync with the session object, which is not true for session + # implementations that use external storage for keeping their keys/values. + flashes = session.get('_flashes', []) + flashes.append((category, message)) + session['_flashes'] = flashes + message_flashed.send(current_app._get_current_object(), + message=message, category=category) + + +def get_flashed_messages(with_categories=False, category_filter=[]): + """Pulls all flashed messages from the session and returns them. + Further calls in the same request to the function will return + the same messages. By default just the messages are returned, + but when `with_categories` is set to ``True``, the return value will + be a list of tuples in the form ``(category, message)`` instead. + + Filter the flashed messages to one or more categories by providing those + categories in `category_filter`. This allows rendering categories in + separate html blocks. The `with_categories` and `category_filter` + arguments are distinct: + + * `with_categories` controls whether categories are returned with message + text (``True`` gives a tuple, where ``False`` gives just the message text). + * `category_filter` filters the messages down to only those matching the + provided categories. + + See :ref:`message-flashing-pattern` for examples. + + .. versionchanged:: 0.3 + `with_categories` parameter added. + + .. versionchanged:: 0.9 + `category_filter` parameter added. + + :param with_categories: set to ``True`` to also receive categories. + :param category_filter: whitelist of categories to limit return values + """ + flashes = _request_ctx_stack.top.flashes + if flashes is None: + _request_ctx_stack.top.flashes = flashes = session.pop('_flashes') \ + if '_flashes' in session else [] + if category_filter: + flashes = list(filter(lambda f: f[0] in category_filter, flashes)) + if not with_categories: + return [x[1] for x in flashes] + return flashes + + +def send_file(filename_or_fp, mimetype=None, as_attachment=False, + attachment_filename=None, add_etags=True, + cache_timeout=None, conditional=False, last_modified=None): + """Sends the contents of a file to the client. This will use the + most efficient method available and configured. By default it will + try to use the WSGI server's file_wrapper support. Alternatively + you can set the application's :attr:`~Flask.use_x_sendfile` attribute + to ``True`` to directly emit an ``X-Sendfile`` header. This however + requires support of the underlying webserver for ``X-Sendfile``. + + By default it will try to guess the mimetype for you, but you can + also explicitly provide one. For extra security you probably want + to send certain files as attachment (HTML for instance). The mimetype + guessing requires a `filename` or an `attachment_filename` to be + provided. + + ETags will also be attached automatically if a `filename` is provided. You + can turn this off by setting `add_etags=False`. + + If `conditional=True` and `filename` is provided, this method will try to + upgrade the response stream to support range requests. This will allow + the request to be answered with partial content response. + + Please never pass filenames to this function from user sources; + you should use :func:`send_from_directory` instead. + + .. versionadded:: 0.2 + + .. versionadded:: 0.5 + The `add_etags`, `cache_timeout` and `conditional` parameters were + added. The default behavior is now to attach etags. + + .. versionchanged:: 0.7 + mimetype guessing and etag support for file objects was + deprecated because it was unreliable. Pass a filename if you are + able to, otherwise attach an etag yourself. This functionality + will be removed in Flask 1.0 + + .. versionchanged:: 0.9 + cache_timeout pulls its default from application config, when None. + + .. versionchanged:: 0.12 + The filename is no longer automatically inferred from file objects. If + you want to use automatic mimetype and etag support, pass a filepath via + `filename_or_fp` or `attachment_filename`. + + .. versionchanged:: 0.12 + The `attachment_filename` is preferred over `filename` for MIME-type + detection. + + .. versionchanged:: 1.0 + UTF-8 filenames, as specified in `RFC 2231`_, are supported. + + .. _RFC 2231: https://tools.ietf.org/html/rfc2231#section-4 + + :param filename_or_fp: the filename of the file to send. + This is relative to the :attr:`~Flask.root_path` + if a relative path is specified. + Alternatively a file object might be provided in + which case ``X-Sendfile`` might not work and fall + back to the traditional method. Make sure that the + file pointer is positioned at the start of data to + send before calling :func:`send_file`. + :param mimetype: the mimetype of the file if provided. If a file path is + given, auto detection happens as fallback, otherwise an + error will be raised. + :param as_attachment: set to ``True`` if you want to send this file with + a ``Content-Disposition: attachment`` header. + :param attachment_filename: the filename for the attachment if it + differs from the file's filename. + :param add_etags: set to ``False`` to disable attaching of etags. + :param conditional: set to ``True`` to enable conditional responses. + + :param cache_timeout: the timeout in seconds for the headers. When ``None`` + (default), this value is set by + :meth:`~Flask.get_send_file_max_age` of + :data:`~flask.current_app`. + :param last_modified: set the ``Last-Modified`` header to this value, + a :class:`~datetime.datetime` or timestamp. + If a file was passed, this overrides its mtime. + """ + mtime = None + fsize = None + if isinstance(filename_or_fp, string_types): + filename = filename_or_fp + if not os.path.isabs(filename): + filename = os.path.join(current_app.root_path, filename) + file = None + if attachment_filename is None: + attachment_filename = os.path.basename(filename) + else: + file = filename_or_fp + filename = None + + if mimetype is None: + if attachment_filename is not None: + mimetype = mimetypes.guess_type(attachment_filename)[0] \ + or 'application/octet-stream' + + if mimetype is None: + raise ValueError( + 'Unable to infer MIME-type because no filename is available. ' + 'Please set either `attachment_filename`, pass a filepath to ' + '`filename_or_fp` or set your own MIME-type via `mimetype`.' + ) + + headers = Headers() + if as_attachment: + if attachment_filename is None: + raise TypeError('filename unavailable, required for ' + 'sending as attachment') + + try: + attachment_filename = attachment_filename.encode('latin-1') + except UnicodeEncodeError: + filenames = { + 'filename': unicodedata.normalize( + 'NFKD', attachment_filename).encode('latin-1', 'ignore'), + 'filename*': "UTF-8''%s" % url_quote(attachment_filename), + } + else: + filenames = {'filename': attachment_filename} + + headers.add('Content-Disposition', 'attachment', **filenames) + + if current_app.use_x_sendfile and filename: + if file is not None: + file.close() + headers['X-Sendfile'] = filename + fsize = os.path.getsize(filename) + headers['Content-Length'] = fsize + data = None + else: + if file is None: + file = open(filename, 'rb') + mtime = os.path.getmtime(filename) + fsize = os.path.getsize(filename) + headers['Content-Length'] = fsize + data = wrap_file(request.environ, file) + + rv = current_app.response_class(data, mimetype=mimetype, headers=headers, + direct_passthrough=True) + + if last_modified is not None: + rv.last_modified = last_modified + elif mtime is not None: + rv.last_modified = mtime + + rv.cache_control.public = True + if cache_timeout is None: + cache_timeout = current_app.get_send_file_max_age(filename) + if cache_timeout is not None: + rv.cache_control.max_age = cache_timeout + rv.expires = int(time() + cache_timeout) + + if add_etags and filename is not None: + from warnings import warn + + try: + rv.set_etag('%s-%s-%s' % ( + os.path.getmtime(filename), + os.path.getsize(filename), + adler32( + filename.encode('utf-8') if isinstance(filename, text_type) + else filename + ) & 0xffffffff + )) + except OSError: + warn('Access %s failed, maybe it does not exist, so ignore etags in ' + 'headers' % filename, stacklevel=2) + + if conditional: + try: + rv = rv.make_conditional(request, accept_ranges=True, + complete_length=fsize) + except RequestedRangeNotSatisfiable: + if file is not None: + file.close() + raise + # make sure we don't send x-sendfile for servers that + # ignore the 304 status code for x-sendfile. + if rv.status_code == 304: + rv.headers.pop('x-sendfile', None) + return rv + + +def safe_join(directory, *pathnames): + """Safely join `directory` and zero or more untrusted `pathnames` + components. + + Example usage:: + + @app.route('/wiki/') + def wiki_page(filename): + filename = safe_join(app.config['WIKI_FOLDER'], filename) + with open(filename, 'rb') as fd: + content = fd.read() # Read and process the file content... + + :param directory: the trusted base directory. + :param pathnames: the untrusted pathnames relative to that directory. + :raises: :class:`~werkzeug.exceptions.NotFound` if one or more passed + paths fall out of its boundaries. + """ + + parts = [directory] + + for filename in pathnames: + if filename != '': + filename = posixpath.normpath(filename) + + if ( + any(sep in filename for sep in _os_alt_seps) + or os.path.isabs(filename) + or filename == '..' + or filename.startswith('../') + ): + raise NotFound() + + parts.append(filename) + + return posixpath.join(*parts) + + +def send_from_directory(directory, filename, **options): + """Send a file from a given directory with :func:`send_file`. This + is a secure way to quickly expose static files from an upload folder + or something similar. + + Example usage:: + + @app.route('/uploads/') + def download_file(filename): + return send_from_directory(app.config['UPLOAD_FOLDER'], + filename, as_attachment=True) + + .. admonition:: Sending files and Performance + + It is strongly recommended to activate either ``X-Sendfile`` support in + your webserver or (if no authentication happens) to tell the webserver + to serve files for the given path on its own without calling into the + web application for improved performance. + + .. versionadded:: 0.5 + + :param directory: the directory where all the files are stored. + :param filename: the filename relative to that directory to + download. + :param options: optional keyword arguments that are directly + forwarded to :func:`send_file`. + """ + filename = safe_join(directory, filename) + if not os.path.isabs(filename): + filename = os.path.join(current_app.root_path, filename) + try: + if not os.path.isfile(filename): + raise NotFound() + except (TypeError, ValueError): + raise BadRequest() + options.setdefault('conditional', True) + return send_file(filename, **options) + + +def get_root_path(import_name): + """Returns the path to a package or cwd if that cannot be found. This + returns the path of a package or the folder that contains a module. + + Not to be confused with the package path returned by :func:`find_package`. + """ + # Module already imported and has a file attribute. Use that first. + mod = sys.modules.get(import_name) + if mod is not None and hasattr(mod, '__file__'): + return os.path.dirname(os.path.abspath(mod.__file__)) + + # Next attempt: check the loader. + loader = pkgutil.get_loader(import_name) + + # Loader does not exist or we're referring to an unloaded main module + # or a main module without path (interactive sessions), go with the + # current working directory. + if loader is None or import_name == '__main__': + return os.getcwd() + + # For .egg, zipimporter does not have get_filename until Python 2.7. + # Some other loaders might exhibit the same behavior. + if hasattr(loader, 'get_filename'): + filepath = loader.get_filename(import_name) + else: + # Fall back to imports. + __import__(import_name) + mod = sys.modules[import_name] + filepath = getattr(mod, '__file__', None) + + # If we don't have a filepath it might be because we are a + # namespace package. In this case we pick the root path from the + # first module that is contained in our package. + if filepath is None: + raise RuntimeError('No root path can be found for the provided ' + 'module "%s". This can happen because the ' + 'module came from an import hook that does ' + 'not provide file name information or because ' + 'it\'s a namespace package. In this case ' + 'the root path needs to be explicitly ' + 'provided.' % import_name) + + # filepath is import_name.py for a module, or __init__.py for a package. + return os.path.dirname(os.path.abspath(filepath)) + + +def _matching_loader_thinks_module_is_package(loader, mod_name): + """Given the loader that loaded a module and the module this function + attempts to figure out if the given module is actually a package. + """ + # If the loader can tell us if something is a package, we can + # directly ask the loader. + if hasattr(loader, 'is_package'): + return loader.is_package(mod_name) + # importlib's namespace loaders do not have this functionality but + # all the modules it loads are packages, so we can take advantage of + # this information. + elif (loader.__class__.__module__ == '_frozen_importlib' and + loader.__class__.__name__ == 'NamespaceLoader'): + return True + # Otherwise we need to fail with an error that explains what went + # wrong. + raise AttributeError( + ('%s.is_package() method is missing but is required by Flask of ' + 'PEP 302 import hooks. If you do not use import hooks and ' + 'you encounter this error please file a bug against Flask.') % + loader.__class__.__name__) + + +def find_package(import_name): + """Finds a package and returns the prefix (or None if the package is + not installed) as well as the folder that contains the package or + module as a tuple. The package path returned is the module that would + have to be added to the pythonpath in order to make it possible to + import the module. The prefix is the path below which a UNIX like + folder structure exists (lib, share etc.). + """ + root_mod_name = import_name.split('.')[0] + loader = pkgutil.get_loader(root_mod_name) + if loader is None or import_name == '__main__': + # import name is not found, or interactive/main module + package_path = os.getcwd() + else: + # For .egg, zipimporter does not have get_filename until Python 2.7. + if hasattr(loader, 'get_filename'): + filename = loader.get_filename(root_mod_name) + elif hasattr(loader, 'archive'): + # zipimporter's loader.archive points to the .egg or .zip + # archive filename is dropped in call to dirname below. + filename = loader.archive + else: + # At least one loader is missing both get_filename and archive: + # Google App Engine's HardenedModulesHook + # + # Fall back to imports. + __import__(import_name) + filename = sys.modules[import_name].__file__ + package_path = os.path.abspath(os.path.dirname(filename)) + + # In case the root module is a package we need to chop of the + # rightmost part. This needs to go through a helper function + # because of python 3.3 namespace packages. + if _matching_loader_thinks_module_is_package( + loader, root_mod_name): + package_path = os.path.dirname(package_path) + + site_parent, site_folder = os.path.split(package_path) + py_prefix = os.path.abspath(sys.prefix) + if package_path.startswith(py_prefix): + return py_prefix, package_path + elif site_folder.lower() == 'site-packages': + parent, folder = os.path.split(site_parent) + # Windows like installations + if folder.lower() == 'lib': + base_dir = parent + # UNIX like installations + elif os.path.basename(parent).lower() == 'lib': + base_dir = os.path.dirname(parent) + else: + base_dir = site_parent + return base_dir, package_path + return None, package_path + + +class locked_cached_property(object): + """A decorator that converts a function into a lazy property. The + function wrapped is called the first time to retrieve the result + and then that calculated result is used the next time you access + the value. Works like the one in Werkzeug but has a lock for + thread safety. + """ + + def __init__(self, func, name=None, doc=None): + self.__name__ = name or func.__name__ + self.__module__ = func.__module__ + self.__doc__ = doc or func.__doc__ + self.func = func + self.lock = RLock() + + def __get__(self, obj, type=None): + if obj is None: + return self + with self.lock: + value = obj.__dict__.get(self.__name__, _missing) + if value is _missing: + value = self.func(obj) + obj.__dict__[self.__name__] = value + return value + + +class _PackageBoundObject(object): + #: The name of the package or module that this app belongs to. Do not + #: change this once it is set by the constructor. + import_name = None + + #: Location of the template files to be added to the template lookup. + #: ``None`` if templates should not be added. + template_folder = None + + #: Absolute path to the package on the filesystem. Used to look up + #: resources contained in the package. + root_path = None + + def __init__(self, import_name, template_folder=None, root_path=None): + self.import_name = import_name + self.template_folder = template_folder + + if root_path is None: + root_path = get_root_path(self.import_name) + + self.root_path = root_path + self._static_folder = None + self._static_url_path = None + + def _get_static_folder(self): + if self._static_folder is not None: + return os.path.join(self.root_path, self._static_folder) + + def _set_static_folder(self, value): + self._static_folder = value + + static_folder = property( + _get_static_folder, _set_static_folder, + doc='The absolute path to the configured static folder.' + ) + del _get_static_folder, _set_static_folder + + def _get_static_url_path(self): + if self._static_url_path is not None: + return self._static_url_path + + if self.static_folder is not None: + return '/' + os.path.basename(self.static_folder) + + def _set_static_url_path(self, value): + self._static_url_path = value + + static_url_path = property( + _get_static_url_path, _set_static_url_path, + doc='The URL prefix that the static route will be registered for.' + ) + del _get_static_url_path, _set_static_url_path + + @property + def has_static_folder(self): + """This is ``True`` if the package bound object's container has a + folder for static files. + + .. versionadded:: 0.5 + """ + return self.static_folder is not None + + @locked_cached_property + def jinja_loader(self): + """The Jinja loader for this package bound object. + + .. versionadded:: 0.5 + """ + if self.template_folder is not None: + return FileSystemLoader(os.path.join(self.root_path, + self.template_folder)) + + def get_send_file_max_age(self, filename): + """Provides default cache_timeout for the :func:`send_file` functions. + + By default, this function returns ``SEND_FILE_MAX_AGE_DEFAULT`` from + the configuration of :data:`~flask.current_app`. + + Static file functions such as :func:`send_from_directory` use this + function, and :func:`send_file` calls this function on + :data:`~flask.current_app` when the given cache_timeout is ``None``. If a + cache_timeout is given in :func:`send_file`, that timeout is used; + otherwise, this method is called. + + This allows subclasses to change the behavior when sending files based + on the filename. For example, to set the cache timeout for .js files + to 60 seconds:: + + class MyFlask(flask.Flask): + def get_send_file_max_age(self, name): + if name.lower().endswith('.js'): + return 60 + return flask.Flask.get_send_file_max_age(self, name) + + .. versionadded:: 0.9 + """ + return total_seconds(current_app.send_file_max_age_default) + + def send_static_file(self, filename): + """Function used internally to send static files from the static + folder to the browser. + + .. versionadded:: 0.5 + """ + if not self.has_static_folder: + raise RuntimeError('No static folder for this object') + # Ensure get_send_file_max_age is called in all cases. + # Here, we ensure get_send_file_max_age is called for Blueprints. + cache_timeout = self.get_send_file_max_age(filename) + return send_from_directory(self.static_folder, filename, + cache_timeout=cache_timeout) + + def open_resource(self, resource, mode='rb'): + """Opens a resource from the application's resource folder. To see + how this works, consider the following folder structure:: + + /myapplication.py + /schema.sql + /static + /style.css + /templates + /layout.html + /index.html + + If you want to open the :file:`schema.sql` file you would do the + following:: + + with app.open_resource('schema.sql') as f: + contents = f.read() + do_something_with(contents) + + :param resource: the name of the resource. To access resources within + subfolders use forward slashes as separator. + :param mode: resource file opening mode, default is 'rb'. + """ + if mode not in ('r', 'rb'): + raise ValueError('Resources can only be opened for reading') + return open(os.path.join(self.root_path, resource), mode) + + +def total_seconds(td): + """Returns the total seconds from a timedelta object. + + :param timedelta td: the timedelta to be converted in seconds + + :returns: number of seconds + :rtype: int + """ + return td.days * 60 * 60 * 24 + td.seconds + + +def is_ip(value): + """Determine if the given string is an IP address. + + Python 2 on Windows doesn't provide ``inet_pton``, so this only + checks IPv4 addresses in that environment. + + :param value: value to check + :type value: str + + :return: True if string is an IP address + :rtype: bool + """ + if PY2 and os.name == 'nt': + try: + socket.inet_aton(value) + return True + except socket.error: + return False + + for family in (socket.AF_INET, socket.AF_INET6): + try: + socket.inet_pton(family, value) + except socket.error: + pass + else: + return True + + return False diff --git a/pyextra/flask/json/__init__.py b/pyextra/flask/json/__init__.py new file mode 100644 index 00000000000000..fbe6b92f0a3712 --- /dev/null +++ b/pyextra/flask/json/__init__.py @@ -0,0 +1,327 @@ +# -*- coding: utf-8 -*- +""" +flask.json +~~~~~~~~~~ + +:copyright: © 2010 by the Pallets team. +:license: BSD, see LICENSE for more details. +""" +import codecs +import io +import uuid +from datetime import date, datetime +from flask.globals import current_app, request +from flask._compat import text_type, PY2 + +from werkzeug.http import http_date +from jinja2 import Markup + +# Use the same json implementation as itsdangerous on which we +# depend anyways. +from itsdangerous import json as _json + + +# Figure out if simplejson escapes slashes. This behavior was changed +# from one version to another without reason. +_slash_escape = '\\/' not in _json.dumps('/') + + +__all__ = ['dump', 'dumps', 'load', 'loads', 'htmlsafe_dump', + 'htmlsafe_dumps', 'JSONDecoder', 'JSONEncoder', + 'jsonify'] + + +def _wrap_reader_for_text(fp, encoding): + if isinstance(fp.read(0), bytes): + fp = io.TextIOWrapper(io.BufferedReader(fp), encoding) + return fp + + +def _wrap_writer_for_text(fp, encoding): + try: + fp.write('') + except TypeError: + fp = io.TextIOWrapper(fp, encoding) + return fp + + +class JSONEncoder(_json.JSONEncoder): + """The default Flask JSON encoder. This one extends the default simplejson + encoder by also supporting ``datetime`` objects, ``UUID`` as well as + ``Markup`` objects which are serialized as RFC 822 datetime strings (same + as the HTTP date format). In order to support more data types override the + :meth:`default` method. + """ + + def default(self, o): + """Implement this method in a subclass such that it returns a + serializable object for ``o``, or calls the base implementation (to + raise a :exc:`TypeError`). + + For example, to support arbitrary iterators, you could implement + default like this:: + + def default(self, o): + try: + iterable = iter(o) + except TypeError: + pass + else: + return list(iterable) + return JSONEncoder.default(self, o) + """ + if isinstance(o, datetime): + return http_date(o.utctimetuple()) + if isinstance(o, date): + return http_date(o.timetuple()) + if isinstance(o, uuid.UUID): + return str(o) + if hasattr(o, '__html__'): + return text_type(o.__html__()) + return _json.JSONEncoder.default(self, o) + + +class JSONDecoder(_json.JSONDecoder): + """The default JSON decoder. This one does not change the behavior from + the default simplejson decoder. Consult the :mod:`json` documentation + for more information. This decoder is not only used for the load + functions of this module but also :attr:`~flask.Request`. + """ + + +def _dump_arg_defaults(kwargs): + """Inject default arguments for dump functions.""" + if current_app: + bp = current_app.blueprints.get(request.blueprint) if request else None + kwargs.setdefault( + 'cls', + bp.json_encoder if bp and bp.json_encoder + else current_app.json_encoder + ) + + if not current_app.config['JSON_AS_ASCII']: + kwargs.setdefault('ensure_ascii', False) + + kwargs.setdefault('sort_keys', current_app.config['JSON_SORT_KEYS']) + else: + kwargs.setdefault('sort_keys', True) + kwargs.setdefault('cls', JSONEncoder) + + +def _load_arg_defaults(kwargs): + """Inject default arguments for load functions.""" + if current_app: + bp = current_app.blueprints.get(request.blueprint) if request else None + kwargs.setdefault( + 'cls', + bp.json_decoder if bp and bp.json_decoder + else current_app.json_decoder + ) + else: + kwargs.setdefault('cls', JSONDecoder) + + +def detect_encoding(data): + """Detect which UTF codec was used to encode the given bytes. + + The latest JSON standard (:rfc:`8259`) suggests that only UTF-8 is + accepted. Older documents allowed 8, 16, or 32. 16 and 32 can be big + or little endian. Some editors or libraries may prepend a BOM. + + :param data: Bytes in unknown UTF encoding. + :return: UTF encoding name + """ + head = data[:4] + + if head[:3] == codecs.BOM_UTF8: + return 'utf-8-sig' + + if b'\x00' not in head: + return 'utf-8' + + if head in (codecs.BOM_UTF32_BE, codecs.BOM_UTF32_LE): + return 'utf-32' + + if head[:2] in (codecs.BOM_UTF16_BE, codecs.BOM_UTF16_LE): + return 'utf-16' + + if len(head) == 4: + if head[:3] == b'\x00\x00\x00': + return 'utf-32-be' + + if head[::2] == b'\x00\x00': + return 'utf-16-be' + + if head[1:] == b'\x00\x00\x00': + return 'utf-32-le' + + if head[1::2] == b'\x00\x00': + return 'utf-16-le' + + if len(head) == 2: + return 'utf-16-be' if head.startswith(b'\x00') else 'utf-16-le' + + return 'utf-8' + + +def dumps(obj, **kwargs): + """Serialize ``obj`` to a JSON formatted ``str`` by using the application's + configured encoder (:attr:`~flask.Flask.json_encoder`) if there is an + application on the stack. + + This function can return ``unicode`` strings or ascii-only bytestrings by + default which coerce into unicode strings automatically. That behavior by + default is controlled by the ``JSON_AS_ASCII`` configuration variable + and can be overridden by the simplejson ``ensure_ascii`` parameter. + """ + _dump_arg_defaults(kwargs) + encoding = kwargs.pop('encoding', None) + rv = _json.dumps(obj, **kwargs) + if encoding is not None and isinstance(rv, text_type): + rv = rv.encode(encoding) + return rv + + +def dump(obj, fp, **kwargs): + """Like :func:`dumps` but writes into a file object.""" + _dump_arg_defaults(kwargs) + encoding = kwargs.pop('encoding', None) + if encoding is not None: + fp = _wrap_writer_for_text(fp, encoding) + _json.dump(obj, fp, **kwargs) + + +def loads(s, **kwargs): + """Unserialize a JSON object from a string ``s`` by using the application's + configured decoder (:attr:`~flask.Flask.json_decoder`) if there is an + application on the stack. + """ + _load_arg_defaults(kwargs) + if isinstance(s, bytes): + encoding = kwargs.pop('encoding', None) + if encoding is None: + encoding = detect_encoding(s) + s = s.decode(encoding) + return _json.loads(s, **kwargs) + + +def load(fp, **kwargs): + """Like :func:`loads` but reads from a file object. + """ + _load_arg_defaults(kwargs) + if not PY2: + fp = _wrap_reader_for_text(fp, kwargs.pop('encoding', None) or 'utf-8') + return _json.load(fp, **kwargs) + + +def htmlsafe_dumps(obj, **kwargs): + """Works exactly like :func:`dumps` but is safe for use in `` + + + + +

+''' +FOOTER = u'''\ + +
+ +
+
+

Console Locked

+

+ The console is locked and needs to be unlocked by entering the PIN. + You can find the PIN printed out on the standard output of your + shell that runs the server. +

+

PIN: + + +

+
+
+ + +''' + +PAGE_HTML = HEADER + u'''\ +

%(exception_type)s

+
+

%(exception)s

+
+

Traceback (most recent call last)

+%(summary)s +
+
+

+ + This is the Copy/Paste friendly version of the traceback. You can also paste this traceback into + a gist: + +

+ +
+
+
+ The debugger caught an exception in your WSGI application. You can now + look at the traceback which led to the error. + If you enable JavaScript you can also use additional features such as code + execution (if the evalex feature is enabled), automatic pasting of the + exceptions and much more. +
+''' + FOOTER + ''' + +''' + +CONSOLE_HTML = HEADER + u'''\ +

Interactive Console

+
+In this console you can execute Python expressions in the context of the +application. The initial namespace was created by the debugger automatically. +
+
The Console requires JavaScript.
+''' + FOOTER + +SUMMARY_HTML = u'''\ +
+ %(title)s +
    %(frames)s
+ %(description)s +
+''' + +FRAME_HTML = u'''\ +
+

File "%(filename)s", + line %(lineno)s, + in %(function_name)s

+
%(lines)s
+
+''' + +SOURCE_LINE_HTML = u'''\ + + %(lineno)s + %(code)s + +''' + + +def render_console_html(secret, evalex_trusted=True): + return CONSOLE_HTML % { + 'evalex': 'true', + 'evalex_trusted': evalex_trusted and 'true' or 'false', + 'console': 'true', + 'title': 'Console', + 'secret': secret, + 'traceback_id': -1 + } + + +def get_current_traceback(ignore_system_exceptions=False, + show_hidden_frames=False, skip=0): + """Get the current exception info as `Traceback` object. Per default + calling this method will reraise system exceptions such as generator exit, + system exit or others. This behavior can be disabled by passing `False` + to the function as first parameter. + """ + exc_type, exc_value, tb = sys.exc_info() + if ignore_system_exceptions and exc_type in system_exceptions: + raise + for x in range_type(skip): + if tb.tb_next is None: + break + tb = tb.tb_next + tb = Traceback(exc_type, exc_value, tb) + if not show_hidden_frames: + tb.filter_hidden_frames() + return tb + + +class Line(object): + """Helper for the source renderer.""" + __slots__ = ('lineno', 'code', 'in_frame', 'current') + + def __init__(self, lineno, code): + self.lineno = lineno + self.code = code + self.in_frame = False + self.current = False + + def classes(self): + rv = ['line'] + if self.in_frame: + rv.append('in-frame') + if self.current: + rv.append('current') + return rv + classes = property(classes) + + def render(self): + return SOURCE_LINE_HTML % { + 'classes': u' '.join(self.classes), + 'lineno': self.lineno, + 'code': escape(self.code) + } + + +class Traceback(object): + """Wraps a traceback.""" + + def __init__(self, exc_type, exc_value, tb): + self.exc_type = exc_type + self.exc_value = exc_value + if not isinstance(exc_type, str): + exception_type = exc_type.__name__ + if exc_type.__module__ not in ('__builtin__', 'exceptions'): + exception_type = exc_type.__module__ + '.' + exception_type + else: + exception_type = exc_type + self.exception_type = exception_type + + # we only add frames to the list that are not hidden. This follows + # the the magic variables as defined by paste.exceptions.collector + self.frames = [] + while tb: + self.frames.append(Frame(exc_type, exc_value, tb)) + tb = tb.tb_next + + def filter_hidden_frames(self): + """Remove the frames according to the paste spec.""" + if not self.frames: + return + + new_frames = [] + hidden = False + for frame in self.frames: + hide = frame.hide + if hide in ('before', 'before_and_this'): + new_frames = [] + hidden = False + if hide == 'before_and_this': + continue + elif hide in ('reset', 'reset_and_this'): + hidden = False + if hide == 'reset_and_this': + continue + elif hide in ('after', 'after_and_this'): + hidden = True + if hide == 'after_and_this': + continue + elif hide or hidden: + continue + new_frames.append(frame) + + # if we only have one frame and that frame is from the codeop + # module, remove it. + if len(new_frames) == 1 and self.frames[0].module == 'codeop': + del self.frames[:] + + # if the last frame is missing something went terrible wrong :( + elif self.frames[-1] in new_frames: + self.frames[:] = new_frames + + def is_syntax_error(self): + """Is it a syntax error?""" + return isinstance(self.exc_value, SyntaxError) + is_syntax_error = property(is_syntax_error) + + def exception(self): + """String representation of the exception.""" + buf = traceback.format_exception_only(self.exc_type, self.exc_value) + rv = ''.join(buf).strip() + return rv.decode('utf-8', 'replace') if PY2 else rv + exception = property(exception) + + def log(self, logfile=None): + """Log the ASCII traceback into a file object.""" + if logfile is None: + logfile = sys.stderr + tb = self.plaintext.rstrip() + u'\n' + if PY2: + tb = tb.encode('utf-8', 'replace') + logfile.write(tb) + + def paste(self): + """Create a paste and return the paste id.""" + data = json.dumps({ + 'description': 'Werkzeug Internal Server Error', + 'public': False, + 'files': { + 'traceback.txt': { + 'content': self.plaintext + } + } + }).encode('utf-8') + try: + from urllib2 import urlopen + except ImportError: + from urllib.request import urlopen + rv = urlopen('https://api.github.com/gists', data=data) + resp = json.loads(rv.read().decode('utf-8')) + rv.close() + return { + 'url': resp['html_url'], + 'id': resp['id'] + } + + def render_summary(self, include_title=True): + """Render the traceback for the interactive console.""" + title = '' + frames = [] + classes = ['traceback'] + if not self.frames: + classes.append('noframe-traceback') + + if include_title: + if self.is_syntax_error: + title = u'Syntax Error' + else: + title = u'Traceback (most recent call last):' + + for frame in self.frames: + frames.append(u'%s' % ( + frame.info and u' title="%s"' % escape(frame.info) or u'', + frame.render() + )) + + if self.is_syntax_error: + description_wrapper = u'
%s
' + else: + description_wrapper = u'
%s
' + + return SUMMARY_HTML % { + 'classes': u' '.join(classes), + 'title': title and u'

%s

' % title or u'', + 'frames': u'\n'.join(frames), + 'description': description_wrapper % escape(self.exception) + } + + def render_full(self, evalex=False, secret=None, + evalex_trusted=True): + """Render the Full HTML page with the traceback info.""" + exc = escape(self.exception) + return PAGE_HTML % { + 'evalex': evalex and 'true' or 'false', + 'evalex_trusted': evalex_trusted and 'true' or 'false', + 'console': 'false', + 'title': exc, + 'exception': exc, + 'exception_type': escape(self.exception_type), + 'summary': self.render_summary(include_title=False), + 'plaintext': escape(self.plaintext), + 'plaintext_cs': re.sub('-{2,}', '-', self.plaintext), + 'traceback_id': self.id, + 'secret': secret + } + + def generate_plaintext_traceback(self): + """Like the plaintext attribute but returns a generator""" + yield u'Traceback (most recent call last):' + for frame in self.frames: + yield u' File "%s", line %s, in %s' % ( + frame.filename, + frame.lineno, + frame.function_name + ) + yield u' ' + frame.current_line.strip() + yield self.exception + + def plaintext(self): + return u'\n'.join(self.generate_plaintext_traceback()) + plaintext = cached_property(plaintext) + + id = property(lambda x: id(x)) + + +class Frame(object): + + """A single frame in a traceback.""" + + def __init__(self, exc_type, exc_value, tb): + self.lineno = tb.tb_lineno + self.function_name = tb.tb_frame.f_code.co_name + self.locals = tb.tb_frame.f_locals + self.globals = tb.tb_frame.f_globals + + fn = inspect.getsourcefile(tb) or inspect.getfile(tb) + if fn[-4:] in ('.pyo', '.pyc'): + fn = fn[:-1] + # if it's a file on the file system resolve the real filename. + if os.path.isfile(fn): + fn = os.path.realpath(fn) + self.filename = to_unicode(fn, get_filesystem_encoding()) + self.module = self.globals.get('__name__') + self.loader = self.globals.get('__loader__') + self.code = tb.tb_frame.f_code + + # support for paste's traceback extensions + self.hide = self.locals.get('__traceback_hide__', False) + info = self.locals.get('__traceback_info__') + if info is not None: + try: + info = text_type(info) + except UnicodeError: + info = str(info).decode('utf-8', 'replace') + self.info = info + + def render(self): + """Render a single frame in a traceback.""" + return FRAME_HTML % { + 'id': self.id, + 'filename': escape(self.filename), + 'lineno': self.lineno, + 'function_name': escape(self.function_name), + 'lines': self.render_line_context(), + } + + def render_line_context(self): + before, current, after = self.get_context_lines() + rv = [] + + def render_line(line, cls): + line = line.expandtabs().rstrip() + stripped_line = line.strip() + prefix = len(line) - len(stripped_line) + rv.append( + '
%s%s
' % ( + cls, ' ' * prefix, escape(stripped_line) or ' ')) + + for line in before: + render_line(line, 'before') + render_line(current, 'current') + for line in after: + render_line(line, 'after') + + return '\n'.join(rv) + + def get_annotated_lines(self): + """Helper function that returns lines with extra information.""" + lines = [Line(idx + 1, x) for idx, x in enumerate(self.sourcelines)] + + # find function definition and mark lines + if hasattr(self.code, 'co_firstlineno'): + lineno = self.code.co_firstlineno - 1 + while lineno > 0: + if _funcdef_re.match(lines[lineno].code): + break + lineno -= 1 + try: + offset = len(inspect.getblock([x.code + '\n' for x + in lines[lineno:]])) + except TokenError: + offset = 0 + for line in lines[lineno:lineno + offset]: + line.in_frame = True + + # mark current line + try: + lines[self.lineno - 1].current = True + except IndexError: + pass + + return lines + + def eval(self, code, mode='single'): + """Evaluate code in the context of the frame.""" + if isinstance(code, string_types): + if PY2 and isinstance(code, unicode): # noqa + code = UTF8_COOKIE + code.encode('utf-8') + code = compile(code, '', mode) + return eval(code, self.globals, self.locals) + + @cached_property + def sourcelines(self): + """The sourcecode of the file as list of unicode strings.""" + # get sourcecode from loader or file + source = None + if self.loader is not None: + try: + if hasattr(self.loader, 'get_source'): + source = self.loader.get_source(self.module) + elif hasattr(self.loader, 'get_source_by_code'): + source = self.loader.get_source_by_code(self.code) + except Exception: + # we munch the exception so that we don't cause troubles + # if the loader is broken. + pass + + if source is None: + try: + f = open(to_native(self.filename, get_filesystem_encoding()), + mode='rb') + except IOError: + return [] + try: + source = f.read() + finally: + f.close() + + # already unicode? return right away + if isinstance(source, text_type): + return source.splitlines() + + # yes. it should be ascii, but we don't want to reject too many + # characters in the debugger if something breaks + charset = 'utf-8' + if source.startswith(UTF8_COOKIE): + source = source[3:] + else: + for idx, match in enumerate(_line_re.finditer(source)): + match = _coding_re.search(match.group()) + if match is not None: + charset = match.group(1) + break + if idx > 1: + break + + # on broken cookies we fall back to utf-8 too + charset = to_native(charset) + try: + codecs.lookup(charset) + except LookupError: + charset = 'utf-8' + + return source.decode(charset, 'replace').splitlines() + + def get_context_lines(self, context=5): + before = self.sourcelines[self.lineno - context - 1:self.lineno - 1] + past = self.sourcelines[self.lineno:self.lineno + context] + return ( + before, + self.current_line, + past, + ) + + @property + def current_line(self): + try: + return self.sourcelines[self.lineno - 1] + except IndexError: + return u'' + + @cached_property + def console(self): + return Console(self.globals, self.locals) + + id = property(lambda x: id(x)) diff --git a/pyextra/werkzeug/exceptions.py b/pyextra/werkzeug/exceptions.py new file mode 100644 index 00000000000000..1d68185a9b7be1 --- /dev/null +++ b/pyextra/werkzeug/exceptions.py @@ -0,0 +1,719 @@ +# -*- coding: utf-8 -*- +""" + werkzeug.exceptions + ~~~~~~~~~~~~~~~~~~~ + + This module implements a number of Python exceptions you can raise from + within your views to trigger a standard non-200 response. + + + Usage Example + ------------- + + :: + + from werkzeug.wrappers import BaseRequest + from werkzeug.wsgi import responder + from werkzeug.exceptions import HTTPException, NotFound + + def view(request): + raise NotFound() + + @responder + def application(environ, start_response): + request = BaseRequest(environ) + try: + return view(request) + except HTTPException as e: + return e + + + As you can see from this example those exceptions are callable WSGI + applications. Because of Python 2.4 compatibility those do not extend + from the response objects but only from the python exception class. + + As a matter of fact they are not Werkzeug response objects. However you + can get a response object by calling ``get_response()`` on a HTTP + exception. + + Keep in mind that you have to pass an environment to ``get_response()`` + because some errors fetch additional information from the WSGI + environment. + + If you want to hook in a different exception page to say, a 404 status + code, you can add a second except for a specific subclass of an error:: + + @responder + def application(environ, start_response): + request = BaseRequest(environ) + try: + return view(request) + except NotFound, e: + return not_found(request) + except HTTPException, e: + return e + + + :copyright: (c) 2014 by the Werkzeug Team, see AUTHORS for more details. + :license: BSD, see LICENSE for more details. +""" +import sys + +# Because of bootstrapping reasons we need to manually patch ourselves +# onto our parent module. +import werkzeug +werkzeug.exceptions = sys.modules[__name__] + +from werkzeug._internal import _get_environ +from werkzeug._compat import iteritems, integer_types, text_type, \ + implements_to_string + +from werkzeug.wrappers import Response + + +@implements_to_string +class HTTPException(Exception): + + """ + Baseclass for all HTTP exceptions. This exception can be called as WSGI + application to render a default error page or you can catch the subclasses + of it independently and render nicer error messages. + """ + + code = None + description = None + + def __init__(self, description=None, response=None): + Exception.__init__(self) + if description is not None: + self.description = description + self.response = response + + @classmethod + def wrap(cls, exception, name=None): + """This method returns a new subclass of the exception provided that + also is a subclass of `BadRequest`. + """ + class newcls(cls, exception): + + def __init__(self, arg=None, *args, **kwargs): + cls.__init__(self, *args, **kwargs) + exception.__init__(self, arg) + newcls.__module__ = sys._getframe(1).f_globals.get('__name__') + newcls.__name__ = name or cls.__name__ + exception.__name__ + return newcls + + @property + def name(self): + """The status name.""" + return HTTP_STATUS_CODES.get(self.code, 'Unknown Error') + + def get_description(self, environ=None): + """Get the description.""" + return u'

%s

' % escape(self.description) + + def get_body(self, environ=None): + """Get the HTML body.""" + return text_type(( + u'\n' + u'%(code)s %(name)s\n' + u'

%(name)s

\n' + u'%(description)s\n' + ) % { + 'code': self.code, + 'name': escape(self.name), + 'description': self.get_description(environ) + }) + + def get_headers(self, environ=None): + """Get a list of headers.""" + return [('Content-Type', 'text/html')] + + def get_response(self, environ=None): + """Get a response object. If one was passed to the exception + it's returned directly. + + :param environ: the optional environ for the request. This + can be used to modify the response depending + on how the request looked like. + :return: a :class:`Response` object or a subclass thereof. + """ + if self.response is not None: + return self.response + if environ is not None: + environ = _get_environ(environ) + headers = self.get_headers(environ) + return Response(self.get_body(environ), self.code, headers) + + def __call__(self, environ, start_response): + """Call the exception as WSGI application. + + :param environ: the WSGI environment. + :param start_response: the response callable provided by the WSGI + server. + """ + response = self.get_response(environ) + return response(environ, start_response) + + def __str__(self): + code = self.code if self.code is not None else '???' + return '%s %s: %s' % (code, self.name, self.description) + + def __repr__(self): + code = self.code if self.code is not None else '???' + return "<%s '%s: %s'>" % (self.__class__.__name__, code, self.name) + + +class BadRequest(HTTPException): + + """*400* `Bad Request` + + Raise if the browser sends something to the application the application + or server cannot handle. + """ + code = 400 + description = ( + 'The browser (or proxy) sent a request that this server could ' + 'not understand.' + ) + + +class ClientDisconnected(BadRequest): + + """Internal exception that is raised if Werkzeug detects a disconnected + client. Since the client is already gone at that point attempting to + send the error message to the client might not work and might ultimately + result in another exception in the server. Mainly this is here so that + it is silenced by default as far as Werkzeug is concerned. + + Since disconnections cannot be reliably detected and are unspecified + by WSGI to a large extent this might or might not be raised if a client + is gone. + + .. versionadded:: 0.8 + """ + + +class SecurityError(BadRequest): + + """Raised if something triggers a security error. This is otherwise + exactly like a bad request error. + + .. versionadded:: 0.9 + """ + + +class BadHost(BadRequest): + + """Raised if the submitted host is badly formatted. + + .. versionadded:: 0.11.2 + """ + + +class Unauthorized(HTTPException): + + """*401* `Unauthorized` + + Raise if the user is not authorized. Also used if you want to use HTTP + basic auth. + """ + code = 401 + description = ( + 'The server could not verify that you are authorized to access ' + 'the URL requested. You either supplied the wrong credentials (e.g. ' + 'a bad password), or your browser doesn\'t understand how to supply ' + 'the credentials required.' + ) + + +class Forbidden(HTTPException): + + """*403* `Forbidden` + + Raise if the user doesn't have the permission for the requested resource + but was authenticated. + """ + code = 403 + description = ( + 'You don\'t have the permission to access the requested resource. ' + 'It is either read-protected or not readable by the server.' + ) + + +class NotFound(HTTPException): + + """*404* `Not Found` + + Raise if a resource does not exist and never existed. + """ + code = 404 + description = ( + 'The requested URL was not found on the server. ' + 'If you entered the URL manually please check your spelling and ' + 'try again.' + ) + + +class MethodNotAllowed(HTTPException): + + """*405* `Method Not Allowed` + + Raise if the server used a method the resource does not handle. For + example `POST` if the resource is view only. Especially useful for REST. + + The first argument for this exception should be a list of allowed methods. + Strictly speaking the response would be invalid if you don't provide valid + methods in the header which you can do with that list. + """ + code = 405 + description = 'The method is not allowed for the requested URL.' + + def __init__(self, valid_methods=None, description=None): + """Takes an optional list of valid http methods + starting with werkzeug 0.3 the list will be mandatory.""" + HTTPException.__init__(self, description) + self.valid_methods = valid_methods + + def get_headers(self, environ): + headers = HTTPException.get_headers(self, environ) + if self.valid_methods: + headers.append(('Allow', ', '.join(self.valid_methods))) + return headers + + +class NotAcceptable(HTTPException): + + """*406* `Not Acceptable` + + Raise if the server can't return any content conforming to the + `Accept` headers of the client. + """ + code = 406 + + description = ( + 'The resource identified by the request is only capable of ' + 'generating response entities which have content characteristics ' + 'not acceptable according to the accept headers sent in the ' + 'request.' + ) + + +class RequestTimeout(HTTPException): + + """*408* `Request Timeout` + + Raise to signalize a timeout. + """ + code = 408 + description = ( + 'The server closed the network connection because the browser ' + 'didn\'t finish the request within the specified time.' + ) + + +class Conflict(HTTPException): + + """*409* `Conflict` + + Raise to signal that a request cannot be completed because it conflicts + with the current state on the server. + + .. versionadded:: 0.7 + """ + code = 409 + description = ( + 'A conflict happened while processing the request. The resource ' + 'might have been modified while the request was being processed.' + ) + + +class Gone(HTTPException): + + """*410* `Gone` + + Raise if a resource existed previously and went away without new location. + """ + code = 410 + description = ( + 'The requested URL is no longer available on this server and there ' + 'is no forwarding address. If you followed a link from a foreign ' + 'page, please contact the author of this page.' + ) + + +class LengthRequired(HTTPException): + + """*411* `Length Required` + + Raise if the browser submitted data but no ``Content-Length`` header which + is required for the kind of processing the server does. + """ + code = 411 + description = ( + 'A request with this method requires a valid Content-' + 'Length header.' + ) + + +class PreconditionFailed(HTTPException): + + """*412* `Precondition Failed` + + Status code used in combination with ``If-Match``, ``If-None-Match``, or + ``If-Unmodified-Since``. + """ + code = 412 + description = ( + 'The precondition on the request for the URL failed positive ' + 'evaluation.' + ) + + +class RequestEntityTooLarge(HTTPException): + + """*413* `Request Entity Too Large` + + The status code one should return if the data submitted exceeded a given + limit. + """ + code = 413 + description = ( + 'The data value transmitted exceeds the capacity limit.' + ) + + +class RequestURITooLarge(HTTPException): + + """*414* `Request URI Too Large` + + Like *413* but for too long URLs. + """ + code = 414 + description = ( + 'The length of the requested URL exceeds the capacity limit ' + 'for this server. The request cannot be processed.' + ) + + +class UnsupportedMediaType(HTTPException): + + """*415* `Unsupported Media Type` + + The status code returned if the server is unable to handle the media type + the client transmitted. + """ + code = 415 + description = ( + 'The server does not support the media type transmitted in ' + 'the request.' + ) + + +class RequestedRangeNotSatisfiable(HTTPException): + + """*416* `Requested Range Not Satisfiable` + + The client asked for an invalid part of the file. + + .. versionadded:: 0.7 + """ + code = 416 + description = ( + 'The server cannot provide the requested range.' + ) + + def __init__(self, length=None, units="bytes", description=None): + """Takes an optional `Content-Range` header value based on ``length`` + parameter. + """ + HTTPException.__init__(self, description) + self.length = length + self.units = units + + def get_headers(self, environ): + headers = HTTPException.get_headers(self, environ) + if self.length is not None: + headers.append( + ('Content-Range', '%s */%d' % (self.units, self.length))) + return headers + + +class ExpectationFailed(HTTPException): + + """*417* `Expectation Failed` + + The server cannot meet the requirements of the Expect request-header. + + .. versionadded:: 0.7 + """ + code = 417 + description = ( + 'The server could not meet the requirements of the Expect header' + ) + + +class ImATeapot(HTTPException): + + """*418* `I'm a teapot` + + The server should return this if it is a teapot and someone attempted + to brew coffee with it. + + .. versionadded:: 0.7 + """ + code = 418 + description = ( + 'This server is a teapot, not a coffee machine' + ) + + +class UnprocessableEntity(HTTPException): + + """*422* `Unprocessable Entity` + + Used if the request is well formed, but the instructions are otherwise + incorrect. + """ + code = 422 + description = ( + 'The request was well-formed but was unable to be followed ' + 'due to semantic errors.' + ) + + +class Locked(HTTPException): + + """*423* `Locked` + + Used if the resource that is being accessed is locked. + """ + code = 423 + description = ( + 'The resource that is being accessed is locked.' + ) + + +class PreconditionRequired(HTTPException): + + """*428* `Precondition Required` + + The server requires this request to be conditional, typically to prevent + the lost update problem, which is a race condition between two or more + clients attempting to update a resource through PUT or DELETE. By requiring + each client to include a conditional header ("If-Match" or "If-Unmodified- + Since") with the proper value retained from a recent GET request, the + server ensures that each client has at least seen the previous revision of + the resource. + """ + code = 428 + description = ( + 'This request is required to be conditional; try using "If-Match" ' + 'or "If-Unmodified-Since".' + ) + + +class TooManyRequests(HTTPException): + + """*429* `Too Many Requests` + + The server is limiting the rate at which this user receives responses, and + this request exceeds that rate. (The server may use any convenient method + to identify users and their request rates). The server may include a + "Retry-After" header to indicate how long the user should wait before + retrying. + """ + code = 429 + description = ( + 'This user has exceeded an allotted request count. Try again later.' + ) + + +class RequestHeaderFieldsTooLarge(HTTPException): + + """*431* `Request Header Fields Too Large` + + The server refuses to process the request because the header fields are too + large. One or more individual fields may be too large, or the set of all + headers is too large. + """ + code = 431 + description = ( + 'One or more header fields exceeds the maximum size.' + ) + + +class UnavailableForLegalReasons(HTTPException): + + """*451* `Unavailable For Legal Reasons` + + This status code indicates that the server is denying access to the + resource as a consequence of a legal demand. + """ + code = 451 + description = ( + 'Unavailable for legal reasons.' + ) + + +class InternalServerError(HTTPException): + + """*500* `Internal Server Error` + + Raise if an internal server error occurred. This is a good fallback if an + unknown error occurred in the dispatcher. + """ + code = 500 + description = ( + 'The server encountered an internal error and was unable to ' + 'complete your request. Either the server is overloaded or there ' + 'is an error in the application.' + ) + + +class NotImplemented(HTTPException): + + """*501* `Not Implemented` + + Raise if the application does not support the action requested by the + browser. + """ + code = 501 + description = ( + 'The server does not support the action requested by the ' + 'browser.' + ) + + +class BadGateway(HTTPException): + + """*502* `Bad Gateway` + + If you do proxying in your application you should return this status code + if you received an invalid response from the upstream server it accessed + in attempting to fulfill the request. + """ + code = 502 + description = ( + 'The proxy server received an invalid response from an upstream ' + 'server.' + ) + + +class ServiceUnavailable(HTTPException): + + """*503* `Service Unavailable` + + Status code you should return if a service is temporarily unavailable. + """ + code = 503 + description = ( + 'The server is temporarily unable to service your request due to ' + 'maintenance downtime or capacity problems. Please try again ' + 'later.' + ) + + +class GatewayTimeout(HTTPException): + + """*504* `Gateway Timeout` + + Status code you should return if a connection to an upstream server + times out. + """ + code = 504 + description = ( + 'The connection to an upstream server timed out.' + ) + + +class HTTPVersionNotSupported(HTTPException): + + """*505* `HTTP Version Not Supported` + + The server does not support the HTTP protocol version used in the request. + """ + code = 505 + description = ( + 'The server does not support the HTTP protocol version used in the ' + 'request.' + ) + + +default_exceptions = {} +__all__ = ['HTTPException'] + + +def _find_exceptions(): + for name, obj in iteritems(globals()): + try: + is_http_exception = issubclass(obj, HTTPException) + except TypeError: + is_http_exception = False + if not is_http_exception or obj.code is None: + continue + __all__.append(obj.__name__) + old_obj = default_exceptions.get(obj.code, None) + if old_obj is not None and issubclass(obj, old_obj): + continue + default_exceptions[obj.code] = obj +_find_exceptions() +del _find_exceptions + + +class Aborter(object): + + """ + When passed a dict of code -> exception items it can be used as + callable that raises exceptions. If the first argument to the + callable is an integer it will be looked up in the mapping, if it's + a WSGI application it will be raised in a proxy exception. + + The rest of the arguments are forwarded to the exception constructor. + """ + + def __init__(self, mapping=None, extra=None): + if mapping is None: + mapping = default_exceptions + self.mapping = dict(mapping) + if extra is not None: + self.mapping.update(extra) + + def __call__(self, code, *args, **kwargs): + if not args and not kwargs and not isinstance(code, integer_types): + raise HTTPException(response=code) + if code not in self.mapping: + raise LookupError('no exception for %r' % code) + raise self.mapping[code](*args, **kwargs) + + +def abort(status, *args, **kwargs): + ''' + Raises an :py:exc:`HTTPException` for the given status code or WSGI + application:: + + abort(404) # 404 Not Found + abort(Response('Hello World')) + + Can be passed a WSGI application or a status code. If a status code is + given it's looked up in the list of exceptions and will raise that + exception, if passed a WSGI application it will wrap it in a proxy WSGI + exception and raise that:: + + abort(404) + abort(Response('Hello World')) + + ''' + return _aborter(status, *args, **kwargs) + +_aborter = Aborter() + + +#: an exception that is used internally to signal both a key error and a +#: bad request. Used by a lot of the datastructures. +BadRequestKeyError = BadRequest.wrap(KeyError) + + +# imported here because of circular dependencies of werkzeug.utils +from werkzeug.utils import escape +from werkzeug.http import HTTP_STATUS_CODES diff --git a/pyextra/werkzeug/filesystem.py b/pyextra/werkzeug/filesystem.py new file mode 100644 index 00000000000000..62467465553477 --- /dev/null +++ b/pyextra/werkzeug/filesystem.py @@ -0,0 +1,66 @@ +# -*- coding: utf-8 -*- +""" + werkzeug.filesystem + ~~~~~~~~~~~~~~~~~~~ + + Various utilities for the local filesystem. + + :copyright: (c) 2015 by the Werkzeug Team, see AUTHORS for more details. + :license: BSD, see LICENSE for more details. +""" + +import codecs +import sys +import warnings + +# We do not trust traditional unixes. +has_likely_buggy_unicode_filesystem = \ + sys.platform.startswith('linux') or 'bsd' in sys.platform + + +def _is_ascii_encoding(encoding): + """ + Given an encoding this figures out if the encoding is actually ASCII (which + is something we don't actually want in most cases). This is necessary + because ASCII comes under many names such as ANSI_X3.4-1968. + """ + if encoding is None: + return False + try: + return codecs.lookup(encoding).name == 'ascii' + except LookupError: + return False + + +class BrokenFilesystemWarning(RuntimeWarning, UnicodeWarning): + '''The warning used by Werkzeug to signal a broken filesystem. Will only be + used once per runtime.''' + + +_warned_about_filesystem_encoding = False + + +def get_filesystem_encoding(): + """ + Returns the filesystem encoding that should be used. Note that this is + different from the Python understanding of the filesystem encoding which + might be deeply flawed. Do not use this value against Python's unicode APIs + because it might be different. See :ref:`filesystem-encoding` for the exact + behavior. + + The concept of a filesystem encoding in generally is not something you + should rely on. As such if you ever need to use this function except for + writing wrapper code reconsider. + """ + global _warned_about_filesystem_encoding + rv = sys.getfilesystemencoding() + if has_likely_buggy_unicode_filesystem and not rv \ + or _is_ascii_encoding(rv): + if not _warned_about_filesystem_encoding: + warnings.warn( + 'Detected a misconfigured UNIX filesystem: Will use UTF-8 as ' + 'filesystem encoding instead of {0!r}'.format(rv), + BrokenFilesystemWarning) + _warned_about_filesystem_encoding = True + return 'utf-8' + return rv diff --git a/pyextra/werkzeug/formparser.py b/pyextra/werkzeug/formparser.py new file mode 100644 index 00000000000000..c56859e905d65b --- /dev/null +++ b/pyextra/werkzeug/formparser.py @@ -0,0 +1,534 @@ +# -*- coding: utf-8 -*- +""" + werkzeug.formparser + ~~~~~~~~~~~~~~~~~~~ + + This module implements the form parsing. It supports url-encoded forms + as well as non-nested multipart uploads. + + :copyright: (c) 2014 by the Werkzeug Team, see AUTHORS for more details. + :license: BSD, see LICENSE for more details. +""" +import re +import codecs + +# there are some platforms where SpooledTemporaryFile is not available. +# In that case we need to provide a fallback. +try: + from tempfile import SpooledTemporaryFile +except ImportError: + from tempfile import TemporaryFile + SpooledTemporaryFile = None + +from itertools import chain, repeat, tee +from functools import update_wrapper + +from werkzeug._compat import to_native, text_type, BytesIO +from werkzeug.urls import url_decode_stream +from werkzeug.wsgi import make_line_iter, \ + get_input_stream, get_content_length +from werkzeug.datastructures import Headers, FileStorage, MultiDict +from werkzeug.http import parse_options_header + + +#: an iterator that yields empty strings +_empty_string_iter = repeat('') + +#: a regular expression for multipart boundaries +_multipart_boundary_re = re.compile('^[ -~]{0,200}[!-~]$') + +#: supported http encodings that are also available in python we support +#: for multipart messages. +_supported_multipart_encodings = frozenset(['base64', 'quoted-printable']) + + +def default_stream_factory(total_content_length, filename, content_type, + content_length=None): + """The stream factory that is used per default.""" + max_size = 1024 * 500 + if SpooledTemporaryFile is not None: + return SpooledTemporaryFile(max_size=max_size, mode='wb+') + if total_content_length is None or total_content_length > max_size: + return TemporaryFile('wb+') + return BytesIO() + + +def parse_form_data(environ, stream_factory=None, charset='utf-8', + errors='replace', max_form_memory_size=None, + max_content_length=None, cls=None, + silent=True): + """Parse the form data in the environ and return it as tuple in the form + ``(stream, form, files)``. You should only call this method if the + transport method is `POST`, `PUT`, or `PATCH`. + + If the mimetype of the data transmitted is `multipart/form-data` the + files multidict will be filled with `FileStorage` objects. If the + mimetype is unknown the input stream is wrapped and returned as first + argument, else the stream is empty. + + This is a shortcut for the common usage of :class:`FormDataParser`. + + Have a look at :ref:`dealing-with-request-data` for more details. + + .. versionadded:: 0.5 + The `max_form_memory_size`, `max_content_length` and + `cls` parameters were added. + + .. versionadded:: 0.5.1 + The optional `silent` flag was added. + + :param environ: the WSGI environment to be used for parsing. + :param stream_factory: An optional callable that returns a new read and + writeable file descriptor. This callable works + the same as :meth:`~BaseResponse._get_file_stream`. + :param charset: The character set for URL and url encoded form data. + :param errors: The encoding error behavior. + :param max_form_memory_size: the maximum number of bytes to be accepted for + in-memory stored form data. If the data + exceeds the value specified an + :exc:`~exceptions.RequestEntityTooLarge` + exception is raised. + :param max_content_length: If this is provided and the transmitted data + is longer than this value an + :exc:`~exceptions.RequestEntityTooLarge` + exception is raised. + :param cls: an optional dict class to use. If this is not specified + or `None` the default :class:`MultiDict` is used. + :param silent: If set to False parsing errors will not be caught. + :return: A tuple in the form ``(stream, form, files)``. + """ + return FormDataParser(stream_factory, charset, errors, + max_form_memory_size, max_content_length, + cls, silent).parse_from_environ(environ) + + +def exhaust_stream(f): + """Helper decorator for methods that exhausts the stream on return.""" + + def wrapper(self, stream, *args, **kwargs): + try: + return f(self, stream, *args, **kwargs) + finally: + exhaust = getattr(stream, 'exhaust', None) + if exhaust is not None: + exhaust() + else: + while 1: + chunk = stream.read(1024 * 64) + if not chunk: + break + return update_wrapper(wrapper, f) + + +class FormDataParser(object): + + """This class implements parsing of form data for Werkzeug. By itself + it can parse multipart and url encoded form data. It can be subclassed + and extended but for most mimetypes it is a better idea to use the + untouched stream and expose it as separate attributes on a request + object. + + .. versionadded:: 0.8 + + :param stream_factory: An optional callable that returns a new read and + writeable file descriptor. This callable works + the same as :meth:`~BaseResponse._get_file_stream`. + :param charset: The character set for URL and url encoded form data. + :param errors: The encoding error behavior. + :param max_form_memory_size: the maximum number of bytes to be accepted for + in-memory stored form data. If the data + exceeds the value specified an + :exc:`~exceptions.RequestEntityTooLarge` + exception is raised. + :param max_content_length: If this is provided and the transmitted data + is longer than this value an + :exc:`~exceptions.RequestEntityTooLarge` + exception is raised. + :param cls: an optional dict class to use. If this is not specified + or `None` the default :class:`MultiDict` is used. + :param silent: If set to False parsing errors will not be caught. + """ + + def __init__(self, stream_factory=None, charset='utf-8', + errors='replace', max_form_memory_size=None, + max_content_length=None, cls=None, + silent=True): + if stream_factory is None: + stream_factory = default_stream_factory + self.stream_factory = stream_factory + self.charset = charset + self.errors = errors + self.max_form_memory_size = max_form_memory_size + self.max_content_length = max_content_length + if cls is None: + cls = MultiDict + self.cls = cls + self.silent = silent + + def get_parse_func(self, mimetype, options): + return self.parse_functions.get(mimetype) + + def parse_from_environ(self, environ): + """Parses the information from the environment as form data. + + :param environ: the WSGI environment to be used for parsing. + :return: A tuple in the form ``(stream, form, files)``. + """ + content_type = environ.get('CONTENT_TYPE', '') + content_length = get_content_length(environ) + mimetype, options = parse_options_header(content_type) + return self.parse(get_input_stream(environ), mimetype, + content_length, options) + + def parse(self, stream, mimetype, content_length, options=None): + """Parses the information from the given stream, mimetype, + content length and mimetype parameters. + + :param stream: an input stream + :param mimetype: the mimetype of the data + :param content_length: the content length of the incoming data + :param options: optional mimetype parameters (used for + the multipart boundary for instance) + :return: A tuple in the form ``(stream, form, files)``. + """ + if self.max_content_length is not None and \ + content_length is not None and \ + content_length > self.max_content_length: + raise exceptions.RequestEntityTooLarge() + if options is None: + options = {} + + parse_func = self.get_parse_func(mimetype, options) + if parse_func is not None: + try: + return parse_func(self, stream, mimetype, + content_length, options) + except ValueError: + if not self.silent: + raise + + return stream, self.cls(), self.cls() + + @exhaust_stream + def _parse_multipart(self, stream, mimetype, content_length, options): + parser = MultiPartParser(self.stream_factory, self.charset, self.errors, + max_form_memory_size=self.max_form_memory_size, + cls=self.cls) + boundary = options.get('boundary') + if boundary is None: + raise ValueError('Missing boundary') + if isinstance(boundary, text_type): + boundary = boundary.encode('ascii') + form, files = parser.parse(stream, boundary, content_length) + return stream, form, files + + @exhaust_stream + def _parse_urlencoded(self, stream, mimetype, content_length, options): + if self.max_form_memory_size is not None and \ + content_length is not None and \ + content_length > self.max_form_memory_size: + raise exceptions.RequestEntityTooLarge() + form = url_decode_stream(stream, self.charset, + errors=self.errors, cls=self.cls) + return stream, form, self.cls() + + #: mapping of mimetypes to parsing functions + parse_functions = { + 'multipart/form-data': _parse_multipart, + 'application/x-www-form-urlencoded': _parse_urlencoded, + 'application/x-url-encoded': _parse_urlencoded + } + + +def is_valid_multipart_boundary(boundary): + """Checks if the string given is a valid multipart boundary.""" + return _multipart_boundary_re.match(boundary) is not None + + +def _line_parse(line): + """Removes line ending characters and returns a tuple (`stripped_line`, + `is_terminated`). + """ + if line[-2:] in ['\r\n', b'\r\n']: + return line[:-2], True + elif line[-1:] in ['\r', '\n', b'\r', b'\n']: + return line[:-1], True + return line, False + + +def parse_multipart_headers(iterable): + """Parses multipart headers from an iterable that yields lines (including + the trailing newline symbol). The iterable has to be newline terminated. + + The iterable will stop at the line where the headers ended so it can be + further consumed. + + :param iterable: iterable of strings that are newline terminated + """ + result = [] + for line in iterable: + line = to_native(line) + line, line_terminated = _line_parse(line) + if not line_terminated: + raise ValueError('unexpected end of line in multipart header') + if not line: + break + elif line[0] in ' \t' and result: + key, value = result[-1] + result[-1] = (key, value + '\n ' + line[1:]) + else: + parts = line.split(':', 1) + if len(parts) == 2: + result.append((parts[0].strip(), parts[1].strip())) + + # we link the list to the headers, no need to create a copy, the + # list was not shared anyways. + return Headers(result) + + +_begin_form = 'begin_form' +_begin_file = 'begin_file' +_cont = 'cont' +_end = 'end' + + +class MultiPartParser(object): + + def __init__(self, stream_factory=None, charset='utf-8', errors='replace', + max_form_memory_size=None, cls=None, buffer_size=64 * 1024): + self.charset = charset + self.errors = errors + self.max_form_memory_size = max_form_memory_size + self.stream_factory = default_stream_factory if stream_factory is None else stream_factory + self.cls = MultiDict if cls is None else cls + + # make sure the buffer size is divisible by four so that we can base64 + # decode chunk by chunk + assert buffer_size % 4 == 0, 'buffer size has to be divisible by 4' + # also the buffer size has to be at least 1024 bytes long or long headers + # will freak out the system + assert buffer_size >= 1024, 'buffer size has to be at least 1KB' + + self.buffer_size = buffer_size + + def _fix_ie_filename(self, filename): + """Internet Explorer 6 transmits the full file name if a file is + uploaded. This function strips the full path if it thinks the + filename is Windows-like absolute. + """ + if filename[1:3] == ':\\' or filename[:2] == '\\\\': + return filename.split('\\')[-1] + return filename + + def _find_terminator(self, iterator): + """The terminator might have some additional newlines before it. + There is at least one application that sends additional newlines + before headers (the python setuptools package). + """ + for line in iterator: + if not line: + break + line = line.strip() + if line: + return line + return b'' + + def fail(self, message): + raise ValueError(message) + + def get_part_encoding(self, headers): + transfer_encoding = headers.get('content-transfer-encoding') + if transfer_encoding is not None and \ + transfer_encoding in _supported_multipart_encodings: + return transfer_encoding + + def get_part_charset(self, headers): + # Figure out input charset for current part + content_type = headers.get('content-type') + if content_type: + mimetype, ct_params = parse_options_header(content_type) + return ct_params.get('charset', self.charset) + return self.charset + + def start_file_streaming(self, filename, headers, total_content_length): + if isinstance(filename, bytes): + filename = filename.decode(self.charset, self.errors) + filename = self._fix_ie_filename(filename) + content_type = headers.get('content-type') + try: + content_length = int(headers['content-length']) + except (KeyError, ValueError): + content_length = 0 + container = self.stream_factory(total_content_length, content_type, + filename, content_length) + return filename, container + + def in_memory_threshold_reached(self, bytes): + raise exceptions.RequestEntityTooLarge() + + def validate_boundary(self, boundary): + if not boundary: + self.fail('Missing boundary') + if not is_valid_multipart_boundary(boundary): + self.fail('Invalid boundary: %s' % boundary) + if len(boundary) > self.buffer_size: # pragma: no cover + # this should never happen because we check for a minimum size + # of 1024 and boundaries may not be longer than 200. The only + # situation when this happens is for non debug builds where + # the assert is skipped. + self.fail('Boundary longer than buffer size') + + def parse_lines(self, file, boundary, content_length, cap_at_buffer=True): + """Generate parts of + ``('begin_form', (headers, name))`` + ``('begin_file', (headers, name, filename))`` + ``('cont', bytestring)`` + ``('end', None)`` + + Always obeys the grammar + parts = ( begin_form cont* end | + begin_file cont* end )* + """ + next_part = b'--' + boundary + last_part = next_part + b'--' + + iterator = chain(make_line_iter(file, limit=content_length, + buffer_size=self.buffer_size, + cap_at_buffer=cap_at_buffer), + _empty_string_iter) + + terminator = self._find_terminator(iterator) + + if terminator == last_part: + return + elif terminator != next_part: + self.fail('Expected boundary at start of multipart data') + + while terminator != last_part: + headers = parse_multipart_headers(iterator) + + disposition = headers.get('content-disposition') + if disposition is None: + self.fail('Missing Content-Disposition header') + disposition, extra = parse_options_header(disposition) + transfer_encoding = self.get_part_encoding(headers) + name = extra.get('name') + + # Accept filename* to support non-ascii filenames as per rfc2231 + filename = extra.get('filename') or extra.get('filename*') + + # if no content type is given we stream into memory. A list is + # used as a temporary container. + if filename is None: + yield _begin_form, (headers, name) + + # otherwise we parse the rest of the headers and ask the stream + # factory for something we can write in. + else: + yield _begin_file, (headers, name, filename) + + buf = b'' + for line in iterator: + if not line: + self.fail('unexpected end of stream') + + if line[:2] == b'--': + terminator = line.rstrip() + if terminator in (next_part, last_part): + break + + if transfer_encoding is not None: + if transfer_encoding == 'base64': + transfer_encoding = 'base64_codec' + try: + line = codecs.decode(line, transfer_encoding) + except Exception: + self.fail('could not decode transfer encoded chunk') + + # we have something in the buffer from the last iteration. + # this is usually a newline delimiter. + if buf: + yield _cont, buf + buf = b'' + + # If the line ends with windows CRLF we write everything except + # the last two bytes. In all other cases however we write + # everything except the last byte. If it was a newline, that's + # fine, otherwise it does not matter because we will write it + # the next iteration. this ensures we do not write the + # final newline into the stream. That way we do not have to + # truncate the stream. However we do have to make sure that + # if something else than a newline is in there we write it + # out. + if line[-2:] == b'\r\n': + buf = b'\r\n' + cutoff = -2 + else: + buf = line[-1:] + cutoff = -1 + yield _cont, line[:cutoff] + + else: # pragma: no cover + raise ValueError('unexpected end of part') + + # if we have a leftover in the buffer that is not a newline + # character we have to flush it, otherwise we will chop of + # certain values. + if buf not in (b'', b'\r', b'\n', b'\r\n'): + yield _cont, buf + + yield _end, None + + def parse_parts(self, file, boundary, content_length): + """Generate ``('file', (name, val))`` and + ``('form', (name, val))`` parts. + """ + in_memory = 0 + + for ellt, ell in self.parse_lines(file, boundary, content_length): + if ellt == _begin_file: + headers, name, filename = ell + is_file = True + guard_memory = False + filename, container = self.start_file_streaming( + filename, headers, content_length) + _write = container.write + + elif ellt == _begin_form: + headers, name = ell + is_file = False + container = [] + _write = container.append + guard_memory = self.max_form_memory_size is not None + + elif ellt == _cont: + _write(ell) + # if we write into memory and there is a memory size limit we + # count the number of bytes in memory and raise an exception if + # there is too much data in memory. + if guard_memory: + in_memory += len(ell) + if in_memory > self.max_form_memory_size: + self.in_memory_threshold_reached(in_memory) + + elif ellt == _end: + if is_file: + container.seek(0) + yield ('file', + (name, FileStorage(container, filename, name, + headers=headers))) + else: + part_charset = self.get_part_charset(headers) + yield ('form', + (name, b''.join(container).decode( + part_charset, self.errors))) + + def parse(self, file, boundary, content_length): + formstream, filestream = tee( + self.parse_parts(file, boundary, content_length), 2) + form = (p[1] for p in formstream if p[0] == 'form') + files = (p[1] for p in filestream if p[0] == 'file') + return self.cls(form), self.cls(files) + + +from werkzeug import exceptions diff --git a/pyextra/werkzeug/http.py b/pyextra/werkzeug/http.py new file mode 100644 index 00000000000000..22197221c8fa3b --- /dev/null +++ b/pyextra/werkzeug/http.py @@ -0,0 +1,1158 @@ +# -*- coding: utf-8 -*- +""" + werkzeug.http + ~~~~~~~~~~~~~ + + Werkzeug comes with a bunch of utilities that help Werkzeug to deal with + HTTP data. Most of the classes and functions provided by this module are + used by the wrappers, but they are useful on their own, too, especially if + the response and request objects are not used. + + This covers some of the more HTTP centric features of WSGI, some other + utilities such as cookie handling are documented in the `werkzeug.utils` + module. + + + :copyright: (c) 2014 by the Werkzeug Team, see AUTHORS for more details. + :license: BSD, see LICENSE for more details. +""" +import re +import warnings +from time import time, gmtime +try: + from email.utils import parsedate_tz +except ImportError: # pragma: no cover + from email.Utils import parsedate_tz +try: + from urllib.request import parse_http_list as _parse_list_header + from urllib.parse import unquote_to_bytes as _unquote +except ImportError: # pragma: no cover + from urllib2 import parse_http_list as _parse_list_header, \ + unquote as _unquote +from datetime import datetime, timedelta +from hashlib import md5 +import base64 + +from werkzeug._internal import _cookie_quote, _make_cookie_domain, \ + _cookie_parse_impl +from werkzeug._compat import to_unicode, iteritems, text_type, \ + string_types, try_coerce_native, to_bytes, PY2, \ + integer_types + + +_cookie_charset = 'latin1' +# for explanation of "media-range", etc. see Sections 5.3.{1,2} of RFC 7231 +_accept_re = re.compile( + r'''( # media-range capturing-parenthesis + [^\s;,]+ # type/subtype + (?:[ \t]*;[ \t]* # ";" + (?: # parameter non-capturing-parenthesis + [^\s;,q][^\s;,]* # token that doesn't start with "q" + | # or + q[^\s;,=][^\s;,]* # token that is more than just "q" + ) + )* # zero or more parameters + ) # end of media-range + (?:[ \t]*;[ \t]*q= # weight is a "q" parameter + (\d*(?:\.\d+)?) # qvalue capturing-parentheses + [^,]* # "extension" accept params: who cares? + )? # accept params are optional + ''', re.VERBOSE) +_token_chars = frozenset("!#$%&'*+-.0123456789ABCDEFGHIJKLMNOPQRSTUVWXYZ" + '^_`abcdefghijklmnopqrstuvwxyz|~') +_etag_re = re.compile(r'([Ww]/)?(?:"(.*?)"|(.*?))(?:\s*,\s*|$)') +_unsafe_header_chars = set('()<>@,;:\"/[]?={} \t') +_option_header_piece_re = re.compile(r''' + ;\s* + (?P + "[^"\\]*(?:\\.[^"\\]*)*" # quoted string + | + [^\s;,=*]+ # token + ) + \s* + (?: # optionally followed by =value + (?: # equals sign, possibly with encoding + \*\s*=\s* # * indicates extended notation + (?P[^\s]+?) + '(?P[^\s]*?)' + | + =\s* # basic notation + ) + (?P + "[^"\\]*(?:\\.[^"\\]*)*" # quoted string + | + [^;,]+ # token + )? + )? + \s* +''', flags=re.VERBOSE) +_option_header_start_mime_type = re.compile(r',\s*([^;,\s]+)([;,]\s*.+)?') + +_entity_headers = frozenset([ + 'allow', 'content-encoding', 'content-language', 'content-length', + 'content-location', 'content-md5', 'content-range', 'content-type', + 'expires', 'last-modified' +]) +_hop_by_hop_headers = frozenset([ + 'connection', 'keep-alive', 'proxy-authenticate', + 'proxy-authorization', 'te', 'trailer', 'transfer-encoding', + 'upgrade' +]) + + +HTTP_STATUS_CODES = { + 100: 'Continue', + 101: 'Switching Protocols', + 102: 'Processing', + 200: 'OK', + 201: 'Created', + 202: 'Accepted', + 203: 'Non Authoritative Information', + 204: 'No Content', + 205: 'Reset Content', + 206: 'Partial Content', + 207: 'Multi Status', + 226: 'IM Used', # see RFC 3229 + 300: 'Multiple Choices', + 301: 'Moved Permanently', + 302: 'Found', + 303: 'See Other', + 304: 'Not Modified', + 305: 'Use Proxy', + 307: 'Temporary Redirect', + 400: 'Bad Request', + 401: 'Unauthorized', + 402: 'Payment Required', # unused + 403: 'Forbidden', + 404: 'Not Found', + 405: 'Method Not Allowed', + 406: 'Not Acceptable', + 407: 'Proxy Authentication Required', + 408: 'Request Timeout', + 409: 'Conflict', + 410: 'Gone', + 411: 'Length Required', + 412: 'Precondition Failed', + 413: 'Request Entity Too Large', + 414: 'Request URI Too Long', + 415: 'Unsupported Media Type', + 416: 'Requested Range Not Satisfiable', + 417: 'Expectation Failed', + 418: 'I\'m a teapot', # see RFC 2324 + 422: 'Unprocessable Entity', + 423: 'Locked', + 424: 'Failed Dependency', + 426: 'Upgrade Required', + 428: 'Precondition Required', # see RFC 6585 + 429: 'Too Many Requests', + 431: 'Request Header Fields Too Large', + 449: 'Retry With', # proprietary MS extension + 451: 'Unavailable For Legal Reasons', + 500: 'Internal Server Error', + 501: 'Not Implemented', + 502: 'Bad Gateway', + 503: 'Service Unavailable', + 504: 'Gateway Timeout', + 505: 'HTTP Version Not Supported', + 507: 'Insufficient Storage', + 510: 'Not Extended' +} + + +def wsgi_to_bytes(data): + """coerce wsgi unicode represented bytes to real ones + + """ + if isinstance(data, bytes): + return data + return data.encode('latin1') # XXX: utf8 fallback? + + +def bytes_to_wsgi(data): + assert isinstance(data, bytes), 'data must be bytes' + if isinstance(data, str): + return data + else: + return data.decode('latin1') + + +def quote_header_value(value, extra_chars='', allow_token=True): + """Quote a header value if necessary. + + .. versionadded:: 0.5 + + :param value: the value to quote. + :param extra_chars: a list of extra characters to skip quoting. + :param allow_token: if this is enabled token values are returned + unchanged. + """ + if isinstance(value, bytes): + value = bytes_to_wsgi(value) + value = str(value) + if allow_token: + token_chars = _token_chars | set(extra_chars) + if set(value).issubset(token_chars): + return value + return '"%s"' % value.replace('\\', '\\\\').replace('"', '\\"') + + +def unquote_header_value(value, is_filename=False): + r"""Unquotes a header value. (Reversal of :func:`quote_header_value`). + This does not use the real unquoting but what browsers are actually + using for quoting. + + .. versionadded:: 0.5 + + :param value: the header value to unquote. + """ + if value and value[0] == value[-1] == '"': + # this is not the real unquoting, but fixing this so that the + # RFC is met will result in bugs with internet explorer and + # probably some other browsers as well. IE for example is + # uploading files with "C:\foo\bar.txt" as filename + value = value[1:-1] + + # if this is a filename and the starting characters look like + # a UNC path, then just return the value without quotes. Using the + # replace sequence below on a UNC path has the effect of turning + # the leading double slash into a single slash and then + # _fix_ie_filename() doesn't work correctly. See #458. + if not is_filename or value[:2] != '\\\\': + return value.replace('\\\\', '\\').replace('\\"', '"') + return value + + +def dump_options_header(header, options): + """The reverse function to :func:`parse_options_header`. + + :param header: the header to dump + :param options: a dict of options to append. + """ + segments = [] + if header is not None: + segments.append(header) + for key, value in iteritems(options): + if value is None: + segments.append(key) + else: + segments.append('%s=%s' % (key, quote_header_value(value))) + return '; '.join(segments) + + +def dump_header(iterable, allow_token=True): + """Dump an HTTP header again. This is the reversal of + :func:`parse_list_header`, :func:`parse_set_header` and + :func:`parse_dict_header`. This also quotes strings that include an + equals sign unless you pass it as dict of key, value pairs. + + >>> dump_header({'foo': 'bar baz'}) + 'foo="bar baz"' + >>> dump_header(('foo', 'bar baz')) + 'foo, "bar baz"' + + :param iterable: the iterable or dict of values to quote. + :param allow_token: if set to `False` tokens as values are disallowed. + See :func:`quote_header_value` for more details. + """ + if isinstance(iterable, dict): + items = [] + for key, value in iteritems(iterable): + if value is None: + items.append(key) + else: + items.append('%s=%s' % ( + key, + quote_header_value(value, allow_token=allow_token) + )) + else: + items = [quote_header_value(x, allow_token=allow_token) + for x in iterable] + return ', '.join(items) + + +def parse_list_header(value): + """Parse lists as described by RFC 2068 Section 2. + + In particular, parse comma-separated lists where the elements of + the list may include quoted-strings. A quoted-string could + contain a comma. A non-quoted string could have quotes in the + middle. Quotes are removed automatically after parsing. + + It basically works like :func:`parse_set_header` just that items + may appear multiple times and case sensitivity is preserved. + + The return value is a standard :class:`list`: + + >>> parse_list_header('token, "quoted value"') + ['token', 'quoted value'] + + To create a header from the :class:`list` again, use the + :func:`dump_header` function. + + :param value: a string with a list header. + :return: :class:`list` + """ + result = [] + for item in _parse_list_header(value): + if item[:1] == item[-1:] == '"': + item = unquote_header_value(item[1:-1]) + result.append(item) + return result + + +def parse_dict_header(value, cls=dict): + """Parse lists of key, value pairs as described by RFC 2068 Section 2 and + convert them into a python dict (or any other mapping object created from + the type with a dict like interface provided by the `cls` argument): + + >>> d = parse_dict_header('foo="is a fish", bar="as well"') + >>> type(d) is dict + True + >>> sorted(d.items()) + [('bar', 'as well'), ('foo', 'is a fish')] + + If there is no value for a key it will be `None`: + + >>> parse_dict_header('key_without_value') + {'key_without_value': None} + + To create a header from the :class:`dict` again, use the + :func:`dump_header` function. + + .. versionchanged:: 0.9 + Added support for `cls` argument. + + :param value: a string with a dict header. + :param cls: callable to use for storage of parsed results. + :return: an instance of `cls` + """ + result = cls() + if not isinstance(value, text_type): + # XXX: validate + value = bytes_to_wsgi(value) + for item in _parse_list_header(value): + if '=' not in item: + result[item] = None + continue + name, value = item.split('=', 1) + if value[:1] == value[-1:] == '"': + value = unquote_header_value(value[1:-1]) + result[name] = value + return result + + +def parse_options_header(value, multiple=False): + """Parse a ``Content-Type`` like header into a tuple with the content + type and the options: + + >>> parse_options_header('text/html; charset=utf8') + ('text/html', {'charset': 'utf8'}) + + This should not be used to parse ``Cache-Control`` like headers that use + a slightly different format. For these headers use the + :func:`parse_dict_header` function. + + .. versionadded:: 0.5 + + :param value: the header to parse. + :param multiple: Whether try to parse and return multiple MIME types + :return: (mimetype, options) or (mimetype, options, mimetype, options, …) + if multiple=True + """ + if not value: + return '', {} + + result = [] + + value = "," + value.replace("\n", ",") + while value: + match = _option_header_start_mime_type.match(value) + if not match: + break + result.append(match.group(1)) # mimetype + options = {} + # Parse options + rest = match.group(2) + while rest: + optmatch = _option_header_piece_re.match(rest) + if not optmatch: + break + option, encoding, _, option_value = optmatch.groups() + option = unquote_header_value(option) + if option_value is not None: + option_value = unquote_header_value( + option_value, + option == 'filename') + if encoding is not None: + option_value = _unquote(option_value).decode(encoding) + options[option] = option_value + rest = rest[optmatch.end():] + result.append(options) + if multiple is False: + return tuple(result) + value = rest + + return tuple(result) if result else ('', {}) + + +def parse_accept_header(value, cls=None): + """Parses an HTTP Accept-* header. This does not implement a complete + valid algorithm but one that supports at least value and quality + extraction. + + Returns a new :class:`Accept` object (basically a list of ``(value, quality)`` + tuples sorted by the quality with some additional accessor methods). + + The second parameter can be a subclass of :class:`Accept` that is created + with the parsed values and returned. + + :param value: the accept header string to be parsed. + :param cls: the wrapper class for the return value (can be + :class:`Accept` or a subclass thereof) + :return: an instance of `cls`. + """ + if cls is None: + cls = Accept + + if not value: + return cls(None) + + result = [] + for match in _accept_re.finditer(value): + quality = match.group(2) + if not quality: + quality = 1 + else: + quality = max(min(float(quality), 1), 0) + result.append((match.group(1), quality)) + return cls(result) + + +def parse_cache_control_header(value, on_update=None, cls=None): + """Parse a cache control header. The RFC differs between response and + request cache control, this method does not. It's your responsibility + to not use the wrong control statements. + + .. versionadded:: 0.5 + The `cls` was added. If not specified an immutable + :class:`~werkzeug.datastructures.RequestCacheControl` is returned. + + :param value: a cache control header to be parsed. + :param on_update: an optional callable that is called every time a value + on the :class:`~werkzeug.datastructures.CacheControl` + object is changed. + :param cls: the class for the returned object. By default + :class:`~werkzeug.datastructures.RequestCacheControl` is used. + :return: a `cls` object. + """ + if cls is None: + cls = RequestCacheControl + if not value: + return cls(None, on_update) + return cls(parse_dict_header(value), on_update) + + +def parse_set_header(value, on_update=None): + """Parse a set-like header and return a + :class:`~werkzeug.datastructures.HeaderSet` object: + + >>> hs = parse_set_header('token, "quoted value"') + + The return value is an object that treats the items case-insensitively + and keeps the order of the items: + + >>> 'TOKEN' in hs + True + >>> hs.index('quoted value') + 1 + >>> hs + HeaderSet(['token', 'quoted value']) + + To create a header from the :class:`HeaderSet` again, use the + :func:`dump_header` function. + + :param value: a set header to be parsed. + :param on_update: an optional callable that is called every time a + value on the :class:`~werkzeug.datastructures.HeaderSet` + object is changed. + :return: a :class:`~werkzeug.datastructures.HeaderSet` + """ + if not value: + return HeaderSet(None, on_update) + return HeaderSet(parse_list_header(value), on_update) + + +def parse_authorization_header(value): + """Parse an HTTP basic/digest authorization header transmitted by the web + browser. The return value is either `None` if the header was invalid or + not given, otherwise an :class:`~werkzeug.datastructures.Authorization` + object. + + :param value: the authorization header to parse. + :return: a :class:`~werkzeug.datastructures.Authorization` object or `None`. + """ + if not value: + return + value = wsgi_to_bytes(value) + try: + auth_type, auth_info = value.split(None, 1) + auth_type = auth_type.lower() + except ValueError: + return + if auth_type == b'basic': + try: + username, password = base64.b64decode(auth_info).split(b':', 1) + except Exception: + return + return Authorization('basic', {'username': bytes_to_wsgi(username), + 'password': bytes_to_wsgi(password)}) + elif auth_type == b'digest': + auth_map = parse_dict_header(auth_info) + for key in 'username', 'realm', 'nonce', 'uri', 'response': + if key not in auth_map: + return + if 'qop' in auth_map: + if not auth_map.get('nc') or not auth_map.get('cnonce'): + return + return Authorization('digest', auth_map) + + +def parse_www_authenticate_header(value, on_update=None): + """Parse an HTTP WWW-Authenticate header into a + :class:`~werkzeug.datastructures.WWWAuthenticate` object. + + :param value: a WWW-Authenticate header to parse. + :param on_update: an optional callable that is called every time a value + on the :class:`~werkzeug.datastructures.WWWAuthenticate` + object is changed. + :return: a :class:`~werkzeug.datastructures.WWWAuthenticate` object. + """ + if not value: + return WWWAuthenticate(on_update=on_update) + try: + auth_type, auth_info = value.split(None, 1) + auth_type = auth_type.lower() + except (ValueError, AttributeError): + return WWWAuthenticate(value.strip().lower(), on_update=on_update) + return WWWAuthenticate(auth_type, parse_dict_header(auth_info), + on_update) + + +def parse_if_range_header(value): + """Parses an if-range header which can be an etag or a date. Returns + a :class:`~werkzeug.datastructures.IfRange` object. + + .. versionadded:: 0.7 + """ + if not value: + return IfRange() + date = parse_date(value) + if date is not None: + return IfRange(date=date) + # drop weakness information + return IfRange(unquote_etag(value)[0]) + + +def parse_range_header(value, make_inclusive=True): + """Parses a range header into a :class:`~werkzeug.datastructures.Range` + object. If the header is missing or malformed `None` is returned. + `ranges` is a list of ``(start, stop)`` tuples where the ranges are + non-inclusive. + + .. versionadded:: 0.7 + """ + if not value or '=' not in value: + return None + + ranges = [] + last_end = 0 + units, rng = value.split('=', 1) + units = units.strip().lower() + + for item in rng.split(','): + item = item.strip() + if '-' not in item: + return None + if item.startswith('-'): + if last_end < 0: + return None + try: + begin = int(item) + except ValueError: + return None + end = None + last_end = -1 + elif '-' in item: + begin, end = item.split('-', 1) + begin = begin.strip() + end = end.strip() + if not begin.isdigit(): + return None + begin = int(begin) + if begin < last_end or last_end < 0: + return None + if end: + if not end.isdigit(): + return None + end = int(end) + 1 + if begin >= end: + return None + else: + end = None + last_end = end + ranges.append((begin, end)) + + return Range(units, ranges) + + +def parse_content_range_header(value, on_update=None): + """Parses a range header into a + :class:`~werkzeug.datastructures.ContentRange` object or `None` if + parsing is not possible. + + .. versionadded:: 0.7 + + :param value: a content range header to be parsed. + :param on_update: an optional callable that is called every time a value + on the :class:`~werkzeug.datastructures.ContentRange` + object is changed. + """ + if value is None: + return None + try: + units, rangedef = (value or '').strip().split(None, 1) + except ValueError: + return None + + if '/' not in rangedef: + return None + rng, length = rangedef.split('/', 1) + if length == '*': + length = None + elif length.isdigit(): + length = int(length) + else: + return None + + if rng == '*': + return ContentRange(units, None, None, length, on_update=on_update) + elif '-' not in rng: + return None + + start, stop = rng.split('-', 1) + try: + start = int(start) + stop = int(stop) + 1 + except ValueError: + return None + + if is_byte_range_valid(start, stop, length): + return ContentRange(units, start, stop, length, on_update=on_update) + + +def quote_etag(etag, weak=False): + """Quote an etag. + + :param etag: the etag to quote. + :param weak: set to `True` to tag it "weak". + """ + if '"' in etag: + raise ValueError('invalid etag') + etag = '"%s"' % etag + if weak: + etag = 'W/' + etag + return etag + + +def unquote_etag(etag): + """Unquote a single etag: + + >>> unquote_etag('W/"bar"') + ('bar', True) + >>> unquote_etag('"bar"') + ('bar', False) + + :param etag: the etag identifier to unquote. + :return: a ``(etag, weak)`` tuple. + """ + if not etag: + return None, None + etag = etag.strip() + weak = False + if etag.startswith(('W/', 'w/')): + weak = True + etag = etag[2:] + if etag[:1] == etag[-1:] == '"': + etag = etag[1:-1] + return etag, weak + + +def parse_etags(value): + """Parse an etag header. + + :param value: the tag header to parse + :return: an :class:`~werkzeug.datastructures.ETags` object. + """ + if not value: + return ETags() + strong = [] + weak = [] + end = len(value) + pos = 0 + while pos < end: + match = _etag_re.match(value, pos) + if match is None: + break + is_weak, quoted, raw = match.groups() + if raw == '*': + return ETags(star_tag=True) + elif quoted: + raw = quoted + if is_weak: + weak.append(raw) + else: + strong.append(raw) + pos = match.end() + return ETags(strong, weak) + + +def generate_etag(data): + """Generate an etag for some data.""" + return md5(data).hexdigest() + + +def parse_date(value): + """Parse one of the following date formats into a datetime object: + + .. sourcecode:: text + + Sun, 06 Nov 1994 08:49:37 GMT ; RFC 822, updated by RFC 1123 + Sunday, 06-Nov-94 08:49:37 GMT ; RFC 850, obsoleted by RFC 1036 + Sun Nov 6 08:49:37 1994 ; ANSI C's asctime() format + + If parsing fails the return value is `None`. + + :param value: a string with a supported date format. + :return: a :class:`datetime.datetime` object. + """ + if value: + t = parsedate_tz(value.strip()) + if t is not None: + try: + year = t[0] + # unfortunately that function does not tell us if two digit + # years were part of the string, or if they were prefixed + # with two zeroes. So what we do is to assume that 69-99 + # refer to 1900, and everything below to 2000 + if year >= 0 and year <= 68: + year += 2000 + elif year >= 69 and year <= 99: + year += 1900 + return datetime(*((year,) + t[1:7])) - \ + timedelta(seconds=t[-1] or 0) + except (ValueError, OverflowError): + return None + + +def _dump_date(d, delim): + """Used for `http_date` and `cookie_date`.""" + if d is None: + d = gmtime() + elif isinstance(d, datetime): + d = d.utctimetuple() + elif isinstance(d, (integer_types, float)): + d = gmtime(d) + return '%s, %02d%s%s%s%s %02d:%02d:%02d GMT' % ( + ('Mon', 'Tue', 'Wed', 'Thu', 'Fri', 'Sat', 'Sun')[d.tm_wday], + d.tm_mday, delim, + ('Jan', 'Feb', 'Mar', 'Apr', 'May', 'Jun', 'Jul', 'Aug', 'Sep', + 'Oct', 'Nov', 'Dec')[d.tm_mon - 1], + delim, str(d.tm_year), d.tm_hour, d.tm_min, d.tm_sec + ) + + +def cookie_date(expires=None): + """Formats the time to ensure compatibility with Netscape's cookie + standard. + + Accepts a floating point number expressed in seconds since the epoch in, a + datetime object or a timetuple. All times in UTC. The :func:`parse_date` + function can be used to parse such a date. + + Outputs a string in the format ``Wdy, DD-Mon-YYYY HH:MM:SS GMT``. + + :param expires: If provided that date is used, otherwise the current. + """ + return _dump_date(expires, '-') + + +def http_date(timestamp=None): + """Formats the time to match the RFC1123 date format. + + Accepts a floating point number expressed in seconds since the epoch in, a + datetime object or a timetuple. All times in UTC. The :func:`parse_date` + function can be used to parse such a date. + + Outputs a string in the format ``Wdy, DD Mon YYYY HH:MM:SS GMT``. + + :param timestamp: If provided that date is used, otherwise the current. + """ + return _dump_date(timestamp, ' ') + + +def parse_age(value=None): + """Parses a base-10 integer count of seconds into a timedelta. + + If parsing fails, the return value is `None`. + + :param value: a string consisting of an integer represented in base-10 + :return: a :class:`datetime.timedelta` object or `None`. + """ + if not value: + return None + try: + seconds = int(value) + except ValueError: + return None + if seconds < 0: + return None + try: + return timedelta(seconds=seconds) + except OverflowError: + return None + + +def dump_age(age=None): + """Formats the duration as a base-10 integer. + + :param age: should be an integer number of seconds, + a :class:`datetime.timedelta` object, or, + if the age is unknown, `None` (default). + """ + if age is None: + return + if isinstance(age, timedelta): + # do the equivalent of Python 2.7's timedelta.total_seconds(), + # but disregarding fractional seconds + age = age.seconds + (age.days * 24 * 3600) + + age = int(age) + if age < 0: + raise ValueError('age cannot be negative') + + return str(age) + + +def is_resource_modified(environ, etag=None, data=None, last_modified=None, + ignore_if_range=True): + """Convenience method for conditional requests. + + :param environ: the WSGI environment of the request to be checked. + :param etag: the etag for the response for comparison. + :param data: or alternatively the data of the response to automatically + generate an etag using :func:`generate_etag`. + :param last_modified: an optional date of the last modification. + :param ignore_if_range: If `False`, `If-Range` header will be taken into + account. + :return: `True` if the resource was modified, otherwise `False`. + """ + if etag is None and data is not None: + etag = generate_etag(data) + elif data is not None: + raise TypeError('both data and etag given') + if environ['REQUEST_METHOD'] not in ('GET', 'HEAD'): + return False + + unmodified = False + if isinstance(last_modified, string_types): + last_modified = parse_date(last_modified) + + # ensure that microsecond is zero because the HTTP spec does not transmit + # that either and we might have some false positives. See issue #39 + if last_modified is not None: + last_modified = last_modified.replace(microsecond=0) + + if_range = None + if not ignore_if_range and 'HTTP_RANGE' in environ: + # http://tools.ietf.org/html/rfc7233#section-3.2 + # A server MUST ignore an If-Range header field received in a request + # that does not contain a Range header field. + if_range = parse_if_range_header(environ.get('HTTP_IF_RANGE')) + + if if_range is not None and if_range.date is not None: + modified_since = if_range.date + else: + modified_since = parse_date(environ.get('HTTP_IF_MODIFIED_SINCE')) + + if modified_since and last_modified and last_modified <= modified_since: + unmodified = True + + if etag: + etag, _ = unquote_etag(etag) + if if_range is not None and if_range.etag is not None: + unmodified = parse_etags(if_range.etag).contains(etag) + else: + if_none_match = parse_etags(environ.get('HTTP_IF_NONE_MATCH')) + if if_none_match: + # http://tools.ietf.org/html/rfc7232#section-3.2 + # "A recipient MUST use the weak comparison function when comparing + # entity-tags for If-None-Match" + unmodified = if_none_match.contains_weak(etag) + + # https://tools.ietf.org/html/rfc7232#section-3.1 + # "Origin server MUST use the strong comparison function when + # comparing entity-tags for If-Match" + if_match = parse_etags(environ.get('HTTP_IF_MATCH')) + if if_match: + unmodified = not if_match.is_strong(etag) + + return not unmodified + + +def remove_entity_headers(headers, allowed=('expires', 'content-location')): + """Remove all entity headers from a list or :class:`Headers` object. This + operation works in-place. `Expires` and `Content-Location` headers are + by default not removed. The reason for this is :rfc:`2616` section + 10.3.5 which specifies some entity headers that should be sent. + + .. versionchanged:: 0.5 + added `allowed` parameter. + + :param headers: a list or :class:`Headers` object. + :param allowed: a list of headers that should still be allowed even though + they are entity headers. + """ + allowed = set(x.lower() for x in allowed) + headers[:] = [(key, value) for key, value in headers if + not is_entity_header(key) or key.lower() in allowed] + + +def remove_hop_by_hop_headers(headers): + """Remove all HTTP/1.1 "Hop-by-Hop" headers from a list or + :class:`Headers` object. This operation works in-place. + + .. versionadded:: 0.5 + + :param headers: a list or :class:`Headers` object. + """ + headers[:] = [(key, value) for key, value in headers if + not is_hop_by_hop_header(key)] + + +def is_entity_header(header): + """Check if a header is an entity header. + + .. versionadded:: 0.5 + + :param header: the header to test. + :return: `True` if it's an entity header, `False` otherwise. + """ + return header.lower() in _entity_headers + + +def is_hop_by_hop_header(header): + """Check if a header is an HTTP/1.1 "Hop-by-Hop" header. + + .. versionadded:: 0.5 + + :param header: the header to test. + :return: `True` if it's an HTTP/1.1 "Hop-by-Hop" header, `False` otherwise. + """ + return header.lower() in _hop_by_hop_headers + + +def parse_cookie(header, charset='utf-8', errors='replace', cls=None): + """Parse a cookie. Either from a string or WSGI environ. + + Per default encoding errors are ignored. If you want a different behavior + you can set `errors` to ``'replace'`` or ``'strict'``. In strict mode a + :exc:`HTTPUnicodeError` is raised. + + .. versionchanged:: 0.5 + This function now returns a :class:`TypeConversionDict` instead of a + regular dict. The `cls` parameter was added. + + :param header: the header to be used to parse the cookie. Alternatively + this can be a WSGI environment. + :param charset: the charset for the cookie values. + :param errors: the error behavior for the charset decoding. + :param cls: an optional dict class to use. If this is not specified + or `None` the default :class:`TypeConversionDict` is + used. + """ + if isinstance(header, dict): + header = header.get('HTTP_COOKIE', '') + elif header is None: + header = '' + + # If the value is an unicode string it's mangled through latin1. This + # is done because on PEP 3333 on Python 3 all headers are assumed latin1 + # which however is incorrect for cookies, which are sent in page encoding. + # As a result we + if isinstance(header, text_type): + header = header.encode('latin1', 'replace') + + if cls is None: + cls = TypeConversionDict + + def _parse_pairs(): + for key, val in _cookie_parse_impl(header): + key = to_unicode(key, charset, errors, allow_none_charset=True) + val = to_unicode(val, charset, errors, allow_none_charset=True) + yield try_coerce_native(key), val + + return cls(_parse_pairs()) + + +def dump_cookie(key, value='', max_age=None, expires=None, path='/', + domain=None, secure=False, httponly=False, + charset='utf-8', sync_expires=True, max_size=4093, + samesite=None): + """Creates a new Set-Cookie header without the ``Set-Cookie`` prefix + The parameters are the same as in the cookie Morsel object in the + Python standard library but it accepts unicode data, too. + + On Python 3 the return value of this function will be a unicode + string, on Python 2 it will be a native string. In both cases the + return value is usually restricted to ascii as the vast majority of + values are properly escaped, but that is no guarantee. If a unicode + string is returned it's tunneled through latin1 as required by + PEP 3333. + + The return value is not ASCII safe if the key contains unicode + characters. This is technically against the specification but + happens in the wild. It's strongly recommended to not use + non-ASCII values for the keys. + + :param max_age: should be a number of seconds, or `None` (default) if + the cookie should last only as long as the client's + browser session. Additionally `timedelta` objects + are accepted, too. + :param expires: should be a `datetime` object or unix timestamp. + :param path: limits the cookie to a given path, per default it will + span the whole domain. + :param domain: Use this if you want to set a cross-domain cookie. For + example, ``domain=".example.com"`` will set a cookie + that is readable by the domain ``www.example.com``, + ``foo.example.com`` etc. Otherwise, a cookie will only + be readable by the domain that set it. + :param secure: The cookie will only be available via HTTPS + :param httponly: disallow JavaScript to access the cookie. This is an + extension to the cookie standard and probably not + supported by all browsers. + :param charset: the encoding for unicode values. + :param sync_expires: automatically set expires if max_age is defined + but expires not. + :param max_size: Warn if the final header value exceeds this size. The + default, 4093, should be safely `supported by most browsers + `_. Set to 0 to disable this check. + :param samesite: Limits the scope of the cookie such that it will only + be attached to requests if those requests are "same-site". + + .. _`cookie`: http://browsercookielimits.squawky.net/ + """ + key = to_bytes(key, charset) + value = to_bytes(value, charset) + + if path is not None: + path = iri_to_uri(path, charset) + domain = _make_cookie_domain(domain) + if isinstance(max_age, timedelta): + max_age = (max_age.days * 60 * 60 * 24) + max_age.seconds + if expires is not None: + if not isinstance(expires, string_types): + expires = cookie_date(expires) + elif max_age is not None and sync_expires: + expires = to_bytes(cookie_date(time() + max_age)) + + samesite = samesite.title() if samesite else None + if samesite not in ('Strict', 'Lax', None): + raise ValueError("invalid SameSite value; must be 'Strict', 'Lax' or None") + + buf = [key + b'=' + _cookie_quote(value)] + + # XXX: In theory all of these parameters that are not marked with `None` + # should be quoted. Because stdlib did not quote it before I did not + # want to introduce quoting there now. + for k, v, q in ((b'Domain', domain, True), + (b'Expires', expires, False,), + (b'Max-Age', max_age, False), + (b'Secure', secure, None), + (b'HttpOnly', httponly, None), + (b'Path', path, False), + (b'SameSite', samesite, False)): + if q is None: + if v: + buf.append(k) + continue + + if v is None: + continue + + tmp = bytearray(k) + if not isinstance(v, (bytes, bytearray)): + v = to_bytes(text_type(v), charset) + if q: + v = _cookie_quote(v) + tmp += b'=' + v + buf.append(bytes(tmp)) + + # The return value will be an incorrectly encoded latin1 header on + # Python 3 for consistency with the headers object and a bytestring + # on Python 2 because that's how the API makes more sense. + rv = b'; '.join(buf) + if not PY2: + rv = rv.decode('latin1') + + # Warn if the final value of the cookie is less than the limit. If the + # cookie is too large, then it may be silently ignored, which can be quite + # hard to debug. + cookie_size = len(rv) + + if max_size and cookie_size > max_size: + value_size = len(value) + warnings.warn( + 'The "{key}" cookie is too large: the value was {value_size} bytes' + ' but the header required {extra_size} extra bytes. The final size' + ' was {cookie_size} bytes but the limit is {max_size} bytes.' + ' Browsers may silently ignore cookies larger than this.'.format( + key=key, + value_size=value_size, + extra_size=cookie_size - value_size, + cookie_size=cookie_size, + max_size=max_size + ), + stacklevel=2 + ) + + return rv + + +def is_byte_range_valid(start, stop, length): + """Checks if a given byte content range is valid for the given length. + + .. versionadded:: 0.7 + """ + if (start is None) != (stop is None): + return False + elif start is None: + return length is None or length >= 0 + elif length is None: + return 0 <= start < stop + elif start >= stop: + return False + return 0 <= start < length + + +# circular dependency fun +from werkzeug.datastructures import Accept, HeaderSet, ETags, Authorization, \ + WWWAuthenticate, TypeConversionDict, IfRange, Range, ContentRange, \ + RequestCacheControl + + +# DEPRECATED +# backwards compatible imports +from werkzeug.datastructures import ( # noqa + MIMEAccept, CharsetAccept, LanguageAccept, Headers +) +from werkzeug.urls import iri_to_uri diff --git a/pyextra/werkzeug/local.py b/pyextra/werkzeug/local.py new file mode 100644 index 00000000000000..e6d7478a0fd070 --- /dev/null +++ b/pyextra/werkzeug/local.py @@ -0,0 +1,420 @@ +# -*- coding: utf-8 -*- +""" + werkzeug.local + ~~~~~~~~~~~~~~ + + This module implements context-local objects. + + :copyright: (c) 2014 by the Werkzeug Team, see AUTHORS for more details. + :license: BSD, see LICENSE for more details. +""" +import copy +from functools import update_wrapper +from werkzeug.wsgi import ClosingIterator +from werkzeug._compat import PY2, implements_bool + +# since each thread has its own greenlet we can just use those as identifiers +# for the context. If greenlets are not available we fall back to the +# current thread ident depending on where it is. +try: + from greenlet import getcurrent as get_ident +except ImportError: + try: + from thread import get_ident + except ImportError: + from _thread import get_ident + + +def release_local(local): + """Releases the contents of the local for the current context. + This makes it possible to use locals without a manager. + + Example:: + + >>> loc = Local() + >>> loc.foo = 42 + >>> release_local(loc) + >>> hasattr(loc, 'foo') + False + + With this function one can release :class:`Local` objects as well + as :class:`LocalStack` objects. However it is not possible to + release data held by proxies that way, one always has to retain + a reference to the underlying local object in order to be able + to release it. + + .. versionadded:: 0.6.1 + """ + local.__release_local__() + + +class Local(object): + __slots__ = ('__storage__', '__ident_func__') + + def __init__(self): + object.__setattr__(self, '__storage__', {}) + object.__setattr__(self, '__ident_func__', get_ident) + + def __iter__(self): + return iter(self.__storage__.items()) + + def __call__(self, proxy): + """Create a proxy for a name.""" + return LocalProxy(self, proxy) + + def __release_local__(self): + self.__storage__.pop(self.__ident_func__(), None) + + def __getattr__(self, name): + try: + return self.__storage__[self.__ident_func__()][name] + except KeyError: + raise AttributeError(name) + + def __setattr__(self, name, value): + ident = self.__ident_func__() + storage = self.__storage__ + try: + storage[ident][name] = value + except KeyError: + storage[ident] = {name: value} + + def __delattr__(self, name): + try: + del self.__storage__[self.__ident_func__()][name] + except KeyError: + raise AttributeError(name) + + +class LocalStack(object): + + """This class works similar to a :class:`Local` but keeps a stack + of objects instead. This is best explained with an example:: + + >>> ls = LocalStack() + >>> ls.push(42) + >>> ls.top + 42 + >>> ls.push(23) + >>> ls.top + 23 + >>> ls.pop() + 23 + >>> ls.top + 42 + + They can be force released by using a :class:`LocalManager` or with + the :func:`release_local` function but the correct way is to pop the + item from the stack after using. When the stack is empty it will + no longer be bound to the current context (and as such released). + + By calling the stack without arguments it returns a proxy that resolves to + the topmost item on the stack. + + .. versionadded:: 0.6.1 + """ + + def __init__(self): + self._local = Local() + + def __release_local__(self): + self._local.__release_local__() + + def _get__ident_func__(self): + return self._local.__ident_func__ + + def _set__ident_func__(self, value): + object.__setattr__(self._local, '__ident_func__', value) + __ident_func__ = property(_get__ident_func__, _set__ident_func__) + del _get__ident_func__, _set__ident_func__ + + def __call__(self): + def _lookup(): + rv = self.top + if rv is None: + raise RuntimeError('object unbound') + return rv + return LocalProxy(_lookup) + + def push(self, obj): + """Pushes a new item to the stack""" + rv = getattr(self._local, 'stack', None) + if rv is None: + self._local.stack = rv = [] + rv.append(obj) + return rv + + def pop(self): + """Removes the topmost item from the stack, will return the + old value or `None` if the stack was already empty. + """ + stack = getattr(self._local, 'stack', None) + if stack is None: + return None + elif len(stack) == 1: + release_local(self._local) + return stack[-1] + else: + return stack.pop() + + @property + def top(self): + """The topmost item on the stack. If the stack is empty, + `None` is returned. + """ + try: + return self._local.stack[-1] + except (AttributeError, IndexError): + return None + + +class LocalManager(object): + + """Local objects cannot manage themselves. For that you need a local + manager. You can pass a local manager multiple locals or add them later + by appending them to `manager.locals`. Every time the manager cleans up, + it will clean up all the data left in the locals for this context. + + The `ident_func` parameter can be added to override the default ident + function for the wrapped locals. + + .. versionchanged:: 0.6.1 + Instead of a manager the :func:`release_local` function can be used + as well. + + .. versionchanged:: 0.7 + `ident_func` was added. + """ + + def __init__(self, locals=None, ident_func=None): + if locals is None: + self.locals = [] + elif isinstance(locals, Local): + self.locals = [locals] + else: + self.locals = list(locals) + if ident_func is not None: + self.ident_func = ident_func + for local in self.locals: + object.__setattr__(local, '__ident_func__', ident_func) + else: + self.ident_func = get_ident + + def get_ident(self): + """Return the context identifier the local objects use internally for + this context. You cannot override this method to change the behavior + but use it to link other context local objects (such as SQLAlchemy's + scoped sessions) to the Werkzeug locals. + + .. versionchanged:: 0.7 + You can pass a different ident function to the local manager that + will then be propagated to all the locals passed to the + constructor. + """ + return self.ident_func() + + def cleanup(self): + """Manually clean up the data in the locals for this context. Call + this at the end of the request or use `make_middleware()`. + """ + for local in self.locals: + release_local(local) + + def make_middleware(self, app): + """Wrap a WSGI application so that cleaning up happens after + request end. + """ + def application(environ, start_response): + return ClosingIterator(app(environ, start_response), self.cleanup) + return application + + def middleware(self, func): + """Like `make_middleware` but for decorating functions. + + Example usage:: + + @manager.middleware + def application(environ, start_response): + ... + + The difference to `make_middleware` is that the function passed + will have all the arguments copied from the inner application + (name, docstring, module). + """ + return update_wrapper(self.make_middleware(func), func) + + def __repr__(self): + return '<%s storages: %d>' % ( + self.__class__.__name__, + len(self.locals) + ) + + +@implements_bool +class LocalProxy(object): + + """Acts as a proxy for a werkzeug local. Forwards all operations to + a proxied object. The only operations not supported for forwarding + are right handed operands and any kind of assignment. + + Example usage:: + + from werkzeug.local import Local + l = Local() + + # these are proxies + request = l('request') + user = l('user') + + + from werkzeug.local import LocalStack + _response_local = LocalStack() + + # this is a proxy + response = _response_local() + + Whenever something is bound to l.user / l.request the proxy objects + will forward all operations. If no object is bound a :exc:`RuntimeError` + will be raised. + + To create proxies to :class:`Local` or :class:`LocalStack` objects, + call the object as shown above. If you want to have a proxy to an + object looked up by a function, you can (as of Werkzeug 0.6.1) pass + a function to the :class:`LocalProxy` constructor:: + + session = LocalProxy(lambda: get_current_request().session) + + .. versionchanged:: 0.6.1 + The class can be instantiated with a callable as well now. + """ + __slots__ = ('__local', '__dict__', '__name__', '__wrapped__') + + def __init__(self, local, name=None): + object.__setattr__(self, '_LocalProxy__local', local) + object.__setattr__(self, '__name__', name) + if callable(local) and not hasattr(local, '__release_local__'): + # "local" is a callable that is not an instance of Local or + # LocalManager: mark it as a wrapped function. + object.__setattr__(self, '__wrapped__', local) + + def _get_current_object(self): + """Return the current object. This is useful if you want the real + object behind the proxy at a time for performance reasons or because + you want to pass the object into a different context. + """ + if not hasattr(self.__local, '__release_local__'): + return self.__local() + try: + return getattr(self.__local, self.__name__) + except AttributeError: + raise RuntimeError('no object bound to %s' % self.__name__) + + @property + def __dict__(self): + try: + return self._get_current_object().__dict__ + except RuntimeError: + raise AttributeError('__dict__') + + def __repr__(self): + try: + obj = self._get_current_object() + except RuntimeError: + return '<%s unbound>' % self.__class__.__name__ + return repr(obj) + + def __bool__(self): + try: + return bool(self._get_current_object()) + except RuntimeError: + return False + + def __unicode__(self): + try: + return unicode(self._get_current_object()) # noqa + except RuntimeError: + return repr(self) + + def __dir__(self): + try: + return dir(self._get_current_object()) + except RuntimeError: + return [] + + def __getattr__(self, name): + if name == '__members__': + return dir(self._get_current_object()) + return getattr(self._get_current_object(), name) + + def __setitem__(self, key, value): + self._get_current_object()[key] = value + + def __delitem__(self, key): + del self._get_current_object()[key] + + if PY2: + __getslice__ = lambda x, i, j: x._get_current_object()[i:j] + + def __setslice__(self, i, j, seq): + self._get_current_object()[i:j] = seq + + def __delslice__(self, i, j): + del self._get_current_object()[i:j] + + __setattr__ = lambda x, n, v: setattr(x._get_current_object(), n, v) + __delattr__ = lambda x, n: delattr(x._get_current_object(), n) + __str__ = lambda x: str(x._get_current_object()) + __lt__ = lambda x, o: x._get_current_object() < o + __le__ = lambda x, o: x._get_current_object() <= o + __eq__ = lambda x, o: x._get_current_object() == o + __ne__ = lambda x, o: x._get_current_object() != o + __gt__ = lambda x, o: x._get_current_object() > o + __ge__ = lambda x, o: x._get_current_object() >= o + __cmp__ = lambda x, o: cmp(x._get_current_object(), o) # noqa + __hash__ = lambda x: hash(x._get_current_object()) + __call__ = lambda x, *a, **kw: x._get_current_object()(*a, **kw) + __len__ = lambda x: len(x._get_current_object()) + __getitem__ = lambda x, i: x._get_current_object()[i] + __iter__ = lambda x: iter(x._get_current_object()) + __contains__ = lambda x, i: i in x._get_current_object() + __add__ = lambda x, o: x._get_current_object() + o + __sub__ = lambda x, o: x._get_current_object() - o + __mul__ = lambda x, o: x._get_current_object() * o + __floordiv__ = lambda x, o: x._get_current_object() // o + __mod__ = lambda x, o: x._get_current_object() % o + __divmod__ = lambda x, o: x._get_current_object().__divmod__(o) + __pow__ = lambda x, o: x._get_current_object() ** o + __lshift__ = lambda x, o: x._get_current_object() << o + __rshift__ = lambda x, o: x._get_current_object() >> o + __and__ = lambda x, o: x._get_current_object() & o + __xor__ = lambda x, o: x._get_current_object() ^ o + __or__ = lambda x, o: x._get_current_object() | o + __div__ = lambda x, o: x._get_current_object().__div__(o) + __truediv__ = lambda x, o: x._get_current_object().__truediv__(o) + __neg__ = lambda x: -(x._get_current_object()) + __pos__ = lambda x: +(x._get_current_object()) + __abs__ = lambda x: abs(x._get_current_object()) + __invert__ = lambda x: ~(x._get_current_object()) + __complex__ = lambda x: complex(x._get_current_object()) + __int__ = lambda x: int(x._get_current_object()) + __long__ = lambda x: long(x._get_current_object()) # noqa + __float__ = lambda x: float(x._get_current_object()) + __oct__ = lambda x: oct(x._get_current_object()) + __hex__ = lambda x: hex(x._get_current_object()) + __index__ = lambda x: x._get_current_object().__index__() + __coerce__ = lambda x, o: x._get_current_object().__coerce__(x, o) + __enter__ = lambda x: x._get_current_object().__enter__() + __exit__ = lambda x, *a, **kw: x._get_current_object().__exit__(*a, **kw) + __radd__ = lambda x, o: o + x._get_current_object() + __rsub__ = lambda x, o: o - x._get_current_object() + __rmul__ = lambda x, o: o * x._get_current_object() + __rdiv__ = lambda x, o: o / x._get_current_object() + if PY2: + __rtruediv__ = lambda x, o: x._get_current_object().__rtruediv__(o) + else: + __rtruediv__ = __rdiv__ + __rfloordiv__ = lambda x, o: o // x._get_current_object() + __rmod__ = lambda x, o: o % x._get_current_object() + __rdivmod__ = lambda x, o: x._get_current_object().__rdivmod__(o) + __copy__ = lambda x: copy.copy(x._get_current_object()) + __deepcopy__ = lambda x, memo: copy.deepcopy(x._get_current_object(), memo) diff --git a/pyextra/werkzeug/posixemulation.py b/pyextra/werkzeug/posixemulation.py new file mode 100644 index 00000000000000..8fd6314f28a2b7 --- /dev/null +++ b/pyextra/werkzeug/posixemulation.py @@ -0,0 +1,106 @@ +# -*- coding: utf-8 -*- +r""" + werkzeug.posixemulation + ~~~~~~~~~~~~~~~~~~~~~~~ + + Provides a POSIX emulation for some features that are relevant to + web applications. The main purpose is to simplify support for + systems such as Windows NT that are not 100% POSIX compatible. + + Currently this only implements a :func:`rename` function that + follows POSIX semantics. Eg: if the target file already exists it + will be replaced without asking. + + This module was introduced in 0.6.1 and is not a public interface. + It might become one in later versions of Werkzeug. + + :copyright: (c) 2014 by the Werkzeug Team, see AUTHORS for more details. + :license: BSD, see LICENSE for more details. +""" +import sys +import os +import errno +import time +import random + +from ._compat import to_unicode +from .filesystem import get_filesystem_encoding + + +can_rename_open_file = False +if os.name == 'nt': # pragma: no cover + _rename = lambda src, dst: False + _rename_atomic = lambda src, dst: False + + try: + import ctypes + + _MOVEFILE_REPLACE_EXISTING = 0x1 + _MOVEFILE_WRITE_THROUGH = 0x8 + _MoveFileEx = ctypes.windll.kernel32.MoveFileExW + + def _rename(src, dst): + src = to_unicode(src, get_filesystem_encoding()) + dst = to_unicode(dst, get_filesystem_encoding()) + if _rename_atomic(src, dst): + return True + retry = 0 + rv = False + while not rv and retry < 100: + rv = _MoveFileEx(src, dst, _MOVEFILE_REPLACE_EXISTING | + _MOVEFILE_WRITE_THROUGH) + if not rv: + time.sleep(0.001) + retry += 1 + return rv + + # new in Vista and Windows Server 2008 + _CreateTransaction = ctypes.windll.ktmw32.CreateTransaction + _CommitTransaction = ctypes.windll.ktmw32.CommitTransaction + _MoveFileTransacted = ctypes.windll.kernel32.MoveFileTransactedW + _CloseHandle = ctypes.windll.kernel32.CloseHandle + can_rename_open_file = True + + def _rename_atomic(src, dst): + ta = _CreateTransaction(None, 0, 0, 0, 0, 1000, 'Werkzeug rename') + if ta == -1: + return False + try: + retry = 0 + rv = False + while not rv and retry < 100: + rv = _MoveFileTransacted(src, dst, None, None, + _MOVEFILE_REPLACE_EXISTING | + _MOVEFILE_WRITE_THROUGH, ta) + if rv: + rv = _CommitTransaction(ta) + break + else: + time.sleep(0.001) + retry += 1 + return rv + finally: + _CloseHandle(ta) + except Exception: + pass + + def rename(src, dst): + # Try atomic or pseudo-atomic rename + if _rename(src, dst): + return + # Fall back to "move away and replace" + try: + os.rename(src, dst) + except OSError as e: + if e.errno != errno.EEXIST: + raise + old = "%s-%08x" % (dst, random.randint(0, sys.maxint)) + os.rename(dst, old) + os.rename(src, dst) + try: + os.unlink(old) + except Exception: + pass +else: + rename = os.rename + can_rename_open_file = True diff --git a/pyextra/werkzeug/routing.py b/pyextra/werkzeug/routing.py new file mode 100644 index 00000000000000..2e4e2f42c1c264 --- /dev/null +++ b/pyextra/werkzeug/routing.py @@ -0,0 +1,1792 @@ +# -*- coding: utf-8 -*- +""" + werkzeug.routing + ~~~~~~~~~~~~~~~~ + + When it comes to combining multiple controller or view functions (however + you want to call them) you need a dispatcher. A simple way would be + applying regular expression tests on the ``PATH_INFO`` and calling + registered callback functions that return the value then. + + This module implements a much more powerful system than simple regular + expression matching because it can also convert values in the URLs and + build URLs. + + Here a simple example that creates an URL map for an application with + two subdomains (www and kb) and some URL rules: + + >>> m = Map([ + ... # Static URLs + ... Rule('/', endpoint='static/index'), + ... Rule('/about', endpoint='static/about'), + ... Rule('/help', endpoint='static/help'), + ... # Knowledge Base + ... Subdomain('kb', [ + ... Rule('/', endpoint='kb/index'), + ... Rule('/browse/', endpoint='kb/browse'), + ... Rule('/browse//', endpoint='kb/browse'), + ... Rule('/browse//', endpoint='kb/browse') + ... ]) + ... ], default_subdomain='www') + + If the application doesn't use subdomains it's perfectly fine to not set + the default subdomain and not use the `Subdomain` rule factory. The endpoint + in the rules can be anything, for example import paths or unique + identifiers. The WSGI application can use those endpoints to get the + handler for that URL. It doesn't have to be a string at all but it's + recommended. + + Now it's possible to create a URL adapter for one of the subdomains and + build URLs: + + >>> c = m.bind('example.com') + >>> c.build("kb/browse", dict(id=42)) + 'http://kb.example.com/browse/42/' + >>> c.build("kb/browse", dict()) + 'http://kb.example.com/browse/' + >>> c.build("kb/browse", dict(id=42, page=3)) + 'http://kb.example.com/browse/42/3' + >>> c.build("static/about") + '/about' + >>> c.build("static/index", force_external=True) + 'http://www.example.com/' + + >>> c = m.bind('example.com', subdomain='kb') + >>> c.build("static/about") + 'http://www.example.com/about' + + The first argument to bind is the server name *without* the subdomain. + Per default it will assume that the script is mounted on the root, but + often that's not the case so you can provide the real mount point as + second argument: + + >>> c = m.bind('example.com', '/applications/example') + + The third argument can be the subdomain, if not given the default + subdomain is used. For more details about binding have a look at the + documentation of the `MapAdapter`. + + And here is how you can match URLs: + + >>> c = m.bind('example.com') + >>> c.match("/") + ('static/index', {}) + >>> c.match("/about") + ('static/about', {}) + >>> c = m.bind('example.com', '/', 'kb') + >>> c.match("/") + ('kb/index', {}) + >>> c.match("/browse/42/23") + ('kb/browse', {'id': 42, 'page': 23}) + + If matching fails you get a `NotFound` exception, if the rule thinks + it's a good idea to redirect (for example because the URL was defined + to have a slash at the end but the request was missing that slash) it + will raise a `RequestRedirect` exception. Both are subclasses of the + `HTTPException` so you can use those errors as responses in the + application. + + If matching succeeded but the URL rule was incompatible to the given + method (for example there were only rules for `GET` and `HEAD` and + routing system tried to match a `POST` request) a `MethodNotAllowed` + exception is raised. + + + :copyright: (c) 2014 by the Werkzeug Team, see AUTHORS for more details. + :license: BSD, see LICENSE for more details. +""" +import difflib +import re +import uuid +import posixpath + +from pprint import pformat +from threading import Lock + +from werkzeug.urls import url_encode, url_quote, url_join +from werkzeug.utils import redirect, format_string +from werkzeug.exceptions import HTTPException, NotFound, MethodNotAllowed, \ + BadHost +from werkzeug._internal import _get_environ, _encode_idna +from werkzeug._compat import itervalues, iteritems, to_unicode, to_bytes, \ + text_type, string_types, native_string_result, \ + implements_to_string, wsgi_decoding_dance +from werkzeug.datastructures import ImmutableDict, MultiDict +from werkzeug.utils import cached_property + + +_rule_re = re.compile(r''' + (?P[^<]*) # static rule data + < + (?: + (?P[a-zA-Z_][a-zA-Z0-9_]*) # converter name + (?:\((?P.*?)\))? # converter arguments + \: # variable delimiter + )? + (?P[a-zA-Z_][a-zA-Z0-9_]*) # variable name + > +''', re.VERBOSE) +_simple_rule_re = re.compile(r'<([^>]+)>') +_converter_args_re = re.compile(r''' + ((?P\w+)\s*=\s*)? + (?P + True|False| + \d+.\d+| + \d+.| + \d+| + [\w\d_.]+| + [urUR]?(?P"[^"]*?"|'[^']*') + )\s*, +''', re.VERBOSE | re.UNICODE) + + +_PYTHON_CONSTANTS = { + 'None': None, + 'True': True, + 'False': False +} + + +def _pythonize(value): + if value in _PYTHON_CONSTANTS: + return _PYTHON_CONSTANTS[value] + for convert in int, float: + try: + return convert(value) + except ValueError: + pass + if value[:1] == value[-1:] and value[0] in '"\'': + value = value[1:-1] + return text_type(value) + + +def parse_converter_args(argstr): + argstr += ',' + args = [] + kwargs = {} + + for item in _converter_args_re.finditer(argstr): + value = item.group('stringval') + if value is None: + value = item.group('value') + value = _pythonize(value) + if not item.group('name'): + args.append(value) + else: + name = item.group('name') + kwargs[name] = value + + return tuple(args), kwargs + + +def parse_rule(rule): + """Parse a rule and return it as generator. Each iteration yields tuples + in the form ``(converter, arguments, variable)``. If the converter is + `None` it's a static url part, otherwise it's a dynamic one. + + :internal: + """ + pos = 0 + end = len(rule) + do_match = _rule_re.match + used_names = set() + while pos < end: + m = do_match(rule, pos) + if m is None: + break + data = m.groupdict() + if data['static']: + yield None, None, data['static'] + variable = data['variable'] + converter = data['converter'] or 'default' + if variable in used_names: + raise ValueError('variable name %r used twice.' % variable) + used_names.add(variable) + yield converter, data['args'] or None, variable + pos = m.end() + if pos < end: + remaining = rule[pos:] + if '>' in remaining or '<' in remaining: + raise ValueError('malformed url rule: %r' % rule) + yield None, None, remaining + + +class RoutingException(Exception): + + """Special exceptions that require the application to redirect, notifying + about missing urls, etc. + + :internal: + """ + + +class RequestRedirect(HTTPException, RoutingException): + + """Raise if the map requests a redirect. This is for example the case if + `strict_slashes` are activated and an url that requires a trailing slash. + + The attribute `new_url` contains the absolute destination url. + """ + code = 301 + + def __init__(self, new_url): + RoutingException.__init__(self, new_url) + self.new_url = new_url + + def get_response(self, environ): + return redirect(self.new_url, self.code) + + +class RequestSlash(RoutingException): + + """Internal exception.""" + + +class RequestAliasRedirect(RoutingException): + + """This rule is an alias and wants to redirect to the canonical URL.""" + + def __init__(self, matched_values): + self.matched_values = matched_values + + +@implements_to_string +class BuildError(RoutingException, LookupError): + + """Raised if the build system cannot find a URL for an endpoint with the + values provided. + """ + + def __init__(self, endpoint, values, method, adapter=None): + LookupError.__init__(self, endpoint, values, method) + self.endpoint = endpoint + self.values = values + self.method = method + self.adapter = adapter + + @cached_property + def suggested(self): + return self.closest_rule(self.adapter) + + def closest_rule(self, adapter): + def _score_rule(rule): + return sum([ + 0.98 * difflib.SequenceMatcher( + None, rule.endpoint, self.endpoint + ).ratio(), + 0.01 * bool(set(self.values or ()).issubset(rule.arguments)), + 0.01 * bool(rule.methods and self.method in rule.methods) + ]) + + if adapter and adapter.map._rules: + return max(adapter.map._rules, key=_score_rule) + + def __str__(self): + message = [] + message.append('Could not build url for endpoint %r' % self.endpoint) + if self.method: + message.append(' (%r)' % self.method) + if self.values: + message.append(' with values %r' % sorted(self.values.keys())) + message.append('.') + if self.suggested: + if self.endpoint == self.suggested.endpoint: + if self.method and self.method not in self.suggested.methods: + message.append(' Did you mean to use methods %r?' % sorted( + self.suggested.methods + )) + missing_values = self.suggested.arguments.union( + set(self.suggested.defaults or ()) + ) - set(self.values.keys()) + if missing_values: + message.append( + ' Did you forget to specify values %r?' % + sorted(missing_values) + ) + else: + message.append( + ' Did you mean %r instead?' % self.suggested.endpoint + ) + return u''.join(message) + + +class ValidationError(ValueError): + + """Validation error. If a rule converter raises this exception the rule + does not match the current URL and the next URL is tried. + """ + + +class RuleFactory(object): + + """As soon as you have more complex URL setups it's a good idea to use rule + factories to avoid repetitive tasks. Some of them are builtin, others can + be added by subclassing `RuleFactory` and overriding `get_rules`. + """ + + def get_rules(self, map): + """Subclasses of `RuleFactory` have to override this method and return + an iterable of rules.""" + raise NotImplementedError() + + +class Subdomain(RuleFactory): + + """All URLs provided by this factory have the subdomain set to a + specific domain. For example if you want to use the subdomain for + the current language this can be a good setup:: + + url_map = Map([ + Rule('/', endpoint='#select_language'), + Subdomain('', [ + Rule('/', endpoint='index'), + Rule('/about', endpoint='about'), + Rule('/help', endpoint='help') + ]) + ]) + + All the rules except for the ``'#select_language'`` endpoint will now + listen on a two letter long subdomain that holds the language code + for the current request. + """ + + def __init__(self, subdomain, rules): + self.subdomain = subdomain + self.rules = rules + + def get_rules(self, map): + for rulefactory in self.rules: + for rule in rulefactory.get_rules(map): + rule = rule.empty() + rule.subdomain = self.subdomain + yield rule + + +class Submount(RuleFactory): + + """Like `Subdomain` but prefixes the URL rule with a given string:: + + url_map = Map([ + Rule('/', endpoint='index'), + Submount('/blog', [ + Rule('/', endpoint='blog/index'), + Rule('/entry/', endpoint='blog/show') + ]) + ]) + + Now the rule ``'blog/show'`` matches ``/blog/entry/``. + """ + + def __init__(self, path, rules): + self.path = path.rstrip('/') + self.rules = rules + + def get_rules(self, map): + for rulefactory in self.rules: + for rule in rulefactory.get_rules(map): + rule = rule.empty() + rule.rule = self.path + rule.rule + yield rule + + +class EndpointPrefix(RuleFactory): + + """Prefixes all endpoints (which must be strings for this factory) with + another string. This can be useful for sub applications:: + + url_map = Map([ + Rule('/', endpoint='index'), + EndpointPrefix('blog/', [Submount('/blog', [ + Rule('/', endpoint='index'), + Rule('/entry/', endpoint='show') + ])]) + ]) + """ + + def __init__(self, prefix, rules): + self.prefix = prefix + self.rules = rules + + def get_rules(self, map): + for rulefactory in self.rules: + for rule in rulefactory.get_rules(map): + rule = rule.empty() + rule.endpoint = self.prefix + rule.endpoint + yield rule + + +class RuleTemplate(object): + + """Returns copies of the rules wrapped and expands string templates in + the endpoint, rule, defaults or subdomain sections. + + Here a small example for such a rule template:: + + from werkzeug.routing import Map, Rule, RuleTemplate + + resource = RuleTemplate([ + Rule('/$name/', endpoint='$name.list'), + Rule('/$name/', endpoint='$name.show') + ]) + + url_map = Map([resource(name='user'), resource(name='page')]) + + When a rule template is called the keyword arguments are used to + replace the placeholders in all the string parameters. + """ + + def __init__(self, rules): + self.rules = list(rules) + + def __call__(self, *args, **kwargs): + return RuleTemplateFactory(self.rules, dict(*args, **kwargs)) + + +class RuleTemplateFactory(RuleFactory): + + """A factory that fills in template variables into rules. Used by + `RuleTemplate` internally. + + :internal: + """ + + def __init__(self, rules, context): + self.rules = rules + self.context = context + + def get_rules(self, map): + for rulefactory in self.rules: + for rule in rulefactory.get_rules(map): + new_defaults = subdomain = None + if rule.defaults: + new_defaults = {} + for key, value in iteritems(rule.defaults): + if isinstance(value, string_types): + value = format_string(value, self.context) + new_defaults[key] = value + if rule.subdomain is not None: + subdomain = format_string(rule.subdomain, self.context) + new_endpoint = rule.endpoint + if isinstance(new_endpoint, string_types): + new_endpoint = format_string(new_endpoint, self.context) + yield Rule( + format_string(rule.rule, self.context), + new_defaults, + subdomain, + rule.methods, + rule.build_only, + new_endpoint, + rule.strict_slashes + ) + + +@implements_to_string +class Rule(RuleFactory): + + """A Rule represents one URL pattern. There are some options for `Rule` + that change the way it behaves and are passed to the `Rule` constructor. + Note that besides the rule-string all arguments *must* be keyword arguments + in order to not break the application on Werkzeug upgrades. + + `string` + Rule strings basically are just normal URL paths with placeholders in + the format ```` where the converter and the + arguments are optional. If no converter is defined the `default` + converter is used which means `string` in the normal configuration. + + URL rules that end with a slash are branch URLs, others are leaves. + If you have `strict_slashes` enabled (which is the default), all + branch URLs that are matched without a trailing slash will trigger a + redirect to the same URL with the missing slash appended. + + The converters are defined on the `Map`. + + `endpoint` + The endpoint for this rule. This can be anything. A reference to a + function, a string, a number etc. The preferred way is using a string + because the endpoint is used for URL generation. + + `defaults` + An optional dict with defaults for other rules with the same endpoint. + This is a bit tricky but useful if you want to have unique URLs:: + + url_map = Map([ + Rule('/all/', defaults={'page': 1}, endpoint='all_entries'), + Rule('/all/page/', endpoint='all_entries') + ]) + + If a user now visits ``http://example.com/all/page/1`` he will be + redirected to ``http://example.com/all/``. If `redirect_defaults` is + disabled on the `Map` instance this will only affect the URL + generation. + + `subdomain` + The subdomain rule string for this rule. If not specified the rule + only matches for the `default_subdomain` of the map. If the map is + not bound to a subdomain this feature is disabled. + + Can be useful if you want to have user profiles on different subdomains + and all subdomains are forwarded to your application:: + + url_map = Map([ + Rule('/', subdomain='', endpoint='user/homepage'), + Rule('/stats', subdomain='', endpoint='user/stats') + ]) + + `methods` + A sequence of http methods this rule applies to. If not specified, all + methods are allowed. For example this can be useful if you want different + endpoints for `POST` and `GET`. If methods are defined and the path + matches but the method matched against is not in this list or in the + list of another rule for that path the error raised is of the type + `MethodNotAllowed` rather than `NotFound`. If `GET` is present in the + list of methods and `HEAD` is not, `HEAD` is added automatically. + + .. versionchanged:: 0.6.1 + `HEAD` is now automatically added to the methods if `GET` is + present. The reason for this is that existing code often did not + work properly in servers not rewriting `HEAD` to `GET` + automatically and it was not documented how `HEAD` should be + treated. This was considered a bug in Werkzeug because of that. + + `strict_slashes` + Override the `Map` setting for `strict_slashes` only for this rule. If + not specified the `Map` setting is used. + + `build_only` + Set this to True and the rule will never match but will create a URL + that can be build. This is useful if you have resources on a subdomain + or folder that are not handled by the WSGI application (like static data) + + `redirect_to` + If given this must be either a string or callable. In case of a + callable it's called with the url adapter that triggered the match and + the values of the URL as keyword arguments and has to return the target + for the redirect, otherwise it has to be a string with placeholders in + rule syntax:: + + def foo_with_slug(adapter, id): + # ask the database for the slug for the old id. this of + # course has nothing to do with werkzeug. + return 'foo/' + Foo.get_slug_for_id(id) + + url_map = Map([ + Rule('/foo/', endpoint='foo'), + Rule('/some/old/url/', redirect_to='foo/'), + Rule('/other/old/url/', redirect_to=foo_with_slug) + ]) + + When the rule is matched the routing system will raise a + `RequestRedirect` exception with the target for the redirect. + + Keep in mind that the URL will be joined against the URL root of the + script so don't use a leading slash on the target URL unless you + really mean root of that domain. + + `alias` + If enabled this rule serves as an alias for another rule with the same + endpoint and arguments. + + `host` + If provided and the URL map has host matching enabled this can be + used to provide a match rule for the whole host. This also means + that the subdomain feature is disabled. + + .. versionadded:: 0.7 + The `alias` and `host` parameters were added. + """ + + def __init__(self, string, defaults=None, subdomain=None, methods=None, + build_only=False, endpoint=None, strict_slashes=None, + redirect_to=None, alias=False, host=None): + if not string.startswith('/'): + raise ValueError('urls must start with a leading slash') + self.rule = string + self.is_leaf = not string.endswith('/') + + self.map = None + self.strict_slashes = strict_slashes + self.subdomain = subdomain + self.host = host + self.defaults = defaults + self.build_only = build_only + self.alias = alias + if methods is None: + self.methods = None + else: + if isinstance(methods, str): + raise TypeError('param `methods` should be `Iterable[str]`, not `str`') + self.methods = set([x.upper() for x in methods]) + if 'HEAD' not in self.methods and 'GET' in self.methods: + self.methods.add('HEAD') + self.endpoint = endpoint + self.redirect_to = redirect_to + + if defaults: + self.arguments = set(map(str, defaults)) + else: + self.arguments = set() + self._trace = self._converters = self._regex = self._argument_weights = None + + def empty(self): + """ + Return an unbound copy of this rule. + + This can be useful if want to reuse an already bound URL for another + map. See ``get_empty_kwargs`` to override what keyword arguments are + provided to the new copy. + """ + return type(self)(self.rule, **self.get_empty_kwargs()) + + def get_empty_kwargs(self): + """ + Provides kwargs for instantiating empty copy with empty() + + Use this method to provide custom keyword arguments to the subclass of + ``Rule`` when calling ``some_rule.empty()``. Helpful when the subclass + has custom keyword arguments that are needed at instantiation. + + Must return a ``dict`` that will be provided as kwargs to the new + instance of ``Rule``, following the initial ``self.rule`` value which + is always provided as the first, required positional argument. + """ + defaults = None + if self.defaults: + defaults = dict(self.defaults) + return dict(defaults=defaults, subdomain=self.subdomain, + methods=self.methods, build_only=self.build_only, + endpoint=self.endpoint, strict_slashes=self.strict_slashes, + redirect_to=self.redirect_to, alias=self.alias, + host=self.host) + + def get_rules(self, map): + yield self + + def refresh(self): + """Rebinds and refreshes the URL. Call this if you modified the + rule in place. + + :internal: + """ + self.bind(self.map, rebind=True) + + def bind(self, map, rebind=False): + """Bind the url to a map and create a regular expression based on + the information from the rule itself and the defaults from the map. + + :internal: + """ + if self.map is not None and not rebind: + raise RuntimeError('url rule %r already bound to map %r' % + (self, self.map)) + self.map = map + if self.strict_slashes is None: + self.strict_slashes = map.strict_slashes + if self.subdomain is None: + self.subdomain = map.default_subdomain + self.compile() + + def get_converter(self, variable_name, converter_name, args, kwargs): + """Looks up the converter for the given parameter. + + .. versionadded:: 0.9 + """ + if converter_name not in self.map.converters: + raise LookupError('the converter %r does not exist' % converter_name) + return self.map.converters[converter_name](self.map, *args, **kwargs) + + def compile(self): + """Compiles the regular expression and stores it.""" + assert self.map is not None, 'rule not bound' + + if self.map.host_matching: + domain_rule = self.host or '' + else: + domain_rule = self.subdomain or '' + + self._trace = [] + self._converters = {} + self._static_weights = [] + self._argument_weights = [] + regex_parts = [] + + def _build_regex(rule): + index = 0 + for converter, arguments, variable in parse_rule(rule): + if converter is None: + regex_parts.append(re.escape(variable)) + self._trace.append((False, variable)) + for part in variable.split('/'): + if part: + self._static_weights.append((index, -len(part))) + else: + if arguments: + c_args, c_kwargs = parse_converter_args(arguments) + else: + c_args = () + c_kwargs = {} + convobj = self.get_converter( + variable, converter, c_args, c_kwargs) + regex_parts.append('(?P<%s>%s)' % (variable, convobj.regex)) + self._converters[variable] = convobj + self._trace.append((True, variable)) + self._argument_weights.append(convobj.weight) + self.arguments.add(str(variable)) + index = index + 1 + + _build_regex(domain_rule) + regex_parts.append('\\|') + self._trace.append((False, '|')) + _build_regex(self.is_leaf and self.rule or self.rule.rstrip('/')) + if not self.is_leaf: + self._trace.append((False, '/')) + + if self.build_only: + return + regex = r'^%s%s$' % ( + u''.join(regex_parts), + (not self.is_leaf or not self.strict_slashes) and + '(?/?)' or '' + ) + self._regex = re.compile(regex, re.UNICODE) + + def match(self, path, method=None): + """Check if the rule matches a given path. Path is a string in the + form ``"subdomain|/path"`` and is assembled by the map. If + the map is doing host matching the subdomain part will be the host + instead. + + If the rule matches a dict with the converted values is returned, + otherwise the return value is `None`. + + :internal: + """ + if not self.build_only: + m = self._regex.search(path) + if m is not None: + groups = m.groupdict() + # we have a folder like part of the url without a trailing + # slash and strict slashes enabled. raise an exception that + # tells the map to redirect to the same url but with a + # trailing slash + if self.strict_slashes and not self.is_leaf and \ + not groups.pop('__suffix__') and \ + (method is None or self.methods is None or + method in self.methods): + raise RequestSlash() + # if we are not in strict slashes mode we have to remove + # a __suffix__ + elif not self.strict_slashes: + del groups['__suffix__'] + + result = {} + for name, value in iteritems(groups): + try: + value = self._converters[name].to_python(value) + except ValidationError: + return + result[str(name)] = value + if self.defaults: + result.update(self.defaults) + + if self.alias and self.map.redirect_defaults: + raise RequestAliasRedirect(result) + + return result + + def build(self, values, append_unknown=True): + """Assembles the relative url for that rule and the subdomain. + If building doesn't work for some reasons `None` is returned. + + :internal: + """ + tmp = [] + add = tmp.append + processed = set(self.arguments) + for is_dynamic, data in self._trace: + if is_dynamic: + try: + add(self._converters[data].to_url(values[data])) + except ValidationError: + return + processed.add(data) + else: + add(url_quote(to_bytes(data, self.map.charset), safe='/:|+')) + domain_part, url = (u''.join(tmp)).split(u'|', 1) + + if append_unknown: + query_vars = MultiDict(values) + for key in processed: + if key in query_vars: + del query_vars[key] + + if query_vars: + url += u'?' + url_encode(query_vars, charset=self.map.charset, + sort=self.map.sort_parameters, + key=self.map.sort_key) + + return domain_part, url + + def provides_defaults_for(self, rule): + """Check if this rule has defaults for a given rule. + + :internal: + """ + return not self.build_only and self.defaults and \ + self.endpoint == rule.endpoint and self != rule and \ + self.arguments == rule.arguments + + def suitable_for(self, values, method=None): + """Check if the dict of values has enough data for url generation. + + :internal: + """ + # if a method was given explicitly and that method is not supported + # by this rule, this rule is not suitable. + if method is not None and self.methods is not None \ + and method not in self.methods: + return False + + defaults = self.defaults or () + + # all arguments required must be either in the defaults dict or + # the value dictionary otherwise it's not suitable + for key in self.arguments: + if key not in defaults and key not in values: + return False + + # in case defaults are given we ensure taht either the value was + # skipped or the value is the same as the default value. + if defaults: + for key, value in iteritems(defaults): + if key in values and value != values[key]: + return False + + return True + + def match_compare_key(self): + """The match compare key for sorting. + + Current implementation: + + 1. rules without any arguments come first for performance + reasons only as we expect them to match faster and some + common ones usually don't have any arguments (index pages etc.) + 2. rules with more static parts come first so the second argument + is the negative length of the number of the static weights. + 3. we order by static weights, which is a combination of index + and length + 4. The more complex rules come first so the next argument is the + negative length of the number of argument weights. + 5. lastly we order by the actual argument weights. + + :internal: + """ + return bool(self.arguments), -len(self._static_weights), self._static_weights,\ + -len(self._argument_weights), self._argument_weights + + def build_compare_key(self): + """The build compare key for sorting. + + :internal: + """ + return self.alias and 1 or 0, -len(self.arguments), \ + -len(self.defaults or ()) + + def __eq__(self, other): + return self.__class__ is other.__class__ and \ + self._trace == other._trace + + __hash__ = None + + def __ne__(self, other): + return not self.__eq__(other) + + def __str__(self): + return self.rule + + @native_string_result + def __repr__(self): + if self.map is None: + return u'<%s (unbound)>' % self.__class__.__name__ + tmp = [] + for is_dynamic, data in self._trace: + if is_dynamic: + tmp.append(u'<%s>' % data) + else: + tmp.append(data) + return u'<%s %s%s -> %s>' % ( + self.__class__.__name__, + repr((u''.join(tmp)).lstrip(u'|')).lstrip(u'u'), + self.methods is not None + and u' (%s)' % u', '.join(self.methods) + or u'', + self.endpoint + ) + + +class BaseConverter(object): + + """Base class for all converters.""" + regex = '[^/]+' + weight = 100 + + def __init__(self, map): + self.map = map + + def to_python(self, value): + return value + + def to_url(self, value): + return url_quote(value, charset=self.map.charset) + + +class UnicodeConverter(BaseConverter): + + """This converter is the default converter and accepts any string but + only one path segment. Thus the string can not include a slash. + + This is the default validator. + + Example:: + + Rule('/pages/'), + Rule('/') + + :param map: the :class:`Map`. + :param minlength: the minimum length of the string. Must be greater + or equal 1. + :param maxlength: the maximum length of the string. + :param length: the exact length of the string. + """ + + def __init__(self, map, minlength=1, maxlength=None, length=None): + BaseConverter.__init__(self, map) + if length is not None: + length = '{%d}' % int(length) + else: + if maxlength is None: + maxlength = '' + else: + maxlength = int(maxlength) + length = '{%s,%s}' % ( + int(minlength), + maxlength + ) + self.regex = '[^/]' + length + + +class AnyConverter(BaseConverter): + + """Matches one of the items provided. Items can either be Python + identifiers or strings:: + + Rule('/') + + :param map: the :class:`Map`. + :param items: this function accepts the possible items as positional + arguments. + """ + + def __init__(self, map, *items): + BaseConverter.__init__(self, map) + self.regex = '(?:%s)' % '|'.join([re.escape(x) for x in items]) + + +class PathConverter(BaseConverter): + + """Like the default :class:`UnicodeConverter`, but it also matches + slashes. This is useful for wikis and similar applications:: + + Rule('/') + Rule('//edit') + + :param map: the :class:`Map`. + """ + regex = '[^/].*?' + weight = 200 + + +class NumberConverter(BaseConverter): + + """Baseclass for `IntegerConverter` and `FloatConverter`. + + :internal: + """ + weight = 50 + + def __init__(self, map, fixed_digits=0, min=None, max=None): + BaseConverter.__init__(self, map) + self.fixed_digits = fixed_digits + self.min = min + self.max = max + + def to_python(self, value): + if (self.fixed_digits and len(value) != self.fixed_digits): + raise ValidationError() + value = self.num_convert(value) + if (self.min is not None and value < self.min) or \ + (self.max is not None and value > self.max): + raise ValidationError() + return value + + def to_url(self, value): + value = self.num_convert(value) + if self.fixed_digits: + value = ('%%0%sd' % self.fixed_digits) % value + return str(value) + + +class IntegerConverter(NumberConverter): + + """This converter only accepts integer values:: + + Rule('/page/') + + This converter does not support negative values. + + :param map: the :class:`Map`. + :param fixed_digits: the number of fixed digits in the URL. If you set + this to ``4`` for example, the application will + only match if the url looks like ``/0001/``. The + default is variable length. + :param min: the minimal value. + :param max: the maximal value. + """ + regex = r'\d+' + num_convert = int + + +class FloatConverter(NumberConverter): + + """This converter only accepts floating point values:: + + Rule('/probability/') + + This converter does not support negative values. + + :param map: the :class:`Map`. + :param min: the minimal value. + :param max: the maximal value. + """ + regex = r'\d+\.\d+' + num_convert = float + + def __init__(self, map, min=None, max=None): + NumberConverter.__init__(self, map, 0, min, max) + + +class UUIDConverter(BaseConverter): + + """This converter only accepts UUID strings:: + + Rule('/object/') + + .. versionadded:: 0.10 + + :param map: the :class:`Map`. + """ + regex = r'[A-Fa-f0-9]{8}-[A-Fa-f0-9]{4}-' \ + r'[A-Fa-f0-9]{4}-[A-Fa-f0-9]{4}-[A-Fa-f0-9]{12}' + + def to_python(self, value): + return uuid.UUID(value) + + def to_url(self, value): + return str(value) + + +#: the default converter mapping for the map. +DEFAULT_CONVERTERS = { + 'default': UnicodeConverter, + 'string': UnicodeConverter, + 'any': AnyConverter, + 'path': PathConverter, + 'int': IntegerConverter, + 'float': FloatConverter, + 'uuid': UUIDConverter, +} + + +class Map(object): + + """The map class stores all the URL rules and some configuration + parameters. Some of the configuration values are only stored on the + `Map` instance since those affect all rules, others are just defaults + and can be overridden for each rule. Note that you have to specify all + arguments besides the `rules` as keyword arguments! + + :param rules: sequence of url rules for this map. + :param default_subdomain: The default subdomain for rules without a + subdomain defined. + :param charset: charset of the url. defaults to ``"utf-8"`` + :param strict_slashes: Take care of trailing slashes. + :param redirect_defaults: This will redirect to the default rule if it + wasn't visited that way. This helps creating + unique URLs. + :param converters: A dict of converters that adds additional converters + to the list of converters. If you redefine one + converter this will override the original one. + :param sort_parameters: If set to `True` the url parameters are sorted. + See `url_encode` for more details. + :param sort_key: The sort key function for `url_encode`. + :param encoding_errors: the error method to use for decoding + :param host_matching: if set to `True` it enables the host matching + feature and disables the subdomain one. If + enabled the `host` parameter to rules is used + instead of the `subdomain` one. + + .. versionadded:: 0.5 + `sort_parameters` and `sort_key` was added. + + .. versionadded:: 0.7 + `encoding_errors` and `host_matching` was added. + """ + + #: .. versionadded:: 0.6 + #: a dict of default converters to be used. + default_converters = ImmutableDict(DEFAULT_CONVERTERS) + + def __init__(self, rules=None, default_subdomain='', charset='utf-8', + strict_slashes=True, redirect_defaults=True, + converters=None, sort_parameters=False, sort_key=None, + encoding_errors='replace', host_matching=False): + self._rules = [] + self._rules_by_endpoint = {} + self._remap = True + self._remap_lock = Lock() + + self.default_subdomain = default_subdomain + self.charset = charset + self.encoding_errors = encoding_errors + self.strict_slashes = strict_slashes + self.redirect_defaults = redirect_defaults + self.host_matching = host_matching + + self.converters = self.default_converters.copy() + if converters: + self.converters.update(converters) + + self.sort_parameters = sort_parameters + self.sort_key = sort_key + + for rulefactory in rules or (): + self.add(rulefactory) + + def is_endpoint_expecting(self, endpoint, *arguments): + """Iterate over all rules and check if the endpoint expects + the arguments provided. This is for example useful if you have + some URLs that expect a language code and others that do not and + you want to wrap the builder a bit so that the current language + code is automatically added if not provided but endpoints expect + it. + + :param endpoint: the endpoint to check. + :param arguments: this function accepts one or more arguments + as positional arguments. Each one of them is + checked. + """ + self.update() + arguments = set(arguments) + for rule in self._rules_by_endpoint[endpoint]: + if arguments.issubset(rule.arguments): + return True + return False + + def iter_rules(self, endpoint=None): + """Iterate over all rules or the rules of an endpoint. + + :param endpoint: if provided only the rules for that endpoint + are returned. + :return: an iterator + """ + self.update() + if endpoint is not None: + return iter(self._rules_by_endpoint[endpoint]) + return iter(self._rules) + + def add(self, rulefactory): + """Add a new rule or factory to the map and bind it. Requires that the + rule is not bound to another map. + + :param rulefactory: a :class:`Rule` or :class:`RuleFactory` + """ + for rule in rulefactory.get_rules(self): + rule.bind(self) + self._rules.append(rule) + self._rules_by_endpoint.setdefault(rule.endpoint, []).append(rule) + self._remap = True + + def bind(self, server_name, script_name=None, subdomain=None, + url_scheme='http', default_method='GET', path_info=None, + query_args=None): + """Return a new :class:`MapAdapter` with the details specified to the + call. Note that `script_name` will default to ``'/'`` if not further + specified or `None`. The `server_name` at least is a requirement + because the HTTP RFC requires absolute URLs for redirects and so all + redirect exceptions raised by Werkzeug will contain the full canonical + URL. + + If no path_info is passed to :meth:`match` it will use the default path + info passed to bind. While this doesn't really make sense for + manual bind calls, it's useful if you bind a map to a WSGI + environment which already contains the path info. + + `subdomain` will default to the `default_subdomain` for this map if + no defined. If there is no `default_subdomain` you cannot use the + subdomain feature. + + .. versionadded:: 0.7 + `query_args` added + + .. versionadded:: 0.8 + `query_args` can now also be a string. + """ + server_name = server_name.lower() + if self.host_matching: + if subdomain is not None: + raise RuntimeError('host matching enabled and a ' + 'subdomain was provided') + elif subdomain is None: + subdomain = self.default_subdomain + if script_name is None: + script_name = '/' + try: + server_name = _encode_idna(server_name) + except UnicodeError: + raise BadHost() + return MapAdapter(self, server_name, script_name, subdomain, + url_scheme, path_info, default_method, query_args) + + def bind_to_environ(self, environ, server_name=None, subdomain=None): + """Like :meth:`bind` but you can pass it an WSGI environment and it + will fetch the information from that dictionary. Note that because of + limitations in the protocol there is no way to get the current + subdomain and real `server_name` from the environment. If you don't + provide it, Werkzeug will use `SERVER_NAME` and `SERVER_PORT` (or + `HTTP_HOST` if provided) as used `server_name` with disabled subdomain + feature. + + If `subdomain` is `None` but an environment and a server name is + provided it will calculate the current subdomain automatically. + Example: `server_name` is ``'example.com'`` and the `SERVER_NAME` + in the wsgi `environ` is ``'staging.dev.example.com'`` the calculated + subdomain will be ``'staging.dev'``. + + If the object passed as environ has an environ attribute, the value of + this attribute is used instead. This allows you to pass request + objects. Additionally `PATH_INFO` added as a default of the + :class:`MapAdapter` so that you don't have to pass the path info to + the match method. + + .. versionchanged:: 0.5 + previously this method accepted a bogus `calculate_subdomain` + parameter that did not have any effect. It was removed because + of that. + + .. versionchanged:: 0.8 + This will no longer raise a ValueError when an unexpected server + name was passed. + + :param environ: a WSGI environment. + :param server_name: an optional server name hint (see above). + :param subdomain: optionally the current subdomain (see above). + """ + environ = _get_environ(environ) + + if 'HTTP_HOST' in environ: + wsgi_server_name = environ['HTTP_HOST'] + + if environ['wsgi.url_scheme'] == 'http' \ + and wsgi_server_name.endswith(':80'): + wsgi_server_name = wsgi_server_name[:-3] + elif environ['wsgi.url_scheme'] == 'https' \ + and wsgi_server_name.endswith(':443'): + wsgi_server_name = wsgi_server_name[:-4] + else: + wsgi_server_name = environ['SERVER_NAME'] + + if (environ['wsgi.url_scheme'], environ['SERVER_PORT']) not \ + in (('https', '443'), ('http', '80')): + wsgi_server_name += ':' + environ['SERVER_PORT'] + + wsgi_server_name = wsgi_server_name.lower() + + if server_name is None: + server_name = wsgi_server_name + else: + server_name = server_name.lower() + + if subdomain is None and not self.host_matching: + cur_server_name = wsgi_server_name.split('.') + real_server_name = server_name.split('.') + offset = -len(real_server_name) + if cur_server_name[offset:] != real_server_name: + # This can happen even with valid configs if the server was + # accesssed directly by IP address under some situations. + # Instead of raising an exception like in Werkzeug 0.7 or + # earlier we go by an invalid subdomain which will result + # in a 404 error on matching. + subdomain = '' + else: + subdomain = '.'.join(filter(None, cur_server_name[:offset])) + + def _get_wsgi_string(name): + val = environ.get(name) + if val is not None: + return wsgi_decoding_dance(val, self.charset) + + script_name = _get_wsgi_string('SCRIPT_NAME') + path_info = _get_wsgi_string('PATH_INFO') + query_args = _get_wsgi_string('QUERY_STRING') + return Map.bind(self, server_name, script_name, + subdomain, environ['wsgi.url_scheme'], + environ['REQUEST_METHOD'], path_info, + query_args=query_args) + + def update(self): + """Called before matching and building to keep the compiled rules + in the correct order after things changed. + """ + if not self._remap: + return + + with self._remap_lock: + if not self._remap: + return + + self._rules.sort(key=lambda x: x.match_compare_key()) + for rules in itervalues(self._rules_by_endpoint): + rules.sort(key=lambda x: x.build_compare_key()) + self._remap = False + + def __repr__(self): + rules = self.iter_rules() + return '%s(%s)' % (self.__class__.__name__, pformat(list(rules))) + + +class MapAdapter(object): + + """Returned by :meth:`Map.bind` or :meth:`Map.bind_to_environ` and does + the URL matching and building based on runtime information. + """ + + def __init__(self, map, server_name, script_name, subdomain, + url_scheme, path_info, default_method, query_args=None): + self.map = map + self.server_name = to_unicode(server_name) + script_name = to_unicode(script_name) + if not script_name.endswith(u'/'): + script_name += u'/' + self.script_name = script_name + self.subdomain = to_unicode(subdomain) + self.url_scheme = to_unicode(url_scheme) + self.path_info = to_unicode(path_info) + self.default_method = to_unicode(default_method) + self.query_args = query_args + + def dispatch(self, view_func, path_info=None, method=None, + catch_http_exceptions=False): + """Does the complete dispatching process. `view_func` is called with + the endpoint and a dict with the values for the view. It should + look up the view function, call it, and return a response object + or WSGI application. http exceptions are not caught by default + so that applications can display nicer error messages by just + catching them by hand. If you want to stick with the default + error messages you can pass it ``catch_http_exceptions=True`` and + it will catch the http exceptions. + + Here a small example for the dispatch usage:: + + from werkzeug.wrappers import Request, Response + from werkzeug.wsgi import responder + from werkzeug.routing import Map, Rule + + def on_index(request): + return Response('Hello from the index') + + url_map = Map([Rule('/', endpoint='index')]) + views = {'index': on_index} + + @responder + def application(environ, start_response): + request = Request(environ) + urls = url_map.bind_to_environ(environ) + return urls.dispatch(lambda e, v: views[e](request, **v), + catch_http_exceptions=True) + + Keep in mind that this method might return exception objects, too, so + use :class:`Response.force_type` to get a response object. + + :param view_func: a function that is called with the endpoint as + first argument and the value dict as second. Has + to dispatch to the actual view function with this + information. (see above) + :param path_info: the path info to use for matching. Overrides the + path info specified on binding. + :param method: the HTTP method used for matching. Overrides the + method specified on binding. + :param catch_http_exceptions: set to `True` to catch any of the + werkzeug :class:`HTTPException`\s. + """ + try: + try: + endpoint, args = self.match(path_info, method) + except RequestRedirect as e: + return e + return view_func(endpoint, args) + except HTTPException as e: + if catch_http_exceptions: + return e + raise + + def match(self, path_info=None, method=None, return_rule=False, + query_args=None): + """The usage is simple: you just pass the match method the current + path info as well as the method (which defaults to `GET`). The + following things can then happen: + + - you receive a `NotFound` exception that indicates that no URL is + matching. A `NotFound` exception is also a WSGI application you + can call to get a default page not found page (happens to be the + same object as `werkzeug.exceptions.NotFound`) + + - you receive a `MethodNotAllowed` exception that indicates that there + is a match for this URL but not for the current request method. + This is useful for RESTful applications. + + - you receive a `RequestRedirect` exception with a `new_url` + attribute. This exception is used to notify you about a request + Werkzeug requests from your WSGI application. This is for example the + case if you request ``/foo`` although the correct URL is ``/foo/`` + You can use the `RequestRedirect` instance as response-like object + similar to all other subclasses of `HTTPException`. + + - you get a tuple in the form ``(endpoint, arguments)`` if there is + a match (unless `return_rule` is True, in which case you get a tuple + in the form ``(rule, arguments)``) + + If the path info is not passed to the match method the default path + info of the map is used (defaults to the root URL if not defined + explicitly). + + All of the exceptions raised are subclasses of `HTTPException` so they + can be used as WSGI responses. They will all render generic error or + redirect pages. + + Here is a small example for matching: + + >>> m = Map([ + ... Rule('/', endpoint='index'), + ... Rule('/downloads/', endpoint='downloads/index'), + ... Rule('/downloads/', endpoint='downloads/show') + ... ]) + >>> urls = m.bind("example.com", "/") + >>> urls.match("/", "GET") + ('index', {}) + >>> urls.match("/downloads/42") + ('downloads/show', {'id': 42}) + + And here is what happens on redirect and missing URLs: + + >>> urls.match("/downloads") + Traceback (most recent call last): + ... + RequestRedirect: http://example.com/downloads/ + >>> urls.match("/missing") + Traceback (most recent call last): + ... + NotFound: 404 Not Found + + :param path_info: the path info to use for matching. Overrides the + path info specified on binding. + :param method: the HTTP method used for matching. Overrides the + method specified on binding. + :param return_rule: return the rule that matched instead of just the + endpoint (defaults to `False`). + :param query_args: optional query arguments that are used for + automatic redirects as string or dictionary. It's + currently not possible to use the query arguments + for URL matching. + + .. versionadded:: 0.6 + `return_rule` was added. + + .. versionadded:: 0.7 + `query_args` was added. + + .. versionchanged:: 0.8 + `query_args` can now also be a string. + """ + self.map.update() + if path_info is None: + path_info = self.path_info + else: + path_info = to_unicode(path_info, self.map.charset) + if query_args is None: + query_args = self.query_args + method = (method or self.default_method).upper() + + path = u'%s|%s' % ( + self.map.host_matching and self.server_name or self.subdomain, + path_info and '/%s' % path_info.lstrip('/') + ) + + have_match_for = set() + for rule in self.map._rules: + try: + rv = rule.match(path, method) + except RequestSlash: + raise RequestRedirect(self.make_redirect_url( + url_quote(path_info, self.map.charset, + safe='/:|+') + '/', query_args)) + except RequestAliasRedirect as e: + raise RequestRedirect(self.make_alias_redirect_url( + path, rule.endpoint, e.matched_values, method, query_args)) + if rv is None: + continue + if rule.methods is not None and method not in rule.methods: + have_match_for.update(rule.methods) + continue + + if self.map.redirect_defaults: + redirect_url = self.get_default_redirect(rule, method, rv, + query_args) + if redirect_url is not None: + raise RequestRedirect(redirect_url) + + if rule.redirect_to is not None: + if isinstance(rule.redirect_to, string_types): + def _handle_match(match): + value = rv[match.group(1)] + return rule._converters[match.group(1)].to_url(value) + redirect_url = _simple_rule_re.sub(_handle_match, + rule.redirect_to) + else: + redirect_url = rule.redirect_to(self, **rv) + raise RequestRedirect(str(url_join('%s://%s%s%s' % ( + self.url_scheme or 'http', + self.subdomain and self.subdomain + '.' or '', + self.server_name, + self.script_name + ), redirect_url))) + + if return_rule: + return rule, rv + else: + return rule.endpoint, rv + + if have_match_for: + raise MethodNotAllowed(valid_methods=list(have_match_for)) + raise NotFound() + + def test(self, path_info=None, method=None): + """Test if a rule would match. Works like `match` but returns `True` + if the URL matches, or `False` if it does not exist. + + :param path_info: the path info to use for matching. Overrides the + path info specified on binding. + :param method: the HTTP method used for matching. Overrides the + method specified on binding. + """ + try: + self.match(path_info, method) + except RequestRedirect: + pass + except HTTPException: + return False + return True + + def allowed_methods(self, path_info=None): + """Returns the valid methods that match for a given path. + + .. versionadded:: 0.7 + """ + try: + self.match(path_info, method='--') + except MethodNotAllowed as e: + return e.valid_methods + except HTTPException as e: + pass + return [] + + def get_host(self, domain_part): + """Figures out the full host name for the given domain part. The + domain part is a subdomain in case host matching is disabled or + a full host name. + """ + if self.map.host_matching: + if domain_part is None: + return self.server_name + return to_unicode(domain_part, 'ascii') + subdomain = domain_part + if subdomain is None: + subdomain = self.subdomain + else: + subdomain = to_unicode(subdomain, 'ascii') + return (subdomain and subdomain + u'.' or u'') + self.server_name + + def get_default_redirect(self, rule, method, values, query_args): + """A helper that returns the URL to redirect to if it finds one. + This is used for default redirecting only. + + :internal: + """ + assert self.map.redirect_defaults + for r in self.map._rules_by_endpoint[rule.endpoint]: + # every rule that comes after this one, including ourself + # has a lower priority for the defaults. We order the ones + # with the highest priority up for building. + if r is rule: + break + if r.provides_defaults_for(rule) and \ + r.suitable_for(values, method): + values.update(r.defaults) + domain_part, path = r.build(values) + return self.make_redirect_url( + path, query_args, domain_part=domain_part) + + def encode_query_args(self, query_args): + if not isinstance(query_args, string_types): + query_args = url_encode(query_args, self.map.charset) + return query_args + + def make_redirect_url(self, path_info, query_args=None, domain_part=None): + """Creates a redirect URL. + + :internal: + """ + suffix = '' + if query_args: + suffix = '?' + self.encode_query_args(query_args) + return str('%s://%s/%s%s' % ( + self.url_scheme or 'http', + self.get_host(domain_part), + posixpath.join(self.script_name[:-1].lstrip('/'), + path_info.lstrip('/')), + suffix + )) + + def make_alias_redirect_url(self, path, endpoint, values, method, query_args): + """Internally called to make an alias redirect URL.""" + url = self.build(endpoint, values, method, append_unknown=False, + force_external=True) + if query_args: + url += '?' + self.encode_query_args(query_args) + assert url != path, 'detected invalid alias setting. No canonical ' \ + 'URL found' + return url + + def _partial_build(self, endpoint, values, method, append_unknown): + """Helper for :meth:`build`. Returns subdomain and path for the + rule that accepts this endpoint, values and method. + + :internal: + """ + # in case the method is none, try with the default method first + if method is None: + rv = self._partial_build(endpoint, values, self.default_method, + append_unknown) + if rv is not None: + return rv + + # default method did not match or a specific method is passed, + # check all and go with first result. + for rule in self.map._rules_by_endpoint.get(endpoint, ()): + if rule.suitable_for(values, method): + rv = rule.build(values, append_unknown) + if rv is not None: + return rv + + def build(self, endpoint, values=None, method=None, force_external=False, + append_unknown=True): + """Building URLs works pretty much the other way round. Instead of + `match` you call `build` and pass it the endpoint and a dict of + arguments for the placeholders. + + The `build` function also accepts an argument called `force_external` + which, if you set it to `True` will force external URLs. Per default + external URLs (include the server name) will only be used if the + target URL is on a different subdomain. + + >>> m = Map([ + ... Rule('/', endpoint='index'), + ... Rule('/downloads/', endpoint='downloads/index'), + ... Rule('/downloads/', endpoint='downloads/show') + ... ]) + >>> urls = m.bind("example.com", "/") + >>> urls.build("index", {}) + '/' + >>> urls.build("downloads/show", {'id': 42}) + '/downloads/42' + >>> urls.build("downloads/show", {'id': 42}, force_external=True) + 'http://example.com/downloads/42' + + Because URLs cannot contain non ASCII data you will always get + bytestrings back. Non ASCII characters are urlencoded with the + charset defined on the map instance. + + Additional values are converted to unicode and appended to the URL as + URL querystring parameters: + + >>> urls.build("index", {'q': 'My Searchstring'}) + '/?q=My+Searchstring' + + When processing those additional values, lists are furthermore + interpreted as multiple values (as per + :py:class:`werkzeug.datastructures.MultiDict`): + + >>> urls.build("index", {'q': ['a', 'b', 'c']}) + '/?q=a&q=b&q=c' + + If a rule does not exist when building a `BuildError` exception is + raised. + + The build method accepts an argument called `method` which allows you + to specify the method you want to have an URL built for if you have + different methods for the same endpoint specified. + + .. versionadded:: 0.6 + the `append_unknown` parameter was added. + + :param endpoint: the endpoint of the URL to build. + :param values: the values for the URL to build. Unhandled values are + appended to the URL as query parameters. + :param method: the HTTP method for the rule if there are different + URLs for different methods on the same endpoint. + :param force_external: enforce full canonical external URLs. If the URL + scheme is not provided, this will generate + a protocol-relative URL. + :param append_unknown: unknown parameters are appended to the generated + URL as query string argument. Disable this + if you want the builder to ignore those. + """ + self.map.update() + if values: + if isinstance(values, MultiDict): + valueiter = iteritems(values, multi=True) + else: + valueiter = iteritems(values) + values = dict((k, v) for k, v in valueiter if v is not None) + else: + values = {} + + rv = self._partial_build(endpoint, values, method, append_unknown) + if rv is None: + raise BuildError(endpoint, values, method, self) + domain_part, path = rv + + host = self.get_host(domain_part) + + # shortcut this. + if not force_external and ( + (self.map.host_matching and host == self.server_name) or + (not self.map.host_matching and domain_part == self.subdomain) + ): + return str(url_join(self.script_name, './' + path.lstrip('/'))) + return str('%s//%s%s/%s' % ( + self.url_scheme + ':' if self.url_scheme else '', + host, + self.script_name[:-1], + path.lstrip('/') + )) diff --git a/pyextra/werkzeug/security.py b/pyextra/werkzeug/security.py new file mode 100644 index 00000000000000..d4c5c9f487b8ce --- /dev/null +++ b/pyextra/werkzeug/security.py @@ -0,0 +1,270 @@ +# -*- coding: utf-8 -*- +""" + werkzeug.security + ~~~~~~~~~~~~~~~~~ + + Security related helpers such as secure password hashing tools. + + :copyright: (c) 2014 by the Werkzeug Team, see AUTHORS for more details. + :license: BSD, see LICENSE for more details. +""" +import os +import hmac +import hashlib +import posixpath +import codecs +from struct import Struct +from random import SystemRandom +from operator import xor +from itertools import starmap + +from werkzeug._compat import range_type, PY2, text_type, izip, to_bytes, \ + string_types, to_native + + +SALT_CHARS = 'abcdefghijklmnopqrstuvwxyzABCDEFGHIJKLMNOPQRSTUVWXYZ0123456789' +DEFAULT_PBKDF2_ITERATIONS = 50000 + + +_pack_int = Struct('>I').pack +_builtin_safe_str_cmp = getattr(hmac, 'compare_digest', None) +_sys_rng = SystemRandom() +_os_alt_seps = list(sep for sep in [os.path.sep, os.path.altsep] + if sep not in (None, '/')) + + +def _find_hashlib_algorithms(): + algos = getattr(hashlib, 'algorithms', None) + if algos is None: + algos = ('md5', 'sha1', 'sha224', 'sha256', 'sha384', 'sha512') + rv = {} + for algo in algos: + func = getattr(hashlib, algo, None) + if func is not None: + rv[algo] = func + return rv +_hash_funcs = _find_hashlib_algorithms() + + +def pbkdf2_hex(data, salt, iterations=DEFAULT_PBKDF2_ITERATIONS, + keylen=None, hashfunc=None): + """Like :func:`pbkdf2_bin`, but returns a hex-encoded string. + + .. versionadded:: 0.9 + + :param data: the data to derive. + :param salt: the salt for the derivation. + :param iterations: the number of iterations. + :param keylen: the length of the resulting key. If not provided, + the digest size will be used. + :param hashfunc: the hash function to use. This can either be the + string name of a known hash function, or a function + from the hashlib module. Defaults to sha256. + """ + rv = pbkdf2_bin(data, salt, iterations, keylen, hashfunc) + return to_native(codecs.encode(rv, 'hex_codec')) + + +_has_native_pbkdf2 = hasattr(hashlib, 'pbkdf2_hmac') + + +def pbkdf2_bin(data, salt, iterations=DEFAULT_PBKDF2_ITERATIONS, + keylen=None, hashfunc=None): + """Returns a binary digest for the PBKDF2 hash algorithm of `data` + with the given `salt`. It iterates `iterations` times and produces a + key of `keylen` bytes. By default, SHA-256 is used as hash function; + a different hashlib `hashfunc` can be provided. + + .. versionadded:: 0.9 + + :param data: the data to derive. + :param salt: the salt for the derivation. + :param iterations: the number of iterations. + :param keylen: the length of the resulting key. If not provided + the digest size will be used. + :param hashfunc: the hash function to use. This can either be the + string name of a known hash function or a function + from the hashlib module. Defaults to sha256. + """ + if isinstance(hashfunc, string_types): + hashfunc = _hash_funcs[hashfunc] + elif not hashfunc: + hashfunc = hashlib.sha256 + data = to_bytes(data) + salt = to_bytes(salt) + + # If we're on Python with pbkdf2_hmac we can try to use it for + # compatible digests. + if _has_native_pbkdf2: + _test_hash = hashfunc() + if hasattr(_test_hash, 'name') and \ + _test_hash.name in _hash_funcs: + return hashlib.pbkdf2_hmac(_test_hash.name, + data, salt, iterations, + keylen) + + mac = hmac.HMAC(data, None, hashfunc) + if not keylen: + keylen = mac.digest_size + + def _pseudorandom(x, mac=mac): + h = mac.copy() + h.update(x) + return bytearray(h.digest()) + buf = bytearray() + for block in range_type(1, -(-keylen // mac.digest_size) + 1): + rv = u = _pseudorandom(salt + _pack_int(block)) + for i in range_type(iterations - 1): + u = _pseudorandom(bytes(u)) + rv = bytearray(starmap(xor, izip(rv, u))) + buf.extend(rv) + return bytes(buf[:keylen]) + + +def safe_str_cmp(a, b): + """This function compares strings in somewhat constant time. This + requires that the length of at least one string is known in advance. + + Returns `True` if the two strings are equal, or `False` if they are not. + + .. versionadded:: 0.7 + """ + if isinstance(a, text_type): + a = a.encode('utf-8') + if isinstance(b, text_type): + b = b.encode('utf-8') + + if _builtin_safe_str_cmp is not None: + return _builtin_safe_str_cmp(a, b) + + if len(a) != len(b): + return False + + rv = 0 + if PY2: + for x, y in izip(a, b): + rv |= ord(x) ^ ord(y) + else: + for x, y in izip(a, b): + rv |= x ^ y + + return rv == 0 + + +def gen_salt(length): + """Generate a random string of SALT_CHARS with specified ``length``.""" + if length <= 0: + raise ValueError('Salt length must be positive') + return ''.join(_sys_rng.choice(SALT_CHARS) for _ in range_type(length)) + + +def _hash_internal(method, salt, password): + """Internal password hash helper. Supports plaintext without salt, + unsalted and salted passwords. In case salted passwords are used + hmac is used. + """ + if method == 'plain': + return password, method + + if isinstance(password, text_type): + password = password.encode('utf-8') + + if method.startswith('pbkdf2:'): + args = method[7:].split(':') + if len(args) not in (1, 2): + raise ValueError('Invalid number of arguments for PBKDF2') + method = args.pop(0) + iterations = args and int(args[0] or 0) or DEFAULT_PBKDF2_ITERATIONS + is_pbkdf2 = True + actual_method = 'pbkdf2:%s:%d' % (method, iterations) + else: + is_pbkdf2 = False + actual_method = method + + hash_func = _hash_funcs.get(method) + if hash_func is None: + raise TypeError('invalid method %r' % method) + + if is_pbkdf2: + if not salt: + raise ValueError('Salt is required for PBKDF2') + rv = pbkdf2_hex(password, salt, iterations, + hashfunc=hash_func) + elif salt: + if isinstance(salt, text_type): + salt = salt.encode('utf-8') + rv = hmac.HMAC(salt, password, hash_func).hexdigest() + else: + h = hash_func() + h.update(password) + rv = h.hexdigest() + return rv, actual_method + + +def generate_password_hash(password, method='pbkdf2:sha256', salt_length=8): + """Hash a password with the given method and salt with a string of + the given length. The format of the string returned includes the method + that was used so that :func:`check_password_hash` can check the hash. + + The format for the hashed string looks like this:: + + method$salt$hash + + This method can **not** generate unsalted passwords but it is possible + to set param method='plain' in order to enforce plaintext passwords. + If a salt is used, hmac is used internally to salt the password. + + If PBKDF2 is wanted it can be enabled by setting the method to + ``pbkdf2:method:iterations`` where iterations is optional:: + + pbkdf2:sha256:80000$salt$hash + pbkdf2:sha256$salt$hash + + :param password: the password to hash. + :param method: the hash method to use (one that hashlib supports). Can + optionally be in the format ``pbkdf2:[:iterations]`` + to enable PBKDF2. + :param salt_length: the length of the salt in letters. + """ + salt = method != 'plain' and gen_salt(salt_length) or '' + h, actual_method = _hash_internal(method, salt, password) + return '%s$%s$%s' % (actual_method, salt, h) + + +def check_password_hash(pwhash, password): + """check a password against a given salted and hashed password value. + In order to support unsalted legacy passwords this method supports + plain text passwords, md5 and sha1 hashes (both salted and unsalted). + + Returns `True` if the password matched, `False` otherwise. + + :param pwhash: a hashed string like returned by + :func:`generate_password_hash`. + :param password: the plaintext password to compare against the hash. + """ + if pwhash.count('$') < 2: + return False + method, salt, hashval = pwhash.split('$', 2) + return safe_str_cmp(_hash_internal(method, salt, password)[0], hashval) + + +def safe_join(directory, *pathnames): + """Safely join `directory` and one or more untrusted `pathnames`. If this + cannot be done, this function returns ``None``. + + :param directory: the base directory. + :param pathnames: the untrusted pathnames relative to that directory. + """ + parts = [directory] + for filename in pathnames: + if filename != '': + filename = posixpath.normpath(filename) + for sep in _os_alt_seps: + if sep in filename: + return None + if os.path.isabs(filename) or \ + filename == '..' or \ + filename.startswith('../'): + return None + parts.append(filename) + return posixpath.join(*parts) diff --git a/pyextra/werkzeug/serving.py b/pyextra/werkzeug/serving.py new file mode 100644 index 00000000000000..902f1aa1c62d3a --- /dev/null +++ b/pyextra/werkzeug/serving.py @@ -0,0 +1,862 @@ +# -*- coding: utf-8 -*- +""" + werkzeug.serving + ~~~~~~~~~~~~~~~~ + + There are many ways to serve a WSGI application. While you're developing + it you usually don't want a full blown webserver like Apache but a simple + standalone one. From Python 2.5 onwards there is the `wsgiref`_ server in + the standard library. If you're using older versions of Python you can + download the package from the cheeseshop. + + However there are some caveats. Sourcecode won't reload itself when + changed and each time you kill the server using ``^C`` you get an + `KeyboardInterrupt` error. While the latter is easy to solve the first + one can be a pain in the ass in some situations. + + The easiest way is creating a small ``start-myproject.py`` that runs the + application:: + + #!/usr/bin/env python + # -*- coding: utf-8 -*- + from myproject import make_app + from werkzeug.serving import run_simple + + app = make_app(...) + run_simple('localhost', 8080, app, use_reloader=True) + + You can also pass it a `extra_files` keyword argument with a list of + additional files (like configuration files) you want to observe. + + For bigger applications you should consider using `click` + (http://click.pocoo.org) instead of a simple start file. + + + :copyright: (c) 2014 by the Werkzeug Team, see AUTHORS for more details. + :license: BSD, see LICENSE for more details. +""" +from __future__ import with_statement + +import io +import os +import socket +import sys +import signal + + +can_fork = hasattr(os, "fork") + + +try: + import termcolor +except ImportError: + termcolor = None + +try: + import ssl +except ImportError: + class _SslDummy(object): + def __getattr__(self, name): + raise RuntimeError('SSL support unavailable') + ssl = _SslDummy() + + +def _get_openssl_crypto_module(): + try: + from OpenSSL import crypto + except ImportError: + raise TypeError('Using ad-hoc certificates requires the pyOpenSSL ' + 'library.') + else: + return crypto + + +try: + import SocketServer as socketserver + from BaseHTTPServer import HTTPServer, BaseHTTPRequestHandler +except ImportError: + import socketserver + from http.server import HTTPServer, BaseHTTPRequestHandler + +ThreadingMixIn = socketserver.ThreadingMixIn + +if can_fork: + ForkingMixIn = socketserver.ForkingMixIn +else: + class ForkingMixIn(object): + pass + +# important: do not use relative imports here or python -m will break +import werkzeug +from werkzeug._internal import _log +from werkzeug._compat import PY2, WIN, reraise, wsgi_encoding_dance +from werkzeug.urls import url_parse, url_unquote +from werkzeug.exceptions import InternalServerError + + +LISTEN_QUEUE = 128 +can_open_by_fd = not WIN and hasattr(socket, 'fromfd') + + +class DechunkedInput(io.RawIOBase): + """An input stream that handles Transfer-Encoding 'chunked'""" + + def __init__(self, rfile): + self._rfile = rfile + self._done = False + self._len = 0 + + def readable(self): + return True + + def read_chunk_len(self): + try: + line = self._rfile.readline().decode('latin1') + _len = int(line.strip(), 16) + except ValueError: + raise IOError('Invalid chunk header') + if _len < 0: + raise IOError('Negative chunk length not allowed') + return _len + + def readinto(self, buf): + read = 0 + while not self._done and read < len(buf): + if self._len == 0: + # This is the first chunk or we fully consumed the previous + # one. Read the next length of the next chunk + self._len = self.read_chunk_len() + + if self._len == 0: + # Found the final chunk of size 0. The stream is now exhausted, + # but there is still a final newline that should be consumed + self._done = True + + if self._len > 0: + # There is data (left) in this chunk, so append it to the + # buffer. If this operation fully consumes the chunk, this will + # reset self._len to 0. + n = min(len(buf), self._len) + buf[read:read + n] = self._rfile.read(n) + self._len -= n + read += n + + if self._len == 0: + # Skip the terminating newline of a chunk that has been fully + # consumed. This also applies to the 0-sized final chunk + terminator = self._rfile.readline() + if terminator not in (b'\n', b'\r\n', b'\r'): + raise IOError('Missing chunk terminating newline') + + return read + + +class WSGIRequestHandler(BaseHTTPRequestHandler, object): + + """A request handler that implements WSGI dispatching.""" + + @property + def server_version(self): + return 'Werkzeug/' + werkzeug.__version__ + + def make_environ(self): + request_url = url_parse(self.path) + + def shutdown_server(): + self.server.shutdown_signal = True + + url_scheme = self.server.ssl_context is None and 'http' or 'https' + path_info = url_unquote(request_url.path) + + environ = { + 'wsgi.version': (1, 0), + 'wsgi.url_scheme': url_scheme, + 'wsgi.input': self.rfile, + 'wsgi.errors': sys.stderr, + 'wsgi.multithread': self.server.multithread, + 'wsgi.multiprocess': self.server.multiprocess, + 'wsgi.run_once': False, + 'werkzeug.server.shutdown': shutdown_server, + 'SERVER_SOFTWARE': self.server_version, + 'REQUEST_METHOD': self.command, + 'SCRIPT_NAME': '', + 'PATH_INFO': wsgi_encoding_dance(path_info), + 'QUERY_STRING': wsgi_encoding_dance(request_url.query), + 'REMOTE_ADDR': self.address_string(), + 'REMOTE_PORT': self.port_integer(), + 'SERVER_NAME': self.server.server_address[0], + 'SERVER_PORT': str(self.server.server_address[1]), + 'SERVER_PROTOCOL': self.request_version + } + + for key, value in self.headers.items(): + key = key.upper().replace('-', '_') + if key not in ('CONTENT_TYPE', 'CONTENT_LENGTH'): + key = 'HTTP_' + key + environ[key] = value + + if environ.get('HTTP_TRANSFER_ENCODING', '').strip().lower() == 'chunked': + environ['wsgi.input_terminated'] = True + environ['wsgi.input'] = DechunkedInput(environ['wsgi.input']) + + if request_url.scheme and request_url.netloc: + environ['HTTP_HOST'] = request_url.netloc + + return environ + + def run_wsgi(self): + if self.headers.get('Expect', '').lower().strip() == '100-continue': + self.wfile.write(b'HTTP/1.1 100 Continue\r\n\r\n') + + self.environ = environ = self.make_environ() + headers_set = [] + headers_sent = [] + + def write(data): + assert headers_set, 'write() before start_response' + if not headers_sent: + status, response_headers = headers_sent[:] = headers_set + try: + code, msg = status.split(None, 1) + except ValueError: + code, msg = status, "" + code = int(code) + self.send_response(code, msg) + header_keys = set() + for key, value in response_headers: + self.send_header(key, value) + key = key.lower() + header_keys.add(key) + if not ('content-length' in header_keys or + environ['REQUEST_METHOD'] == 'HEAD' or + code < 200 or code in (204, 304)): + self.close_connection = True + self.send_header('Connection', 'close') + if 'server' not in header_keys: + self.send_header('Server', self.version_string()) + if 'date' not in header_keys: + self.send_header('Date', self.date_time_string()) + self.end_headers() + + assert isinstance(data, bytes), 'applications must write bytes' + self.wfile.write(data) + self.wfile.flush() + + def start_response(status, response_headers, exc_info=None): + if exc_info: + try: + if headers_sent: + reraise(*exc_info) + finally: + exc_info = None + elif headers_set: + raise AssertionError('Headers already set') + headers_set[:] = [status, response_headers] + return write + + def execute(app): + application_iter = app(environ, start_response) + try: + for data in application_iter: + write(data) + if not headers_sent: + write(b'') + finally: + if hasattr(application_iter, 'close'): + application_iter.close() + application_iter = None + + try: + execute(self.server.app) + except (socket.error, socket.timeout) as e: + self.connection_dropped(e, environ) + except Exception: + if self.server.passthrough_errors: + raise + from werkzeug.debug.tbtools import get_current_traceback + traceback = get_current_traceback(ignore_system_exceptions=True) + try: + # if we haven't yet sent the headers but they are set + # we roll back to be able to set them again. + if not headers_sent: + del headers_set[:] + execute(InternalServerError()) + except Exception: + pass + self.server.log('error', 'Error on request:\n%s', + traceback.plaintext) + + def handle(self): + """Handles a request ignoring dropped connections.""" + rv = None + try: + rv = BaseHTTPRequestHandler.handle(self) + except (socket.error, socket.timeout) as e: + self.connection_dropped(e) + except Exception: + if self.server.ssl_context is None or not is_ssl_error(): + raise + if self.server.shutdown_signal: + self.initiate_shutdown() + return rv + + def initiate_shutdown(self): + """A horrible, horrible way to kill the server for Python 2.6 and + later. It's the best we can do. + """ + # Windows does not provide SIGKILL, go with SIGTERM then. + sig = getattr(signal, 'SIGKILL', signal.SIGTERM) + # reloader active + if os.environ.get('WERKZEUG_RUN_MAIN') == 'true': + os.kill(os.getpid(), sig) + # python 2.7 + self.server._BaseServer__shutdown_request = True + # python 2.6 + self.server._BaseServer__serving = False + + def connection_dropped(self, error, environ=None): + """Called if the connection was closed by the client. By default + nothing happens. + """ + + def handle_one_request(self): + """Handle a single HTTP request.""" + self.raw_requestline = self.rfile.readline() + if not self.raw_requestline: + self.close_connection = 1 + elif self.parse_request(): + return self.run_wsgi() + + def send_response(self, code, message=None): + """Send the response header and log the response code.""" + self.log_request(code) + if message is None: + message = code in self.responses and self.responses[code][0] or '' + if self.request_version != 'HTTP/0.9': + hdr = "%s %d %s\r\n" % (self.protocol_version, code, message) + self.wfile.write(hdr.encode('ascii')) + + def version_string(self): + return BaseHTTPRequestHandler.version_string(self).strip() + + def address_string(self): + if getattr(self, 'environ', None): + return self.environ['REMOTE_ADDR'] + else: + return self.client_address[0] + + def port_integer(self): + return self.client_address[1] + + def log_request(self, code='-', size='-'): + msg = self.requestline + code = str(code) + + if termcolor: + color = termcolor.colored + + if code[0] == '1': # 1xx - Informational + msg = color(msg, attrs=['bold']) + elif code[0] == '2': # 2xx - Success + msg = color(msg, color='white') + elif code == '304': # 304 - Resource Not Modified + msg = color(msg, color='cyan') + elif code[0] == '3': # 3xx - Redirection + msg = color(msg, color='green') + elif code == '404': # 404 - Resource Not Found + msg = color(msg, color='yellow') + elif code[0] == '4': # 4xx - Client Error + msg = color(msg, color='red', attrs=['bold']) + else: # 5xx, or any other response + msg = color(msg, color='magenta', attrs=['bold']) + + self.log('info', '"%s" %s %s', msg, code, size) + + def log_error(self, *args): + self.log('error', *args) + + def log_message(self, format, *args): + self.log('info', format, *args) + + def log(self, type, message, *args): + _log(type, '%s - - [%s] %s\n' % (self.address_string(), + self.log_date_time_string(), + message % args)) + + +#: backwards compatible name if someone is subclassing it +BaseRequestHandler = WSGIRequestHandler + + +def generate_adhoc_ssl_pair(cn=None): + from random import random + crypto = _get_openssl_crypto_module() + + # pretty damn sure that this is not actually accepted by anyone + if cn is None: + cn = '*' + + cert = crypto.X509() + cert.set_serial_number(int(random() * sys.maxsize)) + cert.gmtime_adj_notBefore(0) + cert.gmtime_adj_notAfter(60 * 60 * 24 * 365) + + subject = cert.get_subject() + subject.CN = cn + subject.O = 'Dummy Certificate' # noqa: E741 + + issuer = cert.get_issuer() + issuer.CN = 'Untrusted Authority' + issuer.O = 'Self-Signed' # noqa: E741 + + pkey = crypto.PKey() + pkey.generate_key(crypto.TYPE_RSA, 2048) + cert.set_pubkey(pkey) + cert.sign(pkey, 'sha256') + + return cert, pkey + + +def make_ssl_devcert(base_path, host=None, cn=None): + """Creates an SSL key for development. This should be used instead of + the ``'adhoc'`` key which generates a new cert on each server start. + It accepts a path for where it should store the key and cert and + either a host or CN. If a host is given it will use the CN + ``*.host/CN=host``. + + For more information see :func:`run_simple`. + + .. versionadded:: 0.9 + + :param base_path: the path to the certificate and key. The extension + ``.crt`` is added for the certificate, ``.key`` is + added for the key. + :param host: the name of the host. This can be used as an alternative + for the `cn`. + :param cn: the `CN` to use. + """ + from OpenSSL import crypto + if host is not None: + cn = '*.%s/CN=%s' % (host, host) + cert, pkey = generate_adhoc_ssl_pair(cn=cn) + + cert_file = base_path + '.crt' + pkey_file = base_path + '.key' + + with open(cert_file, 'wb') as f: + f.write(crypto.dump_certificate(crypto.FILETYPE_PEM, cert)) + with open(pkey_file, 'wb') as f: + f.write(crypto.dump_privatekey(crypto.FILETYPE_PEM, pkey)) + + return cert_file, pkey_file + + +def generate_adhoc_ssl_context(): + """Generates an adhoc SSL context for the development server.""" + crypto = _get_openssl_crypto_module() + import tempfile + import atexit + + cert, pkey = generate_adhoc_ssl_pair() + cert_handle, cert_file = tempfile.mkstemp() + pkey_handle, pkey_file = tempfile.mkstemp() + atexit.register(os.remove, pkey_file) + atexit.register(os.remove, cert_file) + + os.write(cert_handle, crypto.dump_certificate(crypto.FILETYPE_PEM, cert)) + os.write(pkey_handle, crypto.dump_privatekey(crypto.FILETYPE_PEM, pkey)) + os.close(cert_handle) + os.close(pkey_handle) + ctx = load_ssl_context(cert_file, pkey_file) + return ctx + + +def load_ssl_context(cert_file, pkey_file=None, protocol=None): + """Loads SSL context from cert/private key files and optional protocol. + Many parameters are directly taken from the API of + :py:class:`ssl.SSLContext`. + + :param cert_file: Path of the certificate to use. + :param pkey_file: Path of the private key to use. If not given, the key + will be obtained from the certificate file. + :param protocol: One of the ``PROTOCOL_*`` constants in the stdlib ``ssl`` + module. Defaults to ``PROTOCOL_SSLv23``. + """ + if protocol is None: + protocol = ssl.PROTOCOL_SSLv23 + ctx = _SSLContext(protocol) + ctx.load_cert_chain(cert_file, pkey_file) + return ctx + + +class _SSLContext(object): + + '''A dummy class with a small subset of Python3's ``ssl.SSLContext``, only + intended to be used with and by Werkzeug.''' + + def __init__(self, protocol): + self._protocol = protocol + self._certfile = None + self._keyfile = None + self._password = None + + def load_cert_chain(self, certfile, keyfile=None, password=None): + self._certfile = certfile + self._keyfile = keyfile or certfile + self._password = password + + def wrap_socket(self, sock, **kwargs): + return ssl.wrap_socket(sock, keyfile=self._keyfile, + certfile=self._certfile, + ssl_version=self._protocol, **kwargs) + + +def is_ssl_error(error=None): + """Checks if the given error (or the current one) is an SSL error.""" + exc_types = (ssl.SSLError,) + try: + from OpenSSL.SSL import Error + exc_types += (Error,) + except ImportError: + pass + + if error is None: + error = sys.exc_info()[1] + return isinstance(error, exc_types) + + +def select_ip_version(host, port): + """Returns AF_INET4 or AF_INET6 depending on where to connect to.""" + # disabled due to problems with current ipv6 implementations + # and various operating systems. Probably this code also is + # not supposed to work, but I can't come up with any other + # ways to implement this. + # try: + # info = socket.getaddrinfo(host, port, socket.AF_UNSPEC, + # socket.SOCK_STREAM, 0, + # socket.AI_PASSIVE) + # if info: + # return info[0][0] + # except socket.gaierror: + # pass + if ':' in host and hasattr(socket, 'AF_INET6'): + return socket.AF_INET6 + return socket.AF_INET + + +def get_sockaddr(host, port, family): + """Returns a fully qualified socket address, that can properly used by + socket.bind""" + try: + res = socket.getaddrinfo(host, port, family, + socket.SOCK_STREAM, socket.SOL_TCP) + except socket.gaierror: + return (host, port) + return res[0][4] + + +class BaseWSGIServer(HTTPServer, object): + + """Simple single-threaded, single-process WSGI server.""" + multithread = False + multiprocess = False + request_queue_size = LISTEN_QUEUE + + def __init__(self, host, port, app, handler=None, + passthrough_errors=False, ssl_context=None, fd=None): + if handler is None: + handler = WSGIRequestHandler + + self.address_family = select_ip_version(host, port) + + if fd is not None: + real_sock = socket.fromfd(fd, self.address_family, + socket.SOCK_STREAM) + port = 0 + HTTPServer.__init__(self, get_sockaddr(host, int(port), + self.address_family), handler) + self.app = app + self.passthrough_errors = passthrough_errors + self.shutdown_signal = False + self.host = host + self.port = self.socket.getsockname()[1] + + # Patch in the original socket. + if fd is not None: + self.socket.close() + self.socket = real_sock + self.server_address = self.socket.getsockname() + + if ssl_context is not None: + if isinstance(ssl_context, tuple): + ssl_context = load_ssl_context(*ssl_context) + if ssl_context == 'adhoc': + ssl_context = generate_adhoc_ssl_context() + # If we are on Python 2 the return value from socket.fromfd + # is an internal socket object but what we need for ssl wrap + # is the wrapper around it :( + sock = self.socket + if PY2 and not isinstance(sock, socket.socket): + sock = socket.socket(sock.family, sock.type, sock.proto, sock) + self.socket = ssl_context.wrap_socket(sock, server_side=True) + self.ssl_context = ssl_context + else: + self.ssl_context = None + + def log(self, type, message, *args): + _log(type, message, *args) + + def serve_forever(self): + self.shutdown_signal = False + try: + HTTPServer.serve_forever(self) + except KeyboardInterrupt: + pass + finally: + self.server_close() + + def handle_error(self, request, client_address): + if self.passthrough_errors: + raise + return HTTPServer.handle_error(self, request, client_address) + + def get_request(self): + con, info = self.socket.accept() + return con, info + + +class ThreadedWSGIServer(ThreadingMixIn, BaseWSGIServer): + + """A WSGI server that does threading.""" + multithread = True + daemon_threads = True + + +class ForkingWSGIServer(ForkingMixIn, BaseWSGIServer): + + """A WSGI server that does forking.""" + multiprocess = True + + def __init__(self, host, port, app, processes=40, handler=None, + passthrough_errors=False, ssl_context=None, fd=None): + if not can_fork: + raise ValueError('Your platform does not support forking.') + BaseWSGIServer.__init__(self, host, port, app, handler, + passthrough_errors, ssl_context, fd) + self.max_children = processes + + +def make_server(host=None, port=None, app=None, threaded=False, processes=1, + request_handler=None, passthrough_errors=False, + ssl_context=None, fd=None): + """Create a new server instance that is either threaded, or forks + or just processes one request after another. + """ + if threaded and processes > 1: + raise ValueError("cannot have a multithreaded and " + "multi process server.") + elif threaded: + return ThreadedWSGIServer(host, port, app, request_handler, + passthrough_errors, ssl_context, fd=fd) + elif processes > 1: + return ForkingWSGIServer(host, port, app, processes, request_handler, + passthrough_errors, ssl_context, fd=fd) + else: + return BaseWSGIServer(host, port, app, request_handler, + passthrough_errors, ssl_context, fd=fd) + + +def is_running_from_reloader(): + """Checks if the application is running from within the Werkzeug + reloader subprocess. + + .. versionadded:: 0.10 + """ + return os.environ.get('WERKZEUG_RUN_MAIN') == 'true' + + +def run_simple(hostname, port, application, use_reloader=False, + use_debugger=False, use_evalex=True, + extra_files=None, reloader_interval=1, + reloader_type='auto', threaded=False, + processes=1, request_handler=None, static_files=None, + passthrough_errors=False, ssl_context=None): + """Start a WSGI application. Optional features include a reloader, + multithreading and fork support. + + This function has a command-line interface too:: + + python -m werkzeug.serving --help + + .. versionadded:: 0.5 + `static_files` was added to simplify serving of static files as well + as `passthrough_errors`. + + .. versionadded:: 0.6 + support for SSL was added. + + .. versionadded:: 0.8 + Added support for automatically loading a SSL context from certificate + file and private key. + + .. versionadded:: 0.9 + Added command-line interface. + + .. versionadded:: 0.10 + Improved the reloader and added support for changing the backend + through the `reloader_type` parameter. See :ref:`reloader` + for more information. + + :param hostname: The host for the application. eg: ``'localhost'`` + :param port: The port for the server. eg: ``8080`` + :param application: the WSGI application to execute + :param use_reloader: should the server automatically restart the python + process if modules were changed? + :param use_debugger: should the werkzeug debugging system be used? + :param use_evalex: should the exception evaluation feature be enabled? + :param extra_files: a list of files the reloader should watch + additionally to the modules. For example configuration + files. + :param reloader_interval: the interval for the reloader in seconds. + :param reloader_type: the type of reloader to use. The default is + auto detection. Valid values are ``'stat'`` and + ``'watchdog'``. See :ref:`reloader` for more + information. + :param threaded: should the process handle each request in a separate + thread? + :param processes: if greater than 1 then handle each request in a new process + up to this maximum number of concurrent processes. + :param request_handler: optional parameter that can be used to replace + the default one. You can use this to replace it + with a different + :class:`~BaseHTTPServer.BaseHTTPRequestHandler` + subclass. + :param static_files: a list or dict of paths for static files. This works + exactly like :class:`SharedDataMiddleware`, it's actually + just wrapping the application in that middleware before + serving. + :param passthrough_errors: set this to `True` to disable the error catching. + This means that the server will die on errors but + it can be useful to hook debuggers in (pdb etc.) + :param ssl_context: an SSL context for the connection. Either an + :class:`ssl.SSLContext`, a tuple in the form + ``(cert_file, pkey_file)``, the string ``'adhoc'`` if + the server should automatically create one, or ``None`` + to disable SSL (which is the default). + """ + if not isinstance(port, int): + raise TypeError('port must be an integer') + if use_debugger: + from werkzeug.debug import DebuggedApplication + application = DebuggedApplication(application, use_evalex) + if static_files: + from werkzeug.wsgi import SharedDataMiddleware + application = SharedDataMiddleware(application, static_files) + + def log_startup(sock): + display_hostname = hostname not in ('', '*') and hostname or 'localhost' + if ':' in display_hostname: + display_hostname = '[%s]' % display_hostname + quit_msg = '(Press CTRL+C to quit)' + port = sock.getsockname()[1] + _log('info', ' * Running on %s://%s:%d/ %s', + ssl_context is None and 'http' or 'https', + display_hostname, port, quit_msg) + + def inner(): + try: + fd = int(os.environ['WERKZEUG_SERVER_FD']) + except (LookupError, ValueError): + fd = None + srv = make_server(hostname, port, application, threaded, + processes, request_handler, + passthrough_errors, ssl_context, + fd=fd) + if fd is None: + log_startup(srv.socket) + srv.serve_forever() + + if use_reloader: + # If we're not running already in the subprocess that is the + # reloader we want to open up a socket early to make sure the + # port is actually available. + if os.environ.get('WERKZEUG_RUN_MAIN') != 'true': + if port == 0 and not can_open_by_fd: + raise ValueError('Cannot bind to a random port with enabled ' + 'reloader if the Python interpreter does ' + 'not support socket opening by fd.') + + # Create and destroy a socket so that any exceptions are + # raised before we spawn a separate Python interpreter and + # lose this ability. + address_family = select_ip_version(hostname, port) + s = socket.socket(address_family, socket.SOCK_STREAM) + s.setsockopt(socket.SOL_SOCKET, socket.SO_REUSEADDR, 1) + s.bind(get_sockaddr(hostname, port, address_family)) + if hasattr(s, 'set_inheritable'): + s.set_inheritable(True) + + # If we can open the socket by file descriptor, then we can just + # reuse this one and our socket will survive the restarts. + if can_open_by_fd: + os.environ['WERKZEUG_SERVER_FD'] = str(s.fileno()) + s.listen(LISTEN_QUEUE) + log_startup(s) + else: + s.close() + + # Do not use relative imports, otherwise "python -m werkzeug.serving" + # breaks. + from werkzeug._reloader import run_with_reloader + run_with_reloader(inner, extra_files, reloader_interval, + reloader_type) + else: + inner() + + +def run_with_reloader(*args, **kwargs): + # People keep using undocumented APIs. Do not use this function + # please, we do not guarantee that it continues working. + from werkzeug._reloader import run_with_reloader + return run_with_reloader(*args, **kwargs) + + +def main(): + '''A simple command-line interface for :py:func:`run_simple`.''' + + # in contrast to argparse, this works at least under Python < 2.7 + import optparse + from werkzeug.utils import import_string + + parser = optparse.OptionParser( + usage='Usage: %prog [options] app_module:app_object') + parser.add_option('-b', '--bind', dest='address', + help='The hostname:port the app should listen on.') + parser.add_option('-d', '--debug', dest='use_debugger', + action='store_true', default=False, + help='Use Werkzeug\'s debugger.') + parser.add_option('-r', '--reload', dest='use_reloader', + action='store_true', default=False, + help='Reload Python process if modules change.') + options, args = parser.parse_args() + + hostname, port = None, None + if options.address: + address = options.address.split(':') + hostname = address[0] + if len(address) > 1: + port = address[1] + + if len(args) != 1: + sys.stdout.write('No application supplied, or too much. See --help\n') + sys.exit(1) + app = import_string(args[0]) + + run_simple( + hostname=(hostname or '127.0.0.1'), port=int(port or 5000), + application=app, use_reloader=options.use_reloader, + use_debugger=options.use_debugger + ) + +if __name__ == '__main__': + main() diff --git a/pyextra/werkzeug/test.py b/pyextra/werkzeug/test.py new file mode 100644 index 00000000000000..acd21793df7133 --- /dev/null +++ b/pyextra/werkzeug/test.py @@ -0,0 +1,948 @@ +# -*- coding: utf-8 -*- +""" + werkzeug.test + ~~~~~~~~~~~~~ + + This module implements a client to WSGI applications for testing. + + :copyright: (c) 2014 by the Werkzeug Team, see AUTHORS for more details. + :license: BSD, see LICENSE for more details. +""" +import sys +import mimetypes +from time import time +from random import random +from itertools import chain +from tempfile import TemporaryFile +from io import BytesIO + +try: + from urllib2 import Request as U2Request +except ImportError: + from urllib.request import Request as U2Request +try: + from http.cookiejar import CookieJar +except ImportError: # Py2 + from cookielib import CookieJar + +from werkzeug._compat import iterlists, iteritems, itervalues, to_bytes, \ + string_types, text_type, reraise, wsgi_encoding_dance, \ + make_literal_wrapper +from werkzeug._internal import _empty_stream, _get_environ +from werkzeug.wrappers import BaseRequest +from werkzeug.urls import url_encode, url_fix, iri_to_uri, url_unquote, \ + url_unparse, url_parse +from werkzeug.wsgi import get_host, get_current_url, ClosingIterator +from werkzeug.utils import dump_cookie, get_content_type +from werkzeug.datastructures import FileMultiDict, MultiDict, \ + CombinedMultiDict, Headers, FileStorage, CallbackDict +from werkzeug.http import dump_options_header, parse_options_header + + +def stream_encode_multipart(values, use_tempfile=True, threshold=1024 * 500, + boundary=None, charset='utf-8'): + """Encode a dict of values (either strings or file descriptors or + :class:`FileStorage` objects.) into a multipart encoded string stored + in a file descriptor. + """ + if boundary is None: + boundary = '---------------WerkzeugFormPart_%s%s' % (time(), random()) + _closure = [BytesIO(), 0, False] + + if use_tempfile: + def write_binary(string): + stream, total_length, on_disk = _closure + if on_disk: + stream.write(string) + else: + length = len(string) + if length + _closure[1] <= threshold: + stream.write(string) + else: + new_stream = TemporaryFile('wb+') + new_stream.write(stream.getvalue()) + new_stream.write(string) + _closure[0] = new_stream + _closure[2] = True + _closure[1] = total_length + length + else: + write_binary = _closure[0].write + + def write(string): + write_binary(string.encode(charset)) + + if not isinstance(values, MultiDict): + values = MultiDict(values) + + for key, values in iterlists(values): + for value in values: + write('--%s\r\nContent-Disposition: form-data; name="%s"' % + (boundary, key)) + reader = getattr(value, 'read', None) + if reader is not None: + filename = getattr(value, 'filename', + getattr(value, 'name', None)) + content_type = getattr(value, 'content_type', None) + if content_type is None: + content_type = filename and \ + mimetypes.guess_type(filename)[0] or \ + 'application/octet-stream' + if filename is not None: + write('; filename="%s"\r\n' % filename) + else: + write('\r\n') + write('Content-Type: %s\r\n\r\n' % content_type) + while 1: + chunk = reader(16384) + if not chunk: + break + write_binary(chunk) + else: + if not isinstance(value, string_types): + value = str(value) + + value = to_bytes(value, charset) + write('\r\n\r\n') + write_binary(value) + write('\r\n') + write('--%s--\r\n' % boundary) + + length = int(_closure[0].tell()) + _closure[0].seek(0) + return _closure[0], length, boundary + + +def encode_multipart(values, boundary=None, charset='utf-8'): + """Like `stream_encode_multipart` but returns a tuple in the form + (``boundary``, ``data``) where data is a bytestring. + """ + stream, length, boundary = stream_encode_multipart( + values, use_tempfile=False, boundary=boundary, charset=charset) + return boundary, stream.read() + + +def File(fd, filename=None, mimetype=None): + """Backwards compat.""" + from warnings import warn + warn(DeprecationWarning('werkzeug.test.File is deprecated, use the ' + 'EnvironBuilder or FileStorage instead')) + return FileStorage(fd, filename=filename, content_type=mimetype) + + +class _TestCookieHeaders(object): + + """A headers adapter for cookielib + """ + + def __init__(self, headers): + self.headers = headers + + def getheaders(self, name): + headers = [] + name = name.lower() + for k, v in self.headers: + if k.lower() == name: + headers.append(v) + return headers + + def get_all(self, name, default=None): + rv = [] + for k, v in self.headers: + if k.lower() == name.lower(): + rv.append(v) + return rv or default or [] + + +class _TestCookieResponse(object): + + """Something that looks like a httplib.HTTPResponse, but is actually just an + adapter for our test responses to make them available for cookielib. + """ + + def __init__(self, headers): + self.headers = _TestCookieHeaders(headers) + + def info(self): + return self.headers + + +class _TestCookieJar(CookieJar): + + """A cookielib.CookieJar modified to inject and read cookie headers from + and to wsgi environments, and wsgi application responses. + """ + + def inject_wsgi(self, environ): + """Inject the cookies as client headers into the server's wsgi + environment. + """ + cvals = [] + for cookie in self: + cvals.append('%s=%s' % (cookie.name, cookie.value)) + if cvals: + environ['HTTP_COOKIE'] = '; '.join(cvals) + + def extract_wsgi(self, environ, headers): + """Extract the server's set-cookie headers as cookies into the + cookie jar. + """ + self.extract_cookies( + _TestCookieResponse(headers), + U2Request(get_current_url(environ)), + ) + + +def _iter_data(data): + """Iterates over a `dict` or :class:`MultiDict` yielding all keys and + values. + This is used to iterate over the data passed to the + :class:`EnvironBuilder`. + """ + if isinstance(data, MultiDict): + for key, values in iterlists(data): + for value in values: + yield key, value + else: + for key, values in iteritems(data): + if isinstance(values, list): + for value in values: + yield key, value + else: + yield key, values + + +class EnvironBuilder(object): + + """This class can be used to conveniently create a WSGI environment + for testing purposes. It can be used to quickly create WSGI environments + or request objects from arbitrary data. + + The signature of this class is also used in some other places as of + Werkzeug 0.5 (:func:`create_environ`, :meth:`BaseResponse.from_values`, + :meth:`Client.open`). Because of this most of the functionality is + available through the constructor alone. + + Files and regular form data can be manipulated independently of each + other with the :attr:`form` and :attr:`files` attributes, but are + passed with the same argument to the constructor: `data`. + + `data` can be any of these values: + + - a `str` or `bytes` object: The object is converted into an + :attr:`input_stream`, the :attr:`content_length` is set and you have to + provide a :attr:`content_type`. + - a `dict` or :class:`MultiDict`: The keys have to be strings. The values + have to be either any of the following objects, or a list of any of the + following objects: + + - a :class:`file`-like object: These are converted into + :class:`FileStorage` objects automatically. + - a `tuple`: The :meth:`~FileMultiDict.add_file` method is called + with the key and the unpacked `tuple` items as positional + arguments. + - a `str`: The string is set as form data for the associated key. + - a file-like object: The object content is loaded in memory and then + handled like a regular `str` or a `bytes`. + + .. versionadded:: 0.6 + `path` and `base_url` can now be unicode strings that are encoded using + the :func:`iri_to_uri` function. + + :param path: the path of the request. In the WSGI environment this will + end up as `PATH_INFO`. If the `query_string` is not defined + and there is a question mark in the `path` everything after + it is used as query string. + :param base_url: the base URL is a URL that is used to extract the WSGI + URL scheme, host (server name + server port) and the + script root (`SCRIPT_NAME`). + :param query_string: an optional string or dict with URL parameters. + :param method: the HTTP method to use, defaults to `GET`. + :param input_stream: an optional input stream. Do not specify this and + `data`. As soon as an input stream is set you can't + modify :attr:`args` and :attr:`files` unless you + set the :attr:`input_stream` to `None` again. + :param content_type: The content type for the request. As of 0.5 you + don't have to provide this when specifying files + and form data via `data`. + :param content_length: The content length for the request. You don't + have to specify this when providing data via + `data`. + :param errors_stream: an optional error stream that is used for + `wsgi.errors`. Defaults to :data:`stderr`. + :param multithread: controls `wsgi.multithread`. Defaults to `False`. + :param multiprocess: controls `wsgi.multiprocess`. Defaults to `False`. + :param run_once: controls `wsgi.run_once`. Defaults to `False`. + :param headers: an optional list or :class:`Headers` object of headers. + :param data: a string or dict of form data or a file-object. + See explanation above. + :param environ_base: an optional dict of environment defaults. + :param environ_overrides: an optional dict of environment overrides. + :param charset: the charset used to encode unicode data. + """ + + #: the server protocol to use. defaults to HTTP/1.1 + server_protocol = 'HTTP/1.1' + + #: the wsgi version to use. defaults to (1, 0) + wsgi_version = (1, 0) + + #: the default request class for :meth:`get_request` + request_class = BaseRequest + + def __init__(self, path='/', base_url=None, query_string=None, + method='GET', input_stream=None, content_type=None, + content_length=None, errors_stream=None, multithread=False, + multiprocess=False, run_once=False, headers=None, data=None, + environ_base=None, environ_overrides=None, charset='utf-8', + mimetype=None): + path_s = make_literal_wrapper(path) + if query_string is None and path_s('?') in path: + path, query_string = path.split(path_s('?'), 1) + self.charset = charset + self.path = iri_to_uri(path) + if base_url is not None: + base_url = url_fix(iri_to_uri(base_url, charset), charset) + self.base_url = base_url + if isinstance(query_string, (bytes, text_type)): + self.query_string = query_string + else: + if query_string is None: + query_string = MultiDict() + elif not isinstance(query_string, MultiDict): + query_string = MultiDict(query_string) + self.args = query_string + self.method = method + if headers is None: + headers = Headers() + elif not isinstance(headers, Headers): + headers = Headers(headers) + self.headers = headers + if content_type is not None: + self.content_type = content_type + if errors_stream is None: + errors_stream = sys.stderr + self.errors_stream = errors_stream + self.multithread = multithread + self.multiprocess = multiprocess + self.run_once = run_once + self.environ_base = environ_base + self.environ_overrides = environ_overrides + self.input_stream = input_stream + self.content_length = content_length + self.closed = False + + if data: + if input_stream is not None: + raise TypeError('can\'t provide input stream and data') + if hasattr(data, 'read'): + data = data.read() + if isinstance(data, text_type): + data = data.encode(self.charset) + if isinstance(data, bytes): + self.input_stream = BytesIO(data) + if self.content_length is None: + self.content_length = len(data) + else: + for key, value in _iter_data(data): + if isinstance(value, (tuple, dict)) or \ + hasattr(value, 'read'): + self._add_file_from_data(key, value) + else: + self.form.setlistdefault(key).append(value) + + if mimetype is not None: + self.mimetype = mimetype + + def _add_file_from_data(self, key, value): + """Called in the EnvironBuilder to add files from the data dict.""" + if isinstance(value, tuple): + self.files.add_file(key, *value) + elif isinstance(value, dict): + from warnings import warn + warn(DeprecationWarning('it\'s no longer possible to pass dicts ' + 'as `data`. Use tuples or FileStorage ' + 'objects instead'), stacklevel=2) + value = dict(value) + mimetype = value.pop('mimetype', None) + if mimetype is not None: + value['content_type'] = mimetype + self.files.add_file(key, **value) + else: + self.files.add_file(key, value) + + def _get_base_url(self): + return url_unparse((self.url_scheme, self.host, + self.script_root, '', '')).rstrip('/') + '/' + + def _set_base_url(self, value): + if value is None: + scheme = 'http' + netloc = 'localhost' + script_root = '' + else: + scheme, netloc, script_root, qs, anchor = url_parse(value) + if qs or anchor: + raise ValueError('base url must not contain a query string ' + 'or fragment') + self.script_root = script_root.rstrip('/') + self.host = netloc + self.url_scheme = scheme + + base_url = property(_get_base_url, _set_base_url, doc=''' + The base URL is a URL that is used to extract the WSGI + URL scheme, host (server name + server port) and the + script root (`SCRIPT_NAME`).''') + del _get_base_url, _set_base_url + + def _get_content_type(self): + ct = self.headers.get('Content-Type') + if ct is None and not self._input_stream: + if self._files: + return 'multipart/form-data' + elif self._form: + return 'application/x-www-form-urlencoded' + return None + return ct + + def _set_content_type(self, value): + if value is None: + self.headers.pop('Content-Type', None) + else: + self.headers['Content-Type'] = value + + content_type = property(_get_content_type, _set_content_type, doc=''' + The content type for the request. Reflected from and to the + :attr:`headers`. Do not set if you set :attr:`files` or + :attr:`form` for auto detection.''') + del _get_content_type, _set_content_type + + def _get_content_length(self): + return self.headers.get('Content-Length', type=int) + + def _get_mimetype(self): + ct = self.content_type + if ct: + return ct.split(';')[0].strip() + + def _set_mimetype(self, value): + self.content_type = get_content_type(value, self.charset) + + def _get_mimetype_params(self): + def on_update(d): + self.headers['Content-Type'] = \ + dump_options_header(self.mimetype, d) + d = parse_options_header(self.headers.get('content-type', ''))[1] + return CallbackDict(d, on_update) + + mimetype = property(_get_mimetype, _set_mimetype, doc=''' + The mimetype (content type without charset etc.) + + .. versionadded:: 0.14 + ''') + mimetype_params = property(_get_mimetype_params, doc=''' + The mimetype parameters as dict. For example if the content + type is ``text/html; charset=utf-8`` the params would be + ``{'charset': 'utf-8'}``. + + .. versionadded:: 0.14 + ''') + del _get_mimetype, _set_mimetype, _get_mimetype_params + + def _set_content_length(self, value): + if value is None: + self.headers.pop('Content-Length', None) + else: + self.headers['Content-Length'] = str(value) + + content_length = property(_get_content_length, _set_content_length, doc=''' + The content length as integer. Reflected from and to the + :attr:`headers`. Do not set if you set :attr:`files` or + :attr:`form` for auto detection.''') + del _get_content_length, _set_content_length + + def form_property(name, storage, doc): + key = '_' + name + + def getter(self): + if self._input_stream is not None: + raise AttributeError('an input stream is defined') + rv = getattr(self, key) + if rv is None: + rv = storage() + setattr(self, key, rv) + + return rv + + def setter(self, value): + self._input_stream = None + setattr(self, key, value) + return property(getter, setter, doc=doc) + + form = form_property('form', MultiDict, doc=''' + A :class:`MultiDict` of form values.''') + files = form_property('files', FileMultiDict, doc=''' + A :class:`FileMultiDict` of uploaded files. You can use the + :meth:`~FileMultiDict.add_file` method to add new files to the + dict.''') + del form_property + + def _get_input_stream(self): + return self._input_stream + + def _set_input_stream(self, value): + self._input_stream = value + self._form = self._files = None + + input_stream = property(_get_input_stream, _set_input_stream, doc=''' + An optional input stream. If you set this it will clear + :attr:`form` and :attr:`files`.''') + del _get_input_stream, _set_input_stream + + def _get_query_string(self): + if self._query_string is None: + if self._args is not None: + return url_encode(self._args, charset=self.charset) + return '' + return self._query_string + + def _set_query_string(self, value): + self._query_string = value + self._args = None + + query_string = property(_get_query_string, _set_query_string, doc=''' + The query string. If you set this to a string :attr:`args` will + no longer be available.''') + del _get_query_string, _set_query_string + + def _get_args(self): + if self._query_string is not None: + raise AttributeError('a query string is defined') + if self._args is None: + self._args = MultiDict() + return self._args + + def _set_args(self, value): + self._query_string = None + self._args = value + + args = property(_get_args, _set_args, doc=''' + The URL arguments as :class:`MultiDict`.''') + del _get_args, _set_args + + @property + def server_name(self): + """The server name (read-only, use :attr:`host` to set)""" + return self.host.split(':', 1)[0] + + @property + def server_port(self): + """The server port as integer (read-only, use :attr:`host` to set)""" + pieces = self.host.split(':', 1) + if len(pieces) == 2 and pieces[1].isdigit(): + return int(pieces[1]) + elif self.url_scheme == 'https': + return 443 + return 80 + + def __del__(self): + try: + self.close() + except Exception: + pass + + def close(self): + """Closes all files. If you put real :class:`file` objects into the + :attr:`files` dict you can call this method to automatically close + them all in one go. + """ + if self.closed: + return + try: + files = itervalues(self.files) + except AttributeError: + files = () + for f in files: + try: + f.close() + except Exception: + pass + self.closed = True + + def get_environ(self): + """Return the built environ.""" + input_stream = self.input_stream + content_length = self.content_length + + mimetype = self.mimetype + content_type = self.content_type + + if input_stream is not None: + start_pos = input_stream.tell() + input_stream.seek(0, 2) + end_pos = input_stream.tell() + input_stream.seek(start_pos) + content_length = end_pos - start_pos + elif mimetype == 'multipart/form-data': + values = CombinedMultiDict([self.form, self.files]) + input_stream, content_length, boundary = \ + stream_encode_multipart(values, charset=self.charset) + content_type = mimetype + '; boundary="%s"' % boundary + elif mimetype == 'application/x-www-form-urlencoded': + # XXX: py2v3 review + values = url_encode(self.form, charset=self.charset) + values = values.encode('ascii') + content_length = len(values) + input_stream = BytesIO(values) + else: + input_stream = _empty_stream + + result = {} + if self.environ_base: + result.update(self.environ_base) + + def _path_encode(x): + return wsgi_encoding_dance(url_unquote(x, self.charset), self.charset) + + qs = wsgi_encoding_dance(self.query_string) + + result.update({ + 'REQUEST_METHOD': self.method, + 'SCRIPT_NAME': _path_encode(self.script_root), + 'PATH_INFO': _path_encode(self.path), + 'QUERY_STRING': qs, + 'SERVER_NAME': self.server_name, + 'SERVER_PORT': str(self.server_port), + 'HTTP_HOST': self.host, + 'SERVER_PROTOCOL': self.server_protocol, + 'CONTENT_TYPE': content_type or '', + 'CONTENT_LENGTH': str(content_length or '0'), + 'wsgi.version': self.wsgi_version, + 'wsgi.url_scheme': self.url_scheme, + 'wsgi.input': input_stream, + 'wsgi.errors': self.errors_stream, + 'wsgi.multithread': self.multithread, + 'wsgi.multiprocess': self.multiprocess, + 'wsgi.run_once': self.run_once + }) + for key, value in self.headers.to_wsgi_list(): + result['HTTP_%s' % key.upper().replace('-', '_')] = value + if self.environ_overrides: + result.update(self.environ_overrides) + return result + + def get_request(self, cls=None): + """Returns a request with the data. If the request class is not + specified :attr:`request_class` is used. + + :param cls: The request wrapper to use. + """ + if cls is None: + cls = self.request_class + return cls(self.get_environ()) + + +class ClientRedirectError(Exception): + + """ + If a redirect loop is detected when using follow_redirects=True with + the :cls:`Client`, then this exception is raised. + """ + + +class Client(object): + + """This class allows to send requests to a wrapped application. + + The response wrapper can be a class or factory function that takes + three arguments: app_iter, status and headers. The default response + wrapper just returns a tuple. + + Example:: + + class ClientResponse(BaseResponse): + ... + + client = Client(MyApplication(), response_wrapper=ClientResponse) + + The use_cookies parameter indicates whether cookies should be stored and + sent for subsequent requests. This is True by default, but passing False + will disable this behaviour. + + If you want to request some subdomain of your application you may set + `allow_subdomain_redirects` to `True` as if not no external redirects + are allowed. + + .. versionadded:: 0.5 + `use_cookies` is new in this version. Older versions did not provide + builtin cookie support. + + .. versionadded:: 0.14 + The `mimetype` parameter was added. + """ + + def __init__(self, application, response_wrapper=None, use_cookies=True, + allow_subdomain_redirects=False): + self.application = application + self.response_wrapper = response_wrapper + if use_cookies: + self.cookie_jar = _TestCookieJar() + else: + self.cookie_jar = None + self.allow_subdomain_redirects = allow_subdomain_redirects + + def set_cookie(self, server_name, key, value='', max_age=None, + expires=None, path='/', domain=None, secure=None, + httponly=False, charset='utf-8'): + """Sets a cookie in the client's cookie jar. The server name + is required and has to match the one that is also passed to + the open call. + """ + assert self.cookie_jar is not None, 'cookies disabled' + header = dump_cookie(key, value, max_age, expires, path, domain, + secure, httponly, charset) + environ = create_environ(path, base_url='http://' + server_name) + headers = [('Set-Cookie', header)] + self.cookie_jar.extract_wsgi(environ, headers) + + def delete_cookie(self, server_name, key, path='/', domain=None): + """Deletes a cookie in the test client.""" + self.set_cookie(server_name, key, expires=0, max_age=0, + path=path, domain=domain) + + def run_wsgi_app(self, environ, buffered=False): + """Runs the wrapped WSGI app with the given environment.""" + if self.cookie_jar is not None: + self.cookie_jar.inject_wsgi(environ) + rv = run_wsgi_app(self.application, environ, buffered=buffered) + if self.cookie_jar is not None: + self.cookie_jar.extract_wsgi(environ, rv[2]) + return rv + + def resolve_redirect(self, response, new_location, environ, buffered=False): + """Resolves a single redirect and triggers the request again + directly on this redirect client. + """ + scheme, netloc, script_root, qs, anchor = url_parse(new_location) + base_url = url_unparse((scheme, netloc, '', '', '')).rstrip('/') + '/' + + cur_server_name = netloc.split(':', 1)[0].split('.') + real_server_name = get_host(environ).rsplit(':', 1)[0].split('.') + if cur_server_name == ['']: + # this is a local redirect having autocorrect_location_header=False + cur_server_name = real_server_name + base_url = EnvironBuilder(environ).base_url + + if self.allow_subdomain_redirects: + allowed = cur_server_name[-len(real_server_name):] == real_server_name + else: + allowed = cur_server_name == real_server_name + + if not allowed: + raise RuntimeError('%r does not support redirect to ' + 'external targets' % self.__class__) + + status_code = int(response[1].split(None, 1)[0]) + if status_code == 307: + method = environ['REQUEST_METHOD'] + else: + method = 'GET' + + # For redirect handling we temporarily disable the response + # wrapper. This is not threadsafe but not a real concern + # since the test client must not be shared anyways. + old_response_wrapper = self.response_wrapper + self.response_wrapper = None + try: + return self.open(path=script_root, base_url=base_url, + query_string=qs, as_tuple=True, + buffered=buffered, method=method) + finally: + self.response_wrapper = old_response_wrapper + + def open(self, *args, **kwargs): + """Takes the same arguments as the :class:`EnvironBuilder` class with + some additions: You can provide a :class:`EnvironBuilder` or a WSGI + environment as only argument instead of the :class:`EnvironBuilder` + arguments and two optional keyword arguments (`as_tuple`, `buffered`) + that change the type of the return value or the way the application is + executed. + + .. versionchanged:: 0.5 + If a dict is provided as file in the dict for the `data` parameter + the content type has to be called `content_type` now instead of + `mimetype`. This change was made for consistency with + :class:`werkzeug.FileWrapper`. + + The `follow_redirects` parameter was added to :func:`open`. + + Additional parameters: + + :param as_tuple: Returns a tuple in the form ``(environ, result)`` + :param buffered: Set this to True to buffer the application run. + This will automatically close the application for + you as well. + :param follow_redirects: Set this to True if the `Client` should + follow HTTP redirects. + """ + as_tuple = kwargs.pop('as_tuple', False) + buffered = kwargs.pop('buffered', False) + follow_redirects = kwargs.pop('follow_redirects', False) + environ = None + if not kwargs and len(args) == 1: + if isinstance(args[0], EnvironBuilder): + environ = args[0].get_environ() + elif isinstance(args[0], dict): + environ = args[0] + if environ is None: + builder = EnvironBuilder(*args, **kwargs) + try: + environ = builder.get_environ() + finally: + builder.close() + + response = self.run_wsgi_app(environ, buffered=buffered) + + # handle redirects + redirect_chain = [] + while 1: + status_code = int(response[1].split(None, 1)[0]) + if status_code not in (301, 302, 303, 305, 307) \ + or not follow_redirects: + break + new_location = response[2]['location'] + new_redirect_entry = (new_location, status_code) + if new_redirect_entry in redirect_chain: + raise ClientRedirectError('loop detected') + redirect_chain.append(new_redirect_entry) + environ, response = self.resolve_redirect(response, new_location, + environ, + buffered=buffered) + + if self.response_wrapper is not None: + response = self.response_wrapper(*response) + if as_tuple: + return environ, response + return response + + def get(self, *args, **kw): + """Like open but method is enforced to GET.""" + kw['method'] = 'GET' + return self.open(*args, **kw) + + def patch(self, *args, **kw): + """Like open but method is enforced to PATCH.""" + kw['method'] = 'PATCH' + return self.open(*args, **kw) + + def post(self, *args, **kw): + """Like open but method is enforced to POST.""" + kw['method'] = 'POST' + return self.open(*args, **kw) + + def head(self, *args, **kw): + """Like open but method is enforced to HEAD.""" + kw['method'] = 'HEAD' + return self.open(*args, **kw) + + def put(self, *args, **kw): + """Like open but method is enforced to PUT.""" + kw['method'] = 'PUT' + return self.open(*args, **kw) + + def delete(self, *args, **kw): + """Like open but method is enforced to DELETE.""" + kw['method'] = 'DELETE' + return self.open(*args, **kw) + + def options(self, *args, **kw): + """Like open but method is enforced to OPTIONS.""" + kw['method'] = 'OPTIONS' + return self.open(*args, **kw) + + def trace(self, *args, **kw): + """Like open but method is enforced to TRACE.""" + kw['method'] = 'TRACE' + return self.open(*args, **kw) + + def __repr__(self): + return '<%s %r>' % ( + self.__class__.__name__, + self.application + ) + + +def create_environ(*args, **kwargs): + """Create a new WSGI environ dict based on the values passed. The first + parameter should be the path of the request which defaults to '/'. The + second one can either be an absolute path (in that case the host is + localhost:80) or a full path to the request with scheme, netloc port and + the path to the script. + + This accepts the same arguments as the :class:`EnvironBuilder` + constructor. + + .. versionchanged:: 0.5 + This function is now a thin wrapper over :class:`EnvironBuilder` which + was added in 0.5. The `headers`, `environ_base`, `environ_overrides` + and `charset` parameters were added. + """ + builder = EnvironBuilder(*args, **kwargs) + try: + return builder.get_environ() + finally: + builder.close() + + +def run_wsgi_app(app, environ, buffered=False): + """Return a tuple in the form (app_iter, status, headers) of the + application output. This works best if you pass it an application that + returns an iterator all the time. + + Sometimes applications may use the `write()` callable returned + by the `start_response` function. This tries to resolve such edge + cases automatically. But if you don't get the expected output you + should set `buffered` to `True` which enforces buffering. + + If passed an invalid WSGI application the behavior of this function is + undefined. Never pass non-conforming WSGI applications to this function. + + :param app: the application to execute. + :param buffered: set to `True` to enforce buffering. + :return: tuple in the form ``(app_iter, status, headers)`` + """ + environ = _get_environ(environ) + response = [] + buffer = [] + + def start_response(status, headers, exc_info=None): + if exc_info is not None: + reraise(*exc_info) + response[:] = [status, headers] + return buffer.append + + app_rv = app(environ, start_response) + close_func = getattr(app_rv, 'close', None) + app_iter = iter(app_rv) + + # when buffering we emit the close call early and convert the + # application iterator into a regular list + if buffered: + try: + app_iter = list(app_iter) + finally: + if close_func is not None: + close_func() + + # otherwise we iterate the application iter until we have a response, chain + # the already received data with the already collected data and wrap it in + # a new `ClosingIterator` if we need to restore a `close` callable from the + # original return value. + else: + while not response: + buffer.append(next(app_iter)) + if buffer: + app_iter = chain(buffer, app_iter) + if close_func is not None and app_iter is not app_rv: + app_iter = ClosingIterator(app_iter, close_func) + + return app_iter, response[0], Headers(response[1]) diff --git a/pyextra/werkzeug/testapp.py b/pyextra/werkzeug/testapp.py new file mode 100644 index 00000000000000..595555a09b00af --- /dev/null +++ b/pyextra/werkzeug/testapp.py @@ -0,0 +1,230 @@ +# -*- coding: utf-8 -*- +""" + werkzeug.testapp + ~~~~~~~~~~~~~~~~ + + Provide a small test application that can be used to test a WSGI server + and check it for WSGI compliance. + + :copyright: (c) 2014 by the Werkzeug Team, see AUTHORS for more details. + :license: BSD, see LICENSE for more details. +""" +import os +import sys +import werkzeug +from textwrap import wrap +from werkzeug.wrappers import BaseRequest as Request, BaseResponse as Response +from werkzeug.utils import escape +import base64 + +logo = Response(base64.b64decode(''' +R0lGODlhoACgAOMIAAEDACwpAEpCAGdgAJaKAM28AOnVAP3rAP///////// +//////////////////////yH5BAEKAAgALAAAAACgAKAAAAT+EMlJq704680R+F0ojmRpnuj0rWnrv +nB8rbRs33gu0bzu/0AObxgsGn3D5HHJbCUFyqZ0ukkSDlAidctNFg7gbI9LZlrBaHGtzAae0eloe25 +7w9EDOX2fst/xenyCIn5/gFqDiVVDV4aGeYiKkhSFjnCQY5OTlZaXgZp8nJ2ekaB0SQOjqphrpnOiq +ncEn65UsLGytLVmQ6m4sQazpbtLqL/HwpnER8bHyLrLOc3Oz8PRONPU1crXN9na263dMt/g4SzjMeX +m5yDpLqgG7OzJ4u8lT/P69ej3JPn69kHzN2OIAHkB9RUYSFCFQYQJFTIkCDBiwoXWGnowaLEjRm7+G +p9A7Hhx4rUkAUaSLJlxHMqVMD/aSycSZkyTplCqtGnRAM5NQ1Ly5OmzZc6gO4d6DGAUKA+hSocWYAo +SlM6oUWX2O/o0KdaVU5vuSQLAa0ADwQgMEMB2AIECZhVSnTno6spgbtXmHcBUrQACcc2FrTrWS8wAf +78cMFBgwIBgbN+qvTt3ayikRBk7BoyGAGABAdYyfdzRQGV3l4coxrqQ84GpUBmrdR3xNIDUPAKDBSA +ADIGDhhqTZIWaDcrVX8EsbNzbkvCOxG8bN5w8ly9H8jyTJHC6DFndQydbguh2e/ctZJFXRxMAqqPVA +tQH5E64SPr1f0zz7sQYjAHg0In+JQ11+N2B0XXBeeYZgBZFx4tqBToiTCPv0YBgQv8JqA6BEf6RhXx +w1ENhRBnWV8ctEX4Ul2zc3aVGcQNC2KElyTDYyYUWvShdjDyMOGMuFjqnII45aogPhz/CodUHFwaDx +lTgsaOjNyhGWJQd+lFoAGk8ObghI0kawg+EV5blH3dr+digkYuAGSaQZFHFz2P/cTaLmhF52QeSb45 +Jwxd+uSVGHlqOZpOeJpCFZ5J+rkAkFjQ0N1tah7JJSZUFNsrkeJUJMIBi8jyaEKIhKPomnC91Uo+NB +yyaJ5umnnpInIFh4t6ZSpGaAVmizqjpByDegYl8tPE0phCYrhcMWSv+uAqHfgH88ak5UXZmlKLVJhd +dj78s1Fxnzo6yUCrV6rrDOkluG+QzCAUTbCwf9SrmMLzK6p+OPHx7DF+bsfMRq7Ec61Av9i6GLw23r +idnZ+/OO0a99pbIrJkproCQMA17OPG6suq3cca5ruDfXCCDoS7BEdvmJn5otdqscn+uogRHHXs8cbh +EIfYaDY1AkrC0cqwcZpnM6ludx72x0p7Fo/hZAcpJDjax0UdHavMKAbiKltMWCF3xxh9k25N/Viud8 +ba78iCvUkt+V6BpwMlErmcgc502x+u1nSxJSJP9Mi52awD1V4yB/QHONsnU3L+A/zR4VL/indx/y64 +gqcj+qgTeweM86f0Qy1QVbvmWH1D9h+alqg254QD8HJXHvjQaGOqEqC22M54PcftZVKVSQG9jhkv7C +JyTyDoAJfPdu8v7DRZAxsP/ky9MJ3OL36DJfCFPASC3/aXlfLOOON9vGZZHydGf8LnxYJuuVIbl83y +Az5n/RPz07E+9+zw2A2ahz4HxHo9Kt79HTMx1Q7ma7zAzHgHqYH0SoZWyTuOLMiHwSfZDAQTn0ajk9 +YQqodnUYjByQZhZak9Wu4gYQsMyEpIOAOQKze8CmEF45KuAHTvIDOfHJNipwoHMuGHBnJElUoDmAyX +c2Qm/R8Ah/iILCCJOEokGowdhDYc/yoL+vpRGwyVSCWFYZNljkhEirGXsalWcAgOdeAdoXcktF2udb +qbUhjWyMQxYO01o6KYKOr6iK3fE4MaS+DsvBsGOBaMb0Y6IxADaJhFICaOLmiWTlDAnY1KzDG4ambL +cWBA8mUzjJsN2KjSaSXGqMCVXYpYkj33mcIApyhQf6YqgeNAmNvuC0t4CsDbSshZJkCS1eNisKqlyG +cF8G2JeiDX6tO6Mv0SmjCa3MFb0bJaGPMU0X7c8XcpvMaOQmCajwSeY9G0WqbBmKv34DsMIEztU6Y2 +KiDlFdt6jnCSqx7Dmt6XnqSKaFFHNO5+FmODxMCWBEaco77lNDGXBM0ECYB/+s7nKFdwSF5hgXumQe +EZ7amRg39RHy3zIjyRCykQh8Zo2iviRKyTDn/zx6EefptJj2Cw+Ep2FSc01U5ry4KLPYsTyWnVGnvb +UpyGlhjBUljyjHhWpf8OFaXwhp9O4T1gU9UeyPPa8A2l0p1kNqPXEVRm1AOs1oAGZU596t6SOR2mcB +Oco1srWtkaVrMUzIErrKri85keKqRQYX9VX0/eAUK1hrSu6HMEX3Qh2sCh0q0D2CtnUqS4hj62sE/z +aDs2Sg7MBS6xnQeooc2R2tC9YrKpEi9pLXfYXp20tDCpSP8rKlrD4axprb9u1Df5hSbz9QU0cRpfgn +kiIzwKucd0wsEHlLpe5yHXuc6FrNelOl7pY2+11kTWx7VpRu97dXA3DO1vbkhcb4zyvERYajQgAADs +='''), mimetype='image/png') + + +TEMPLATE = u'''\ + +WSGI Information + +
+ +

WSGI Information

+

+ This page displays all available information about the WSGI server and + the underlying Python interpreter. +

Python Interpreter

+ + + + + + +
Python Version + %(python_version)s +
Platform + %(platform)s [%(os)s] +
API Version + %(api_version)s +
Byteorder + %(byteorder)s +
Werkzeug Version + %(werkzeug_version)s +
+

WSGI Environment

+ %(wsgi_env)s
+

Installed Eggs

+

+ The following python packages were installed on the system as + Python eggs: +

    %(python_eggs)s
+

System Path

+

+ The following paths are the current contents of the load path. The + following entries are looked up for Python packages. Note that not + all items in this path are folders. Gray and underlined items are + entries pointing to invalid resources or used by custom import hooks + such as the zip importer. +

+ Items with a bright background were expanded for display from a relative + path. If you encounter such paths in the output you might want to check + your setup as relative paths are usually problematic in multithreaded + environments. +

    %(sys_path)s
+
+''' + + +def iter_sys_path(): + if os.name == 'posix': + def strip(x): + prefix = os.path.expanduser('~') + if x.startswith(prefix): + x = '~' + x[len(prefix):] + return x + else: + strip = lambda x: x + + cwd = os.path.abspath(os.getcwd()) + for item in sys.path: + path = os.path.join(cwd, item or os.path.curdir) + yield strip(os.path.normpath(path)), \ + not os.path.isdir(path), path != item + + +def render_testapp(req): + try: + import pkg_resources + except ImportError: + eggs = () + else: + eggs = sorted(pkg_resources.working_set, + key=lambda x: x.project_name.lower()) + python_eggs = [] + for egg in eggs: + try: + version = egg.version + except (ValueError, AttributeError): + version = 'unknown' + python_eggs.append('
  • %s [%s]' % ( + escape(egg.project_name), + escape(version) + )) + + wsgi_env = [] + sorted_environ = sorted(req.environ.items(), + key=lambda x: repr(x[0]).lower()) + for key, value in sorted_environ: + wsgi_env.append('%s%s' % ( + escape(str(key)), + ' '.join(wrap(escape(repr(value)))) + )) + + sys_path = [] + for item, virtual, expanded in iter_sys_path(): + class_ = [] + if virtual: + class_.append('virtual') + if expanded: + class_.append('exp') + sys_path.append('%s' % ( + class_ and ' class="%s"' % ' '.join(class_) or '', + escape(item) + )) + + return (TEMPLATE % { + 'python_version': '
    '.join(escape(sys.version).splitlines()), + 'platform': escape(sys.platform), + 'os': escape(os.name), + 'api_version': sys.api_version, + 'byteorder': sys.byteorder, + 'werkzeug_version': werkzeug.__version__, + 'python_eggs': '\n'.join(python_eggs), + 'wsgi_env': '\n'.join(wsgi_env), + 'sys_path': '\n'.join(sys_path) + }).encode('utf-8') + + +def test_app(environ, start_response): + """Simple test application that dumps the environment. You can use + it to check if Werkzeug is working properly: + + .. sourcecode:: pycon + + >>> from werkzeug.serving import run_simple + >>> from werkzeug.testapp import test_app + >>> run_simple('localhost', 3000, test_app) + * Running on http://localhost:3000/ + + The application displays important information from the WSGI environment, + the Python interpreter and the installed libraries. + """ + req = Request(environ, populate_request=False) + if req.args.get('resource') == 'logo': + response = logo + else: + response = Response(render_testapp(req), mimetype='text/html') + return response(environ, start_response) + + +if __name__ == '__main__': + from werkzeug.serving import run_simple + run_simple('localhost', 5000, test_app, use_reloader=True) diff --git a/pyextra/werkzeug/urls.py b/pyextra/werkzeug/urls.py new file mode 100644 index 00000000000000..5bd9a40d899248 --- /dev/null +++ b/pyextra/werkzeug/urls.py @@ -0,0 +1,1007 @@ +# -*- coding: utf-8 -*- +""" + werkzeug.urls + ~~~~~~~~~~~~~ + + ``werkzeug.urls`` used to provide several wrapper functions for Python 2 + urlparse, whose main purpose were to work around the behavior of the Py2 + stdlib and its lack of unicode support. While this was already a somewhat + inconvenient situation, it got even more complicated because Python 3's + ``urllib.parse`` actually does handle unicode properly. In other words, + this module would wrap two libraries with completely different behavior. So + now this module contains a 2-and-3-compatible backport of Python 3's + ``urllib.parse``, which is mostly API-compatible. + + :copyright: (c) 2014 by the Werkzeug Team, see AUTHORS for more details. + :license: BSD, see LICENSE for more details. +""" +import os +import re +from werkzeug._compat import text_type, PY2, to_unicode, \ + to_native, implements_to_string, try_coerce_native, \ + normalize_string_tuple, make_literal_wrapper, \ + fix_tuple_repr +from werkzeug._internal import _encode_idna, _decode_idna +from werkzeug.datastructures import MultiDict, iter_multi_items +from collections import namedtuple + + +# A regular expression for what a valid schema looks like +_scheme_re = re.compile(r'^[a-zA-Z0-9+-.]+$') + +# Characters that are safe in any part of an URL. +_always_safe = (b'abcdefghijklmnopqrstuvwxyz' + b'ABCDEFGHIJKLMNOPQRSTUVWXYZ0123456789_.-+') + +_hexdigits = '0123456789ABCDEFabcdef' +_hextobyte = dict( + ((a + b).encode(), int(a + b, 16)) + for a in _hexdigits for b in _hexdigits +) +_bytetohex = [ + ('%%%02X' % char).encode('ascii') for char in range(256) +] + + +_URLTuple = fix_tuple_repr(namedtuple( + '_URLTuple', + ['scheme', 'netloc', 'path', 'query', 'fragment'] +)) + + +class BaseURL(_URLTuple): + + '''Superclass of :py:class:`URL` and :py:class:`BytesURL`.''' + __slots__ = () + + def replace(self, **kwargs): + """Return an URL with the same values, except for those parameters + given new values by whichever keyword arguments are specified.""" + return self._replace(**kwargs) + + @property + def host(self): + """The host part of the URL if available, otherwise `None`. The + host is either the hostname or the IP address mentioned in the + URL. It will not contain the port. + """ + return self._split_host()[0] + + @property + def ascii_host(self): + """Works exactly like :attr:`host` but will return a result that + is restricted to ASCII. If it finds a netloc that is not ASCII + it will attempt to idna decode it. This is useful for socket + operations when the URL might include internationalized characters. + """ + rv = self.host + if rv is not None and isinstance(rv, text_type): + try: + rv = _encode_idna(rv) + except UnicodeError: + rv = rv.encode('ascii', 'ignore') + return to_native(rv, 'ascii', 'ignore') + + @property + def port(self): + """The port in the URL as an integer if it was present, `None` + otherwise. This does not fill in default ports. + """ + try: + rv = int(to_native(self._split_host()[1])) + if 0 <= rv <= 65535: + return rv + except (ValueError, TypeError): + pass + + @property + def auth(self): + """The authentication part in the URL if available, `None` + otherwise. + """ + return self._split_netloc()[0] + + @property + def username(self): + """The username if it was part of the URL, `None` otherwise. + This undergoes URL decoding and will always be a unicode string. + """ + rv = self._split_auth()[0] + if rv is not None: + return _url_unquote_legacy(rv) + + @property + def raw_username(self): + """The username if it was part of the URL, `None` otherwise. + Unlike :attr:`username` this one is not being decoded. + """ + return self._split_auth()[0] + + @property + def password(self): + """The password if it was part of the URL, `None` otherwise. + This undergoes URL decoding and will always be a unicode string. + """ + rv = self._split_auth()[1] + if rv is not None: + return _url_unquote_legacy(rv) + + @property + def raw_password(self): + """The password if it was part of the URL, `None` otherwise. + Unlike :attr:`password` this one is not being decoded. + """ + return self._split_auth()[1] + + def decode_query(self, *args, **kwargs): + """Decodes the query part of the URL. Ths is a shortcut for + calling :func:`url_decode` on the query argument. The arguments and + keyword arguments are forwarded to :func:`url_decode` unchanged. + """ + return url_decode(self.query, *args, **kwargs) + + def join(self, *args, **kwargs): + """Joins this URL with another one. This is just a convenience + function for calling into :meth:`url_join` and then parsing the + return value again. + """ + return url_parse(url_join(self, *args, **kwargs)) + + def to_url(self): + """Returns a URL string or bytes depending on the type of the + information stored. This is just a convenience function + for calling :meth:`url_unparse` for this URL. + """ + return url_unparse(self) + + def decode_netloc(self): + """Decodes the netloc part into a string.""" + rv = _decode_idna(self.host or '') + + if ':' in rv: + rv = '[%s]' % rv + port = self.port + if port is not None: + rv = '%s:%d' % (rv, port) + auth = ':'.join(filter(None, [ + _url_unquote_legacy(self.raw_username or '', '/:%@'), + _url_unquote_legacy(self.raw_password or '', '/:%@'), + ])) + if auth: + rv = '%s@%s' % (auth, rv) + return rv + + def to_uri_tuple(self): + """Returns a :class:`BytesURL` tuple that holds a URI. This will + encode all the information in the URL properly to ASCII using the + rules a web browser would follow. + + It's usually more interesting to directly call :meth:`iri_to_uri` which + will return a string. + """ + return url_parse(iri_to_uri(self).encode('ascii')) + + def to_iri_tuple(self): + """Returns a :class:`URL` tuple that holds a IRI. This will try + to decode as much information as possible in the URL without + losing information similar to how a web browser does it for the + URL bar. + + It's usually more interesting to directly call :meth:`uri_to_iri` which + will return a string. + """ + return url_parse(uri_to_iri(self)) + + def get_file_location(self, pathformat=None): + """Returns a tuple with the location of the file in the form + ``(server, location)``. If the netloc is empty in the URL or + points to localhost, it's represented as ``None``. + + The `pathformat` by default is autodetection but needs to be set + when working with URLs of a specific system. The supported values + are ``'windows'`` when working with Windows or DOS paths and + ``'posix'`` when working with posix paths. + + If the URL does not point to to a local file, the server and location + are both represented as ``None``. + + :param pathformat: The expected format of the path component. + Currently ``'windows'`` and ``'posix'`` are + supported. Defaults to ``None`` which is + autodetect. + """ + if self.scheme != 'file': + return None, None + + path = url_unquote(self.path) + host = self.netloc or None + + if pathformat is None: + if os.name == 'nt': + pathformat = 'windows' + else: + pathformat = 'posix' + + if pathformat == 'windows': + if path[:1] == '/' and path[1:2].isalpha() and path[2:3] in '|:': + path = path[1:2] + ':' + path[3:] + windows_share = path[:3] in ('\\' * 3, '/' * 3) + import ntpath + path = ntpath.normpath(path) + # Windows shared drives are represented as ``\\host\\directory``. + # That results in a URL like ``file://///host/directory``, and a + # path like ``///host/directory``. We need to special-case this + # because the path contains the hostname. + if windows_share and host is None: + parts = path.lstrip('\\').split('\\', 1) + if len(parts) == 2: + host, path = parts + else: + host = parts[0] + path = '' + elif pathformat == 'posix': + import posixpath + path = posixpath.normpath(path) + else: + raise TypeError('Invalid path format %s' % repr(pathformat)) + + if host in ('127.0.0.1', '::1', 'localhost'): + host = None + + return host, path + + def _split_netloc(self): + if self._at in self.netloc: + return self.netloc.split(self._at, 1) + return None, self.netloc + + def _split_auth(self): + auth = self._split_netloc()[0] + if not auth: + return None, None + if self._colon not in auth: + return auth, None + return auth.split(self._colon, 1) + + def _split_host(self): + rv = self._split_netloc()[1] + if not rv: + return None, None + + if not rv.startswith(self._lbracket): + if self._colon in rv: + return rv.split(self._colon, 1) + return rv, None + + idx = rv.find(self._rbracket) + if idx < 0: + return rv, None + + host = rv[1:idx] + rest = rv[idx + 1:] + if rest.startswith(self._colon): + return host, rest[1:] + return host, None + + +@implements_to_string +class URL(BaseURL): + + """Represents a parsed URL. This behaves like a regular tuple but + also has some extra attributes that give further insight into the + URL. + """ + __slots__ = () + _at = '@' + _colon = ':' + _lbracket = '[' + _rbracket = ']' + + def __str__(self): + return self.to_url() + + def encode_netloc(self): + """Encodes the netloc part to an ASCII safe URL as bytes.""" + rv = self.ascii_host or '' + if ':' in rv: + rv = '[%s]' % rv + port = self.port + if port is not None: + rv = '%s:%d' % (rv, port) + auth = ':'.join(filter(None, [ + url_quote(self.raw_username or '', 'utf-8', 'strict', '/:%'), + url_quote(self.raw_password or '', 'utf-8', 'strict', '/:%'), + ])) + if auth: + rv = '%s@%s' % (auth, rv) + return to_native(rv) + + def encode(self, charset='utf-8', errors='replace'): + """Encodes the URL to a tuple made out of bytes. The charset is + only being used for the path, query and fragment. + """ + return BytesURL( + self.scheme.encode('ascii'), + self.encode_netloc(), + self.path.encode(charset, errors), + self.query.encode(charset, errors), + self.fragment.encode(charset, errors) + ) + + +class BytesURL(BaseURL): + + """Represents a parsed URL in bytes.""" + __slots__ = () + _at = b'@' + _colon = b':' + _lbracket = b'[' + _rbracket = b']' + + def __str__(self): + return self.to_url().decode('utf-8', 'replace') + + def encode_netloc(self): + """Returns the netloc unchanged as bytes.""" + return self.netloc + + def decode(self, charset='utf-8', errors='replace'): + """Decodes the URL to a tuple made out of strings. The charset is + only being used for the path, query and fragment. + """ + return URL( + self.scheme.decode('ascii'), + self.decode_netloc(), + self.path.decode(charset, errors), + self.query.decode(charset, errors), + self.fragment.decode(charset, errors) + ) + + +def _unquote_to_bytes(string, unsafe=''): + if isinstance(string, text_type): + string = string.encode('utf-8') + if isinstance(unsafe, text_type): + unsafe = unsafe.encode('utf-8') + unsafe = frozenset(bytearray(unsafe)) + bits = iter(string.split(b'%')) + result = bytearray(next(bits, b'')) + for item in bits: + try: + char = _hextobyte[item[:2]] + if char in unsafe: + raise KeyError() + result.append(char) + result.extend(item[2:]) + except KeyError: + result.extend(b'%') + result.extend(item) + return bytes(result) + + +def _url_encode_impl(obj, charset, encode_keys, sort, key): + iterable = iter_multi_items(obj) + if sort: + iterable = sorted(iterable, key=key) + for key, value in iterable: + if value is None: + continue + if not isinstance(key, bytes): + key = text_type(key).encode(charset) + if not isinstance(value, bytes): + value = text_type(value).encode(charset) + yield url_quote_plus(key) + '=' + url_quote_plus(value) + + +def _url_unquote_legacy(value, unsafe=''): + try: + return url_unquote(value, charset='utf-8', + errors='strict', unsafe=unsafe) + except UnicodeError: + return url_unquote(value, charset='latin1', unsafe=unsafe) + + +def url_parse(url, scheme=None, allow_fragments=True): + """Parses a URL from a string into a :class:`URL` tuple. If the URL + is lacking a scheme it can be provided as second argument. Otherwise, + it is ignored. Optionally fragments can be stripped from the URL + by setting `allow_fragments` to `False`. + + The inverse of this function is :func:`url_unparse`. + + :param url: the URL to parse. + :param scheme: the default schema to use if the URL is schemaless. + :param allow_fragments: if set to `False` a fragment will be removed + from the URL. + """ + s = make_literal_wrapper(url) + is_text_based = isinstance(url, text_type) + + if scheme is None: + scheme = s('') + netloc = query = fragment = s('') + i = url.find(s(':')) + if i > 0 and _scheme_re.match(to_native(url[:i], errors='replace')): + # make sure "iri" is not actually a port number (in which case + # "scheme" is really part of the path) + rest = url[i + 1:] + if not rest or any(c not in s('0123456789') for c in rest): + # not a port number + scheme, url = url[:i].lower(), rest + + if url[:2] == s('//'): + delim = len(url) + for c in s('/?#'): + wdelim = url.find(c, 2) + if wdelim >= 0: + delim = min(delim, wdelim) + netloc, url = url[2:delim], url[delim:] + if (s('[') in netloc and s(']') not in netloc) or \ + (s(']') in netloc and s('[') not in netloc): + raise ValueError('Invalid IPv6 URL') + + if allow_fragments and s('#') in url: + url, fragment = url.split(s('#'), 1) + if s('?') in url: + url, query = url.split(s('?'), 1) + + result_type = is_text_based and URL or BytesURL + return result_type(scheme, netloc, url, query, fragment) + + +def url_quote(string, charset='utf-8', errors='strict', safe='/:', unsafe=''): + """URL encode a single string with a given encoding. + + :param s: the string to quote. + :param charset: the charset to be used. + :param safe: an optional sequence of safe characters. + :param unsafe: an optional sequence of unsafe characters. + + .. versionadded:: 0.9.2 + The `unsafe` parameter was added. + """ + if not isinstance(string, (text_type, bytes, bytearray)): + string = text_type(string) + if isinstance(string, text_type): + string = string.encode(charset, errors) + if isinstance(safe, text_type): + safe = safe.encode(charset, errors) + if isinstance(unsafe, text_type): + unsafe = unsafe.encode(charset, errors) + safe = frozenset(bytearray(safe) + _always_safe) - frozenset(bytearray(unsafe)) + rv = bytearray() + for char in bytearray(string): + if char in safe: + rv.append(char) + else: + rv.extend(_bytetohex[char]) + return to_native(bytes(rv)) + + +def url_quote_plus(string, charset='utf-8', errors='strict', safe=''): + """URL encode a single string with the given encoding and convert + whitespace to "+". + + :param s: The string to quote. + :param charset: The charset to be used. + :param safe: An optional sequence of safe characters. + """ + return url_quote(string, charset, errors, safe + ' ', '+').replace(' ', '+') + + +def url_unparse(components): + """The reverse operation to :meth:`url_parse`. This accepts arbitrary + as well as :class:`URL` tuples and returns a URL as a string. + + :param components: the parsed URL as tuple which should be converted + into a URL string. + """ + scheme, netloc, path, query, fragment = \ + normalize_string_tuple(components) + s = make_literal_wrapper(scheme) + url = s('') + + # We generally treat file:///x and file:/x the same which is also + # what browsers seem to do. This also allows us to ignore a schema + # register for netloc utilization or having to differenciate between + # empty and missing netloc. + if netloc or (scheme and path.startswith(s('/'))): + if path and path[:1] != s('/'): + path = s('/') + path + url = s('//') + (netloc or s('')) + path + elif path: + url += path + if scheme: + url = scheme + s(':') + url + if query: + url = url + s('?') + query + if fragment: + url = url + s('#') + fragment + return url + + +def url_unquote(string, charset='utf-8', errors='replace', unsafe=''): + """URL decode a single string with a given encoding. If the charset + is set to `None` no unicode decoding is performed and raw bytes + are returned. + + :param s: the string to unquote. + :param charset: the charset of the query string. If set to `None` + no unicode decoding will take place. + :param errors: the error handling for the charset decoding. + """ + rv = _unquote_to_bytes(string, unsafe) + if charset is not None: + rv = rv.decode(charset, errors) + return rv + + +def url_unquote_plus(s, charset='utf-8', errors='replace'): + """URL decode a single string with the given `charset` and decode "+" to + whitespace. + + Per default encoding errors are ignored. If you want a different behavior + you can set `errors` to ``'replace'`` or ``'strict'``. In strict mode a + :exc:`HTTPUnicodeError` is raised. + + :param s: The string to unquote. + :param charset: the charset of the query string. If set to `None` + no unicode decoding will take place. + :param errors: The error handling for the `charset` decoding. + """ + if isinstance(s, text_type): + s = s.replace(u'+', u' ') + else: + s = s.replace(b'+', b' ') + return url_unquote(s, charset, errors) + + +def url_fix(s, charset='utf-8'): + r"""Sometimes you get an URL by a user that just isn't a real URL because + it contains unsafe characters like ' ' and so on. This function can fix + some of the problems in a similar way browsers handle data entered by the + user: + + >>> url_fix(u'http://de.wikipedia.org/wiki/Elf (Begriffskl\xe4rung)') + 'http://de.wikipedia.org/wiki/Elf%20(Begriffskl%C3%A4rung)' + + :param s: the string with the URL to fix. + :param charset: The target charset for the URL if the url was given as + unicode string. + """ + # First step is to switch to unicode processing and to convert + # backslashes (which are invalid in URLs anyways) to slashes. This is + # consistent with what Chrome does. + s = to_unicode(s, charset, 'replace').replace('\\', '/') + + # For the specific case that we look like a malformed windows URL + # we want to fix this up manually: + if s.startswith('file://') and s[7:8].isalpha() and s[8:10] in (':/', '|/'): + s = 'file:///' + s[7:] + + url = url_parse(s) + path = url_quote(url.path, charset, safe='/%+$!*\'(),') + qs = url_quote_plus(url.query, charset, safe=':&%=+$!*\'(),') + anchor = url_quote_plus(url.fragment, charset, safe=':&%=+$!*\'(),') + return to_native(url_unparse((url.scheme, url.encode_netloc(), + path, qs, anchor))) + + +def uri_to_iri(uri, charset='utf-8', errors='replace'): + r""" + Converts a URI in a given charset to a IRI. + + Examples for URI versus IRI: + + >>> uri_to_iri(b'http://xn--n3h.net/') + u'http://\u2603.net/' + >>> uri_to_iri(b'http://%C3%BCser:p%C3%A4ssword@xn--n3h.net/p%C3%A5th') + u'http://\xfcser:p\xe4ssword@\u2603.net/p\xe5th' + + Query strings are left unchanged: + + >>> uri_to_iri('/?foo=24&x=%26%2f') + u'/?foo=24&x=%26%2f' + + .. versionadded:: 0.6 + + :param uri: The URI to convert. + :param charset: The charset of the URI. + :param errors: The error handling on decode. + """ + if isinstance(uri, tuple): + uri = url_unparse(uri) + uri = url_parse(to_unicode(uri, charset)) + path = url_unquote(uri.path, charset, errors, '%/;?') + query = url_unquote(uri.query, charset, errors, '%;/?:@&=+,$#') + fragment = url_unquote(uri.fragment, charset, errors, '%;/?:@&=+,$#') + return url_unparse((uri.scheme, uri.decode_netloc(), + path, query, fragment)) + + +def iri_to_uri(iri, charset='utf-8', errors='strict', safe_conversion=False): + r""" + Converts any unicode based IRI to an acceptable ASCII URI. Werkzeug always + uses utf-8 URLs internally because this is what browsers and HTTP do as + well. In some places where it accepts an URL it also accepts a unicode IRI + and converts it into a URI. + + Examples for IRI versus URI: + + >>> iri_to_uri(u'http://☃.net/') + 'http://xn--n3h.net/' + >>> iri_to_uri(u'http://üser:pässword@☃.net/påth') + 'http://%C3%BCser:p%C3%A4ssword@xn--n3h.net/p%C3%A5th' + + There is a general problem with IRI and URI conversion with some + protocols that appear in the wild that are in violation of the URI + specification. In places where Werkzeug goes through a forced IRI to + URI conversion it will set the `safe_conversion` flag which will + not perform a conversion if the end result is already ASCII. This + can mean that the return value is not an entirely correct URI but + it will not destroy such invalid URLs in the process. + + As an example consider the following two IRIs:: + + magnet:?xt=uri:whatever + itms-services://?action=download-manifest + + The internal representation after parsing of those URLs is the same + and there is no way to reconstruct the original one. If safe + conversion is enabled however this function becomes a noop for both of + those strings as they both can be considered URIs. + + .. versionadded:: 0.6 + + .. versionchanged:: 0.9.6 + The `safe_conversion` parameter was added. + + :param iri: The IRI to convert. + :param charset: The charset for the URI. + :param safe_conversion: indicates if a safe conversion should take place. + For more information see the explanation above. + """ + if isinstance(iri, tuple): + iri = url_unparse(iri) + + if safe_conversion: + try: + native_iri = to_native(iri) + ascii_iri = to_native(iri).encode('ascii') + if ascii_iri.split() == [ascii_iri]: + return native_iri + except UnicodeError: + pass + + iri = url_parse(to_unicode(iri, charset, errors)) + + netloc = iri.encode_netloc() + path = url_quote(iri.path, charset, errors, '/:~+%') + query = url_quote(iri.query, charset, errors, '%&[]:;$*()+,!?*/=') + fragment = url_quote(iri.fragment, charset, errors, '=%&[]:;$()+,!?*/') + + return to_native(url_unparse((iri.scheme, netloc, + path, query, fragment))) + + +def url_decode(s, charset='utf-8', decode_keys=False, include_empty=True, + errors='replace', separator='&', cls=None): + """ + Parse a querystring and return it as :class:`MultiDict`. There is a + difference in key decoding on different Python versions. On Python 3 + keys will always be fully decoded whereas on Python 2, keys will + remain bytestrings if they fit into ASCII. On 2.x keys can be forced + to be unicode by setting `decode_keys` to `True`. + + If the charset is set to `None` no unicode decoding will happen and + raw bytes will be returned. + + Per default a missing value for a key will default to an empty key. If + you don't want that behavior you can set `include_empty` to `False`. + + Per default encoding errors are ignored. If you want a different behavior + you can set `errors` to ``'replace'`` or ``'strict'``. In strict mode a + `HTTPUnicodeError` is raised. + + .. versionchanged:: 0.5 + In previous versions ";" and "&" could be used for url decoding. + This changed in 0.5 where only "&" is supported. If you want to + use ";" instead a different `separator` can be provided. + + The `cls` parameter was added. + + :param s: a string with the query string to decode. + :param charset: the charset of the query string. If set to `None` + no unicode decoding will take place. + :param decode_keys: Used on Python 2.x to control whether keys should + be forced to be unicode objects. If set to `True` + then keys will be unicode in all cases. Otherwise, + they remain `str` if they fit into ASCII. + :param include_empty: Set to `False` if you don't want empty values to + appear in the dict. + :param errors: the decoding error behavior. + :param separator: the pair separator to be used, defaults to ``&`` + :param cls: an optional dict class to use. If this is not specified + or `None` the default :class:`MultiDict` is used. + """ + if cls is None: + cls = MultiDict + if isinstance(s, text_type) and not isinstance(separator, text_type): + separator = separator.decode(charset or 'ascii') + elif isinstance(s, bytes) and not isinstance(separator, bytes): + separator = separator.encode(charset or 'ascii') + return cls(_url_decode_impl(s.split(separator), charset, decode_keys, + include_empty, errors)) + + +def url_decode_stream(stream, charset='utf-8', decode_keys=False, + include_empty=True, errors='replace', separator='&', + cls=None, limit=None, return_iterator=False): + """Works like :func:`url_decode` but decodes a stream. The behavior + of stream and limit follows functions like + :func:`~werkzeug.wsgi.make_line_iter`. The generator of pairs is + directly fed to the `cls` so you can consume the data while it's + parsed. + + .. versionadded:: 0.8 + + :param stream: a stream with the encoded querystring + :param charset: the charset of the query string. If set to `None` + no unicode decoding will take place. + :param decode_keys: Used on Python 2.x to control whether keys should + be forced to be unicode objects. If set to `True`, + keys will be unicode in all cases. Otherwise, they + remain `str` if they fit into ASCII. + :param include_empty: Set to `False` if you don't want empty values to + appear in the dict. + :param errors: the decoding error behavior. + :param separator: the pair separator to be used, defaults to ``&`` + :param cls: an optional dict class to use. If this is not specified + or `None` the default :class:`MultiDict` is used. + :param limit: the content length of the URL data. Not necessary if + a limited stream is provided. + :param return_iterator: if set to `True` the `cls` argument is ignored + and an iterator over all decoded pairs is + returned + """ + from werkzeug.wsgi import make_chunk_iter + if return_iterator: + cls = lambda x: x + elif cls is None: + cls = MultiDict + pair_iter = make_chunk_iter(stream, separator, limit) + return cls(_url_decode_impl(pair_iter, charset, decode_keys, + include_empty, errors)) + + +def _url_decode_impl(pair_iter, charset, decode_keys, include_empty, errors): + for pair in pair_iter: + if not pair: + continue + s = make_literal_wrapper(pair) + equal = s('=') + if equal in pair: + key, value = pair.split(equal, 1) + else: + if not include_empty: + continue + key = pair + value = s('') + key = url_unquote_plus(key, charset, errors) + if charset is not None and PY2 and not decode_keys: + key = try_coerce_native(key) + yield key, url_unquote_plus(value, charset, errors) + + +def url_encode(obj, charset='utf-8', encode_keys=False, sort=False, key=None, + separator=b'&'): + """URL encode a dict/`MultiDict`. If a value is `None` it will not appear + in the result string. Per default only values are encoded into the target + charset strings. If `encode_keys` is set to ``True`` unicode keys are + supported too. + + If `sort` is set to `True` the items are sorted by `key` or the default + sorting algorithm. + + .. versionadded:: 0.5 + `sort`, `key`, and `separator` were added. + + :param obj: the object to encode into a query string. + :param charset: the charset of the query string. + :param encode_keys: set to `True` if you have unicode keys. (Ignored on + Python 3.x) + :param sort: set to `True` if you want parameters to be sorted by `key`. + :param separator: the separator to be used for the pairs. + :param key: an optional function to be used for sorting. For more details + check out the :func:`sorted` documentation. + """ + separator = to_native(separator, 'ascii') + return separator.join(_url_encode_impl(obj, charset, encode_keys, sort, key)) + + +def url_encode_stream(obj, stream=None, charset='utf-8', encode_keys=False, + sort=False, key=None, separator=b'&'): + """Like :meth:`url_encode` but writes the results to a stream + object. If the stream is `None` a generator over all encoded + pairs is returned. + + .. versionadded:: 0.8 + + :param obj: the object to encode into a query string. + :param stream: a stream to write the encoded object into or `None` if + an iterator over the encoded pairs should be returned. In + that case the separator argument is ignored. + :param charset: the charset of the query string. + :param encode_keys: set to `True` if you have unicode keys. (Ignored on + Python 3.x) + :param sort: set to `True` if you want parameters to be sorted by `key`. + :param separator: the separator to be used for the pairs. + :param key: an optional function to be used for sorting. For more details + check out the :func:`sorted` documentation. + """ + separator = to_native(separator, 'ascii') + gen = _url_encode_impl(obj, charset, encode_keys, sort, key) + if stream is None: + return gen + for idx, chunk in enumerate(gen): + if idx: + stream.write(separator) + stream.write(chunk) + + +def url_join(base, url, allow_fragments=True): + """Join a base URL and a possibly relative URL to form an absolute + interpretation of the latter. + + :param base: the base URL for the join operation. + :param url: the URL to join. + :param allow_fragments: indicates whether fragments should be allowed. + """ + if isinstance(base, tuple): + base = url_unparse(base) + if isinstance(url, tuple): + url = url_unparse(url) + + base, url = normalize_string_tuple((base, url)) + s = make_literal_wrapper(base) + + if not base: + return url + if not url: + return base + + bscheme, bnetloc, bpath, bquery, bfragment = \ + url_parse(base, allow_fragments=allow_fragments) + scheme, netloc, path, query, fragment = \ + url_parse(url, bscheme, allow_fragments) + if scheme != bscheme: + return url + if netloc: + return url_unparse((scheme, netloc, path, query, fragment)) + netloc = bnetloc + + if path[:1] == s('/'): + segments = path.split(s('/')) + elif not path: + segments = bpath.split(s('/')) + if not query: + query = bquery + else: + segments = bpath.split(s('/'))[:-1] + path.split(s('/')) + + # If the rightmost part is "./" we want to keep the slash but + # remove the dot. + if segments[-1] == s('.'): + segments[-1] = s('') + + # Resolve ".." and "." + segments = [segment for segment in segments if segment != s('.')] + while 1: + i = 1 + n = len(segments) - 1 + while i < n: + if segments[i] == s('..') and \ + segments[i - 1] not in (s(''), s('..')): + del segments[i - 1:i + 1] + break + i += 1 + else: + break + + # Remove trailing ".." if the URL is absolute + unwanted_marker = [s(''), s('..')] + while segments[:2] == unwanted_marker: + del segments[1] + + path = s('/').join(segments) + return url_unparse((scheme, netloc, path, query, fragment)) + + +class Href(object): + + """Implements a callable that constructs URLs with the given base. The + function can be called with any number of positional and keyword + arguments which than are used to assemble the URL. Works with URLs + and posix paths. + + Positional arguments are appended as individual segments to + the path of the URL: + + >>> href = Href('/foo') + >>> href('bar', 23) + '/foo/bar/23' + >>> href('foo', bar=23) + '/foo/foo?bar=23' + + If any of the arguments (positional or keyword) evaluates to `None` it + will be skipped. If no keyword arguments are given the last argument + can be a :class:`dict` or :class:`MultiDict` (or any other dict subclass), + otherwise the keyword arguments are used for the query parameters, cutting + off the first trailing underscore of the parameter name: + + >>> href(is_=42) + '/foo?is=42' + >>> href({'foo': 'bar'}) + '/foo?foo=bar' + + Combining of both methods is not allowed: + + >>> href({'foo': 'bar'}, bar=42) + Traceback (most recent call last): + ... + TypeError: keyword arguments and query-dicts can't be combined + + Accessing attributes on the href object creates a new href object with + the attribute name as prefix: + + >>> bar_href = href.bar + >>> bar_href("blub") + '/foo/bar/blub' + + If `sort` is set to `True` the items are sorted by `key` or the default + sorting algorithm: + + >>> href = Href("/", sort=True) + >>> href(a=1, b=2, c=3) + '/?a=1&b=2&c=3' + + .. versionadded:: 0.5 + `sort` and `key` were added. + """ + + def __init__(self, base='./', charset='utf-8', sort=False, key=None): + if not base: + base = './' + self.base = base + self.charset = charset + self.sort = sort + self.key = key + + def __getattr__(self, name): + if name[:2] == '__': + raise AttributeError(name) + base = self.base + if base[-1:] != '/': + base += '/' + return Href(url_join(base, name), self.charset, self.sort, self.key) + + def __call__(self, *path, **query): + if path and isinstance(path[-1], dict): + if query: + raise TypeError('keyword arguments and query-dicts ' + 'can\'t be combined') + query, path = path[-1], path[:-1] + elif query: + query = dict([(k.endswith('_') and k[:-1] or k, v) + for k, v in query.items()]) + path = '/'.join([to_unicode(url_quote(x, self.charset), 'ascii') + for x in path if x is not None]).lstrip('/') + rv = self.base + if path: + if not rv.endswith('/'): + rv += '/' + rv = url_join(rv, './' + path) + if query: + rv += '?' + to_unicode(url_encode(query, self.charset, sort=self.sort, + key=self.key), 'ascii') + return to_native(rv) diff --git a/pyextra/werkzeug/useragents.py b/pyextra/werkzeug/useragents.py new file mode 100644 index 00000000000000..4d7d41f1cf4ebc --- /dev/null +++ b/pyextra/werkzeug/useragents.py @@ -0,0 +1,212 @@ +# -*- coding: utf-8 -*- +""" + werkzeug.useragents + ~~~~~~~~~~~~~~~~~~~ + + This module provides a helper to inspect user agent strings. This module + is far from complete but should work for most of the currently available + browsers. + + + :copyright: (c) 2014 by the Werkzeug Team, see AUTHORS for more details. + :license: BSD, see LICENSE for more details. +""" +import re + + +class UserAgentParser(object): + + """A simple user agent parser. Used by the `UserAgent`.""" + + platforms = ( + ('cros', 'chromeos'), + ('iphone|ios', 'iphone'), + ('ipad', 'ipad'), + (r'darwin|mac|os\s*x', 'macos'), + ('win', 'windows'), + (r'android', 'android'), + ('netbsd', 'netbsd'), + ('openbsd', 'openbsd'), + ('freebsd', 'freebsd'), + ('dragonfly', 'dragonflybsd'), + ('(sun|i86)os', 'solaris'), + (r'x11|lin(\b|ux)?', 'linux'), + (r'nintendo\s+wii', 'wii'), + ('irix', 'irix'), + ('hp-?ux', 'hpux'), + ('aix', 'aix'), + ('sco|unix_sv', 'sco'), + ('bsd', 'bsd'), + ('amiga', 'amiga'), + ('blackberry|playbook', 'blackberry'), + ('symbian', 'symbian') + ) + browsers = ( + ('googlebot', 'google'), + ('msnbot', 'msn'), + ('yahoo', 'yahoo'), + ('ask jeeves', 'ask'), + (r'aol|america\s+online\s+browser', 'aol'), + ('opera', 'opera'), + ('edge', 'edge'), + ('chrome', 'chrome'), + ('seamonkey', 'seamonkey'), + ('firefox|firebird|phoenix|iceweasel', 'firefox'), + ('galeon', 'galeon'), + ('safari|version', 'safari'), + ('webkit', 'webkit'), + ('camino', 'camino'), + ('konqueror', 'konqueror'), + ('k-meleon', 'kmeleon'), + ('netscape', 'netscape'), + (r'msie|microsoft\s+internet\s+explorer|trident/.+? rv:', 'msie'), + ('lynx', 'lynx'), + ('links', 'links'), + ('Baiduspider', 'baidu'), + ('bingbot', 'bing'), + ('mozilla', 'mozilla') + ) + + _browser_version_re = r'(?:%s)[/\sa-z(]*(\d+[.\da-z]+)?' + _language_re = re.compile( + r'(?:;\s*|\s+)(\b\w{2}\b(?:-\b\w{2}\b)?)\s*;|' + r'(?:\(|\[|;)\s*(\b\w{2}\b(?:-\b\w{2}\b)?)\s*(?:\]|\)|;)' + ) + + def __init__(self): + self.platforms = [(b, re.compile(a, re.I)) for a, b in self.platforms] + self.browsers = [(b, re.compile(self._browser_version_re % a, re.I)) + for a, b in self.browsers] + + def __call__(self, user_agent): + for platform, regex in self.platforms: + match = regex.search(user_agent) + if match is not None: + break + else: + platform = None + for browser, regex in self.browsers: + match = regex.search(user_agent) + if match is not None: + version = match.group(1) + break + else: + browser = version = None + match = self._language_re.search(user_agent) + if match is not None: + language = match.group(1) or match.group(2) + else: + language = None + return platform, browser, version, language + + +class UserAgent(object): + + """Represents a user agent. Pass it a WSGI environment or a user agent + string and you can inspect some of the details from the user agent + string via the attributes. The following attributes exist: + + .. attribute:: string + + the raw user agent string + + .. attribute:: platform + + the browser platform. The following platforms are currently + recognized: + + - `aix` + - `amiga` + - `android` + - `blackberry` + - `bsd` + - `chromeos` + - `dragonflybsd` + - `freebsd` + - `hpux` + - `ipad` + - `iphone` + - `irix` + - `linux` + - `macos` + - `netbsd` + - `openbsd` + - `sco` + - `solaris` + - `symbian` + - `wii` + - `windows` + + .. attribute:: browser + + the name of the browser. The following browsers are currently + recognized: + + - `aol` * + - `ask` * + - `baidu` * + - `bing` * + - `camino` + - `chrome` + - `firefox` + - `galeon` + - `google` * + - `kmeleon` + - `konqueror` + - `links` + - `lynx` + - `mozilla` + - `msie` + - `msn` + - `netscape` + - `opera` + - `safari` + - `seamonkey` + - `webkit` + - `yahoo` * + + (Browsers marked with a star (``*``) are crawlers.) + + .. attribute:: version + + the version of the browser + + .. attribute:: language + + the language of the browser + """ + + _parser = UserAgentParser() + + def __init__(self, environ_or_string): + if isinstance(environ_or_string, dict): + environ_or_string = environ_or_string.get('HTTP_USER_AGENT', '') + self.string = environ_or_string + self.platform, self.browser, self.version, self.language = \ + self._parser(environ_or_string) + + def to_header(self): + return self.string + + def __str__(self): + return self.string + + def __nonzero__(self): + return bool(self.browser) + + __bool__ = __nonzero__ + + def __repr__(self): + return '<%s %r/%s>' % ( + self.__class__.__name__, + self.browser, + self.version + ) + + +# conceptionally this belongs in this module but because we want to lazily +# load the user agent module (which happens in wrappers.py) we have to import +# it afterwards. The class itself has the module set to this module so +# pickle, inspect and similar modules treat the object as if it was really +# implemented here. +from werkzeug.wrappers import UserAgentMixin # noqa diff --git a/pyextra/werkzeug/utils.py b/pyextra/werkzeug/utils.py new file mode 100644 index 00000000000000..918e7e5b60170b --- /dev/null +++ b/pyextra/werkzeug/utils.py @@ -0,0 +1,628 @@ +# -*- coding: utf-8 -*- +""" + werkzeug.utils + ~~~~~~~~~~~~~~ + + This module implements various utilities for WSGI applications. Most of + them are used by the request and response wrappers but especially for + middleware development it makes sense to use them without the wrappers. + + :copyright: (c) 2014 by the Werkzeug Team, see AUTHORS for more details. + :license: BSD, see LICENSE for more details. +""" +import re +import os +import sys +import pkgutil +try: + from html.entities import name2codepoint +except ImportError: + from htmlentitydefs import name2codepoint + +from werkzeug._compat import unichr, text_type, string_types, iteritems, \ + reraise, PY2 +from werkzeug._internal import _DictAccessorProperty, \ + _parse_signature, _missing + + +_format_re = re.compile(r'\$(?:(%s)|\{(%s)\})' % (('[a-zA-Z_][a-zA-Z0-9_]*',) * 2)) +_entity_re = re.compile(r'&([^;]+);') +_filename_ascii_strip_re = re.compile(r'[^A-Za-z0-9_.-]') +_windows_device_files = ('CON', 'AUX', 'COM1', 'COM2', 'COM3', 'COM4', 'LPT1', + 'LPT2', 'LPT3', 'PRN', 'NUL') + + +class cached_property(property): + + """A decorator that converts a function into a lazy property. The + function wrapped is called the first time to retrieve the result + and then that calculated result is used the next time you access + the value:: + + class Foo(object): + + @cached_property + def foo(self): + # calculate something important here + return 42 + + The class has to have a `__dict__` in order for this property to + work. + """ + + # implementation detail: A subclass of python's builtin property + # decorator, we override __get__ to check for a cached value. If one + # choses to invoke __get__ by hand the property will still work as + # expected because the lookup logic is replicated in __get__ for + # manual invocation. + + def __init__(self, func, name=None, doc=None): + self.__name__ = name or func.__name__ + self.__module__ = func.__module__ + self.__doc__ = doc or func.__doc__ + self.func = func + + def __set__(self, obj, value): + obj.__dict__[self.__name__] = value + + def __get__(self, obj, type=None): + if obj is None: + return self + value = obj.__dict__.get(self.__name__, _missing) + if value is _missing: + value = self.func(obj) + obj.__dict__[self.__name__] = value + return value + + +class environ_property(_DictAccessorProperty): + + """Maps request attributes to environment variables. This works not only + for the Werzeug request object, but also any other class with an + environ attribute: + + >>> class Test(object): + ... environ = {'key': 'value'} + ... test = environ_property('key') + >>> var = Test() + >>> var.test + 'value' + + If you pass it a second value it's used as default if the key does not + exist, the third one can be a converter that takes a value and converts + it. If it raises :exc:`ValueError` or :exc:`TypeError` the default value + is used. If no default value is provided `None` is used. + + Per default the property is read only. You have to explicitly enable it + by passing ``read_only=False`` to the constructor. + """ + + read_only = True + + def lookup(self, obj): + return obj.environ + + +class header_property(_DictAccessorProperty): + + """Like `environ_property` but for headers.""" + + def lookup(self, obj): + return obj.headers + + +class HTMLBuilder(object): + + """Helper object for HTML generation. + + Per default there are two instances of that class. The `html` one, and + the `xhtml` one for those two dialects. The class uses keyword parameters + and positional parameters to generate small snippets of HTML. + + Keyword parameters are converted to XML/SGML attributes, positional + arguments are used as children. Because Python accepts positional + arguments before keyword arguments it's a good idea to use a list with the + star-syntax for some children: + + >>> html.p(class_='foo', *[html.a('foo', href='foo.html'), ' ', + ... html.a('bar', href='bar.html')]) + u'

    foo bar

    ' + + This class works around some browser limitations and can not be used for + arbitrary SGML/XML generation. For that purpose lxml and similar + libraries exist. + + Calling the builder escapes the string passed: + + >>> html.p(html("")) + u'

    <foo>

    ' + """ + + _entity_re = re.compile(r'&([^;]+);') + _entities = name2codepoint.copy() + _entities['apos'] = 39 + _empty_elements = set([ + 'area', 'base', 'basefont', 'br', 'col', 'command', 'embed', 'frame', + 'hr', 'img', 'input', 'keygen', 'isindex', 'link', 'meta', 'param', + 'source', 'wbr' + ]) + _boolean_attributes = set([ + 'selected', 'checked', 'compact', 'declare', 'defer', 'disabled', + 'ismap', 'multiple', 'nohref', 'noresize', 'noshade', 'nowrap' + ]) + _plaintext_elements = set(['textarea']) + _c_like_cdata = set(['script', 'style']) + + def __init__(self, dialect): + self._dialect = dialect + + def __call__(self, s): + return escape(s) + + def __getattr__(self, tag): + if tag[:2] == '__': + raise AttributeError(tag) + + def proxy(*children, **arguments): + buffer = '<' + tag + for key, value in iteritems(arguments): + if value is None: + continue + if key[-1] == '_': + key = key[:-1] + if key in self._boolean_attributes: + if not value: + continue + if self._dialect == 'xhtml': + value = '="' + key + '"' + else: + value = '' + else: + value = '="' + escape(value) + '"' + buffer += ' ' + key + value + if not children and tag in self._empty_elements: + if self._dialect == 'xhtml': + buffer += ' />' + else: + buffer += '>' + return buffer + buffer += '>' + + children_as_string = ''.join([text_type(x) for x in children + if x is not None]) + + if children_as_string: + if tag in self._plaintext_elements: + children_as_string = escape(children_as_string) + elif tag in self._c_like_cdata and self._dialect == 'xhtml': + children_as_string = '/**/' + buffer += children_as_string + '' + return buffer + return proxy + + def __repr__(self): + return '<%s for %r>' % ( + self.__class__.__name__, + self._dialect + ) + + +html = HTMLBuilder('html') +xhtml = HTMLBuilder('xhtml') + + +def get_content_type(mimetype, charset): + """Returns the full content type string with charset for a mimetype. + + If the mimetype represents text the charset will be appended as charset + parameter, otherwise the mimetype is returned unchanged. + + :param mimetype: the mimetype to be used as content type. + :param charset: the charset to be appended in case it was a text mimetype. + :return: the content type. + """ + if mimetype.startswith('text/') or \ + mimetype == 'application/xml' or \ + (mimetype.startswith('application/') and + mimetype.endswith('+xml')): + mimetype += '; charset=' + charset + return mimetype + + +def format_string(string, context): + """String-template format a string: + + >>> format_string('$foo and ${foo}s', dict(foo=42)) + '42 and 42s' + + This does not do any attribute lookup etc. For more advanced string + formattings have a look at the `werkzeug.template` module. + + :param string: the format string. + :param context: a dict with the variables to insert. + """ + def lookup_arg(match): + x = context[match.group(1) or match.group(2)] + if not isinstance(x, string_types): + x = type(string)(x) + return x + return _format_re.sub(lookup_arg, string) + + +def secure_filename(filename): + r"""Pass it a filename and it will return a secure version of it. This + filename can then safely be stored on a regular file system and passed + to :func:`os.path.join`. The filename returned is an ASCII only string + for maximum portability. + + On windows systems the function also makes sure that the file is not + named after one of the special device files. + + >>> secure_filename("My cool movie.mov") + 'My_cool_movie.mov' + >>> secure_filename("../../../etc/passwd") + 'etc_passwd' + >>> secure_filename(u'i contain cool \xfcml\xe4uts.txt') + 'i_contain_cool_umlauts.txt' + + The function might return an empty filename. It's your responsibility + to ensure that the filename is unique and that you generate random + filename if the function returned an empty one. + + .. versionadded:: 0.5 + + :param filename: the filename to secure + """ + if isinstance(filename, text_type): + from unicodedata import normalize + filename = normalize('NFKD', filename).encode('ascii', 'ignore') + if not PY2: + filename = filename.decode('ascii') + for sep in os.path.sep, os.path.altsep: + if sep: + filename = filename.replace(sep, ' ') + filename = str(_filename_ascii_strip_re.sub('', '_'.join( + filename.split()))).strip('._') + + # on nt a couple of special files are present in each folder. We + # have to ensure that the target file is not such a filename. In + # this case we prepend an underline + if os.name == 'nt' and filename and \ + filename.split('.')[0].upper() in _windows_device_files: + filename = '_' + filename + + return filename + + +def escape(s, quote=None): + """Replace special characters "&", "<", ">" and (") to HTML-safe sequences. + + There is a special handling for `None` which escapes to an empty string. + + .. versionchanged:: 0.9 + `quote` is now implicitly on. + + :param s: the string to escape. + :param quote: ignored. + """ + if s is None: + return '' + elif hasattr(s, '__html__'): + return text_type(s.__html__()) + elif not isinstance(s, string_types): + s = text_type(s) + if quote is not None: + from warnings import warn + warn(DeprecationWarning('quote parameter is implicit now'), stacklevel=2) + s = s.replace('&', '&').replace('<', '<') \ + .replace('>', '>').replace('"', """) + return s + + +def unescape(s): + """The reverse function of `escape`. This unescapes all the HTML + entities, not only the XML entities inserted by `escape`. + + :param s: the string to unescape. + """ + def handle_match(m): + name = m.group(1) + if name in HTMLBuilder._entities: + return unichr(HTMLBuilder._entities[name]) + try: + if name[:2] in ('#x', '#X'): + return unichr(int(name[2:], 16)) + elif name.startswith('#'): + return unichr(int(name[1:])) + except ValueError: + pass + return u'' + return _entity_re.sub(handle_match, s) + + +def redirect(location, code=302, Response=None): + """Returns a response object (a WSGI application) that, if called, + redirects the client to the target location. Supported codes are 301, + 302, 303, 305, and 307. 300 is not supported because it's not a real + redirect and 304 because it's the answer for a request with a request + with defined If-Modified-Since headers. + + .. versionadded:: 0.6 + The location can now be a unicode string that is encoded using + the :func:`iri_to_uri` function. + + .. versionadded:: 0.10 + The class used for the Response object can now be passed in. + + :param location: the location the response should redirect to. + :param code: the redirect status code. defaults to 302. + :param class Response: a Response class to use when instantiating a + response. The default is :class:`werkzeug.wrappers.Response` if + unspecified. + """ + if Response is None: + from werkzeug.wrappers import Response + + display_location = escape(location) + if isinstance(location, text_type): + # Safe conversion is necessary here as we might redirect + # to a broken URI scheme (for instance itms-services). + from werkzeug.urls import iri_to_uri + location = iri_to_uri(location, safe_conversion=True) + response = Response( + '\n' + 'Redirecting...\n' + '

    Redirecting...

    \n' + '

    You should be redirected automatically to target URL: ' + '%s. If not click the link.' % + (escape(location), display_location), code, mimetype='text/html') + response.headers['Location'] = location + return response + + +def append_slash_redirect(environ, code=301): + """Redirects to the same URL but with a slash appended. The behavior + of this function is undefined if the path ends with a slash already. + + :param environ: the WSGI environment for the request that triggers + the redirect. + :param code: the status code for the redirect. + """ + new_path = environ['PATH_INFO'].strip('/') + '/' + query_string = environ.get('QUERY_STRING') + if query_string: + new_path += '?' + query_string + return redirect(new_path, code) + + +def import_string(import_name, silent=False): + """Imports an object based on a string. This is useful if you want to + use import paths as endpoints or something similar. An import path can + be specified either in dotted notation (``xml.sax.saxutils.escape``) + or with a colon as object delimiter (``xml.sax.saxutils:escape``). + + If `silent` is True the return value will be `None` if the import fails. + + :param import_name: the dotted name for the object to import. + :param silent: if set to `True` import errors are ignored and + `None` is returned instead. + :return: imported object + """ + # force the import name to automatically convert to strings + # __import__ is not able to handle unicode strings in the fromlist + # if the module is a package + import_name = str(import_name).replace(':', '.') + try: + try: + __import__(import_name) + except ImportError: + if '.' not in import_name: + raise + else: + return sys.modules[import_name] + + module_name, obj_name = import_name.rsplit('.', 1) + try: + module = __import__(module_name, None, None, [obj_name]) + except ImportError: + # support importing modules not yet set up by the parent module + # (or package for that matter) + module = import_string(module_name) + + try: + return getattr(module, obj_name) + except AttributeError as e: + raise ImportError(e) + + except ImportError as e: + if not silent: + reraise( + ImportStringError, + ImportStringError(import_name, e), + sys.exc_info()[2]) + + +def find_modules(import_path, include_packages=False, recursive=False): + """Finds all the modules below a package. This can be useful to + automatically import all views / controllers so that their metaclasses / + function decorators have a chance to register themselves on the + application. + + Packages are not returned unless `include_packages` is `True`. This can + also recursively list modules but in that case it will import all the + packages to get the correct load path of that module. + + :param import_path: the dotted name for the package to find child modules. + :param include_packages: set to `True` if packages should be returned, too. + :param recursive: set to `True` if recursion should happen. + :return: generator + """ + module = import_string(import_path) + path = getattr(module, '__path__', None) + if path is None: + raise ValueError('%r is not a package' % import_path) + basename = module.__name__ + '.' + for importer, modname, ispkg in pkgutil.iter_modules(path): + modname = basename + modname + if ispkg: + if include_packages: + yield modname + if recursive: + for item in find_modules(modname, include_packages, True): + yield item + else: + yield modname + + +def validate_arguments(func, args, kwargs, drop_extra=True): + """Checks if the function accepts the arguments and keyword arguments. + Returns a new ``(args, kwargs)`` tuple that can safely be passed to + the function without causing a `TypeError` because the function signature + is incompatible. If `drop_extra` is set to `True` (which is the default) + any extra positional or keyword arguments are dropped automatically. + + The exception raised provides three attributes: + + `missing` + A set of argument names that the function expected but where + missing. + + `extra` + A dict of keyword arguments that the function can not handle but + where provided. + + `extra_positional` + A list of values that where given by positional argument but the + function cannot accept. + + This can be useful for decorators that forward user submitted data to + a view function:: + + from werkzeug.utils import ArgumentValidationError, validate_arguments + + def sanitize(f): + def proxy(request): + data = request.values.to_dict() + try: + args, kwargs = validate_arguments(f, (request,), data) + except ArgumentValidationError: + raise BadRequest('The browser failed to transmit all ' + 'the data expected.') + return f(*args, **kwargs) + return proxy + + :param func: the function the validation is performed against. + :param args: a tuple of positional arguments. + :param kwargs: a dict of keyword arguments. + :param drop_extra: set to `False` if you don't want extra arguments + to be silently dropped. + :return: tuple in the form ``(args, kwargs)``. + """ + parser = _parse_signature(func) + args, kwargs, missing, extra, extra_positional = parser(args, kwargs)[:5] + if missing: + raise ArgumentValidationError(tuple(missing)) + elif (extra or extra_positional) and not drop_extra: + raise ArgumentValidationError(None, extra, extra_positional) + return tuple(args), kwargs + + +def bind_arguments(func, args, kwargs): + """Bind the arguments provided into a dict. When passed a function, + a tuple of arguments and a dict of keyword arguments `bind_arguments` + returns a dict of names as the function would see it. This can be useful + to implement a cache decorator that uses the function arguments to build + the cache key based on the values of the arguments. + + :param func: the function the arguments should be bound for. + :param args: tuple of positional arguments. + :param kwargs: a dict of keyword arguments. + :return: a :class:`dict` of bound keyword arguments. + """ + args, kwargs, missing, extra, extra_positional, \ + arg_spec, vararg_var, kwarg_var = _parse_signature(func)(args, kwargs) + values = {} + for (name, has_default, default), value in zip(arg_spec, args): + values[name] = value + if vararg_var is not None: + values[vararg_var] = tuple(extra_positional) + elif extra_positional: + raise TypeError('too many positional arguments') + if kwarg_var is not None: + multikw = set(extra) & set([x[0] for x in arg_spec]) + if multikw: + raise TypeError('got multiple values for keyword argument ' + + repr(next(iter(multikw)))) + values[kwarg_var] = extra + elif extra: + raise TypeError('got unexpected keyword argument ' + + repr(next(iter(extra)))) + return values + + +class ArgumentValidationError(ValueError): + + """Raised if :func:`validate_arguments` fails to validate""" + + def __init__(self, missing=None, extra=None, extra_positional=None): + self.missing = set(missing or ()) + self.extra = extra or {} + self.extra_positional = extra_positional or [] + ValueError.__init__(self, 'function arguments invalid. (' + '%d missing, %d additional)' % ( + len(self.missing), + len(self.extra) + len(self.extra_positional) + )) + + +class ImportStringError(ImportError): + + """Provides information about a failed :func:`import_string` attempt.""" + + #: String in dotted notation that failed to be imported. + import_name = None + #: Wrapped exception. + exception = None + + def __init__(self, import_name, exception): + self.import_name = import_name + self.exception = exception + + msg = ( + 'import_string() failed for %r. Possible reasons are:\n\n' + '- missing __init__.py in a package;\n' + '- package or module path not included in sys.path;\n' + '- duplicated package or module name taking precedence in ' + 'sys.path;\n' + '- missing module, class, function or variable;\n\n' + 'Debugged import:\n\n%s\n\n' + 'Original exception:\n\n%s: %s') + + name = '' + tracked = [] + for part in import_name.replace(':', '.').split('.'): + name += (name and '.') + part + imported = import_string(name, silent=True) + if imported: + tracked.append((name, getattr(imported, '__file__', None))) + else: + track = ['- %r found in %r.' % (n, i) for n, i in tracked] + track.append('- %r not found.' % name) + msg = msg % (import_name, '\n'.join(track), + exception.__class__.__name__, str(exception)) + break + + ImportError.__init__(self, msg) + + def __repr__(self): + return '<%s(%r, %r)>' % (self.__class__.__name__, self.import_name, + self.exception) + + +# DEPRECATED +# these objects were previously in this module as well. we import +# them here for backwards compatibility with old pickles. +from werkzeug.datastructures import ( # noqa + MultiDict, CombinedMultiDict, Headers, EnvironHeaders) +from werkzeug.http import parse_cookie, dump_cookie # noqa diff --git a/pyextra/werkzeug/websocket.py b/pyextra/werkzeug/websocket.py new file mode 100644 index 00000000000000..764698b70337ea --- /dev/null +++ b/pyextra/werkzeug/websocket.py @@ -0,0 +1,337 @@ +import re +import errno +import socket +import struct +import collections + +from base64 import b64decode, b64encode +from hashlib import sha1 + + +WS_KEY = b'258EAFA5-E914-47DA-95CA-C5AB0DC85B11' + + +def pack_message(message): + """Pack the message inside ``00`` and ``FF`` + As per the dataframing section (5.3) for the websocket spec + """ + if isinstance(message, unicode): + message = message.encode('utf-8') + elif not isinstance(message, str): + message = str(message) + packed = "\x00%s\xFF" % message + return packed + + +def encode_hybi(buf, opcode, base64=False): + """ Encode a HyBi style WebSocket frame. + Optional opcode: + 0x0 - continuation + 0x1 - text frame (base64 encode buf) + 0x2 - binary frame (use raw buf) + 0x8 - connection close + 0x9 - ping + 0xA - pong + """ + if base64: + buf = b64encode(buf) + b1 = 0x80 | (opcode & 0x0f) # FIN + opcode + payload_len = len(buf) + if payload_len <= 125: + header = struct.pack('>BB', b1, payload_len) + elif payload_len > 125 and payload_len < 65536: + header = struct.pack('>BBH', b1, 126, payload_len) + elif payload_len >= 65536: + header = struct.pack('>BBQ', b1, 127, payload_len) + return header + buf, len(header), 0 + + +def decode_hybi(buf, base64=False): + """Decode HyBi style WebSocket packets.""" + f = {'fin' : 0, + 'opcode' : 0, + 'mask' : 0, + 'hlen' : 2, + 'length' : 0, + 'payload' : None, + 'left' : 0, + 'close_code' : None, + 'close_reason' : None} + + blen = len(buf) + f['left'] = blen + + if blen < f['hlen']: + return f # Incomplete frame header + + b1, b2 = struct.unpack_from(">BB", buf) + f['opcode'] = b1 & 0x0f + f['fin'] = (b1 & 0x80) >> 7 + has_mask = (b2 & 0x80) >> 7 + + f['length'] = b2 & 0x7f + + if f['length'] == 126: + f['hlen'] = 4 + if blen < f['hlen']: + return f # Incomplete frame header + (f['length'],) = struct.unpack_from('>xxH', buf) + elif f['length'] == 127: + f['hlen'] = 10 + if blen < f['hlen']: + return f # Incomplete frame header + (f['length'],) = struct.unpack_from('>xxQ', buf) + + full_len = f['hlen'] + has_mask * 4 + f['length'] + + if blen < full_len: # Incomplete frame + return f # Incomplete frame header + + # Number of bytes that are part of the next frame(s) + f['left'] = blen - full_len + + # Process 1 frame + if has_mask: + # unmask payload + f['mask'] = buf[f['hlen']:f['hlen']+4] + b = c = '' + if f['length'] >= 4: + data = struct.unpack('= 2: + f['close_code'] = struct.unpack_from(">H", f['payload']) + if f['length'] > 3: + f['close_reason'] = f['payload'][2:] + + return f + + +class WebSocketWSGI(object): + + def __init__(self, handler): + self.handler = handler + + def verify_client(self, ws): + pass + + def __call__(self, environ, start_response): + if not (environ.get('HTTP_CONNECTION').find('Upgrade') != -1 and + environ['HTTP_UPGRADE'].lower() == 'websocket'): + # need to check a few more things here for true compliance + start_response('400 Bad Request', [('Connection','close')]) + return [] + + sock = environ['gunicorn.socket'] + + ws = WebSocket(sock, environ) + + handshake_reply = ("HTTP/1.1 101 Switching Protocols\r\n" + "Upgrade: websocket\r\n" + "Connection: Upgrade\r\n") + + path = environ['PATH_INFO'] + key = environ.get('HTTP_SEC_WEBSOCKET_KEY') + if key: + ws_key = b64decode(key) + if len(ws_key) != 16: + start_response('400 Bad Request', [('Connection','close')]) + return [] + + protocols = [] + subprotocols = environ.get('HTTP_SEC_WEBSOCKET_PROTOCOL') + ws_protocols = [] + if subprotocols: + for s in subprotocols.split(','): + s = s.strip() + if s in protocols: + ws_protocols.append(s) + if ws_protocols: + handshake_reply += 'Sec-WebSocket-Protocol: %s\r\n' % ', '.join(ws_protocols) + + exts = [] + extensions = environ.get('HTTP_SEC_WEBSOCKET_EXTENSIONS') + ws_extensions = [] + if extensions: + for ext in extensions.split(','): + ext = ext.strip() + if ext in exts: + ws_extensions.append(ext) + if ws_extensions: + handshake_reply += 'Sec-WebSocket-Extensions: %s\r\n' % ', '.join(ws_extensions) + + handshake_reply += ( + "Sec-WebSocket-Origin: %s\r\n" + "Sec-WebSocket-Location: ws://%s%s\r\n" + "Sec-WebSocket-Version: %s\r\n" + "Sec-WebSocket-Accept: %s\r\n\r\n" + % ( + environ.get('HTTP_ORIGIN'), + environ.get('HTTP_HOST'), + path, + ws.version, + b64encode(sha1(key + WS_KEY).digest()) + )) + + else: + + handshake_reply += ( + "WebSocket-Origin: %s\r\n" + "WebSocket-Location: ws://%s%s\r\n\r\n" % ( + environ.get('HTTP_ORIGIN'), + environ.get('HTTP_HOST'), + path)) + + sock.sendall(handshake_reply) + + try: + self.handler(ws) + except socket.error as e: + if e[0] != errno.EPIPE: + raise + + # use this undocumented feature of grainbows to ensure that it + # doesn't barf on the fact that we didn't call start_response + return ALREADY_HANDLED + + +class WebSocket(object): + + def __init__(self, sock, environ, version=76): + self._socket = sock + try: + version = int(environ.get('HTTP_SEC_WEBSOCKET_VERSION')) + except (ValueError, TypeError): + version = 76 + self.version = version + self.closed = False + self.accepted = False + self._buf = b'' + self._msgs = collections.deque() + + def _parse_messages(self): + """ Parses for messages in the buffer *buf*. It is assumed that + the buffer contains the start character for a message, but that it + may contain only part of the rest of the message. + Returns an array of messages, and the buffer remainder that + didn't contain any full messages.""" + msgs = [] + end_idx = 0 + buf = self._buf + while buf: + if self.version in (7, 8, 13): + frame = decode_hybi(buf, base64=False) + + if frame['payload'] == None: + break + else: + if frame['opcode'] == 0x8: # connection close + self.closed = True + break + else: + msgs.append(frame['payload']); + if frame['left']: + buf = buf[-frame['left']:] + else: + buf = b'' + + else: + frame_type = ord(buf[0]) + if frame_type == 0: + # Normal message. + end_idx = buf.find("\xFF") + if end_idx == -1: #pragma NO COVER + break + msgs.append(buf[1:end_idx].decode('utf-8', 'replace')) + buf = buf[end_idx+1:] + elif frame_type == 255: + # Closing handshake. + assert ord(buf[1]) == 0, "Unexpected closing handshake: %r" % buf + self.closed = True + break + else: + raise ValueError("Don't understand how to parse this type of message: %r" % buf) + self._buf = buf + return msgs + + def send(self, message): + """Send a message to the browser. + *message* should be convertable to a string; unicode objects should be + encodable as utf-8. Raises socket.error with errno of 32 + (broken pipe) if the socket has already been closed by the client. + """ + if self.version in (7, 8, 13): + packed, lenhead, lentail = encode_hybi( + message, opcode=0x01, base64=False) + else: + packed = pack_message(message) + self._socket.sendall(packed) + + def wait(self): + """Waits for and deserializes messages. + Returns a single message; the oldest not yet processed. If the client + has already closed the connection, returns None. This is different + from normal socket behavior because the empty string is a valid + websocket message.""" + while not self._msgs: + # Websocket might be closed already. + if self.closed: + return None + # no parsed messages, must mean buf needs more data + delta = self._socket.recv(8096) + if delta == '': + return None + self._buf += delta + msgs = self._parse_messages() + self._msgs.extend(msgs) + return self._msgs.popleft() + + def _send_closing_frame(self, ignore_send_errors=False): + """Sends the closing frame to the client, if required.""" + if self.version in (7, 8, 13) and not self.closed: + msg = '' + #if code != None: + # msg = struct.pack(">H%ds" % (len(reason)), code) + + buf, h, t = encode_hybi(msg, opcode=0x08, base64=False) + self._socket.sendall(buf) + self.closed = True + + elif self.version == 76 and not self.closed: + try: + self._socket.sendall("\xff\x00") + except socket.error: + # Sometimes, like when the remote side cuts off the connection, + # we don't care about this. + if not ignore_send_errors: #pragma NO COVER + raise + self.closed = True + + def close(self): + """Forcibly close the websocket; generally it is preferable to + return from the handler method.""" + self._send_closing_frame() + self._socket.shutdown(True) + self._socket.close() diff --git a/pyextra/werkzeug/wrappers.py b/pyextra/werkzeug/wrappers.py new file mode 100644 index 00000000000000..92dfa5dacc0dcb --- /dev/null +++ b/pyextra/werkzeug/wrappers.py @@ -0,0 +1,2028 @@ +# -*- coding: utf-8 -*- +""" + werkzeug.wrappers + ~~~~~~~~~~~~~~~~~ + + The wrappers are simple request and response objects which you can + subclass to do whatever you want them to do. The request object contains + the information transmitted by the client (webbrowser) and the response + object contains all the information sent back to the browser. + + An important detail is that the request object is created with the WSGI + environ and will act as high-level proxy whereas the response object is an + actual WSGI application. + + Like everything else in Werkzeug these objects will work correctly with + unicode data. Incoming form data parsed by the response object will be + decoded into an unicode object if possible and if it makes sense. + + + :copyright: (c) 2014 by the Werkzeug Team, see AUTHORS for more details. + :license: BSD, see LICENSE for more details. +""" +from functools import update_wrapper +from datetime import datetime, timedelta +from warnings import warn + +from werkzeug.http import HTTP_STATUS_CODES, \ + parse_accept_header, parse_cache_control_header, parse_etags, \ + parse_date, generate_etag, is_resource_modified, unquote_etag, \ + quote_etag, parse_set_header, parse_authorization_header, \ + parse_www_authenticate_header, remove_entity_headers, \ + parse_options_header, dump_options_header, http_date, \ + parse_if_range_header, parse_cookie, dump_cookie, \ + parse_range_header, parse_content_range_header, dump_header, \ + parse_age, dump_age +from werkzeug.urls import url_decode, iri_to_uri, url_join +from werkzeug.formparser import FormDataParser, default_stream_factory +from werkzeug.utils import cached_property, environ_property, \ + header_property, get_content_type +from werkzeug.wsgi import get_current_url, get_host, \ + ClosingIterator, get_input_stream, get_content_length, _RangeWrapper +from werkzeug.datastructures import MultiDict, CombinedMultiDict, Headers, \ + EnvironHeaders, ImmutableMultiDict, ImmutableTypeConversionDict, \ + ImmutableList, MIMEAccept, CharsetAccept, LanguageAccept, \ + ResponseCacheControl, RequestCacheControl, CallbackDict, \ + ContentRange, iter_multi_items +from werkzeug._internal import _get_environ +from werkzeug._compat import to_bytes, string_types, text_type, \ + integer_types, wsgi_decoding_dance, wsgi_get_bytes, \ + to_unicode, to_native, BytesIO + + +def _run_wsgi_app(*args): + """This function replaces itself to ensure that the test module is not + imported unless required. DO NOT USE! + """ + global _run_wsgi_app + from werkzeug.test import run_wsgi_app as _run_wsgi_app + return _run_wsgi_app(*args) + + +def _warn_if_string(iterable): + """Helper for the response objects to check if the iterable returned + to the WSGI server is not a string. + """ + if isinstance(iterable, string_types): + warn(Warning('response iterable was set to a string. This appears ' + 'to work but means that the server will send the ' + 'data to the client char, by char. This is almost ' + 'never intended behavior, use response.data to assign ' + 'strings to the response object.'), stacklevel=2) + + +def _assert_not_shallow(request): + if request.shallow: + raise RuntimeError('A shallow request tried to consume ' + 'form data. If you really want to do ' + 'that, set `shallow` to False.') + + +def _iter_encoded(iterable, charset): + for item in iterable: + if isinstance(item, text_type): + yield item.encode(charset) + else: + yield item + + +def _clean_accept_ranges(accept_ranges): + if accept_ranges is True: + return "bytes" + elif accept_ranges is False: + return "none" + elif isinstance(accept_ranges, text_type): + return to_native(accept_ranges) + raise ValueError("Invalid accept_ranges value") + + +class BaseRequest(object): + + """Very basic request object. This does not implement advanced stuff like + entity tag parsing or cache controls. The request object is created with + the WSGI environment as first argument and will add itself to the WSGI + environment as ``'werkzeug.request'`` unless it's created with + `populate_request` set to False. + + There are a couple of mixins available that add additional functionality + to the request object, there is also a class called `Request` which + subclasses `BaseRequest` and all the important mixins. + + It's a good idea to create a custom subclass of the :class:`BaseRequest` + and add missing functionality either via mixins or direct implementation. + Here an example for such subclasses:: + + from werkzeug.wrappers import BaseRequest, ETagRequestMixin + + class Request(BaseRequest, ETagRequestMixin): + pass + + Request objects are **read only**. As of 0.5 modifications are not + allowed in any place. Unlike the lower level parsing functions the + request object will use immutable objects everywhere possible. + + Per default the request object will assume all the text data is `utf-8` + encoded. Please refer to `the unicode chapter `_ for more + details about customizing the behavior. + + Per default the request object will be added to the WSGI + environment as `werkzeug.request` to support the debugging system. + If you don't want that, set `populate_request` to `False`. + + If `shallow` is `True` the environment is initialized as shallow + object around the environ. Every operation that would modify the + environ in any way (such as consuming form data) raises an exception + unless the `shallow` attribute is explicitly set to `False`. This + is useful for middlewares where you don't want to consume the form + data by accident. A shallow request is not populated to the WSGI + environment. + + .. versionchanged:: 0.5 + read-only mode was enforced by using immutables classes for all + data. + """ + + #: the charset for the request, defaults to utf-8 + charset = 'utf-8' + + #: the error handling procedure for errors, defaults to 'replace' + encoding_errors = 'replace' + + #: the maximum content length. This is forwarded to the form data + #: parsing function (:func:`parse_form_data`). When set and the + #: :attr:`form` or :attr:`files` attribute is accessed and the + #: parsing fails because more than the specified value is transmitted + #: a :exc:`~werkzeug.exceptions.RequestEntityTooLarge` exception is raised. + #: + #: Have a look at :ref:`dealing-with-request-data` for more details. + #: + #: .. versionadded:: 0.5 + max_content_length = None + + #: the maximum form field size. This is forwarded to the form data + #: parsing function (:func:`parse_form_data`). When set and the + #: :attr:`form` or :attr:`files` attribute is accessed and the + #: data in memory for post data is longer than the specified value a + #: :exc:`~werkzeug.exceptions.RequestEntityTooLarge` exception is raised. + #: + #: Have a look at :ref:`dealing-with-request-data` for more details. + #: + #: .. versionadded:: 0.5 + max_form_memory_size = None + + #: the class to use for `args` and `form`. The default is an + #: :class:`~werkzeug.datastructures.ImmutableMultiDict` which supports + #: multiple values per key. alternatively it makes sense to use an + #: :class:`~werkzeug.datastructures.ImmutableOrderedMultiDict` which + #: preserves order or a :class:`~werkzeug.datastructures.ImmutableDict` + #: which is the fastest but only remembers the last key. It is also + #: possible to use mutable structures, but this is not recommended. + #: + #: .. versionadded:: 0.6 + parameter_storage_class = ImmutableMultiDict + + #: the type to be used for list values from the incoming WSGI environment. + #: By default an :class:`~werkzeug.datastructures.ImmutableList` is used + #: (for example for :attr:`access_list`). + #: + #: .. versionadded:: 0.6 + list_storage_class = ImmutableList + + #: the type to be used for dict values from the incoming WSGI environment. + #: By default an + #: :class:`~werkzeug.datastructures.ImmutableTypeConversionDict` is used + #: (for example for :attr:`cookies`). + #: + #: .. versionadded:: 0.6 + dict_storage_class = ImmutableTypeConversionDict + + #: The form data parser that shoud be used. Can be replaced to customize + #: the form date parsing. + form_data_parser_class = FormDataParser + + #: Optionally a list of hosts that is trusted by this request. By default + #: all hosts are trusted which means that whatever the client sends the + #: host is will be accepted. + #: + #: This is the recommended setup as a webserver should manually be set up + #: to only route correct hosts to the application, and remove the + #: `X-Forwarded-Host` header if it is not being used (see + #: :func:`werkzeug.wsgi.get_host`). + #: + #: .. versionadded:: 0.9 + trusted_hosts = None + + #: Indicates whether the data descriptor should be allowed to read and + #: buffer up the input stream. By default it's enabled. + #: + #: .. versionadded:: 0.9 + disable_data_descriptor = False + + def __init__(self, environ, populate_request=True, shallow=False): + self.environ = environ + if populate_request and not shallow: + self.environ['werkzeug.request'] = self + self.shallow = shallow + + def __repr__(self): + # make sure the __repr__ even works if the request was created + # from an invalid WSGI environment. If we display the request + # in a debug session we don't want the repr to blow up. + args = [] + try: + args.append("'%s'" % to_native(self.url, self.url_charset)) + args.append('[%s]' % self.method) + except Exception: + args.append('(invalid WSGI environ)') + + return '<%s %s>' % ( + self.__class__.__name__, + ' '.join(args) + ) + + @property + def url_charset(self): + """The charset that is assumed for URLs. Defaults to the value + of :attr:`charset`. + + .. versionadded:: 0.6 + """ + return self.charset + + @classmethod + def from_values(cls, *args, **kwargs): + """Create a new request object based on the values provided. If + environ is given missing values are filled from there. This method is + useful for small scripts when you need to simulate a request from an URL. + Do not use this method for unittesting, there is a full featured client + object (:class:`Client`) that allows to create multipart requests, + support for cookies etc. + + This accepts the same options as the + :class:`~werkzeug.test.EnvironBuilder`. + + .. versionchanged:: 0.5 + This method now accepts the same arguments as + :class:`~werkzeug.test.EnvironBuilder`. Because of this the + `environ` parameter is now called `environ_overrides`. + + :return: request object + """ + from werkzeug.test import EnvironBuilder + charset = kwargs.pop('charset', cls.charset) + kwargs['charset'] = charset + builder = EnvironBuilder(*args, **kwargs) + try: + return builder.get_request(cls) + finally: + builder.close() + + @classmethod + def application(cls, f): + """Decorate a function as responder that accepts the request as first + argument. This works like the :func:`responder` decorator but the + function is passed the request object as first argument and the + request object will be closed automatically:: + + @Request.application + def my_wsgi_app(request): + return Response('Hello World!') + + As of Werkzeug 0.14 HTTP exceptions are automatically caught and + converted to responses instead of failing. + + :param f: the WSGI callable to decorate + :return: a new WSGI callable + """ + #: return a callable that wraps the -2nd argument with the request + #: and calls the function with all the arguments up to that one and + #: the request. The return value is then called with the latest + #: two arguments. This makes it possible to use this decorator for + #: both methods and standalone WSGI functions. + from werkzeug.exceptions import HTTPException + + def application(*args): + request = cls(args[-2]) + with request: + try: + resp = f(*args[:-2] + (request,)) + except HTTPException as e: + resp = e.get_response(args[-2]) + return resp(*args[-2:]) + + return update_wrapper(application, f) + + def _get_file_stream(self, total_content_length, content_type, filename=None, + content_length=None): + """Called to get a stream for the file upload. + + This must provide a file-like class with `read()`, `readline()` + and `seek()` methods that is both writeable and readable. + + The default implementation returns a temporary file if the total + content length is higher than 500KB. Because many browsers do not + provide a content length for the files only the total content + length matters. + + :param total_content_length: the total content length of all the + data in the request combined. This value + is guaranteed to be there. + :param content_type: the mimetype of the uploaded file. + :param filename: the filename of the uploaded file. May be `None`. + :param content_length: the length of this file. This value is usually + not provided because webbrowsers do not provide + this value. + """ + return default_stream_factory( + total_content_length=total_content_length, + content_type=content_type, + filename=filename, + content_length=content_length) + + @property + def want_form_data_parsed(self): + """Returns True if the request method carries content. As of + Werkzeug 0.9 this will be the case if a content type is transmitted. + + .. versionadded:: 0.8 + """ + return bool(self.environ.get('CONTENT_TYPE')) + + def make_form_data_parser(self): + """Creates the form data parser. Instantiates the + :attr:`form_data_parser_class` with some parameters. + + .. versionadded:: 0.8 + """ + return self.form_data_parser_class(self._get_file_stream, + self.charset, + self.encoding_errors, + self.max_form_memory_size, + self.max_content_length, + self.parameter_storage_class) + + def _load_form_data(self): + """Method used internally to retrieve submitted data. After calling + this sets `form` and `files` on the request object to multi dicts + filled with the incoming form data. As a matter of fact the input + stream will be empty afterwards. You can also call this method to + force the parsing of the form data. + + .. versionadded:: 0.8 + """ + # abort early if we have already consumed the stream + if 'form' in self.__dict__: + return + + _assert_not_shallow(self) + + if self.want_form_data_parsed: + content_type = self.environ.get('CONTENT_TYPE', '') + content_length = get_content_length(self.environ) + mimetype, options = parse_options_header(content_type) + parser = self.make_form_data_parser() + data = parser.parse(self._get_stream_for_parsing(), + mimetype, content_length, options) + else: + data = (self.stream, self.parameter_storage_class(), + self.parameter_storage_class()) + + # inject the values into the instance dict so that we bypass + # our cached_property non-data descriptor. + d = self.__dict__ + d['stream'], d['form'], d['files'] = data + + def _get_stream_for_parsing(self): + """This is the same as accessing :attr:`stream` with the difference + that if it finds cached data from calling :meth:`get_data` first it + will create a new stream out of the cached data. + + .. versionadded:: 0.9.3 + """ + cached_data = getattr(self, '_cached_data', None) + if cached_data is not None: + return BytesIO(cached_data) + return self.stream + + def close(self): + """Closes associated resources of this request object. This + closes all file handles explicitly. You can also use the request + object in a with statement which will automatically close it. + + .. versionadded:: 0.9 + """ + files = self.__dict__.get('files') + for key, value in iter_multi_items(files or ()): + value.close() + + def __enter__(self): + return self + + def __exit__(self, exc_type, exc_value, tb): + self.close() + + @cached_property + def stream(self): + """ + If the incoming form data was not encoded with a known mimetype + the data is stored unmodified in this stream for consumption. Most + of the time it is a better idea to use :attr:`data` which will give + you that data as a string. The stream only returns the data once. + + Unlike :attr:`input_stream` this stream is properly guarded that you + can't accidentally read past the length of the input. Werkzeug will + internally always refer to this stream to read data which makes it + possible to wrap this object with a stream that does filtering. + + .. versionchanged:: 0.9 + This stream is now always available but might be consumed by the + form parser later on. Previously the stream was only set if no + parsing happened. + """ + _assert_not_shallow(self) + return get_input_stream(self.environ) + + input_stream = environ_property('wsgi.input', """ + The WSGI input stream. + + In general it's a bad idea to use this one because you can easily read past + the boundary. Use the :attr:`stream` instead. + """) + + @cached_property + def args(self): + """The parsed URL parameters (the part in the URL after the question + mark). + + By default an + :class:`~werkzeug.datastructures.ImmutableMultiDict` + is returned from this function. This can be changed by setting + :attr:`parameter_storage_class` to a different type. This might + be necessary if the order of the form data is important. + """ + return url_decode(wsgi_get_bytes(self.environ.get('QUERY_STRING', '')), + self.url_charset, errors=self.encoding_errors, + cls=self.parameter_storage_class) + + @cached_property + def data(self): + """ + Contains the incoming request data as string in case it came with + a mimetype Werkzeug does not handle. + """ + + if self.disable_data_descriptor: + raise AttributeError('data descriptor is disabled') + # XXX: this should eventually be deprecated. + + # We trigger form data parsing first which means that the descriptor + # will not cache the data that would otherwise be .form or .files + # data. This restores the behavior that was there in Werkzeug + # before 0.9. New code should use :meth:`get_data` explicitly as + # this will make behavior explicit. + return self.get_data(parse_form_data=True) + + def get_data(self, cache=True, as_text=False, parse_form_data=False): + """This reads the buffered incoming data from the client into one + bytestring. By default this is cached but that behavior can be + changed by setting `cache` to `False`. + + Usually it's a bad idea to call this method without checking the + content length first as a client could send dozens of megabytes or more + to cause memory problems on the server. + + Note that if the form data was already parsed this method will not + return anything as form data parsing does not cache the data like + this method does. To implicitly invoke form data parsing function + set `parse_form_data` to `True`. When this is done the return value + of this method will be an empty string if the form parser handles + the data. This generally is not necessary as if the whole data is + cached (which is the default) the form parser will used the cached + data to parse the form data. Please be generally aware of checking + the content length first in any case before calling this method + to avoid exhausting server memory. + + If `as_text` is set to `True` the return value will be a decoded + unicode string. + + .. versionadded:: 0.9 + """ + rv = getattr(self, '_cached_data', None) + if rv is None: + if parse_form_data: + self._load_form_data() + rv = self.stream.read() + if cache: + self._cached_data = rv + if as_text: + rv = rv.decode(self.charset, self.encoding_errors) + return rv + + @cached_property + def form(self): + """The form parameters. By default an + :class:`~werkzeug.datastructures.ImmutableMultiDict` + is returned from this function. This can be changed by setting + :attr:`parameter_storage_class` to a different type. This might + be necessary if the order of the form data is important. + + Please keep in mind that file uploads will not end up here, but instead + in the :attr:`files` attribute. + + .. versionchanged:: 0.9 + + Previous to Werkzeug 0.9 this would only contain form data for POST + and PUT requests. + """ + self._load_form_data() + return self.form + + @cached_property + def values(self): + """A :class:`werkzeug.datastructures.CombinedMultiDict` that combines + :attr:`args` and :attr:`form`.""" + args = [] + for d in self.args, self.form: + if not isinstance(d, MultiDict): + d = MultiDict(d) + args.append(d) + return CombinedMultiDict(args) + + @cached_property + def files(self): + """:class:`~werkzeug.datastructures.MultiDict` object containing + all uploaded files. Each key in :attr:`files` is the name from the + ````. Each value in :attr:`files` is a + Werkzeug :class:`~werkzeug.datastructures.FileStorage` object. + + It basically behaves like a standard file object you know from Python, + with the difference that it also has a + :meth:`~werkzeug.datastructures.FileStorage.save` function that can + store the file on the filesystem. + + Note that :attr:`files` will only contain data if the request method was + POST, PUT or PATCH and the ``

    `` that posted to the request had + ``enctype="multipart/form-data"``. It will be empty otherwise. + + See the :class:`~werkzeug.datastructures.MultiDict` / + :class:`~werkzeug.datastructures.FileStorage` documentation for + more details about the used data structure. + """ + self._load_form_data() + return self.files + + @cached_property + def cookies(self): + """A :class:`dict` with the contents of all cookies transmitted with + the request.""" + return parse_cookie(self.environ, self.charset, + self.encoding_errors, + cls=self.dict_storage_class) + + @cached_property + def headers(self): + """The headers from the WSGI environ as immutable + :class:`~werkzeug.datastructures.EnvironHeaders`. + """ + return EnvironHeaders(self.environ) + + @cached_property + def path(self): + """Requested path as unicode. This works a bit like the regular path + info in the WSGI environment but will always include a leading slash, + even if the URL root is accessed. + """ + raw_path = wsgi_decoding_dance(self.environ.get('PATH_INFO') or '', + self.charset, self.encoding_errors) + return '/' + raw_path.lstrip('/') + + @cached_property + def full_path(self): + """Requested path as unicode, including the query string.""" + return self.path + u'?' + to_unicode(self.query_string, self.url_charset) + + @cached_property + def script_root(self): + """The root path of the script without the trailing slash.""" + raw_path = wsgi_decoding_dance(self.environ.get('SCRIPT_NAME') or '', + self.charset, self.encoding_errors) + return raw_path.rstrip('/') + + @cached_property + def url(self): + """The reconstructed current URL as IRI. + See also: :attr:`trusted_hosts`. + """ + return get_current_url(self.environ, + trusted_hosts=self.trusted_hosts) + + @cached_property + def base_url(self): + """Like :attr:`url` but without the querystring + See also: :attr:`trusted_hosts`. + """ + return get_current_url(self.environ, strip_querystring=True, + trusted_hosts=self.trusted_hosts) + + @cached_property + def url_root(self): + """The full URL root (with hostname), this is the application + root as IRI. + See also: :attr:`trusted_hosts`. + """ + return get_current_url(self.environ, True, + trusted_hosts=self.trusted_hosts) + + @cached_property + def host_url(self): + """Just the host with scheme as IRI. + See also: :attr:`trusted_hosts`. + """ + return get_current_url(self.environ, host_only=True, + trusted_hosts=self.trusted_hosts) + + @cached_property + def host(self): + """Just the host including the port if available. + See also: :attr:`trusted_hosts`. + """ + return get_host(self.environ, trusted_hosts=self.trusted_hosts) + + query_string = environ_property( + 'QUERY_STRING', '', read_only=True, + load_func=wsgi_get_bytes, doc='The URL parameters as raw bytestring.') + method = environ_property( + 'REQUEST_METHOD', 'GET', read_only=True, + load_func=lambda x: x.upper(), + doc="The request method. (For example ``'GET'`` or ``'POST'``).") + + @cached_property + def access_route(self): + """If a forwarded header exists this is a list of all ip addresses + from the client ip to the last proxy server. + """ + if 'HTTP_X_FORWARDED_FOR' in self.environ: + addr = self.environ['HTTP_X_FORWARDED_FOR'].split(',') + return self.list_storage_class([x.strip() for x in addr]) + elif 'REMOTE_ADDR' in self.environ: + return self.list_storage_class([self.environ['REMOTE_ADDR']]) + return self.list_storage_class() + + @property + def remote_addr(self): + """The remote address of the client.""" + return self.environ.get('REMOTE_ADDR') + + remote_user = environ_property('REMOTE_USER', doc=''' + If the server supports user authentication, and the script is + protected, this attribute contains the username the user has + authenticated as.''') + + scheme = environ_property('wsgi.url_scheme', doc=''' + URL scheme (http or https). + + .. versionadded:: 0.7''') + + @property + def is_xhr(self): + """True if the request was triggered via a JavaScript XMLHttpRequest. + This only works with libraries that support the ``X-Requested-With`` + header and set it to "XMLHttpRequest". Libraries that do that are + prototype, jQuery and Mochikit and probably some more. + + .. deprecated:: 0.13 + ``X-Requested-With`` is not standard and is unreliable. + """ + warn(DeprecationWarning( + 'Request.is_xhr is deprecated. Given that the X-Requested-With ' + 'header is not a part of any spec, it is not reliable' + ), stacklevel=2) + return self.environ.get( + 'HTTP_X_REQUESTED_WITH', '' + ).lower() == 'xmlhttprequest' + + is_secure = property(lambda x: x.environ['wsgi.url_scheme'] == 'https', + doc='`True` if the request is secure.') + is_multithread = environ_property('wsgi.multithread', doc=''' + boolean that is `True` if the application is served by + a multithreaded WSGI server.''') + is_multiprocess = environ_property('wsgi.multiprocess', doc=''' + boolean that is `True` if the application is served by + a WSGI server that spawns multiple processes.''') + is_run_once = environ_property('wsgi.run_once', doc=''' + boolean that is `True` if the application will be executed only + once in a process lifetime. This is the case for CGI for example, + but it's not guaranteed that the execution only happens one time.''') + + +class BaseResponse(object): + + """Base response class. The most important fact about a response object + is that it's a regular WSGI application. It's initialized with a couple + of response parameters (headers, body, status code etc.) and will start a + valid WSGI response when called with the environ and start response + callable. + + Because it's a WSGI application itself processing usually ends before the + actual response is sent to the server. This helps debugging systems + because they can catch all the exceptions before responses are started. + + Here a small example WSGI application that takes advantage of the + response objects:: + + from werkzeug.wrappers import BaseResponse as Response + + def index(): + return Response('Index page') + + def application(environ, start_response): + path = environ.get('PATH_INFO') or '/' + if path == '/': + response = index() + else: + response = Response('Not Found', status=404) + return response(environ, start_response) + + Like :class:`BaseRequest` which object is lacking a lot of functionality + implemented in mixins. This gives you a better control about the actual + API of your response objects, so you can create subclasses and add custom + functionality. A full featured response object is available as + :class:`Response` which implements a couple of useful mixins. + + To enforce a new type of already existing responses you can use the + :meth:`force_type` method. This is useful if you're working with different + subclasses of response objects and you want to post process them with a + known interface. + + Per default the response object will assume all the text data is `utf-8` + encoded. Please refer to `the unicode chapter `_ for more + details about customizing the behavior. + + Response can be any kind of iterable or string. If it's a string it's + considered being an iterable with one item which is the string passed. + Headers can be a list of tuples or a + :class:`~werkzeug.datastructures.Headers` object. + + Special note for `mimetype` and `content_type`: For most mime types + `mimetype` and `content_type` work the same, the difference affects + only 'text' mimetypes. If the mimetype passed with `mimetype` is a + mimetype starting with `text/`, the charset parameter of the response + object is appended to it. In contrast the `content_type` parameter is + always added as header unmodified. + + .. versionchanged:: 0.5 + the `direct_passthrough` parameter was added. + + :param response: a string or response iterable. + :param status: a string with a status or an integer with the status code. + :param headers: a list of headers or a + :class:`~werkzeug.datastructures.Headers` object. + :param mimetype: the mimetype for the response. See notice above. + :param content_type: the content type for the response. See notice above. + :param direct_passthrough: if set to `True` :meth:`iter_encoded` is not + called before iteration which makes it + possible to pass special iterators through + unchanged (see :func:`wrap_file` for more + details.) + """ + + #: the charset of the response. + charset = 'utf-8' + + #: the default status if none is provided. + default_status = 200 + + #: the default mimetype if none is provided. + default_mimetype = 'text/plain' + + #: if set to `False` accessing properties on the response object will + #: not try to consume the response iterator and convert it into a list. + #: + #: .. versionadded:: 0.6.2 + #: + #: That attribute was previously called `implicit_seqence_conversion`. + #: (Notice the typo). If you did use this feature, you have to adapt + #: your code to the name change. + implicit_sequence_conversion = True + + #: Should this response object correct the location header to be RFC + #: conformant? This is true by default. + #: + #: .. versionadded:: 0.8 + autocorrect_location_header = True + + #: Should this response object automatically set the content-length + #: header if possible? This is true by default. + #: + #: .. versionadded:: 0.8 + automatically_set_content_length = True + + #: Warn if a cookie header exceeds this size. The default, 4093, should be + #: safely `supported by most browsers `_. A cookie larger than + #: this size will still be sent, but it may be ignored or handled + #: incorrectly by some browsers. Set to 0 to disable this check. + #: + #: .. versionadded:: 0.13 + #: + #: .. _`cookie`: http://browsercookielimits.squawky.net/ + max_cookie_size = 4093 + + def __init__(self, response=None, status=None, headers=None, + mimetype=None, content_type=None, direct_passthrough=False): + if isinstance(headers, Headers): + self.headers = headers + elif not headers: + self.headers = Headers() + else: + self.headers = Headers(headers) + + if content_type is None: + if mimetype is None and 'content-type' not in self.headers: + mimetype = self.default_mimetype + if mimetype is not None: + mimetype = get_content_type(mimetype, self.charset) + content_type = mimetype + if content_type is not None: + self.headers['Content-Type'] = content_type + if status is None: + status = self.default_status + if isinstance(status, integer_types): + self.status_code = status + else: + self.status = status + + self.direct_passthrough = direct_passthrough + self._on_close = [] + + # we set the response after the headers so that if a class changes + # the charset attribute, the data is set in the correct charset. + if response is None: + self.response = [] + elif isinstance(response, (text_type, bytes, bytearray)): + self.set_data(response) + else: + self.response = response + + def call_on_close(self, func): + """Adds a function to the internal list of functions that should + be called as part of closing down the response. Since 0.7 this + function also returns the function that was passed so that this + can be used as a decorator. + + .. versionadded:: 0.6 + """ + self._on_close.append(func) + return func + + def __repr__(self): + if self.is_sequence: + body_info = '%d bytes' % sum(map(len, self.iter_encoded())) + else: + body_info = 'streamed' if self.is_streamed else 'likely-streamed' + return '<%s %s [%s]>' % ( + self.__class__.__name__, + body_info, + self.status + ) + + @classmethod + def force_type(cls, response, environ=None): + """Enforce that the WSGI response is a response object of the current + type. Werkzeug will use the :class:`BaseResponse` internally in many + situations like the exceptions. If you call :meth:`get_response` on an + exception you will get back a regular :class:`BaseResponse` object, even + if you are using a custom subclass. + + This method can enforce a given response type, and it will also + convert arbitrary WSGI callables into response objects if an environ + is provided:: + + # convert a Werkzeug response object into an instance of the + # MyResponseClass subclass. + response = MyResponseClass.force_type(response) + + # convert any WSGI application into a response object + response = MyResponseClass.force_type(response, environ) + + This is especially useful if you want to post-process responses in + the main dispatcher and use functionality provided by your subclass. + + Keep in mind that this will modify response objects in place if + possible! + + :param response: a response object or wsgi application. + :param environ: a WSGI environment object. + :return: a response object. + """ + if not isinstance(response, BaseResponse): + if environ is None: + raise TypeError('cannot convert WSGI application into ' + 'response objects without an environ') + response = BaseResponse(*_run_wsgi_app(response, environ)) + response.__class__ = cls + return response + + @classmethod + def from_app(cls, app, environ, buffered=False): + """Create a new response object from an application output. This + works best if you pass it an application that returns a generator all + the time. Sometimes applications may use the `write()` callable + returned by the `start_response` function. This tries to resolve such + edge cases automatically. But if you don't get the expected output + you should set `buffered` to `True` which enforces buffering. + + :param app: the WSGI application to execute. + :param environ: the WSGI environment to execute against. + :param buffered: set to `True` to enforce buffering. + :return: a response object. + """ + return cls(*_run_wsgi_app(app, environ, buffered)) + + def _get_status_code(self): + return self._status_code + + def _set_status_code(self, code): + self._status_code = code + try: + self._status = '%d %s' % (code, HTTP_STATUS_CODES[code].upper()) + except KeyError: + self._status = '%d UNKNOWN' % code + status_code = property(_get_status_code, _set_status_code, + doc='The HTTP Status code as number') + del _get_status_code, _set_status_code + + def _get_status(self): + return self._status + + def _set_status(self, value): + try: + self._status = to_native(value) + except AttributeError: + raise TypeError('Invalid status argument') + + try: + self._status_code = int(self._status.split(None, 1)[0]) + except ValueError: + self._status_code = 0 + self._status = '0 %s' % self._status + except IndexError: + raise ValueError('Empty status argument') + status = property(_get_status, _set_status, doc='The HTTP Status code') + del _get_status, _set_status + + def get_data(self, as_text=False): + """The string representation of the request body. Whenever you call + this property the request iterable is encoded and flattened. This + can lead to unwanted behavior if you stream big data. + + This behavior can be disabled by setting + :attr:`implicit_sequence_conversion` to `False`. + + If `as_text` is set to `True` the return value will be a decoded + unicode string. + + .. versionadded:: 0.9 + """ + self._ensure_sequence() + rv = b''.join(self.iter_encoded()) + if as_text: + rv = rv.decode(self.charset) + return rv + + def set_data(self, value): + """Sets a new string as response. The value set must either by a + unicode or bytestring. If a unicode string is set it's encoded + automatically to the charset of the response (utf-8 by default). + + .. versionadded:: 0.9 + """ + # if an unicode string is set, it's encoded directly so that we + # can set the content length + if isinstance(value, text_type): + value = value.encode(self.charset) + else: + value = bytes(value) + self.response = [value] + if self.automatically_set_content_length: + self.headers['Content-Length'] = str(len(value)) + + data = property(get_data, set_data, doc=''' + A descriptor that calls :meth:`get_data` and :meth:`set_data`. This + should not be used and will eventually get deprecated. + ''') + + def calculate_content_length(self): + """Returns the content length if available or `None` otherwise.""" + try: + self._ensure_sequence() + except RuntimeError: + return None + return sum(len(x) for x in self.iter_encoded()) + + def _ensure_sequence(self, mutable=False): + """This method can be called by methods that need a sequence. If + `mutable` is true, it will also ensure that the response sequence + is a standard Python list. + + .. versionadded:: 0.6 + """ + if self.is_sequence: + # if we need a mutable object, we ensure it's a list. + if mutable and not isinstance(self.response, list): + self.response = list(self.response) + return + if self.direct_passthrough: + raise RuntimeError('Attempted implicit sequence conversion ' + 'but the response object is in direct ' + 'passthrough mode.') + if not self.implicit_sequence_conversion: + raise RuntimeError('The response object required the iterable ' + 'to be a sequence, but the implicit ' + 'conversion was disabled. Call ' + 'make_sequence() yourself.') + self.make_sequence() + + def make_sequence(self): + """Converts the response iterator in a list. By default this happens + automatically if required. If `implicit_sequence_conversion` is + disabled, this method is not automatically called and some properties + might raise exceptions. This also encodes all the items. + + .. versionadded:: 0.6 + """ + if not self.is_sequence: + # if we consume an iterable we have to ensure that the close + # method of the iterable is called if available when we tear + # down the response + close = getattr(self.response, 'close', None) + self.response = list(self.iter_encoded()) + if close is not None: + self.call_on_close(close) + + def iter_encoded(self): + """Iter the response encoded with the encoding of the response. + If the response object is invoked as WSGI application the return + value of this method is used as application iterator unless + :attr:`direct_passthrough` was activated. + """ + if __debug__: + _warn_if_string(self.response) + # Encode in a separate function so that self.response is fetched + # early. This allows us to wrap the response with the return + # value from get_app_iter or iter_encoded. + return _iter_encoded(self.response, self.charset) + + def set_cookie(self, key, value='', max_age=None, expires=None, + path='/', domain=None, secure=False, httponly=False, + samesite=None): + """Sets a cookie. The parameters are the same as in the cookie `Morsel` + object in the Python standard library but it accepts unicode data, too. + + A warning is raised if the size of the cookie header exceeds + :attr:`max_cookie_size`, but the header will still be set. + + :param key: the key (name) of the cookie to be set. + :param value: the value of the cookie. + :param max_age: should be a number of seconds, or `None` (default) if + the cookie should last only as long as the client's + browser session. + :param expires: should be a `datetime` object or UNIX timestamp. + :param path: limits the cookie to a given path, per default it will + span the whole domain. + :param domain: if you want to set a cross-domain cookie. For example, + ``domain=".example.com"`` will set a cookie that is + readable by the domain ``www.example.com``, + ``foo.example.com`` etc. Otherwise, a cookie will only + be readable by the domain that set it. + :param secure: If `True`, the cookie will only be available via HTTPS + :param httponly: disallow JavaScript to access the cookie. This is an + extension to the cookie standard and probably not + supported by all browsers. + :param samesite: Limits the scope of the cookie such that it will only + be attached to requests if those requests are + "same-site". + """ + self.headers.add('Set-Cookie', dump_cookie( + key, + value=value, + max_age=max_age, + expires=expires, + path=path, + domain=domain, + secure=secure, + httponly=httponly, + charset=self.charset, + max_size=self.max_cookie_size, + samesite=samesite + )) + + def delete_cookie(self, key, path='/', domain=None): + """Delete a cookie. Fails silently if key doesn't exist. + + :param key: the key (name) of the cookie to be deleted. + :param path: if the cookie that should be deleted was limited to a + path, the path has to be defined here. + :param domain: if the cookie that should be deleted was limited to a + domain, that domain has to be defined here. + """ + self.set_cookie(key, expires=0, max_age=0, path=path, domain=domain) + + @property + def is_streamed(self): + """If the response is streamed (the response is not an iterable with + a length information) this property is `True`. In this case streamed + means that there is no information about the number of iterations. + This is usually `True` if a generator is passed to the response object. + + This is useful for checking before applying some sort of post + filtering that should not take place for streamed responses. + """ + try: + len(self.response) + except (TypeError, AttributeError): + return True + return False + + @property + def is_sequence(self): + """If the iterator is buffered, this property will be `True`. A + response object will consider an iterator to be buffered if the + response attribute is a list or tuple. + + .. versionadded:: 0.6 + """ + return isinstance(self.response, (tuple, list)) + + def close(self): + """Close the wrapped response if possible. You can also use the object + in a with statement which will automatically close it. + + .. versionadded:: 0.9 + Can now be used in a with statement. + """ + if hasattr(self.response, 'close'): + self.response.close() + for func in self._on_close: + func() + + def __enter__(self): + return self + + def __exit__(self, exc_type, exc_value, tb): + self.close() + + def freeze(self): + """Call this method if you want to make your response object ready for + being pickled. This buffers the generator if there is one. It will + also set the `Content-Length` header to the length of the body. + + .. versionchanged:: 0.6 + The `Content-Length` header is now set. + """ + # we explicitly set the length to a list of the *encoded* response + # iterator. Even if the implicit sequence conversion is disabled. + self.response = list(self.iter_encoded()) + self.headers['Content-Length'] = str(sum(map(len, self.response))) + + def get_wsgi_headers(self, environ): + """This is automatically called right before the response is started + and returns headers modified for the given environment. It returns a + copy of the headers from the response with some modifications applied + if necessary. + + For example the location header (if present) is joined with the root + URL of the environment. Also the content length is automatically set + to zero here for certain status codes. + + .. versionchanged:: 0.6 + Previously that function was called `fix_headers` and modified + the response object in place. Also since 0.6, IRIs in location + and content-location headers are handled properly. + + Also starting with 0.6, Werkzeug will attempt to set the content + length if it is able to figure it out on its own. This is the + case if all the strings in the response iterable are already + encoded and the iterable is buffered. + + :param environ: the WSGI environment of the request. + :return: returns a new :class:`~werkzeug.datastructures.Headers` + object. + """ + headers = Headers(self.headers) + location = None + content_location = None + content_length = None + status = self.status_code + + # iterate over the headers to find all values in one go. Because + # get_wsgi_headers is used each response that gives us a tiny + # speedup. + for key, value in headers: + ikey = key.lower() + if ikey == u'location': + location = value + elif ikey == u'content-location': + content_location = value + elif ikey == u'content-length': + content_length = value + + # make sure the location header is an absolute URL + if location is not None: + old_location = location + if isinstance(location, text_type): + # Safe conversion is necessary here as we might redirect + # to a broken URI scheme (for instance itms-services). + location = iri_to_uri(location, safe_conversion=True) + + if self.autocorrect_location_header: + current_url = get_current_url(environ, root_only=True) + if isinstance(current_url, text_type): + current_url = iri_to_uri(current_url) + location = url_join(current_url, location) + if location != old_location: + headers['Location'] = location + + # make sure the content location is a URL + if content_location is not None and \ + isinstance(content_location, text_type): + headers['Content-Location'] = iri_to_uri(content_location) + + if status in (304, 412): + remove_entity_headers(headers) + + # if we can determine the content length automatically, we + # should try to do that. But only if this does not involve + # flattening the iterator or encoding of unicode strings in + # the response. We however should not do that if we have a 304 + # response. + if self.automatically_set_content_length and \ + self.is_sequence and content_length is None and \ + status not in (204, 304) and \ + not (100 <= status < 200): + try: + content_length = sum(len(to_bytes(x, 'ascii')) + for x in self.response) + except UnicodeError: + # aha, something non-bytestringy in there, too bad, we + # can't safely figure out the length of the response. + pass + else: + headers['Content-Length'] = str(content_length) + + return headers + + def get_app_iter(self, environ): + """Returns the application iterator for the given environ. Depending + on the request method and the current status code the return value + might be an empty response rather than the one from the response. + + If the request method is `HEAD` or the status code is in a range + where the HTTP specification requires an empty response, an empty + iterable is returned. + + .. versionadded:: 0.6 + + :param environ: the WSGI environment of the request. + :return: a response iterable. + """ + status = self.status_code + if environ['REQUEST_METHOD'] == 'HEAD' or \ + 100 <= status < 200 or status in (204, 304, 412): + iterable = () + elif self.direct_passthrough: + if __debug__: + _warn_if_string(self.response) + return self.response + else: + iterable = self.iter_encoded() + return ClosingIterator(iterable, self.close) + + def get_wsgi_response(self, environ): + """Returns the final WSGI response as tuple. The first item in + the tuple is the application iterator, the second the status and + the third the list of headers. The response returned is created + specially for the given environment. For example if the request + method in the WSGI environment is ``'HEAD'`` the response will + be empty and only the headers and status code will be present. + + .. versionadded:: 0.6 + + :param environ: the WSGI environment of the request. + :return: an ``(app_iter, status, headers)`` tuple. + """ + headers = self.get_wsgi_headers(environ) + app_iter = self.get_app_iter(environ) + return app_iter, self.status, headers.to_wsgi_list() + + def __call__(self, environ, start_response): + """Process this response as WSGI application. + + :param environ: the WSGI environment. + :param start_response: the response callable provided by the WSGI + server. + :return: an application iterator + """ + app_iter, status, headers = self.get_wsgi_response(environ) + start_response(status, headers) + return app_iter + + +class AcceptMixin(object): + + """A mixin for classes with an :attr:`~BaseResponse.environ` attribute + to get all the HTTP accept headers as + :class:`~werkzeug.datastructures.Accept` objects (or subclasses + thereof). + """ + + @cached_property + def accept_mimetypes(self): + """List of mimetypes this client supports as + :class:`~werkzeug.datastructures.MIMEAccept` object. + """ + return parse_accept_header(self.environ.get('HTTP_ACCEPT'), MIMEAccept) + + @cached_property + def accept_charsets(self): + """List of charsets this client supports as + :class:`~werkzeug.datastructures.CharsetAccept` object. + """ + return parse_accept_header(self.environ.get('HTTP_ACCEPT_CHARSET'), + CharsetAccept) + + @cached_property + def accept_encodings(self): + """List of encodings this client accepts. Encodings in a HTTP term + are compression encodings such as gzip. For charsets have a look at + :attr:`accept_charset`. + """ + return parse_accept_header(self.environ.get('HTTP_ACCEPT_ENCODING')) + + @cached_property + def accept_languages(self): + """List of languages this client accepts as + :class:`~werkzeug.datastructures.LanguageAccept` object. + + .. versionchanged 0.5 + In previous versions this was a regular + :class:`~werkzeug.datastructures.Accept` object. + """ + return parse_accept_header(self.environ.get('HTTP_ACCEPT_LANGUAGE'), + LanguageAccept) + + +class ETagRequestMixin(object): + + """Add entity tag and cache descriptors to a request object or object with + a WSGI environment available as :attr:`~BaseRequest.environ`. This not + only provides access to etags but also to the cache control header. + """ + + @cached_property + def cache_control(self): + """A :class:`~werkzeug.datastructures.RequestCacheControl` object + for the incoming cache control headers. + """ + cache_control = self.environ.get('HTTP_CACHE_CONTROL') + return parse_cache_control_header(cache_control, None, + RequestCacheControl) + + @cached_property + def if_match(self): + """An object containing all the etags in the `If-Match` header. + + :rtype: :class:`~werkzeug.datastructures.ETags` + """ + return parse_etags(self.environ.get('HTTP_IF_MATCH')) + + @cached_property + def if_none_match(self): + """An object containing all the etags in the `If-None-Match` header. + + :rtype: :class:`~werkzeug.datastructures.ETags` + """ + return parse_etags(self.environ.get('HTTP_IF_NONE_MATCH')) + + @cached_property + def if_modified_since(self): + """The parsed `If-Modified-Since` header as datetime object.""" + return parse_date(self.environ.get('HTTP_IF_MODIFIED_SINCE')) + + @cached_property + def if_unmodified_since(self): + """The parsed `If-Unmodified-Since` header as datetime object.""" + return parse_date(self.environ.get('HTTP_IF_UNMODIFIED_SINCE')) + + @cached_property + def if_range(self): + """The parsed `If-Range` header. + + .. versionadded:: 0.7 + + :rtype: :class:`~werkzeug.datastructures.IfRange` + """ + return parse_if_range_header(self.environ.get('HTTP_IF_RANGE')) + + @cached_property + def range(self): + """The parsed `Range` header. + + .. versionadded:: 0.7 + + :rtype: :class:`~werkzeug.datastructures.Range` + """ + return parse_range_header(self.environ.get('HTTP_RANGE')) + + +class UserAgentMixin(object): + + """Adds a `user_agent` attribute to the request object which contains the + parsed user agent of the browser that triggered the request as a + :class:`~werkzeug.useragents.UserAgent` object. + """ + + @cached_property + def user_agent(self): + """The current user agent.""" + from werkzeug.useragents import UserAgent + return UserAgent(self.environ) + + +class AuthorizationMixin(object): + + """Adds an :attr:`authorization` property that represents the parsed + value of the `Authorization` header as + :class:`~werkzeug.datastructures.Authorization` object. + """ + + @cached_property + def authorization(self): + """The `Authorization` object in parsed form.""" + header = self.environ.get('HTTP_AUTHORIZATION') + return parse_authorization_header(header) + + +class StreamOnlyMixin(object): + + """If mixed in before the request object this will change the bahavior + of it to disable handling of form parsing. This disables the + :attr:`files`, :attr:`form` attributes and will just provide a + :attr:`stream` attribute that however is always available. + + .. versionadded:: 0.9 + """ + + disable_data_descriptor = True + want_form_data_parsed = False + + +class ETagResponseMixin(object): + + """Adds extra functionality to a response object for etag and cache + handling. This mixin requires an object with at least a `headers` + object that implements a dict like interface similar to + :class:`~werkzeug.datastructures.Headers`. + + If you want the :meth:`freeze` method to automatically add an etag, you + have to mixin this method before the response base class. The default + response class does not do that. + """ + + @property + def cache_control(self): + """The Cache-Control general-header field is used to specify + directives that MUST be obeyed by all caching mechanisms along the + request/response chain. + """ + def on_update(cache_control): + if not cache_control and 'cache-control' in self.headers: + del self.headers['cache-control'] + elif cache_control: + self.headers['Cache-Control'] = cache_control.to_header() + return parse_cache_control_header(self.headers.get('cache-control'), + on_update, + ResponseCacheControl) + + def _wrap_response(self, start, length): + """Wrap existing Response in case of Range Request context.""" + if self.status_code == 206: + self.response = _RangeWrapper(self.response, start, length) + + def _is_range_request_processable(self, environ): + """Return ``True`` if `Range` header is present and if underlying + resource is considered unchanged when compared with `If-Range` header. + """ + return ( + 'HTTP_IF_RANGE' not in environ + or not is_resource_modified( + environ, self.headers.get('etag'), None, + self.headers.get('last-modified'), ignore_if_range=False + ) + ) and 'HTTP_RANGE' in environ + + def _process_range_request(self, environ, complete_length=None, accept_ranges=None): + """Handle Range Request related headers (RFC7233). If `Accept-Ranges` + header is valid, and Range Request is processable, we set the headers + as described by the RFC, and wrap the underlying response in a + RangeWrapper. + + Returns ``True`` if Range Request can be fulfilled, ``False`` otherwise. + + :raises: :class:`~werkzeug.exceptions.RequestedRangeNotSatisfiable` + if `Range` header could not be parsed or satisfied. + """ + from werkzeug.exceptions import RequestedRangeNotSatisfiable + if accept_ranges is None: + return False + self.headers['Accept-Ranges'] = accept_ranges + if not self._is_range_request_processable(environ) or complete_length is None: + return False + parsed_range = parse_range_header(environ.get('HTTP_RANGE')) + if parsed_range is None: + raise RequestedRangeNotSatisfiable(complete_length) + range_tuple = parsed_range.range_for_length(complete_length) + content_range_header = parsed_range.to_content_range_header(complete_length) + if range_tuple is None or content_range_header is None: + raise RequestedRangeNotSatisfiable(complete_length) + content_length = range_tuple[1] - range_tuple[0] + # Be sure not to send 206 response + # if requested range is the full content. + if content_length != complete_length: + self.headers['Content-Length'] = content_length + self.content_range = content_range_header + self.status_code = 206 + self._wrap_response(range_tuple[0], content_length) + return True + return False + + def make_conditional(self, request_or_environ, accept_ranges=False, + complete_length=None): + """Make the response conditional to the request. This method works + best if an etag was defined for the response already. The `add_etag` + method can be used to do that. If called without etag just the date + header is set. + + This does nothing if the request method in the request or environ is + anything but GET or HEAD. + + For optimal performance when handling range requests, it's recommended + that your response data object implements `seekable`, `seek` and `tell` + methods as described by :py:class:`io.IOBase`. Objects returned by + :meth:`~werkzeug.wsgi.wrap_file` automatically implement those methods. + + It does not remove the body of the response because that's something + the :meth:`__call__` function does for us automatically. + + Returns self so that you can do ``return resp.make_conditional(req)`` + but modifies the object in-place. + + :param request_or_environ: a request object or WSGI environment to be + used to make the response conditional + against. + :param accept_ranges: This parameter dictates the value of + `Accept-Ranges` header. If ``False`` (default), + the header is not set. If ``True``, it will be set + to ``"bytes"``. If ``None``, it will be set to + ``"none"``. If it's a string, it will use this + value. + :param complete_length: Will be used only in valid Range Requests. + It will set `Content-Range` complete length + value and compute `Content-Length` real value. + This parameter is mandatory for successful + Range Requests completion. + :raises: :class:`~werkzeug.exceptions.RequestedRangeNotSatisfiable` + if `Range` header could not be parsed or satisfied. + """ + environ = _get_environ(request_or_environ) + if environ['REQUEST_METHOD'] in ('GET', 'HEAD'): + # if the date is not in the headers, add it now. We however + # will not override an already existing header. Unfortunately + # this header will be overriden by many WSGI servers including + # wsgiref. + if 'date' not in self.headers: + self.headers['Date'] = http_date() + accept_ranges = _clean_accept_ranges(accept_ranges) + is206 = self._process_range_request(environ, complete_length, accept_ranges) + if not is206 and not is_resource_modified( + environ, self.headers.get('etag'), None, + self.headers.get('last-modified') + ): + if parse_etags(environ.get('HTTP_IF_MATCH')): + self.status_code = 412 + else: + self.status_code = 304 + if self.automatically_set_content_length and 'content-length' not in self.headers: + length = self.calculate_content_length() + if length is not None: + self.headers['Content-Length'] = length + return self + + def add_etag(self, overwrite=False, weak=False): + """Add an etag for the current response if there is none yet.""" + if overwrite or 'etag' not in self.headers: + self.set_etag(generate_etag(self.get_data()), weak) + + def set_etag(self, etag, weak=False): + """Set the etag, and override the old one if there was one.""" + self.headers['ETag'] = quote_etag(etag, weak) + + def get_etag(self): + """Return a tuple in the form ``(etag, is_weak)``. If there is no + ETag the return value is ``(None, None)``. + """ + return unquote_etag(self.headers.get('ETag')) + + def freeze(self, no_etag=False): + """Call this method if you want to make your response object ready for + pickeling. This buffers the generator if there is one. This also + sets the etag unless `no_etag` is set to `True`. + """ + if not no_etag: + self.add_etag() + super(ETagResponseMixin, self).freeze() + + accept_ranges = header_property('Accept-Ranges', doc=''' + The `Accept-Ranges` header. Even though the name would indicate + that multiple values are supported, it must be one string token only. + + The values ``'bytes'`` and ``'none'`` are common. + + .. versionadded:: 0.7''') + + def _get_content_range(self): + def on_update(rng): + if not rng: + del self.headers['content-range'] + else: + self.headers['Content-Range'] = rng.to_header() + rv = parse_content_range_header(self.headers.get('content-range'), + on_update) + # always provide a content range object to make the descriptor + # more user friendly. It provides an unset() method that can be + # used to remove the header quickly. + if rv is None: + rv = ContentRange(None, None, None, on_update=on_update) + return rv + + def _set_content_range(self, value): + if not value: + del self.headers['content-range'] + elif isinstance(value, string_types): + self.headers['Content-Range'] = value + else: + self.headers['Content-Range'] = value.to_header() + content_range = property(_get_content_range, _set_content_range, doc=''' + The `Content-Range` header as + :class:`~werkzeug.datastructures.ContentRange` object. Even if the + header is not set it wil provide such an object for easier + manipulation. + + .. versionadded:: 0.7''') + del _get_content_range, _set_content_range + + +class ResponseStream(object): + + """A file descriptor like object used by the :class:`ResponseStreamMixin` to + represent the body of the stream. It directly pushes into the response + iterable of the response object. + """ + + mode = 'wb+' + + def __init__(self, response): + self.response = response + self.closed = False + + def write(self, value): + if self.closed: + raise ValueError('I/O operation on closed file') + self.response._ensure_sequence(mutable=True) + self.response.response.append(value) + self.response.headers.pop('Content-Length', None) + return len(value) + + def writelines(self, seq): + for item in seq: + self.write(item) + + def close(self): + self.closed = True + + def flush(self): + if self.closed: + raise ValueError('I/O operation on closed file') + + def isatty(self): + if self.closed: + raise ValueError('I/O operation on closed file') + return False + + def tell(self): + self.response._ensure_sequence() + return sum(map(len, self.response.response)) + + @property + def encoding(self): + return self.response.charset + + +class ResponseStreamMixin(object): + + """Mixin for :class:`BaseRequest` subclasses. Classes that inherit from + this mixin will automatically get a :attr:`stream` property that provides + a write-only interface to the response iterable. + """ + + @cached_property + def stream(self): + """The response iterable as write-only stream.""" + return ResponseStream(self) + + +class CommonRequestDescriptorsMixin(object): + + """A mixin for :class:`BaseRequest` subclasses. Request objects that + mix this class in will automatically get descriptors for a couple of + HTTP headers with automatic type conversion. + + .. versionadded:: 0.5 + """ + + content_type = environ_property('CONTENT_TYPE', doc=''' + The Content-Type entity-header field indicates the media type of + the entity-body sent to the recipient or, in the case of the HEAD + method, the media type that would have been sent had the request + been a GET.''') + + @cached_property + def content_length(self): + """The Content-Length entity-header field indicates the size of the + entity-body in bytes or, in the case of the HEAD method, the size of + the entity-body that would have been sent had the request been a + GET. + """ + return get_content_length(self.environ) + + content_encoding = environ_property('HTTP_CONTENT_ENCODING', doc=''' + The Content-Encoding entity-header field is used as a modifier to the + media-type. When present, its value indicates what additional content + codings have been applied to the entity-body, and thus what decoding + mechanisms must be applied in order to obtain the media-type + referenced by the Content-Type header field. + + .. versionadded:: 0.9''') + content_md5 = environ_property('HTTP_CONTENT_MD5', doc=''' + The Content-MD5 entity-header field, as defined in RFC 1864, is an + MD5 digest of the entity-body for the purpose of providing an + end-to-end message integrity check (MIC) of the entity-body. (Note: + a MIC is good for detecting accidental modification of the + entity-body in transit, but is not proof against malicious attacks.) + + .. versionadded:: 0.9''') + referrer = environ_property('HTTP_REFERER', doc=''' + The Referer[sic] request-header field allows the client to specify, + for the server's benefit, the address (URI) of the resource from which + the Request-URI was obtained (the "referrer", although the header + field is misspelled).''') + date = environ_property('HTTP_DATE', None, parse_date, doc=''' + The Date general-header field represents the date and time at which + the message was originated, having the same semantics as orig-date + in RFC 822.''') + max_forwards = environ_property('HTTP_MAX_FORWARDS', None, int, doc=''' + The Max-Forwards request-header field provides a mechanism with the + TRACE and OPTIONS methods to limit the number of proxies or gateways + that can forward the request to the next inbound server.''') + + def _parse_content_type(self): + if not hasattr(self, '_parsed_content_type'): + self._parsed_content_type = \ + parse_options_header(self.environ.get('CONTENT_TYPE', '')) + + @property + def mimetype(self): + """Like :attr:`content_type`, but without parameters (eg, without + charset, type etc.) and always lowercase. For example if the content + type is ``text/HTML; charset=utf-8`` the mimetype would be + ``'text/html'``. + """ + self._parse_content_type() + return self._parsed_content_type[0].lower() + + @property + def mimetype_params(self): + """The mimetype parameters as dict. For example if the content + type is ``text/html; charset=utf-8`` the params would be + ``{'charset': 'utf-8'}``. + """ + self._parse_content_type() + return self._parsed_content_type[1] + + @cached_property + def pragma(self): + """The Pragma general-header field is used to include + implementation-specific directives that might apply to any recipient + along the request/response chain. All pragma directives specify + optional behavior from the viewpoint of the protocol; however, some + systems MAY require that behavior be consistent with the directives. + """ + return parse_set_header(self.environ.get('HTTP_PRAGMA', '')) + + +class CommonResponseDescriptorsMixin(object): + + """A mixin for :class:`BaseResponse` subclasses. Response objects that + mix this class in will automatically get descriptors for a couple of + HTTP headers with automatic type conversion. + """ + + def _get_mimetype(self): + ct = self.headers.get('content-type') + if ct: + return ct.split(';')[0].strip() + + def _set_mimetype(self, value): + self.headers['Content-Type'] = get_content_type(value, self.charset) + + def _get_mimetype_params(self): + def on_update(d): + self.headers['Content-Type'] = \ + dump_options_header(self.mimetype, d) + d = parse_options_header(self.headers.get('content-type', ''))[1] + return CallbackDict(d, on_update) + + mimetype = property(_get_mimetype, _set_mimetype, doc=''' + The mimetype (content type without charset etc.)''') + mimetype_params = property(_get_mimetype_params, doc=''' + The mimetype parameters as dict. For example if the content + type is ``text/html; charset=utf-8`` the params would be + ``{'charset': 'utf-8'}``. + + .. versionadded:: 0.5 + ''') + location = header_property('Location', doc=''' + The Location response-header field is used to redirect the recipient + to a location other than the Request-URI for completion of the request + or identification of a new resource.''') + age = header_property('Age', None, parse_age, dump_age, doc=''' + The Age response-header field conveys the sender's estimate of the + amount of time since the response (or its revalidation) was + generated at the origin server. + + Age values are non-negative decimal integers, representing time in + seconds.''') + content_type = header_property('Content-Type', doc=''' + The Content-Type entity-header field indicates the media type of the + entity-body sent to the recipient or, in the case of the HEAD method, + the media type that would have been sent had the request been a GET. + ''') + content_length = header_property('Content-Length', None, int, str, doc=''' + The Content-Length entity-header field indicates the size of the + entity-body, in decimal number of OCTETs, sent to the recipient or, + in the case of the HEAD method, the size of the entity-body that would + have been sent had the request been a GET.''') + content_location = header_property('Content-Location', doc=''' + The Content-Location entity-header field MAY be used to supply the + resource location for the entity enclosed in the message when that + entity is accessible from a location separate from the requested + resource's URI.''') + content_encoding = header_property('Content-Encoding', doc=''' + The Content-Encoding entity-header field is used as a modifier to the + media-type. When present, its value indicates what additional content + codings have been applied to the entity-body, and thus what decoding + mechanisms must be applied in order to obtain the media-type + referenced by the Content-Type header field.''') + content_md5 = header_property('Content-MD5', doc=''' + The Content-MD5 entity-header field, as defined in RFC 1864, is an + MD5 digest of the entity-body for the purpose of providing an + end-to-end message integrity check (MIC) of the entity-body. (Note: + a MIC is good for detecting accidental modification of the + entity-body in transit, but is not proof against malicious attacks.) + ''') + date = header_property('Date', None, parse_date, http_date, doc=''' + The Date general-header field represents the date and time at which + the message was originated, having the same semantics as orig-date + in RFC 822.''') + expires = header_property('Expires', None, parse_date, http_date, doc=''' + The Expires entity-header field gives the date/time after which the + response is considered stale. A stale cache entry may not normally be + returned by a cache.''') + last_modified = header_property('Last-Modified', None, parse_date, + http_date, doc=''' + The Last-Modified entity-header field indicates the date and time at + which the origin server believes the variant was last modified.''') + + def _get_retry_after(self): + value = self.headers.get('retry-after') + if value is None: + return + elif value.isdigit(): + return datetime.utcnow() + timedelta(seconds=int(value)) + return parse_date(value) + + def _set_retry_after(self, value): + if value is None: + if 'retry-after' in self.headers: + del self.headers['retry-after'] + return + elif isinstance(value, datetime): + value = http_date(value) + else: + value = str(value) + self.headers['Retry-After'] = value + + retry_after = property(_get_retry_after, _set_retry_after, doc=''' + The Retry-After response-header field can be used with a 503 (Service + Unavailable) response to indicate how long the service is expected + to be unavailable to the requesting client. + + Time in seconds until expiration or date.''') + + def _set_property(name, doc=None): + def fget(self): + def on_update(header_set): + if not header_set and name in self.headers: + del self.headers[name] + elif header_set: + self.headers[name] = header_set.to_header() + return parse_set_header(self.headers.get(name), on_update) + + def fset(self, value): + if not value: + del self.headers[name] + elif isinstance(value, string_types): + self.headers[name] = value + else: + self.headers[name] = dump_header(value) + return property(fget, fset, doc=doc) + + vary = _set_property('Vary', doc=''' + The Vary field value indicates the set of request-header fields that + fully determines, while the response is fresh, whether a cache is + permitted to use the response to reply to a subsequent request + without revalidation.''') + content_language = _set_property('Content-Language', doc=''' + The Content-Language entity-header field describes the natural + language(s) of the intended audience for the enclosed entity. Note + that this might not be equivalent to all the languages used within + the entity-body.''') + allow = _set_property('Allow', doc=''' + The Allow entity-header field lists the set of methods supported + by the resource identified by the Request-URI. The purpose of this + field is strictly to inform the recipient of valid methods + associated with the resource. An Allow header field MUST be + present in a 405 (Method Not Allowed) response.''') + + del _set_property, _get_mimetype, _set_mimetype, _get_retry_after, \ + _set_retry_after + + +class WWWAuthenticateMixin(object): + + """Adds a :attr:`www_authenticate` property to a response object.""" + + @property + def www_authenticate(self): + """The `WWW-Authenticate` header in a parsed form.""" + def on_update(www_auth): + if not www_auth and 'www-authenticate' in self.headers: + del self.headers['www-authenticate'] + elif www_auth: + self.headers['WWW-Authenticate'] = www_auth.to_header() + header = self.headers.get('www-authenticate') + return parse_www_authenticate_header(header, on_update) + + +class Request(BaseRequest, AcceptMixin, ETagRequestMixin, + UserAgentMixin, AuthorizationMixin, + CommonRequestDescriptorsMixin): + + """Full featured request object implementing the following mixins: + + - :class:`AcceptMixin` for accept header parsing + - :class:`ETagRequestMixin` for etag and cache control handling + - :class:`UserAgentMixin` for user agent introspection + - :class:`AuthorizationMixin` for http auth handling + - :class:`CommonRequestDescriptorsMixin` for common headers + """ + + +class PlainRequest(StreamOnlyMixin, Request): + + """A request object without special form parsing capabilities. + + .. versionadded:: 0.9 + """ + + +class Response(BaseResponse, ETagResponseMixin, ResponseStreamMixin, + CommonResponseDescriptorsMixin, + WWWAuthenticateMixin): + + """Full featured response object implementing the following mixins: + + - :class:`ETagResponseMixin` for etag and cache control handling + - :class:`ResponseStreamMixin` to add support for the `stream` property + - :class:`CommonResponseDescriptorsMixin` for various HTTP descriptors + - :class:`WWWAuthenticateMixin` for HTTP authentication support + """ diff --git a/pyextra/werkzeug/wsgi.py b/pyextra/werkzeug/wsgi.py new file mode 100644 index 00000000000000..c30021a7b6ae51 --- /dev/null +++ b/pyextra/werkzeug/wsgi.py @@ -0,0 +1,1364 @@ +# -*- coding: utf-8 -*- +""" + werkzeug.wsgi + ~~~~~~~~~~~~~ + + This module implements WSGI related helpers. + + :copyright: (c) 2014 by the Werkzeug Team, see AUTHORS for more details. + :license: BSD, see LICENSE for more details. +""" +import io +try: + import httplib +except ImportError: + from http import client as httplib +import mimetypes +import os +import posixpath +import re +import socket +from datetime import datetime +from functools import partial, update_wrapper +from itertools import chain +from time import mktime, time +from zlib import adler32 + +from werkzeug._compat import BytesIO, PY2, implements_iterator, iteritems, \ + make_literal_wrapper, string_types, text_type, to_bytes, to_unicode, \ + try_coerce_native, wsgi_get_bytes +from werkzeug._internal import _empty_stream, _encode_idna +from werkzeug.filesystem import get_filesystem_encoding +from werkzeug.http import http_date, is_resource_modified, \ + is_hop_by_hop_header +from werkzeug.urls import uri_to_iri, url_join, url_parse, url_quote +from werkzeug.datastructures import EnvironHeaders + + +def responder(f): + """Marks a function as responder. Decorate a function with it and it + will automatically call the return value as WSGI application. + + Example:: + + @responder + def application(environ, start_response): + return Response('Hello World!') + """ + return update_wrapper(lambda *a: f(*a)(*a[-2:]), f) + + +def get_current_url(environ, root_only=False, strip_querystring=False, + host_only=False, trusted_hosts=None): + """A handy helper function that recreates the full URL as IRI for the + current request or parts of it. Here's an example: + + >>> from werkzeug.test import create_environ + >>> env = create_environ("/?param=foo", "http://localhost/script") + >>> get_current_url(env) + 'http://localhost/script/?param=foo' + >>> get_current_url(env, root_only=True) + 'http://localhost/script/' + >>> get_current_url(env, host_only=True) + 'http://localhost/' + >>> get_current_url(env, strip_querystring=True) + 'http://localhost/script/' + + This optionally it verifies that the host is in a list of trusted hosts. + If the host is not in there it will raise a + :exc:`~werkzeug.exceptions.SecurityError`. + + Note that the string returned might contain unicode characters as the + representation is an IRI not an URI. If you need an ASCII only + representation you can use the :func:`~werkzeug.urls.iri_to_uri` + function: + + >>> from werkzeug.urls import iri_to_uri + >>> iri_to_uri(get_current_url(env)) + 'http://localhost/script/?param=foo' + + :param environ: the WSGI environment to get the current URL from. + :param root_only: set `True` if you only want the root URL. + :param strip_querystring: set to `True` if you don't want the querystring. + :param host_only: set to `True` if the host URL should be returned. + :param trusted_hosts: a list of trusted hosts, see :func:`host_is_trusted` + for more information. + """ + tmp = [environ['wsgi.url_scheme'], '://', get_host(environ, trusted_hosts)] + cat = tmp.append + if host_only: + return uri_to_iri(''.join(tmp) + '/') + cat(url_quote(wsgi_get_bytes(environ.get('SCRIPT_NAME', ''))).rstrip('/')) + cat('/') + if not root_only: + cat(url_quote(wsgi_get_bytes(environ.get('PATH_INFO', '')).lstrip(b'/'))) + if not strip_querystring: + qs = get_query_string(environ) + if qs: + cat('?' + qs) + return uri_to_iri(''.join(tmp)) + + +def host_is_trusted(hostname, trusted_list): + """Checks if a host is trusted against a list. This also takes care + of port normalization. + + .. versionadded:: 0.9 + + :param hostname: the hostname to check + :param trusted_list: a list of hostnames to check against. If a + hostname starts with a dot it will match against + all subdomains as well. + """ + if not hostname: + return False + + if isinstance(trusted_list, string_types): + trusted_list = [trusted_list] + + def _normalize(hostname): + if ':' in hostname: + hostname = hostname.rsplit(':', 1)[0] + return _encode_idna(hostname) + + try: + hostname = _normalize(hostname) + except UnicodeError: + return False + for ref in trusted_list: + if ref.startswith('.'): + ref = ref[1:] + suffix_match = True + else: + suffix_match = False + try: + ref = _normalize(ref) + except UnicodeError: + return False + if ref == hostname: + return True + if suffix_match and hostname.endswith(b'.' + ref): + return True + return False + + +def get_host(environ, trusted_hosts=None): + """Return the real host for the given WSGI environment. This first checks + the `X-Forwarded-Host` header, then the normal `Host` header, and finally + the `SERVER_NAME` environment variable (using the first one it finds). + + Optionally it verifies that the host is in a list of trusted hosts. + If the host is not in there it will raise a + :exc:`~werkzeug.exceptions.SecurityError`. + + :param environ: the WSGI environment to get the host of. + :param trusted_hosts: a list of trusted hosts, see :func:`host_is_trusted` + for more information. + """ + if 'HTTP_X_FORWARDED_HOST' in environ: + rv = environ['HTTP_X_FORWARDED_HOST'].split(',', 1)[0].strip() + elif 'HTTP_HOST' in environ: + rv = environ['HTTP_HOST'] + else: + rv = environ['SERVER_NAME'] + if (environ['wsgi.url_scheme'], environ['SERVER_PORT']) not \ + in (('https', '443'), ('http', '80')): + rv += ':' + environ['SERVER_PORT'] + if trusted_hosts is not None: + if not host_is_trusted(rv, trusted_hosts): + from werkzeug.exceptions import SecurityError + raise SecurityError('Host "%s" is not trusted' % rv) + return rv + + +def get_content_length(environ): + """Returns the content length from the WSGI environment as + integer. If it's not available or chunked transfer encoding is used, + ``None`` is returned. + + .. versionadded:: 0.9 + + :param environ: the WSGI environ to fetch the content length from. + """ + if environ.get('HTTP_TRANSFER_ENCODING', '') == 'chunked': + return None + + content_length = environ.get('CONTENT_LENGTH') + if content_length is not None: + try: + return max(0, int(content_length)) + except (ValueError, TypeError): + pass + + +def get_input_stream(environ, safe_fallback=True): + """Returns the input stream from the WSGI environment and wraps it + in the most sensible way possible. The stream returned is not the + raw WSGI stream in most cases but one that is safe to read from + without taking into account the content length. + + If content length is not set, the stream will be empty for safety reasons. + If the WSGI server supports chunked or infinite streams, it should set + the ``wsgi.input_terminated`` value in the WSGI environ to indicate that. + + .. versionadded:: 0.9 + + :param environ: the WSGI environ to fetch the stream from. + :param safe_fallback: use an empty stream as a safe fallback when the + content length is not set. Disabling this allows infinite streams, + which can be a denial-of-service risk. + """ + stream = environ['wsgi.input'] + content_length = get_content_length(environ) + + # A wsgi extension that tells us if the input is terminated. In + # that case we return the stream unchanged as we know we can safely + # read it until the end. + if environ.get('wsgi.input_terminated'): + return stream + + # If the request doesn't specify a content length, returning the stream is + # potentially dangerous because it could be infinite, malicious or not. If + # safe_fallback is true, return an empty stream instead for safety. + if content_length is None: + return safe_fallback and _empty_stream or stream + + # Otherwise limit the stream to the content length + return LimitedStream(stream, content_length) + + +def get_query_string(environ): + """Returns the `QUERY_STRING` from the WSGI environment. This also takes + care about the WSGI decoding dance on Python 3 environments as a + native string. The string returned will be restricted to ASCII + characters. + + .. versionadded:: 0.9 + + :param environ: the WSGI environment object to get the query string from. + """ + qs = wsgi_get_bytes(environ.get('QUERY_STRING', '')) + # QUERY_STRING really should be ascii safe but some browsers + # will send us some unicode stuff (I am looking at you IE). + # In that case we want to urllib quote it badly. + return try_coerce_native(url_quote(qs, safe=':&%=+$!*\'(),')) + + +def get_path_info(environ, charset='utf-8', errors='replace'): + """Returns the `PATH_INFO` from the WSGI environment and properly + decodes it. This also takes care about the WSGI decoding dance + on Python 3 environments. if the `charset` is set to `None` a + bytestring is returned. + + .. versionadded:: 0.9 + + :param environ: the WSGI environment object to get the path from. + :param charset: the charset for the path info, or `None` if no + decoding should be performed. + :param errors: the decoding error handling. + """ + path = wsgi_get_bytes(environ.get('PATH_INFO', '')) + return to_unicode(path, charset, errors, allow_none_charset=True) + + +def get_script_name(environ, charset='utf-8', errors='replace'): + """Returns the `SCRIPT_NAME` from the WSGI environment and properly + decodes it. This also takes care about the WSGI decoding dance + on Python 3 environments. if the `charset` is set to `None` a + bytestring is returned. + + .. versionadded:: 0.9 + + :param environ: the WSGI environment object to get the path from. + :param charset: the charset for the path, or `None` if no + decoding should be performed. + :param errors: the decoding error handling. + """ + path = wsgi_get_bytes(environ.get('SCRIPT_NAME', '')) + return to_unicode(path, charset, errors, allow_none_charset=True) + + +def pop_path_info(environ, charset='utf-8', errors='replace'): + """Removes and returns the next segment of `PATH_INFO`, pushing it onto + `SCRIPT_NAME`. Returns `None` if there is nothing left on `PATH_INFO`. + + If the `charset` is set to `None` a bytestring is returned. + + If there are empty segments (``'/foo//bar``) these are ignored but + properly pushed to the `SCRIPT_NAME`: + + >>> env = {'SCRIPT_NAME': '/foo', 'PATH_INFO': '/a/b'} + >>> pop_path_info(env) + 'a' + >>> env['SCRIPT_NAME'] + '/foo/a' + >>> pop_path_info(env) + 'b' + >>> env['SCRIPT_NAME'] + '/foo/a/b' + + .. versionadded:: 0.5 + + .. versionchanged:: 0.9 + The path is now decoded and a charset and encoding + parameter can be provided. + + :param environ: the WSGI environment that is modified. + """ + path = environ.get('PATH_INFO') + if not path: + return None + + script_name = environ.get('SCRIPT_NAME', '') + + # shift multiple leading slashes over + old_path = path + path = path.lstrip('/') + if path != old_path: + script_name += '/' * (len(old_path) - len(path)) + + if '/' not in path: + environ['PATH_INFO'] = '' + environ['SCRIPT_NAME'] = script_name + path + rv = wsgi_get_bytes(path) + else: + segment, path = path.split('/', 1) + environ['PATH_INFO'] = '/' + path + environ['SCRIPT_NAME'] = script_name + segment + rv = wsgi_get_bytes(segment) + + return to_unicode(rv, charset, errors, allow_none_charset=True) + + +def peek_path_info(environ, charset='utf-8', errors='replace'): + """Returns the next segment on the `PATH_INFO` or `None` if there + is none. Works like :func:`pop_path_info` without modifying the + environment: + + >>> env = {'SCRIPT_NAME': '/foo', 'PATH_INFO': '/a/b'} + >>> peek_path_info(env) + 'a' + >>> peek_path_info(env) + 'a' + + If the `charset` is set to `None` a bytestring is returned. + + .. versionadded:: 0.5 + + .. versionchanged:: 0.9 + The path is now decoded and a charset and encoding + parameter can be provided. + + :param environ: the WSGI environment that is checked. + """ + segments = environ.get('PATH_INFO', '').lstrip('/').split('/', 1) + if segments: + return to_unicode(wsgi_get_bytes(segments[0]), + charset, errors, allow_none_charset=True) + + +def extract_path_info(environ_or_baseurl, path_or_url, charset='utf-8', + errors='replace', collapse_http_schemes=True): + """Extracts the path info from the given URL (or WSGI environment) and + path. The path info returned is a unicode string, not a bytestring + suitable for a WSGI environment. The URLs might also be IRIs. + + If the path info could not be determined, `None` is returned. + + Some examples: + + >>> extract_path_info('http://example.com/app', '/app/hello') + u'/hello' + >>> extract_path_info('http://example.com/app', + ... 'https://example.com/app/hello') + u'/hello' + >>> extract_path_info('http://example.com/app', + ... 'https://example.com/app/hello', + ... collapse_http_schemes=False) is None + True + + Instead of providing a base URL you can also pass a WSGI environment. + + .. versionadded:: 0.6 + + :param environ_or_baseurl: a WSGI environment dict, a base URL or + base IRI. This is the root of the + application. + :param path_or_url: an absolute path from the server root, a + relative path (in which case it's the path info) + or a full URL. Also accepts IRIs and unicode + parameters. + :param charset: the charset for byte data in URLs + :param errors: the error handling on decode + :param collapse_http_schemes: if set to `False` the algorithm does + not assume that http and https on the + same server point to the same + resource. + """ + def _normalize_netloc(scheme, netloc): + parts = netloc.split(u'@', 1)[-1].split(u':', 1) + if len(parts) == 2: + netloc, port = parts + if (scheme == u'http' and port == u'80') or \ + (scheme == u'https' and port == u'443'): + port = None + else: + netloc = parts[0] + port = None + if port is not None: + netloc += u':' + port + return netloc + + # make sure whatever we are working on is a IRI and parse it + path = uri_to_iri(path_or_url, charset, errors) + if isinstance(environ_or_baseurl, dict): + environ_or_baseurl = get_current_url(environ_or_baseurl, + root_only=True) + base_iri = uri_to_iri(environ_or_baseurl, charset, errors) + base_scheme, base_netloc, base_path = url_parse(base_iri)[:3] + cur_scheme, cur_netloc, cur_path, = \ + url_parse(url_join(base_iri, path))[:3] + + # normalize the network location + base_netloc = _normalize_netloc(base_scheme, base_netloc) + cur_netloc = _normalize_netloc(cur_scheme, cur_netloc) + + # is that IRI even on a known HTTP scheme? + if collapse_http_schemes: + for scheme in base_scheme, cur_scheme: + if scheme not in (u'http', u'https'): + return None + else: + if not (base_scheme in (u'http', u'https') and + base_scheme == cur_scheme): + return None + + # are the netlocs compatible? + if base_netloc != cur_netloc: + return None + + # are we below the application path? + base_path = base_path.rstrip(u'/') + if not cur_path.startswith(base_path): + return None + + return u'/' + cur_path[len(base_path):].lstrip(u'/') + + +class ProxyMiddleware(object): + """This middleware routes some requests to the provided WSGI app and + proxies some requests to an external server. This is not something that + can generally be done on the WSGI layer and some HTTP requests will not + tunnel through correctly (for instance websocket requests cannot be + proxied through WSGI). As a result this is only really useful for some + basic requests that can be forwarded. + + Example configuration:: + + app = ProxyMiddleware(app, { + '/static/': { + 'target': 'http://127.0.0.1:5001/', + } + }) + + For each host options can be specified. The following options are + supported: + + ``target``: + the target URL to dispatch to + ``remove_prefix``: + if set to `True` the prefix is chopped off the URL before + dispatching it to the server. + ``host``: + When set to ``''`` which is the default the host header is + automatically rewritten to the URL of the target. If set to `None` + then the host header is unmodified from the client request. Any + other value overwrites the host header with that value. + ``headers``: + An optional dictionary of headers that should be sent with the + request to the target host. + ``ssl_context``: + In case this is an HTTPS target host then an SSL context can be + provided here (:class:`ssl.SSLContext`). This can be used for instance + to disable SSL verification. + + In this case everything below ``'/static/'`` is proxied to the server on + port 5001. The host header is automatically rewritten and so are request + URLs (eg: the leading `/static/` prefix here gets chopped off). + + .. versionadded:: 0.14 + """ + + def __init__(self, app, targets, chunk_size=2 << 13, timeout=10): + def _set_defaults(opts): + opts.setdefault('remove_prefix', False) + opts.setdefault('host', '') + opts.setdefault('headers', {}) + opts.setdefault('ssl_context', None) + return opts + self.app = app + self.targets = dict(('/%s/' % k.strip('/'), _set_defaults(v)) + for k, v in iteritems(targets)) + self.chunk_size = chunk_size + self.timeout = timeout + + def proxy_to(self, opts, path, prefix): + target = url_parse(opts['target']) + + def application(environ, start_response): + headers = list(EnvironHeaders(environ).items()) + headers[:] = [(k, v) for k, v in headers + if not is_hop_by_hop_header(k) and + k.lower() not in ('content-length', 'host')] + headers.append(('Connection', 'close')) + if opts['host'] == '': + headers.append(('Host', target.ascii_host)) + elif opts['host'] is None: + headers.append(('Host', environ['HTTP_HOST'])) + else: + headers.append(('Host', opts['host'])) + headers.extend(opts['headers'].items()) + + remote_path = path + if opts['remove_prefix']: + remote_path = '%s/%s' % ( + target.path.rstrip('/'), + remote_path[len(prefix):].lstrip('/') + ) + + content_length = environ.get('CONTENT_LENGTH') + chunked = False + if content_length not in ('', None): + headers.append(('Content-Length', content_length)) + elif content_length is not None: + headers.append(('Transfer-Encoding', 'chunked')) + chunked = True + + try: + if target.scheme == 'http': + con = httplib.HTTPConnection( + target.ascii_host, target.port or 80, + timeout=self.timeout) + elif target.scheme == 'https': + con = httplib.HTTPSConnection( + target.ascii_host, target.port or 443, + timeout=self.timeout, + context=opts['ssl_context']) + con.connect() + con.putrequest(environ['REQUEST_METHOD'], url_quote(remote_path), + skip_host=True) + + for k, v in headers: + if k.lower() == 'connection': + v = 'close' + con.putheader(k, v) + con.endheaders() + + stream = get_input_stream(environ) + while 1: + data = stream.read(self.chunk_size) + if not data: + break + if chunked: + con.send(b'%x\r\n%s\r\n' % (len(data), data)) + else: + con.send(data) + + resp = con.getresponse() + except socket.error: + from werkzeug.exceptions import BadGateway + return BadGateway()(environ, start_response) + + start_response('%d %s' % (resp.status, resp.reason), + [(k.title(), v) for k, v in resp.getheaders() + if not is_hop_by_hop_header(k)]) + + def read(): + while 1: + try: + data = resp.read(self.chunk_size) + except socket.error: + break + if not data: + break + yield data + return read() + return application + + def __call__(self, environ, start_response): + path = environ['PATH_INFO'] + app = self.app + for prefix, opts in iteritems(self.targets): + if path.startswith(prefix): + app = self.proxy_to(opts, path, prefix) + break + return app(environ, start_response) + + +class SharedDataMiddleware(object): + + """A WSGI middleware that provides static content for development + environments or simple server setups. Usage is quite simple:: + + import os + from werkzeug.wsgi import SharedDataMiddleware + + app = SharedDataMiddleware(app, { + '/shared': os.path.join(os.path.dirname(__file__), 'shared') + }) + + The contents of the folder ``./shared`` will now be available on + ``http://example.com/shared/``. This is pretty useful during development + because a standalone media server is not required. One can also mount + files on the root folder and still continue to use the application because + the shared data middleware forwards all unhandled requests to the + application, even if the requests are below one of the shared folders. + + If `pkg_resources` is available you can also tell the middleware to serve + files from package data:: + + app = SharedDataMiddleware(app, { + '/shared': ('myapplication', 'shared_files') + }) + + This will then serve the ``shared_files`` folder in the `myapplication` + Python package. + + The optional `disallow` parameter can be a list of :func:`~fnmatch.fnmatch` + rules for files that are not accessible from the web. If `cache` is set to + `False` no caching headers are sent. + + Currently the middleware does not support non ASCII filenames. If the + encoding on the file system happens to be the encoding of the URI it may + work but this could also be by accident. We strongly suggest using ASCII + only file names for static files. + + The middleware will guess the mimetype using the Python `mimetype` + module. If it's unable to figure out the charset it will fall back + to `fallback_mimetype`. + + .. versionchanged:: 0.5 + The cache timeout is configurable now. + + .. versionadded:: 0.6 + The `fallback_mimetype` parameter was added. + + :param app: the application to wrap. If you don't want to wrap an + application you can pass it :exc:`NotFound`. + :param exports: a list or dict of exported files and folders. + :param disallow: a list of :func:`~fnmatch.fnmatch` rules. + :param fallback_mimetype: the fallback mimetype for unknown files. + :param cache: enable or disable caching headers. + :param cache_timeout: the cache timeout in seconds for the headers. + """ + + def __init__(self, app, exports, disallow=None, cache=True, + cache_timeout=60 * 60 * 12, fallback_mimetype='text/plain'): + self.app = app + self.exports = [] + self.cache = cache + self.cache_timeout = cache_timeout + if hasattr(exports, 'items'): + exports = iteritems(exports) + for key, value in exports: + if isinstance(value, tuple): + loader = self.get_package_loader(*value) + elif isinstance(value, string_types): + if os.path.isfile(value): + loader = self.get_file_loader(value) + else: + loader = self.get_directory_loader(value) + else: + raise TypeError('unknown def %r' % value) + self.exports.append((key, loader)) + if disallow is not None: + from fnmatch import fnmatch + self.is_allowed = lambda x: not fnmatch(x, disallow) + self.fallback_mimetype = fallback_mimetype + + def is_allowed(self, filename): + """Subclasses can override this method to disallow the access to + certain files. However by providing `disallow` in the constructor + this method is overwritten. + """ + return True + + def _opener(self, filename): + return lambda: ( + open(filename, 'rb'), + datetime.utcfromtimestamp(os.path.getmtime(filename)), + int(os.path.getsize(filename)) + ) + + def get_file_loader(self, filename): + return lambda x: (os.path.basename(filename), self._opener(filename)) + + def get_package_loader(self, package, package_path): + from pkg_resources import DefaultProvider, ResourceManager, \ + get_provider + loadtime = datetime.utcnow() + provider = get_provider(package) + manager = ResourceManager() + filesystem_bound = isinstance(provider, DefaultProvider) + + def loader(path): + if path is None: + return None, None + path = posixpath.join(package_path, path) + if not provider.has_resource(path): + return None, None + basename = posixpath.basename(path) + if filesystem_bound: + return basename, self._opener( + provider.get_resource_filename(manager, path)) + s = provider.get_resource_string(manager, path) + return basename, lambda: ( + BytesIO(s), + loadtime, + len(s) + ) + return loader + + def get_directory_loader(self, directory): + def loader(path): + if path is not None: + path = os.path.join(directory, path) + else: + path = directory + if os.path.isfile(path): + return os.path.basename(path), self._opener(path) + return None, None + return loader + + def generate_etag(self, mtime, file_size, real_filename): + if not isinstance(real_filename, bytes): + real_filename = real_filename.encode(get_filesystem_encoding()) + return 'wzsdm-%d-%s-%s' % ( + mktime(mtime.timetuple()), + file_size, + adler32(real_filename) & 0xffffffff + ) + + def __call__(self, environ, start_response): + cleaned_path = get_path_info(environ) + if PY2: + cleaned_path = cleaned_path.encode(get_filesystem_encoding()) + # sanitize the path for non unix systems + cleaned_path = cleaned_path.strip('/') + for sep in os.sep, os.altsep: + if sep and sep != '/': + cleaned_path = cleaned_path.replace(sep, '/') + path = '/' + '/'.join(x for x in cleaned_path.split('/') + if x and x != '..') + file_loader = None + for search_path, loader in self.exports: + if search_path == path: + real_filename, file_loader = loader(None) + if file_loader is not None: + break + if not search_path.endswith('/'): + search_path += '/' + if path.startswith(search_path): + real_filename, file_loader = loader(path[len(search_path):]) + if file_loader is not None: + break + if file_loader is None or not self.is_allowed(real_filename): + return self.app(environ, start_response) + + guessed_type = mimetypes.guess_type(real_filename) + mime_type = guessed_type[0] or self.fallback_mimetype + f, mtime, file_size = file_loader() + + headers = [('Date', http_date())] + if self.cache: + timeout = self.cache_timeout + etag = self.generate_etag(mtime, file_size, real_filename) + headers += [ + ('Etag', '"%s"' % etag), + ('Cache-Control', 'max-age=%d, public' % timeout) + ] + if not is_resource_modified(environ, etag, last_modified=mtime): + f.close() + start_response('304 Not Modified', headers) + return [] + headers.append(('Expires', http_date(time() + timeout))) + else: + headers.append(('Cache-Control', 'public')) + + headers.extend(( + ('Content-Type', mime_type), + ('Content-Length', str(file_size)), + ('Last-Modified', http_date(mtime)) + )) + start_response('200 OK', headers) + return wrap_file(environ, f) + + +class DispatcherMiddleware(object): + + """Allows one to mount middlewares or applications in a WSGI application. + This is useful if you want to combine multiple WSGI applications:: + + app = DispatcherMiddleware(app, { + '/app2': app2, + '/app3': app3 + }) + """ + + def __init__(self, app, mounts=None): + self.app = app + self.mounts = mounts or {} + + def __call__(self, environ, start_response): + script = environ.get('PATH_INFO', '') + path_info = '' + while '/' in script: + if script in self.mounts: + app = self.mounts[script] + break + script, last_item = script.rsplit('/', 1) + path_info = '/%s%s' % (last_item, path_info) + else: + app = self.mounts.get(script, self.app) + original_script_name = environ.get('SCRIPT_NAME', '') + environ['SCRIPT_NAME'] = original_script_name + script + environ['PATH_INFO'] = path_info + return app(environ, start_response) + + +@implements_iterator +class ClosingIterator(object): + + """The WSGI specification requires that all middlewares and gateways + respect the `close` callback of an iterator. Because it is useful to add + another close action to a returned iterator and adding a custom iterator + is a boring task this class can be used for that:: + + return ClosingIterator(app(environ, start_response), [cleanup_session, + cleanup_locals]) + + If there is just one close function it can be passed instead of the list. + + A closing iterator is not needed if the application uses response objects + and finishes the processing if the response is started:: + + try: + return response(environ, start_response) + finally: + cleanup_session() + cleanup_locals() + """ + + def __init__(self, iterable, callbacks=None): + iterator = iter(iterable) + self._next = partial(next, iterator) + if callbacks is None: + callbacks = [] + elif callable(callbacks): + callbacks = [callbacks] + else: + callbacks = list(callbacks) + iterable_close = getattr(iterator, 'close', None) + if iterable_close: + callbacks.insert(0, iterable_close) + self._callbacks = callbacks + + def __iter__(self): + return self + + def __next__(self): + return self._next() + + def close(self): + for callback in self._callbacks: + callback() + + +def wrap_file(environ, file, buffer_size=8192): + """Wraps a file. This uses the WSGI server's file wrapper if available + or otherwise the generic :class:`FileWrapper`. + + .. versionadded:: 0.5 + + If the file wrapper from the WSGI server is used it's important to not + iterate over it from inside the application but to pass it through + unchanged. If you want to pass out a file wrapper inside a response + object you have to set :attr:`~BaseResponse.direct_passthrough` to `True`. + + More information about file wrappers are available in :pep:`333`. + + :param file: a :class:`file`-like object with a :meth:`~file.read` method. + :param buffer_size: number of bytes for one iteration. + """ + return environ.get('wsgi.file_wrapper', FileWrapper)(file, buffer_size) + + +@implements_iterator +class FileWrapper(object): + + """This class can be used to convert a :class:`file`-like object into + an iterable. It yields `buffer_size` blocks until the file is fully + read. + + You should not use this class directly but rather use the + :func:`wrap_file` function that uses the WSGI server's file wrapper + support if it's available. + + .. versionadded:: 0.5 + + If you're using this object together with a :class:`BaseResponse` you have + to use the `direct_passthrough` mode. + + :param file: a :class:`file`-like object with a :meth:`~file.read` method. + :param buffer_size: number of bytes for one iteration. + """ + + def __init__(self, file, buffer_size=8192): + self.file = file + self.buffer_size = buffer_size + + def close(self): + if hasattr(self.file, 'close'): + self.file.close() + + def seekable(self): + if hasattr(self.file, 'seekable'): + return self.file.seekable() + if hasattr(self.file, 'seek'): + return True + return False + + def seek(self, *args): + if hasattr(self.file, 'seek'): + self.file.seek(*args) + + def tell(self): + if hasattr(self.file, 'tell'): + return self.file.tell() + return None + + def __iter__(self): + return self + + def __next__(self): + data = self.file.read(self.buffer_size) + if data: + return data + raise StopIteration() + + +@implements_iterator +class _RangeWrapper(object): + # private for now, but should we make it public in the future ? + + """This class can be used to convert an iterable object into + an iterable that will only yield a piece of the underlying content. + It yields blocks until the underlying stream range is fully read. + The yielded blocks will have a size that can't exceed the original + iterator defined block size, but that can be smaller. + + If you're using this object together with a :class:`BaseResponse` you have + to use the `direct_passthrough` mode. + + :param iterable: an iterable object with a :meth:`__next__` method. + :param start_byte: byte from which read will start. + :param byte_range: how many bytes to read. + """ + + def __init__(self, iterable, start_byte=0, byte_range=None): + self.iterable = iter(iterable) + self.byte_range = byte_range + self.start_byte = start_byte + self.end_byte = None + if byte_range is not None: + self.end_byte = self.start_byte + self.byte_range + self.read_length = 0 + self.seekable = hasattr(iterable, 'seekable') and iterable.seekable() + self.end_reached = False + + def __iter__(self): + return self + + def _next_chunk(self): + try: + chunk = next(self.iterable) + self.read_length += len(chunk) + return chunk + except StopIteration: + self.end_reached = True + raise + + def _first_iteration(self): + chunk = None + if self.seekable: + self.iterable.seek(self.start_byte) + self.read_length = self.iterable.tell() + contextual_read_length = self.read_length + else: + while self.read_length <= self.start_byte: + chunk = self._next_chunk() + if chunk is not None: + chunk = chunk[self.start_byte - self.read_length:] + contextual_read_length = self.start_byte + return chunk, contextual_read_length + + def _next(self): + if self.end_reached: + raise StopIteration() + chunk = None + contextual_read_length = self.read_length + if self.read_length == 0: + chunk, contextual_read_length = self._first_iteration() + if chunk is None: + chunk = self._next_chunk() + if self.end_byte is not None and self.read_length >= self.end_byte: + self.end_reached = True + return chunk[:self.end_byte - contextual_read_length] + return chunk + + def __next__(self): + chunk = self._next() + if chunk: + return chunk + self.end_reached = True + raise StopIteration() + + def close(self): + if hasattr(self.iterable, 'close'): + self.iterable.close() + + +def _make_chunk_iter(stream, limit, buffer_size): + """Helper for the line and chunk iter functions.""" + if isinstance(stream, (bytes, bytearray, text_type)): + raise TypeError('Passed a string or byte object instead of ' + 'true iterator or stream.') + if not hasattr(stream, 'read'): + for item in stream: + if item: + yield item + return + if not isinstance(stream, LimitedStream) and limit is not None: + stream = LimitedStream(stream, limit) + _read = stream.read + while 1: + item = _read(buffer_size) + if not item: + break + yield item + + +def make_line_iter(stream, limit=None, buffer_size=10 * 1024, + cap_at_buffer=False): + """Safely iterates line-based over an input stream. If the input stream + is not a :class:`LimitedStream` the `limit` parameter is mandatory. + + This uses the stream's :meth:`~file.read` method internally as opposite + to the :meth:`~file.readline` method that is unsafe and can only be used + in violation of the WSGI specification. The same problem applies to the + `__iter__` function of the input stream which calls :meth:`~file.readline` + without arguments. + + If you need line-by-line processing it's strongly recommended to iterate + over the input stream using this helper function. + + .. versionchanged:: 0.8 + This function now ensures that the limit was reached. + + .. versionadded:: 0.9 + added support for iterators as input stream. + + .. versionadded:: 0.11.10 + added support for the `cap_at_buffer` parameter. + + :param stream: the stream or iterate to iterate over. + :param limit: the limit in bytes for the stream. (Usually + content length. Not necessary if the `stream` + is a :class:`LimitedStream`. + :param buffer_size: The optional buffer size. + :param cap_at_buffer: if this is set chunks are split if they are longer + than the buffer size. Internally this is implemented + that the buffer size might be exhausted by a factor + of two however. + """ + _iter = _make_chunk_iter(stream, limit, buffer_size) + + first_item = next(_iter, '') + if not first_item: + return + + s = make_literal_wrapper(first_item) + empty = s('') + cr = s('\r') + lf = s('\n') + crlf = s('\r\n') + + _iter = chain((first_item,), _iter) + + def _iter_basic_lines(): + _join = empty.join + buffer = [] + while 1: + new_data = next(_iter, '') + if not new_data: + break + new_buf = [] + buf_size = 0 + for item in chain(buffer, new_data.splitlines(True)): + new_buf.append(item) + buf_size += len(item) + if item and item[-1:] in crlf: + yield _join(new_buf) + new_buf = [] + elif cap_at_buffer and buf_size >= buffer_size: + rv = _join(new_buf) + while len(rv) >= buffer_size: + yield rv[:buffer_size] + rv = rv[buffer_size:] + new_buf = [rv] + buffer = new_buf + if buffer: + yield _join(buffer) + + # This hackery is necessary to merge 'foo\r' and '\n' into one item + # of 'foo\r\n' if we were unlucky and we hit a chunk boundary. + previous = empty + for item in _iter_basic_lines(): + if item == lf and previous[-1:] == cr: + previous += item + item = empty + if previous: + yield previous + previous = item + if previous: + yield previous + + +def make_chunk_iter(stream, separator, limit=None, buffer_size=10 * 1024, + cap_at_buffer=False): + """Works like :func:`make_line_iter` but accepts a separator + which divides chunks. If you want newline based processing + you should use :func:`make_line_iter` instead as it + supports arbitrary newline markers. + + .. versionadded:: 0.8 + + .. versionadded:: 0.9 + added support for iterators as input stream. + + .. versionadded:: 0.11.10 + added support for the `cap_at_buffer` parameter. + + :param stream: the stream or iterate to iterate over. + :param separator: the separator that divides chunks. + :param limit: the limit in bytes for the stream. (Usually + content length. Not necessary if the `stream` + is otherwise already limited). + :param buffer_size: The optional buffer size. + :param cap_at_buffer: if this is set chunks are split if they are longer + than the buffer size. Internally this is implemented + that the buffer size might be exhausted by a factor + of two however. + """ + _iter = _make_chunk_iter(stream, limit, buffer_size) + + first_item = next(_iter, '') + if not first_item: + return + + _iter = chain((first_item,), _iter) + if isinstance(first_item, text_type): + separator = to_unicode(separator) + _split = re.compile(r'(%s)' % re.escape(separator)).split + _join = u''.join + else: + separator = to_bytes(separator) + _split = re.compile(b'(' + re.escape(separator) + b')').split + _join = b''.join + + buffer = [] + while 1: + new_data = next(_iter, '') + if not new_data: + break + chunks = _split(new_data) + new_buf = [] + buf_size = 0 + for item in chain(buffer, chunks): + if item == separator: + yield _join(new_buf) + new_buf = [] + buf_size = 0 + else: + buf_size += len(item) + new_buf.append(item) + + if cap_at_buffer and buf_size >= buffer_size: + rv = _join(new_buf) + while len(rv) >= buffer_size: + yield rv[:buffer_size] + rv = rv[buffer_size:] + new_buf = [rv] + buf_size = len(rv) + + buffer = new_buf + if buffer: + yield _join(buffer) + + +@implements_iterator +class LimitedStream(io.IOBase): + + """Wraps a stream so that it doesn't read more than n bytes. If the + stream is exhausted and the caller tries to get more bytes from it + :func:`on_exhausted` is called which by default returns an empty + string. The return value of that function is forwarded + to the reader function. So if it returns an empty string + :meth:`read` will return an empty string as well. + + The limit however must never be higher than what the stream can + output. Otherwise :meth:`readlines` will try to read past the + limit. + + .. admonition:: Note on WSGI compliance + + calls to :meth:`readline` and :meth:`readlines` are not + WSGI compliant because it passes a size argument to the + readline methods. Unfortunately the WSGI PEP is not safely + implementable without a size argument to :meth:`readline` + because there is no EOF marker in the stream. As a result + of that the use of :meth:`readline` is discouraged. + + For the same reason iterating over the :class:`LimitedStream` + is not portable. It internally calls :meth:`readline`. + + We strongly suggest using :meth:`read` only or using the + :func:`make_line_iter` which safely iterates line-based + over a WSGI input stream. + + :param stream: the stream to wrap. + :param limit: the limit for the stream, must not be longer than + what the string can provide if the stream does not + end with `EOF` (like `wsgi.input`) + """ + + def __init__(self, stream, limit): + self._read = stream.read + self._readline = stream.readline + self._pos = 0 + self.limit = limit + + def __iter__(self): + return self + + @property + def is_exhausted(self): + """If the stream is exhausted this attribute is `True`.""" + return self._pos >= self.limit + + def on_exhausted(self): + """This is called when the stream tries to read past the limit. + The return value of this function is returned from the reading + function. + """ + # Read null bytes from the stream so that we get the + # correct end of stream marker. + return self._read(0) + + def on_disconnect(self): + """What should happen if a disconnect is detected? The return + value of this function is returned from read functions in case + the client went away. By default a + :exc:`~werkzeug.exceptions.ClientDisconnected` exception is raised. + """ + from werkzeug.exceptions import ClientDisconnected + raise ClientDisconnected() + + def exhaust(self, chunk_size=1024 * 64): + """Exhaust the stream. This consumes all the data left until the + limit is reached. + + :param chunk_size: the size for a chunk. It will read the chunk + until the stream is exhausted and throw away + the results. + """ + to_read = self.limit - self._pos + chunk = chunk_size + while to_read > 0: + chunk = min(to_read, chunk) + self.read(chunk) + to_read -= chunk + + def read(self, size=None): + """Read `size` bytes or if size is not provided everything is read. + + :param size: the number of bytes read. + """ + if self._pos >= self.limit: + return self.on_exhausted() + if size is None or size == -1: # -1 is for consistence with file + size = self.limit + to_read = min(self.limit - self._pos, size) + try: + read = self._read(to_read) + except (IOError, ValueError): + return self.on_disconnect() + if to_read and len(read) != to_read: + return self.on_disconnect() + self._pos += len(read) + return read + + def readline(self, size=None): + """Reads one line from the stream.""" + if self._pos >= self.limit: + return self.on_exhausted() + if size is None: + size = self.limit - self._pos + else: + size = min(size, self.limit - self._pos) + try: + line = self._readline(size) + except (ValueError, IOError): + return self.on_disconnect() + if size and not line: + return self.on_disconnect() + self._pos += len(line) + return line + + def readlines(self, size=None): + """Reads a file into a list of strings. It calls :meth:`readline` + until the file is read to the end. It does support the optional + `size` argument if the underlaying stream supports it for + `readline`. + """ + last_pos = self._pos + result = [] + if size is not None: + end = min(self.limit, last_pos + size) + else: + end = self.limit + while 1: + if size is not None: + size -= last_pos - self._pos + if self._pos >= end: + break + result.append(self.readline(size)) + if size is not None: + last_pos = self._pos + return result + + def tell(self): + """Returns the position of the stream. + + .. versionadded:: 0.9 + """ + return self._pos + + def __next__(self): + line = self.readline() + if not line: + raise StopIteration() + return line + + def readable(self): + return True diff --git a/requirements_openpilot.txt b/requirements_openpilot.txt new file mode 100644 index 00000000000000..2e892560fffb6d --- /dev/null +++ b/requirements_openpilot.txt @@ -0,0 +1,66 @@ +# This are the packages installed on the EON +-e git+https://github.com/commaai/le_python.git@5eef8f5be5929d33973e1b10e686fa0cdcd6792f#egg=Logentries +-e git+https://github.com/commaai/python-overpy.git@f86529af402d4642e1faeb146671c40284007323#egg=overpy +Cython==0.27.3 +Flask==1.0.2 +#PyGObject==3.28.2 This is installed on the EON, but requires a ton of dependencies to install +PyYAML==3.12 +appdirs==1.4.0 +atomicwrites==1.1.5 +attrs==16.0.0 +bitstring==3.1.5 +capnpy==0.4.2 +certifi==2016.8.31 +cffi==1.11.5 +contextlib2==0.5.4 +crc16==0.1.1 +crcmod==1.7 +cryptography==1.4 +cycler==0.10.0 +decorator==4.0.10 +docopt==0.6.2 +enum34==1.1.6 +evdev==0.6.1 +fastcluster==1.1.20 +filterpy==1.2.4 +ipaddress==1.0.16 +libusb1==1.5.0 +lmdb==0.92 +mpmath==1.0.0 +nose==1.3.7 +numpy==1.11.1 +pause==0.1.2 +py==1.4.31 +pyOpenSSL==16.0.0 +pyasn1-modules==0.0.8 +pyasn1==0.1.9 +pycapnp==0.6.3 +pycparser==2.18 +pycrypto==2.6.1 +pyflakes==1.6.0 +pyopencl==2016.1 +pyparsing==2.1.10 +#pypcap==1.1.5 needs extra dependencies and is not used +pyproj==1.9.5.1 +pypytools==0.4.3 +pyserial==3.1.1 +pytest==2.9.2 +python-dateutil==2.6.0 +pytools==2016.2.1 +pytz==2016.10 +pyyaml==3.12 +pyzmq==15.4.0 +raven==5.23.0 +recordclass==0.4.1 +requests==2.10.0 +scipy==0.19.1 +service-identity==16.0.0 +setproctitle==1.1.10 +simplejson==3.8.2 +six==1.10.0 +smbus-cffi==0.5.1 +smbus2==0.2.0 +sympy==1.1.1 +tqdm==4.23.1 +ujson==1.35 +v4l2==0.2 diff --git a/run_docker_tests.sh b/run_docker_tests.sh new file mode 100755 index 00000000000000..a153aac73b53c5 --- /dev/null +++ b/run_docker_tests.sh @@ -0,0 +1,8 @@ +#!/bin/bash +set -e + +docker build -t tmppilot -f Dockerfile.openpilot . + +docker run --rm \ + -v "$(pwd)"/selfdrive/test/tests/plant/out:/tmp/openpilot/selfdrive/test/tests/plant/out \ + tmppilot /bin/sh -c 'cd /tmp/openpilot/selfdrive/test/tests/plant && OPTEST=1 ./test_longitudinal.py' diff --git a/selfdrive/__init__.py b/selfdrive/__init__.py new file mode 100644 index 00000000000000..e69de29bb2d1d6 diff --git a/selfdrive/assets/OpenSans-Bold.ttf b/selfdrive/assets/OpenSans-Bold.ttf new file mode 100644 index 00000000000000..7b529456032abf Binary files /dev/null and b/selfdrive/assets/OpenSans-Bold.ttf differ diff --git a/selfdrive/assets/OpenSans-Regular.ttf b/selfdrive/assets/OpenSans-Regular.ttf new file mode 100644 index 00000000000000..2e31d02424ed50 Binary files /dev/null and b/selfdrive/assets/OpenSans-Regular.ttf differ diff --git a/selfdrive/assets/OpenSans-SemiBold.ttf b/selfdrive/assets/OpenSans-SemiBold.ttf new file mode 100644 index 00000000000000..99db86aa0282e4 Binary files /dev/null and b/selfdrive/assets/OpenSans-SemiBold.ttf differ diff --git a/selfdrive/assets/Roboto-Bold.ttf b/selfdrive/assets/Roboto-Bold.ttf new file mode 100644 index 00000000000000..a355c27cde02b1 Binary files /dev/null and b/selfdrive/assets/Roboto-Bold.ttf differ diff --git a/selfdrive/assets/courbd.ttf b/selfdrive/assets/courbd.ttf new file mode 100644 index 00000000000000..a4f26b4b5e15c2 Binary files /dev/null and b/selfdrive/assets/courbd.ttf differ diff --git a/selfdrive/assets/img_chffr_wheel.png b/selfdrive/assets/img_chffr_wheel.png new file mode 100644 index 00000000000000..3f09a35a79bf45 Binary files /dev/null and b/selfdrive/assets/img_chffr_wheel.png differ diff --git a/selfdrive/assets/img_driver_face.png b/selfdrive/assets/img_driver_face.png new file mode 100644 index 00000000000000..ddde478cd789ec Binary files /dev/null and b/selfdrive/assets/img_driver_face.png differ diff --git a/selfdrive/assets/img_map.png b/selfdrive/assets/img_map.png new file mode 100644 index 00000000000000..8bdae4d7d81e0b Binary files /dev/null and b/selfdrive/assets/img_map.png differ diff --git a/selfdrive/assets/img_spinner_comma.png b/selfdrive/assets/img_spinner_comma.png new file mode 100644 index 00000000000000..16109557f85911 Binary files /dev/null and b/selfdrive/assets/img_spinner_comma.png differ diff --git a/selfdrive/assets/img_spinner_track.png b/selfdrive/assets/img_spinner_track.png new file mode 100644 index 00000000000000..931c17e8367cef Binary files /dev/null and b/selfdrive/assets/img_spinner_track.png differ diff --git a/selfdrive/assets/img_trafficLight_green.png b/selfdrive/assets/img_trafficLight_green.png new file mode 100644 index 00000000000000..b2e07dab0323cc Binary files /dev/null and b/selfdrive/assets/img_trafficLight_green.png differ diff --git a/selfdrive/assets/img_trafficLight_none.png b/selfdrive/assets/img_trafficLight_none.png new file mode 100644 index 00000000000000..01deb5a009980a Binary files /dev/null and b/selfdrive/assets/img_trafficLight_none.png differ diff --git a/selfdrive/assets/img_trafficLight_red.png b/selfdrive/assets/img_trafficLight_red.png new file mode 100644 index 00000000000000..4c440250e4e1c7 Binary files /dev/null and b/selfdrive/assets/img_trafficLight_red.png differ diff --git a/selfdrive/assets/img_trafficLight_yellow.png b/selfdrive/assets/img_trafficLight_yellow.png new file mode 100644 index 00000000000000..8dd5bd42c37a33 Binary files /dev/null and b/selfdrive/assets/img_trafficLight_yellow.png differ diff --git a/selfdrive/assets/img_trafficSign_stop.png b/selfdrive/assets/img_trafficSign_stop.png new file mode 100644 index 00000000000000..9261c47472e9a5 Binary files /dev/null and b/selfdrive/assets/img_trafficSign_stop.png differ diff --git a/selfdrive/assets/img_trafficSign_turn.png b/selfdrive/assets/img_trafficSign_turn.png new file mode 100644 index 00000000000000..c304d1bf2c8e53 Binary files /dev/null and b/selfdrive/assets/img_trafficSign_turn.png differ diff --git a/selfdrive/assets/sounds/disengaged.wav b/selfdrive/assets/sounds/disengaged.wav new file mode 100644 index 00000000000000..958e08fd85b3e6 Binary files /dev/null and b/selfdrive/assets/sounds/disengaged.wav differ diff --git a/selfdrive/assets/sounds/engaged.wav b/selfdrive/assets/sounds/engaged.wav new file mode 100644 index 00000000000000..c6c088e01c8b73 Binary files /dev/null and b/selfdrive/assets/sounds/engaged.wav differ diff --git a/selfdrive/assets/sounds/error.wav b/selfdrive/assets/sounds/error.wav new file mode 100644 index 00000000000000..1ff0c540d26ab0 Binary files /dev/null and b/selfdrive/assets/sounds/error.wav differ diff --git a/selfdrive/assets/sounds/warning_1.wav b/selfdrive/assets/sounds/warning_1.wav new file mode 100644 index 00000000000000..67b8d76fe804fa Binary files /dev/null and b/selfdrive/assets/sounds/warning_1.wav differ diff --git a/selfdrive/assets/sounds/warning_2.wav b/selfdrive/assets/sounds/warning_2.wav new file mode 100644 index 00000000000000..8e1b1d7d9161a7 Binary files /dev/null and b/selfdrive/assets/sounds/warning_2.wav differ diff --git a/selfdrive/boardd/.gitignore b/selfdrive/boardd/.gitignore new file mode 100644 index 00000000000000..b030dc97cdec07 --- /dev/null +++ b/selfdrive/boardd/.gitignore @@ -0,0 +1 @@ +boardd diff --git a/selfdrive/boardd/Makefile b/selfdrive/boardd/Makefile new file mode 100644 index 00000000000000..893edde545b848 --- /dev/null +++ b/selfdrive/boardd/Makefile @@ -0,0 +1,88 @@ +CC = clang +CXX = clang++ + +ARCH := $(shell uname -m) +OS := $(shell uname -o) + +BASEDIR = ../.. +PHONELIBS = ../../phonelibs + +WARN_FLAGS = -Werror=implicit-function-declaration \ + -Werror=incompatible-pointer-types \ + -Werror=int-conversion \ + -Werror=return-type \ + -Werror=format-extra-args + +CFLAGS = -std=gnu11 -g -fPIC -I../ -I../../ -O2 $(WARN_FLAGS) +CXXFLAGS = -std=c++11 -g -fPIC -I../ -I../../ -O2 $(WARN_FLAGS) + +ZMQ_FLAGS = -I$(PHONELIBS)/zmq/aarch64/include +ZMQ_LIBS = -L$(PHONELIBS)/zmq/aarch64/lib \ + -l:libczmq.a -l:libzmq.a \ + -lgnustl_shared + +JSON_FLAGS = -I$(PHONELIBS)/json/src + +EXTRA_LIBS = -lusb + +# ifeq ($(OS),GNU/Linux) +# # for Drive PX2 +# ZMQ_LIBS = -lczmq -lzmq +# CEREAL_LIBS = -lcapnp -lkj -lcapnp_c +# EXTRA_LIBS = -lusb-1.0 -lpthread +# endif + +ifeq ($(ARCH),x86_64) +ZMQ_LIBS = -L$(BASEDIR)/external/zmq/lib/ \ + -l:libczmq.a -l:libzmq.a +EXTRA_LIBS = -lusb-1.0 -lpthread +CXXFLAGS += -I/usr/include/libusb-1.0 +CFLAGS += -I/usr/include/libusb-1.0 +endif + +.PHONY: all +all: boardd + +include ../common/cereal.mk + +OBJS = boardd.o \ + ../common/swaglog.o \ + ../common/params.o \ + ../common/util.o \ + $(PHONELIBS)/json/src/json.o \ + $(CEREAL_OBJS) + +DEPS := $(OBJS:.o=.d) + +boardd: $(OBJS) + @echo "[ LINK ] $@" + $(CXX) -fPIC -o '$@' $^ \ + $(CEREAL_LIBS) \ + $(ZMQ_LIBS) \ + $(EXTRA_LIBS) + +boardd.o: boardd.cc + @echo "[ CXX ] $@" + $(CXX) $(CXXFLAGS) \ + -I$(PHONELIBS)/android_system_core/include \ + $(CEREAL_CFLAGS) \ + $(CEREAL_CXXFLAGS) \ + $(ZMQ_FLAGS) \ + -I../ \ + -I../../ \ + -c -o '$@' '$<' + +%.o: %.c + @echo "[ CC ] $@" + $(CC) $(CFLAGS) -MMD \ + -Iinclude -I.. -I../.. \ + $(CEREAL_CFLAGS) \ + $(ZMQ_FLAGS) \ + $(JSON_FLAGS) \ + -c -o '$@' '$<' + +.PHONY: clean +clean: + rm -f boardd $(OBJS) $(DEPS) + +-include $(DEPS) diff --git a/selfdrive/boardd/__init__.py b/selfdrive/boardd/__init__.py new file mode 100644 index 00000000000000..e69de29bb2d1d6 diff --git a/selfdrive/boardd/boardd.cc b/selfdrive/boardd/boardd.cc new file mode 100644 index 00000000000000..74b1f4c5de9616 --- /dev/null +++ b/selfdrive/boardd/boardd.cc @@ -0,0 +1,704 @@ +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include + +#include +#include + +#include +#include "cereal/gen/cpp/log.capnp.h" +#include "cereal/gen/cpp/car.capnp.h" + +#include "common/params.h" +#include "common/swaglog.h" +#include "common/timing.h" + +#include + +// double the FIFO size +#define RECV_SIZE (0x1000) +#define TIMEOUT 0 + +#define SAFETY_NOOUTPUT 0 +#define SAFETY_HONDA 1 +#define SAFETY_TOYOTA 2 +#define SAFETY_ELM327 0xE327 +#define SAFETY_GM 3 +#define SAFETY_HONDA_BOSCH 4 +#define SAFETY_FORD 5 +#define SAFETY_CADILLAC 6 +#define SAFETY_HYUNDAI 7 +#define SAFETY_TESLA 8 +#define SAFETY_CHRYSLER 9 +#define SAFETY_TOYOTA_IPAS 0x1335 +#define SAFETY_TOYOTA_NOLIMITS 0x1336 +#define SAFETY_ALLOUTPUT 0x1337 +#define SAFETY_ELM327 0xE327 + +namespace { + +volatile int do_exit = 0; + +libusb_context *ctx = NULL; +libusb_device_handle *dev_handle; +pthread_mutex_t usb_lock; + +bool spoofing_started = false; +bool fake_send = false; +bool loopback_can = false; +bool is_grey_panda = false; + +pthread_t safety_setter_thread_handle = -1; +pthread_t pigeon_thread_handle = -1; +bool pigeon_needs_init; + +void pigeon_init(); +void *pigeon_thread(void *crap); + +void *safety_setter_thread(void *s) { + char *value; + size_t value_sz = 0; + + LOGW("waiting for params to set safety model"); + while (1) { + if (do_exit) return NULL; + + const int result = read_db_value(NULL, "CarParams", &value, &value_sz); + if (value_sz > 0) break; + usleep(100*1000); + } + LOGW("got %d bytes CarParams", value_sz); + + // format for board, make copy due to alignment issues, will be freed on out of scope + auto amsg = kj::heapArray((value_sz / sizeof(capnp::word)) + 1); + memcpy(amsg.begin(), value, value_sz); + + capnp::FlatArrayMessageReader cmsg(amsg); + cereal::CarParams::Reader car_params = cmsg.getRoot(); + + auto safety_model = car_params.getSafetyModel(); + auto safety_param = car_params.getSafetyParam(); + LOGW("setting safety model: %d with param %d", safety_model, safety_param); + + int safety_setting = 0; + switch (safety_model) { + case (int)cereal::CarParams::SafetyModels::NO_OUTPUT: + safety_setting = SAFETY_NOOUTPUT; + break; + case (int)cereal::CarParams::SafetyModels::HONDA: + safety_setting = SAFETY_HONDA; + break; + case (int)cereal::CarParams::SafetyModels::TOYOTA: + safety_setting = SAFETY_TOYOTA; + break; + case (int)cereal::CarParams::SafetyModels::ELM327: + safety_setting = SAFETY_ELM327; + break; + case (int)cereal::CarParams::SafetyModels::GM: + safety_setting = SAFETY_GM; + break; + case (int)cereal::CarParams::SafetyModels::HONDA_BOSCH: + safety_setting = SAFETY_HONDA_BOSCH; + break; + case (int)cereal::CarParams::SafetyModels::FORD: + safety_setting = SAFETY_FORD; + break; + case (int)cereal::CarParams::SafetyModels::CADILLAC: + safety_setting = SAFETY_CADILLAC; + break; + case (int)cereal::CarParams::SafetyModels::HYUNDAI: + safety_setting = SAFETY_HYUNDAI; + break; + case (int)cereal::CarParams::SafetyModels::CHRYSLER: + safety_setting = SAFETY_CHRYSLER; + break; + default: + LOGE("unknown safety model: %d", safety_model); + } + + pthread_mutex_lock(&usb_lock); + + // set in the mutex to avoid race + safety_setter_thread_handle = -1; + + libusb_control_transfer(dev_handle, 0x40, 0xdc, safety_setting, safety_param, NULL, 0, TIMEOUT); + + pthread_mutex_unlock(&usb_lock); + + return NULL; +} + +// must be called before threads or with mutex +bool usb_connect() { + int err; + unsigned char is_pigeon[1] = {0}; + + dev_handle = libusb_open_device_with_vid_pid(ctx, 0xbbaa, 0xddcc); + if (dev_handle == NULL) { goto fail; } + + err = libusb_set_configuration(dev_handle, 1); + if (err != 0) { goto fail; } + + err = libusb_claim_interface(dev_handle, 0); + if (err != 0) { goto fail; } + + if (loopback_can) { + libusb_control_transfer(dev_handle, 0xc0, 0xe5, 1, 0, NULL, 0, TIMEOUT); + } + + // power off ESP + libusb_control_transfer(dev_handle, 0xc0, 0xd9, 0, 0, NULL, 0, TIMEOUT); + + // power on charging (may trigger a reconnection, should be okay) + #ifndef __x86_64__ + libusb_control_transfer(dev_handle, 0xc0, 0xe6, 1, 0, NULL, 0, TIMEOUT); + #else + LOGW("not enabling charging on x86_64"); + #endif + + // no output is the default + if (getenv("RECVMOCK")) { + libusb_control_transfer(dev_handle, 0x40, 0xdc, SAFETY_ELM327, 0, NULL, 0, TIMEOUT); + } else { + libusb_control_transfer(dev_handle, 0x40, 0xdc, SAFETY_NOOUTPUT, 0, NULL, 0, TIMEOUT); + } + + if (safety_setter_thread_handle == -1) { + err = pthread_create(&safety_setter_thread_handle, NULL, safety_setter_thread, NULL); + assert(err == 0); + } + + libusb_control_transfer(dev_handle, 0xc0, 0xc1, 0, 0, is_pigeon, 1, TIMEOUT); + + if (is_pigeon[0]) { + LOGW("grey panda detected"); + is_grey_panda = true; + pigeon_needs_init = true; + if (pigeon_thread_handle == -1) { + err = pthread_create(&pigeon_thread_handle, NULL, pigeon_thread, NULL); + assert(err == 0); + } + } + + return true; +fail: + return false; +} + +void usb_retry_connect() { + LOG("attempting to connect"); + while (!usb_connect()) { usleep(100*1000); } + LOGW("connected to board"); +} + +void handle_usb_issue(int err, const char func[]) { + LOGE_100("usb error %d \"%s\" in %s", err, libusb_strerror((enum libusb_error)err), func); + if (err == -4) { + LOGE("lost connection"); + usb_retry_connect(); + } + // TODO: check other errors, is simply retrying okay? +} + +void can_recv(void *s) { + int err; + uint32_t data[RECV_SIZE/4]; + int recv; + uint32_t f1, f2; + + // do recv + pthread_mutex_lock(&usb_lock); + + do { + err = libusb_bulk_transfer(dev_handle, 0x81, (uint8_t*)data, RECV_SIZE, &recv, TIMEOUT); + if (err != 0) { handle_usb_issue(err, __func__); } + if (err == -8) { LOGE_100("overflow got 0x%x", recv); }; + + // timeout is okay to exit, recv still happened + if (err == -7) { break; } + } while(err != 0); + + pthread_mutex_unlock(&usb_lock); + + // return if length is 0 + if (recv <= 0) { + return; + } + + // create message + capnp::MallocMessageBuilder msg; + cereal::Event::Builder event = msg.initRoot(); + event.setLogMonoTime(nanos_since_boot()); + + auto canData = event.initCan(recv/0x10); + + // populate message + for (int i = 0; i<(recv/0x10); i++) { + if (data[i*4] & 4) { + // extended + canData[i].setAddress(data[i*4] >> 3); + //printf("got extended: %x\n", data[i*4] >> 3); + } else { + // normal + canData[i].setAddress(data[i*4] >> 21); + } + canData[i].setBusTime(data[i*4+1] >> 16); + int len = data[i*4+1]&0xF; + canData[i].setDat(kj::arrayPtr((uint8_t*)&data[i*4+2], len)); + canData[i].setSrc((data[i*4+1] >> 4) & 0xff); + } + + // send to can + auto words = capnp::messageToFlatArray(msg); + auto bytes = words.asBytes(); + zmq_send(s, bytes.begin(), bytes.size(), 0); +} + +void can_health(void *s) { + int cnt; + + // copied from board/main.c + struct __attribute__((packed)) health { + uint32_t voltage; + uint32_t current; + uint8_t started; + uint8_t controls_allowed; + uint8_t gas_interceptor_detected; + uint8_t started_signal_detected; + uint8_t started_alt; + } health; + + // recv from board + pthread_mutex_lock(&usb_lock); + + do { + cnt = libusb_control_transfer(dev_handle, 0xc0, 0xd2, 0, 0, (unsigned char*)&health, sizeof(health), TIMEOUT); + if (cnt != sizeof(health)) { handle_usb_issue(cnt, __func__); } + } while(cnt != sizeof(health)); + + pthread_mutex_unlock(&usb_lock); + + // create message + capnp::MallocMessageBuilder msg; + cereal::Event::Builder event = msg.initRoot(); + event.setLogMonoTime(nanos_since_boot()); + auto healthData = event.initHealth(); + + // set fields + healthData.setVoltage(health.voltage); + healthData.setCurrent(health.current); + if (spoofing_started) { + healthData.setStarted(1); + } else { + healthData.setStarted(health.started); + } + healthData.setControlsAllowed(health.controls_allowed); + healthData.setGasInterceptorDetected(health.gas_interceptor_detected); + healthData.setStartedSignalDetected(health.started_signal_detected); + healthData.setIsGreyPanda(is_grey_panda); + + // send to health + auto words = capnp::messageToFlatArray(msg); + auto bytes = words.asBytes(); + zmq_send(s, bytes.begin(), bytes.size(), 0); +} + + +void can_send(void *s) { + int err; + + // recv from sendcan + zmq_msg_t msg; + zmq_msg_init(&msg); + err = zmq_msg_recv(&msg, s, 0); + assert(err >= 0); + + // format for board, make copy due to alignment issues, will be freed on out of scope + auto amsg = kj::heapArray((zmq_msg_size(&msg) / sizeof(capnp::word)) + 1); + memcpy(amsg.begin(), zmq_msg_data(&msg), zmq_msg_size(&msg)); + + capnp::FlatArrayMessageReader cmsg(amsg); + cereal::Event::Reader event = cmsg.getRoot(); + int msg_count = event.getCan().size(); + + uint32_t *send = (uint32_t*)malloc(msg_count*0x10); + memset(send, 0, msg_count*0x10); + + for (int i = 0; i < msg_count; i++) { + auto cmsg = event.getSendcan()[i]; + if (cmsg.getAddress() >= 0x800) { + // extended + send[i*4] = (cmsg.getAddress() << 3) | 5; + } else { + // normal + send[i*4] = (cmsg.getAddress() << 21) | 1; + } + assert(cmsg.getDat().size() <= 8); + send[i*4+1] = cmsg.getDat().size() | (cmsg.getSrc() << 4); + memcpy(&send[i*4+2], cmsg.getDat().begin(), cmsg.getDat().size()); + } + + // release msg + zmq_msg_close(&msg); + + // send to board + int sent; + pthread_mutex_lock(&usb_lock); + + if (!fake_send) { + do { + err = libusb_bulk_transfer(dev_handle, 3, (uint8_t*)send, msg_count*0x10, &sent, TIMEOUT); + if (err != 0 || msg_count*0x10 != sent) { handle_usb_issue(err, __func__); } + } while(err != 0); + } + + pthread_mutex_unlock(&usb_lock); + + // done + free(send); +} + + +// **** threads **** + +void *thermal_thread(void *crap) { + int err; + LOGD("start thermal thread"); + + // thermal = 8005 + void *context = zmq_ctx_new(); + void *subscriber = zmq_socket(context, ZMQ_SUB); + zmq_setsockopt(subscriber, ZMQ_SUBSCRIBE, "", 0); + zmq_connect(subscriber, "tcp://127.0.0.1:8005"); + + // run as fast as messages come in + while (!do_exit) { + // recv from thermal + zmq_msg_t msg; + zmq_msg_init(&msg); + err = zmq_msg_recv(&msg, subscriber, 0); + assert(err >= 0); + + // format for board, make copy due to alignment issues, will be freed on out of scope + // copied from send thread... + auto amsg = kj::heapArray((zmq_msg_size(&msg) / sizeof(capnp::word)) + 1); + memcpy(amsg.begin(), zmq_msg_data(&msg), zmq_msg_size(&msg)); + + capnp::FlatArrayMessageReader cmsg(amsg); + cereal::Event::Reader event = cmsg.getRoot(); + + uint16_t target_fan_speed = event.getThermal().getFanSpeed(); + //LOGW("setting fan speed %d", target_fan_speed); + + pthread_mutex_lock(&usb_lock); + libusb_control_transfer(dev_handle, 0xc0, 0xd3, target_fan_speed, 0, NULL, 0, TIMEOUT); + pthread_mutex_unlock(&usb_lock); + + zmq_msg_close(&msg); + } + + // turn the fan off when we exit + libusb_control_transfer(dev_handle, 0xc0, 0xd3, 0, 0, NULL, 0, TIMEOUT); + + return NULL; +} + +void *can_send_thread(void *crap) { + LOGD("start send thread"); + + // sendcan = 8017 + void *context = zmq_ctx_new(); + void *subscriber = zmq_socket(context, ZMQ_SUB); + zmq_setsockopt(subscriber, ZMQ_SUBSCRIBE, "", 0); + zmq_connect(subscriber, "tcp://127.0.0.1:8017"); + + // drain sendcan to delete any stale messages from previous runs + zmq_msg_t msg; + zmq_msg_init(&msg); + int err = 0; + while(err >= 0) { + err = zmq_msg_recv(&msg, subscriber, ZMQ_DONTWAIT); + } + + // run as fast as messages come in + while (!do_exit) { + can_send(subscriber); + } + return NULL; +} + +void *can_recv_thread(void *crap) { + LOGD("start recv thread"); + + // can = 8006 + void *context = zmq_ctx_new(); + void *publisher = zmq_socket(context, ZMQ_PUB); + zmq_bind(publisher, "tcp://*:8006"); + + // run at ~200hz + while (!do_exit) { + can_recv(publisher); + // 5ms + usleep(5*1000); + } + return NULL; +} + +void *can_health_thread(void *crap) { + LOGD("start health thread"); + + // health = 8011 + void *context = zmq_ctx_new(); + void *publisher = zmq_socket(context, ZMQ_PUB); + zmq_bind(publisher, "tcp://*:8011"); + + // run at 1hz + while (!do_exit) { + can_health(publisher); + usleep(1000*1000); + } + return NULL; +} + +#define pigeon_send(x) _pigeon_send(x, sizeof(x)-1) + +void hexdump(unsigned char *d, int l) { + for (int i = 0; i < l; i++) { + if (i!=0 && i%0x10 == 0) printf("\n"); + printf("%2.2X ", d[i]); + } + printf("\n"); +} + +void _pigeon_send(const char *dat, int len) { + int sent; + unsigned char a[0x20]; + int err; + a[0] = 1; + for (int i=0; i(); + event.setLogMonoTime(nanos_since_boot()); + auto ublox_raw = event.initUbloxRaw(alen); + memcpy(ublox_raw.begin(), dat, alen); + + // send to ubloxRaw + auto words = capnp::messageToFlatArray(msg); + auto bytes = words.asBytes(); + zmq_send(publisher, bytes.begin(), bytes.size(), 0); +} + + +void *pigeon_thread(void *crap) { + // ubloxRaw = 8042 + void *context = zmq_ctx_new(); + void *publisher = zmq_socket(context, ZMQ_PUB); + zmq_bind(publisher, "tcp://*:8042"); + + // run at ~100hz + unsigned char dat[0x1000]; + uint64_t cnt = 0; + while (!do_exit) { + if (pigeon_needs_init) { + pigeon_needs_init = false; + pigeon_init(); + } + int alen = 0; + while (alen < 0xfc0) { + pthread_mutex_lock(&usb_lock); + int len = libusb_control_transfer(dev_handle, 0xc0, 0xe0, 1, 0, dat+alen, 0x40, TIMEOUT); + if (len < 0) { handle_usb_issue(len, __func__); } + pthread_mutex_unlock(&usb_lock); + if (len <= 0) break; + + //printf("got %d\n", len); + alen += len; + } + if (alen > 0) { + if (dat[0] == (char)0x00){ + LOGW("received invalid ublox message, resetting pigeon"); + pigeon_init(); + } else { + pigeon_publish_raw(publisher, dat, alen); + } + } + + // 10ms + usleep(10*1000); + cnt++; + } + + return NULL; +} + +int set_realtime_priority(int level) { + // should match python using chrt + struct sched_param sa; + memset(&sa, 0, sizeof(sa)); + sa.sched_priority = level; + return sched_setscheduler(getpid(), SCHED_FIFO, &sa); +} + +} + +int main() { + int err; + LOGW("starting boardd"); + + // set process priority + err = set_realtime_priority(4); + LOG("setpriority returns %d", err); + + // check the environment + if (getenv("STARTED")) { + spoofing_started = true; + } + + if (getenv("FAKESEND")) { + fake_send = true; + } + + if (getenv("BOARDD_LOOPBACK")){ + loopback_can = true; + } + + // init libusb + err = libusb_init(&ctx); + assert(err == 0); + libusb_set_debug(ctx, 3); + + // connect to the board + usb_retry_connect(); + + + // create threads + pthread_t can_health_thread_handle; + err = pthread_create(&can_health_thread_handle, NULL, + can_health_thread, NULL); + assert(err == 0); + + pthread_t can_send_thread_handle; + err = pthread_create(&can_send_thread_handle, NULL, + can_send_thread, NULL); + assert(err == 0); + + pthread_t can_recv_thread_handle; + err = pthread_create(&can_recv_thread_handle, NULL, + can_recv_thread, NULL); + assert(err == 0); + + pthread_t thermal_thread_handle; + err = pthread_create(&thermal_thread_handle, NULL, + thermal_thread, NULL); + assert(err == 0); + + // join threads + + err = pthread_join(thermal_thread_handle, NULL); + assert(err == 0); + + err = pthread_join(can_recv_thread_handle, NULL); + assert(err == 0); + + err = pthread_join(can_send_thread_handle, NULL); + assert(err == 0); + + err = pthread_join(can_health_thread_handle, NULL); + assert(err == 0); + + //while (!do_exit) usleep(1000); + + // destruct libusb + + libusb_close(dev_handle); + libusb_exit(ctx); +} diff --git a/selfdrive/boardd/boardd.py b/selfdrive/boardd/boardd.py new file mode 100755 index 00000000000000..fb045bb3aafdc2 --- /dev/null +++ b/selfdrive/boardd/boardd.py @@ -0,0 +1,252 @@ +#!/usr/bin/env python + +# This file is not used by OpenPilot. Only boardd.cc is used. +# The python version is slower, but has more options for development. + +# TODO: merge the extra functionalities of this file (like MOCK) in boardd.c and +# delete this python version of boardd + +import os +import struct +import zmq +import time + +import selfdrive.messaging as messaging +from common.realtime import Ratekeeper +from selfdrive.services import service_list +from selfdrive.swaglog import cloudlog + +# USB is optional +try: + import usb1 + from usb1 import USBErrorIO, USBErrorOverflow #pylint: disable=no-name-in-module +except Exception: + pass + +SAFETY_NOOUTPUT = 0 +SAFETY_HONDA = 1 +SAFETY_TOYOTA = 2 +SAFETY_CHRYSLER = 9 +SAFETY_TOYOTA_NOLIMITS = 0x1336 +SAFETY_ALLOUTPUT = 0x1337 + +# *** serialization functions *** +def can_list_to_can_capnp(can_msgs, msgtype='can'): + dat = messaging.new_message() + dat.init(msgtype, len(can_msgs)) + for i, can_msg in enumerate(can_msgs): + if msgtype == 'sendcan': + cc = dat.sendcan[i] + else: + cc = dat.can[i] + cc.address = can_msg[0] + cc.busTime = can_msg[1] + cc.dat = str(can_msg[2]) + cc.src = can_msg[3] + return dat + +def can_capnp_to_can_list(can, src_filter=None): + ret = [] + for msg in can: + if src_filter is None or msg.src in src_filter: + ret.append((msg.address, msg.busTime, msg.dat, msg.src)) + return ret + +# *** can driver *** +def can_health(): + while 1: + try: + dat = handle.controlRead(usb1.TYPE_VENDOR | usb1.RECIPIENT_DEVICE, 0xd2, 0, 0, 0x10) + break + except (USBErrorIO, USBErrorOverflow): + cloudlog.exception("CAN: BAD HEALTH, RETRYING") + v, i, started = struct.unpack("IIB", dat[0:9]) + # TODO: units + return {"voltage": v, "current": i, "started": bool(started)} + +def __parse_can_buffer(dat): + ret = [] + for j in range(0, len(dat), 0x10): + ddat = dat[j:j+0x10] + f1, f2 = struct.unpack("II", ddat[0:8]) + ret.append((f1 >> 21, f2>>16, ddat[8:8+(f2&0xF)], (f2>>4)&0xF)) + return ret + +def can_send_many(arr): + snds = [] + for addr, _, dat, alt in arr: + if addr < 0x800: # only support 11 bit addr + snd = struct.pack("II", ((addr << 21) | 1), len(dat) | (alt << 4)) + dat + snd = snd.ljust(0x10, '\x00') + snds.append(snd) + while 1: + try: + handle.bulkWrite(3, ''.join(snds)) + break + except (USBErrorIO, USBErrorOverflow): + cloudlog.exception("CAN: BAD SEND MANY, RETRYING") + +def can_recv(): + dat = "" + while 1: + try: + dat = handle.bulkRead(1, 0x10*256) + break + except (USBErrorIO, USBErrorOverflow): + cloudlog.exception("CAN: BAD RECV, RETRYING") + return __parse_can_buffer(dat) + +def can_init(): + global handle, context + handle = None + cloudlog.info("attempting can init") + + context = usb1.USBContext() + #context.setDebug(9) + + for device in context.getDeviceList(skip_on_error=True): + if device.getVendorID() == 0xbbaa and device.getProductID() == 0xddcc: + handle = device.open() + handle.claimInterface(0) + handle.controlWrite(0x40, 0xdc, SAFETY_ALLOUTPUT, 0, b'') + + if handle is None: + cloudlog.warn("CAN NOT FOUND") + exit(-1) + + cloudlog.info("got handle") + cloudlog.info("can init done") + +def boardd_mock_loop(): + context = zmq.Context() + can_init() + handle.controlWrite(0x40, 0xdc, SAFETY_ALLOUTPUT, 0, b'') + + logcan = messaging.sub_sock(context, service_list['can'].port) + sendcan = messaging.pub_sock(context, service_list['sendcan'].port) + + while 1: + tsc = messaging.drain_sock(logcan, wait_for_one=True) + snds = map(lambda x: can_capnp_to_can_list(x.can), tsc) + snd = [] + for s in snds: + snd += s + snd = filter(lambda x: x[-1] <= 1, snd) + can_send_many(snd) + + # recv @ 100hz + can_msgs = can_recv() + print("sent %d got %d" % (len(snd), len(can_msgs))) + m = can_list_to_can_capnp(can_msgs) + sendcan.send(m.to_bytes()) + +def boardd_test_loop(): + can_init() + cnt = 0 + while 1: + can_send_many([[0xbb,0,"\xaa\xaa\xaa\xaa",0], [0xaa,0,"\xaa\xaa\xaa\xaa"+struct.pack("!I", cnt),1]]) + #can_send_many([[0xaa,0,"\xaa\xaa\xaa\xaa",0]]) + #can_send_many([[0xaa,0,"\xaa\xaa\xaa\xaa",1]]) + # recv @ 100hz + can_msgs = can_recv() + print("got %d" % (len(can_msgs))) + time.sleep(0.01) + cnt += 1 + +# *** main loop *** +def boardd_loop(rate=200): + rk = Ratekeeper(rate) + context = zmq.Context() + + can_init() + + # *** publishes can and health + logcan = messaging.pub_sock(context, service_list['can'].port) + health_sock = messaging.pub_sock(context, service_list['health'].port) + + # *** subscribes to can send + sendcan = messaging.sub_sock(context, service_list['sendcan'].port) + + # drain sendcan to delete any stale messages from previous runs + messaging.drain_sock(sendcan) + + while 1: + # health packet @ 1hz + if (rk.frame%rate) == 0: + health = can_health() + msg = messaging.new_message() + msg.init('health') + + # store the health to be logged + msg.health.voltage = health['voltage'] + msg.health.current = health['current'] + msg.health.started = health['started'] + msg.health.controlsAllowed = True + + health_sock.send(msg.to_bytes()) + + # recv @ 100hz + can_msgs = can_recv() + + # publish to logger + # TODO: refactor for speed + if len(can_msgs) > 0: + dat = can_list_to_can_capnp(can_msgs) + logcan.send(dat.to_bytes()) + + # send can if we have a packet + tsc = messaging.recv_sock(sendcan) + if tsc is not None: + can_send_many(can_capnp_to_can_list(tsc.sendcan)) + + rk.keep_time() + +# *** main loop *** +def boardd_proxy_loop(rate=200, address="192.168.2.251"): + rk = Ratekeeper(rate) + context = zmq.Context() + + can_init() + + # *** subscribes can + logcan = messaging.sub_sock(context, service_list['can'].port, addr=address) + # *** publishes to can send + sendcan = messaging.pub_sock(context, service_list['sendcan'].port) + + # drain sendcan to delete any stale messages from previous runs + messaging.drain_sock(sendcan) + + while 1: + # recv @ 100hz + can_msgs = can_recv() + #for m in can_msgs: + # print "R:",hex(m[0]), str(m[2]).encode("hex") + + # publish to logger + # TODO: refactor for speed + if len(can_msgs) > 0: + dat = can_list_to_can_capnp(can_msgs, "sendcan") + sendcan.send(dat.to_bytes()) + + # send can if we have a packet + tsc = messaging.recv_sock(logcan) + if tsc is not None: + cl = can_capnp_to_can_list(tsc.can) + #for m in cl: + # print "S:",hex(m[0]), str(m[2]).encode("hex") + can_send_many(cl) + + rk.keep_time() + +def main(gctx=None): + if os.getenv("MOCK") is not None: + boardd_mock_loop() + elif os.getenv("PROXY") is not None: + boardd_proxy_loop() + elif os.getenv("BOARDTEST") is not None: + boardd_test_loop() + else: + boardd_loop() + +if __name__ == "__main__": + main() diff --git a/selfdrive/can/Makefile b/selfdrive/can/Makefile new file mode 100644 index 00000000000000..b140aa5f87e2a1 --- /dev/null +++ b/selfdrive/can/Makefile @@ -0,0 +1,70 @@ +CC = clang +CXX = clang++ + +BASEDIR = ../.. +PHONELIBS := ../../phonelibs + +UNAME_S := $(shell uname -s) +UNAME_M := $(shell uname -m) + +WARN_FLAGS = -Werror=implicit-function-declaration \ + -Werror=incompatible-pointer-types \ + -Werror=int-conversion \ + -Werror=return-type \ + -Werror=format-extra-args \ + -Wno-deprecated-declarations + +CFLAGS = -std=gnu11 -g -fPIC -O2 $(WARN_FLAGS) +CXXFLAGS = -std=c++11 -g -fPIC -O2 $(WARN_FLAGS) + +ifeq ($(UNAME_S),Darwin) + ZMQ_LIBS = -L/usr/local/lib -lzmq +else ifeq ($(OPTEST),1) + ZMQ_LIBS = -lzmq +else ifeq ($(UNAME_M),x86_64) + EXTERNAL := ../../external + ZMQ_FLAGS = -I$(EXTERNAL)/zmq/include + ZMQ_LIBS = -L$(EXTERNAL)/zmq/lib -l:libzmq.a +else ifeq ($(UNAME_M),aarch64) + ZMQ_FLAGS = -I$(PHONELIBS)/zmq/aarch64/include + ZMQ_LIBS = -L$(PHONELIBS)/zmq/aarch64/lib -l:libzmq.a + CXXFLAGS += -lgnustl_shared +endif + +OPENDBC_PATH := $(shell python -c 'import opendbc; print opendbc.DBC_PATH') + +DBC_SOURCES := $(wildcard $(OPENDBC_PATH)/*.dbc) +DBC_CCS := $(patsubst $(OPENDBC_PATH)/%.dbc,dbc_out/%.cc,$(DBC_SOURCES)) + +CWD := $(shell pwd) + +.PHONY: all +all: libdbc.so + +include ../common/cereal.mk + +# make sure cereal is built +libdbc.so:: ../../cereal/gen/cpp/log.capnp.h + +../../cereal/gen/cpp/log.capnp.h: + cd ../../cereal && make + +libdbc.so:: dbc.cc parser.cc packer.cc $(DBC_CCS) + $(CXX) -fPIC -shared -o '$@' $^ \ + -I. \ + -I../.. \ + $(CXXFLAGS) \ + $(ZMQ_FLAGS) \ + $(ZMQ_LIBS) \ + $(CEREAL_CXXFLAGS) \ + $(CEREAL_LIBS) + +dbc_out/%.cc: $(OPENDBC_PATH)/%.dbc process_dbc.py dbc_template.cc + PYTHONPATH=$(PYTHONPATH):$(CWD)/../../pyextra ./process_dbc.py '$<' '$@' + +.PHONY: clean +clean: + rm -rf libdbc.so* + rm -f dbc_out/*.cc + rm -f dbcs.txt + rm -f dbcs.csv diff --git a/selfdrive/can/__init__.py b/selfdrive/can/__init__.py new file mode 100644 index 00000000000000..e69de29bb2d1d6 diff --git a/selfdrive/can/common.h b/selfdrive/can/common.h new file mode 100644 index 00000000000000..f8d07ae681f760 --- /dev/null +++ b/selfdrive/can/common.h @@ -0,0 +1,87 @@ +#ifndef SELFDRIVE_CAN_COMMON_H +#define SELFDRIVE_CAN_COMMON_H + +#include +#include +#include + +#define ARRAYSIZE(x) (sizeof(x)/sizeof(x[0])) + + +unsigned int honda_checksum(unsigned int address, uint64_t d, int l); +unsigned int toyota_checksum(unsigned int address, uint64_t d, int l); + +struct SignalPackValue { + const char* name; + double value; +}; + + +struct SignalParseOptions { + uint32_t address; + const char* name; + double default_value; +}; + +struct MessageParseOptions { + uint32_t address; + int check_frequency; +}; + +struct SignalValue { + uint32_t address; + uint16_t ts; + const char* name; + double value; +}; + + +enum SignalType { + DEFAULT, + HONDA_CHECKSUM, + HONDA_COUNTER, + TOYOTA_CHECKSUM, +}; + +struct Signal { + const char* name; + int b1, b2, bo; + bool is_signed; + double factor, offset; + bool is_little_endian; + SignalType type; +}; + +struct Msg { + const char* name; + uint32_t address; + unsigned int size; + size_t num_sigs; + const Signal *sigs; +}; + +struct Val { + const char* name; + uint32_t address; + const char* def_val; + const Signal *sigs; +}; + +struct DBC { + const char* name; + size_t num_msgs; + const Msg *msgs; + const Val *vals; + size_t num_vals; +}; + +const DBC* dbc_lookup(const std::string& dbc_name); + +void dbc_register(const DBC* dbc); + +#define dbc_init(dbc) \ +static void __attribute__((constructor)) do_dbc_init_ ## dbc(void) { \ + dbc_register(&dbc); \ +} + +#endif diff --git a/selfdrive/can/dbc.cc b/selfdrive/can/dbc.cc new file mode 100644 index 00000000000000..95d5e4d791394a --- /dev/null +++ b/selfdrive/can/dbc.cc @@ -0,0 +1,32 @@ +#include +#include + +#include "common.h" + +namespace { + +std::vector& get_dbcs() { + static std::vector vec; + return vec; +} + +} + +const DBC* dbc_lookup(const std::string& dbc_name) { + for (const auto& dbci : get_dbcs()) { + if (dbc_name == dbci->name) { + return dbci; + } + } + return NULL; +} + +void dbc_register(const DBC* dbc) { + get_dbcs().push_back(dbc); +} + +extern "C" { + const DBC* dbc_lookup(const char* dbc_name) { + return dbc_lookup(std::string(dbc_name)); + } +} diff --git a/selfdrive/can/dbc_out/.gitignore b/selfdrive/can/dbc_out/.gitignore new file mode 100644 index 00000000000000..4625581a8553ca --- /dev/null +++ b/selfdrive/can/dbc_out/.gitignore @@ -0,0 +1,2 @@ +*.cc + diff --git a/selfdrive/can/dbc_out/.gitkeep b/selfdrive/can/dbc_out/.gitkeep new file mode 100644 index 00000000000000..e69de29bb2d1d6 diff --git a/selfdrive/can/dbc_template.cc b/selfdrive/can/dbc_template.cc new file mode 100644 index 00000000000000..2d4fb9570a0170 --- /dev/null +++ b/selfdrive/can/dbc_template.cc @@ -0,0 +1,75 @@ +#include + +#include "common.h" + +namespace { + +{% for address, msg_name, msg_size, sigs in msgs %} +const Signal sigs_{{address}}[] = { + {% for sig in sigs %} + { + {% if sig.is_little_endian %} + {% set b1 = sig.start_bit %} + {% else %} + {% set b1 = (sig.start_bit//8)*8 + (-sig.start_bit-1) % 8 %} + {% endif %} + .name = "{{sig.name}}", + .b1 = {{b1}}, + .b2 = {{sig.size}}, + .bo = {{64 - (b1 + sig.size)}}, + .is_signed = {{"true" if sig.is_signed else "false"}}, + .factor = {{sig.factor}}, + .offset = {{sig.offset}}, + .is_little_endian = {{"true" if sig.is_little_endian else "false"}}, + {% if checksum_type == "honda" and sig.name == "CHECKSUM" %} + .type = SignalType::HONDA_CHECKSUM, + {% elif checksum_type == "honda" and sig.name == "COUNTER" %} + .type = SignalType::HONDA_COUNTER, + {% elif checksum_type == "toyota" and sig.name == "CHECKSUM" %} + .type = SignalType::TOYOTA_CHECKSUM, + {% else %} + .type = SignalType::DEFAULT, + {% endif %} + }, + {% endfor %} +}; +{% endfor %} + +const Msg msgs[] = { +{% for address, msg_name, msg_size, sigs in msgs %} + {% set address_hex = "0x%X" % address %} + { + .name = "{{msg_name}}", + .address = {{address_hex}}, + .size = {{msg_size}}, + .num_sigs = ARRAYSIZE(sigs_{{address}}), + .sigs = sigs_{{address}}, + }, +{% endfor %} +}; + +const Val vals[] = { +{% for address, sig in def_vals %} + {% for sg_name, def_val in sig %} + {% set address_hex = "0x%X" % address %} + { + .name = "{{sg_name}}", + .address = {{address_hex}}, + .def_val = {{def_val}}, + .sigs = sigs_{{address}}, + }, + {% endfor %} +{% endfor %} +}; + +} + +const DBC {{dbc.name}} = { + .name = "{{dbc.name}}", + .num_msgs = ARRAYSIZE(msgs), + .msgs = msgs, + .vals = vals, + .num_vals = ARRAYSIZE(vals), +}; + +dbc_init({{dbc.name}}) diff --git a/selfdrive/can/libdbc_py.py b/selfdrive/can/libdbc_py.py new file mode 100644 index 00000000000000..09f5e5121dcc1f --- /dev/null +++ b/selfdrive/can/libdbc_py.py @@ -0,0 +1,92 @@ +import os +import subprocess + +from cffi import FFI + +can_dir = os.path.dirname(os.path.abspath(__file__)) +libdbc_fn = os.path.join(can_dir, "libdbc.so") +subprocess.check_call(["make"], cwd=can_dir) + +ffi = FFI() +ffi.cdef(""" + +typedef struct { + const char* name; + double value; +} SignalPackValue; + +typedef struct { + uint32_t address; + const char* name; + double default_value; +} SignalParseOptions; + +typedef struct { + uint32_t address; + int check_frequency; +} MessageParseOptions; + +typedef struct { + uint32_t address; + uint16_t ts; + const char* name; + double value; +} SignalValue; + + +typedef enum { + DEFAULT, + HONDA_CHECKSUM, + HONDA_COUNTER, + TOYOTA_CHECKSUM, +} SignalType; + +typedef struct { + const char* name; + int b1, b2, bo; + bool is_signed; + double factor, offset; + SignalType type; +} Signal; + +typedef struct { + const char* name; + uint32_t address; + unsigned int size; + size_t num_sigs; + const Signal *sigs; +} Msg; + +typedef struct { + const char* name; + uint32_t address; + const char* def_val; + const Signal *sigs; +} Val; + +typedef struct { + const char* name; + size_t num_msgs; + const Msg *msgs; + const Val *vals; + size_t num_vals; +} DBC; + + +void* can_init(int bus, const char* dbc_name, + size_t num_message_options, const MessageParseOptions* message_options, + size_t num_signal_options, const SignalParseOptions* signal_options, bool sendcan, + const char* tcp_addr); + +void can_update(void* can, uint64_t sec, bool wait); + +size_t can_query(void* can, uint64_t sec, bool *out_can_valid, size_t out_values_size, SignalValue* out_values); + +const DBC* dbc_lookup(const char* dbc_name); + +void* canpack_init(const char* dbc_name); + +uint64_t canpack_pack(void* inst, uint32_t address, size_t num_vals, const SignalPackValue *vals, int counter); +""") + +libdbc = ffi.dlopen(libdbc_fn) diff --git a/selfdrive/can/packer.cc b/selfdrive/can/packer.cc new file mode 100644 index 00000000000000..17171f15503048 --- /dev/null +++ b/selfdrive/can/packer.cc @@ -0,0 +1,132 @@ +#include +#include +#include +#include +#include +#include +#include + +#include "common.h" + +#define WARN printf + +namespace { + + // this is the same as read_u64_le, but uses uint64_t as in/out + uint64_t ReverseBytes(uint64_t x) { + return ((x & 0xff00000000000000ull) >> 56) | + ((x & 0x00ff000000000000ull) >> 40) | + ((x & 0x0000ff0000000000ull) >> 24) | + ((x & 0x000000ff00000000ull) >> 8) | + ((x & 0x00000000ff000000ull) << 8) | + ((x & 0x0000000000ff0000ull) << 24) | + ((x & 0x000000000000ff00ull) << 40) | + ((x & 0x00000000000000ffull) << 56); + } + + uint64_t set_value(uint64_t ret, Signal sig, int64_t ival){ + int shift = sig.is_little_endian? sig.b1 : sig.bo; + uint64_t mask = ((1ULL << sig.b2)-1) << shift; + uint64_t dat = (ival & ((1ULL << sig.b2)-1)) << shift; + if (sig.is_little_endian) { + dat = ReverseBytes(dat); + mask = ReverseBytes(mask); + } + ret &= ~mask; + ret |= dat; + return ret; + } + + class CANPacker { + public: + CANPacker(const std::string& dbc_name) { + dbc = dbc_lookup(dbc_name); + assert(dbc); + + for (int i=0; inum_msgs; i++) { + const Msg* msg = &dbc->msgs[i]; + message_lookup[msg->address] = *msg; + for (int j=0; jnum_sigs; j++) { + const Signal* sig = &msg->sigs[j]; + signal_lookup[std::make_pair(msg->address, std::string(sig->name))] = *sig; + } + } + } + + uint64_t pack(uint32_t address, const std::vector &signals, int counter) { + uint64_t ret = 0; + for (const auto& sigval : signals) { + std::string name = std::string(sigval.name); + double value = sigval.value; + + auto sig_it = signal_lookup.find(std::make_pair(address, name)); + if (sig_it == signal_lookup.end()) { + WARN("undefined signal %s - %d\n", name.c_str(), address); + continue; + } + auto sig = sig_it->second; + + int64_t ival = (int64_t)(round((value - sig.offset) / sig.factor)); + if (ival < 0) { + ival = (1ULL << sig.b2) + ival; + } + + ret = set_value(ret, sig, ival); + } + + if (counter >= 0){ + auto sig_it = signal_lookup.find(std::make_pair(address, "COUNTER")); + if (sig_it == signal_lookup.end()) { + WARN("COUNTER not defined\n"); + return ret; + } + auto sig = sig_it->second; + + if (sig.type != SignalType::HONDA_COUNTER){ + WARN("COUNTER signal type not valid\n"); + } + + ret = set_value(ret, sig, counter); + } + + auto sig_it = signal_lookup.find(std::make_pair(address, "CHECKSUM")); + if (sig_it != signal_lookup.end()) { + auto sig = sig_it->second; + if (sig.type == SignalType::HONDA_CHECKSUM){ + unsigned int chksm = honda_checksum(address, ret, message_lookup[address].size); + ret = set_value(ret, sig, chksm); + } + else if (sig.type == SignalType::TOYOTA_CHECKSUM){ + unsigned int chksm = toyota_checksum(address, ret, message_lookup[address].size); + ret = set_value(ret, sig, chksm); + } else { + //WARN("CHECKSUM signal type not valid\n"); + } + } + + return ret; + } + + + + private: + const DBC *dbc = NULL; + std::map, Signal> signal_lookup; + std::map message_lookup; + }; + +} + +extern "C" { + void* canpack_init(const char* dbc_name) { + CANPacker *ret = new CANPacker(std::string(dbc_name)); + return (void*)ret; + } + + uint64_t canpack_pack(void* inst, uint32_t address, size_t num_vals, const SignalPackValue *vals, int counter, bool checksum) { + CANPacker *cp = (CANPacker*)inst; + + return cp->pack(address, std::vector(vals, vals+num_vals), counter); + } + +} diff --git a/selfdrive/can/packer.py b/selfdrive/can/packer.py new file mode 100644 index 00000000000000..cc669e60c6a23c --- /dev/null +++ b/selfdrive/can/packer.py @@ -0,0 +1,67 @@ +import struct +from selfdrive.can.libdbc_py import libdbc, ffi + + +class CANPacker(object): + def __init__(self, dbc_name): + self.packer = libdbc.canpack_init(dbc_name) + self.dbc = libdbc.dbc_lookup(dbc_name) + self.sig_names = {} + self.name_to_address_and_size = {} + + num_msgs = self.dbc[0].num_msgs + for i in range(num_msgs): + msg = self.dbc[0].msgs[i] + + name = ffi.string(msg.name) + address = msg.address + self.name_to_address_and_size[name] = (address, msg.size) + self.name_to_address_and_size[address] = (address, msg.size) + + def pack(self, addr, values, counter): + values_thing = [] + for name, value in values.iteritems(): + if name not in self.sig_names: + self.sig_names[name] = ffi.new("char[]", name) + + values_thing.append({ + 'name': self.sig_names[name], + 'value': value + }) + + values_c = ffi.new("SignalPackValue[]", values_thing) + + return libdbc.canpack_pack(self.packer, addr, len(values_thing), values_c, counter) + + def pack_bytes(self, addr, values, counter=-1): + addr, size = self.name_to_address_and_size[addr] + + val = self.pack(addr, values, counter) + r = struct.pack(">Q", val) + return addr, r[:size] + + def make_can_msg(self, addr, bus, values, counter=-1): + addr, msg = self.pack_bytes(addr, values, counter) + return [addr, 0, msg, bus] + + +if __name__ == "__main__": + ## little endian test + cp = CANPacker("hyundai_santa_fe_2019_ccan") + s = cp.pack_bytes(0x340, { + "CR_Lkas_StrToqReq": -0.06, + #"CF_Lkas_FcwBasReq": 1, + "CF_Lkas_MsgCount": 7, + "CF_Lkas_HbaSysState": 0, + #"CF_Lkas_Chksum": 3, + }) + s = cp.pack_bytes(0x340, { + "CF_Lkas_MsgCount": 1, + }) + # big endian test + #cp = CANPacker("honda_civic_touring_2016_can_generated") + #s = cp.pack_bytes(0xe4, { + # "STEER_TORQUE": -2, + #}) + print [hex(ord(v)) for v in s[1]] + print(s[1].encode("hex")) diff --git a/selfdrive/can/parser.cc b/selfdrive/can/parser.cc new file mode 100644 index 00000000000000..c8ce001c43a130 --- /dev/null +++ b/selfdrive/can/parser.cc @@ -0,0 +1,525 @@ +#include +#include +#include +#include + +#include +#include +#include +#include + +#include +#include +#include +#include + +#include + +#include +#include "cereal/gen/cpp/log.capnp.h" + +#include "common.h" + +#define DEBUG(...) +// #define DEBUG printf +#define INFO printf + + +#define MAX_BAD_COUNTER 5 + +unsigned int honda_checksum(unsigned int address, uint64_t d, int l) { + d >>= ((8-l)*8); // remove padding + d >>= 4; // remove checksum + + int s = 0; + while (address) { s += (address & 0xF); address >>= 4; } + while (d) { s += (d & 0xF); d >>= 4; } + s = 8-s; + s &= 0xF; + + return s; +} + +unsigned int toyota_checksum(unsigned int address, uint64_t d, int l) { + d >>= ((8-l)*8); // remove padding + d >>= 8; // remove checksum + + unsigned int s = l; + while (address) { s += address & 0xff; address >>= 8; } + while (d) { s += d & 0xff; d >>= 8; } + + return s & 0xFF; +} + +namespace { + +uint64_t read_u64_be(const uint8_t* v) { + return (((uint64_t)v[0] << 56) + | ((uint64_t)v[1] << 48) + | ((uint64_t)v[2] << 40) + | ((uint64_t)v[3] << 32) + | ((uint64_t)v[4] << 24) + | ((uint64_t)v[5] << 16) + | ((uint64_t)v[6] << 8) + | (uint64_t)v[7]); +} + +uint64_t read_u64_le(const uint8_t* v) { + return ((uint64_t)v[0] + | ((uint64_t)v[1] << 8) + | ((uint64_t)v[2] << 16) + | ((uint64_t)v[3] << 24) + | ((uint64_t)v[4] << 32) + | ((uint64_t)v[5] << 40) + | ((uint64_t)v[6] << 48) + | ((uint64_t)v[7] << 56)); +} + + +struct MessageState { + uint32_t address; + unsigned int size; + + std::vector parse_sigs; + std::vector vals; + + uint16_t ts; + uint64_t seen; + uint64_t check_threshold; + + uint8_t counter; + uint8_t counter_fail; + + bool parse(uint64_t sec, uint16_t ts_, uint64_t dat) { + for (int i=0; i < parse_sigs.size(); i++) { + auto& sig = parse_sigs[i]; + int64_t tmp; + + if (sig.is_little_endian){ + tmp = (dat >> sig.b1) & ((1ULL << sig.b2)-1); + } else { + tmp = (dat >> sig.bo) & ((1ULL << sig.b2)-1); + } + + if (sig.is_signed) { + tmp -= (tmp >> (sig.b2-1)) ? (1ULL << sig.b2) : 0; //signed + } + + DEBUG("parse %X %s -> %lld\n", address, sig.name, tmp); + + if (sig.type == SignalType::HONDA_CHECKSUM) { + if (honda_checksum(address, dat, size) != tmp) { + INFO("%X CHECKSUM FAIL\n", address); + return false; + } + } else if (sig.type == SignalType::HONDA_COUNTER) { + if (!honda_update_counter(tmp)) { + return false; + } + } else if (sig.type == SignalType::TOYOTA_CHECKSUM) { + // INFO("CHECKSUM %d %d %018llX - %lld vs %d\n", address, size, dat, tmp, toyota_checksum(address, dat, size)); + + if (toyota_checksum(address, dat, size) != tmp) { + INFO("%X CHECKSUM FAIL\n", address); + return false; + } + } + + vals[i] = tmp * sig.factor + sig.offset; + } + ts = ts_; + seen = sec; + + return true; + } + + + bool honda_update_counter(int64_t v) { + uint8_t old_counter = counter; + counter = v; + if (((old_counter+1) & 3) != v) { + counter_fail += 1; + if (counter_fail > 1) { + INFO("%X COUNTER FAIL %d -- %d vs %d\n", address, counter_fail, old_counter, (int)v); + } + if (counter_fail >= MAX_BAD_COUNTER) { + return false; + } + } else if (counter_fail > 0) { + counter_fail--; + } + return true; + } + +}; + + +class CANParser { + public: + CANParser(int abus, const std::string& dbc_name, + const std::vector &options, + const std::vector &sigoptions, + bool sendcan, const std::string& tcp_addr) + : bus(abus) { + // connect to can on 8006 + context = zmq_ctx_new(); + subscriber = zmq_socket(context, ZMQ_SUB); + zmq_setsockopt(subscriber, ZMQ_SUBSCRIBE, "", 0); + + forwarder = zmq_socket(context, ZMQ_PUB); + zmq_bind(forwarder, "tcp://*:8592"); + + std::string tcp_addr_str; + + if (sendcan) { + tcp_addr_str = "tcp://" + tcp_addr + ":8017"; + } else { + tcp_addr_str = "tcp://" + tcp_addr + ":8006"; + } + const char *tcp_addr_char = tcp_addr_str.c_str(); + + zmq_connect(subscriber, tcp_addr_char); + + // drain sendcan to delete any stale messages from previous runs + zmq_msg_t msgDrain; + zmq_msg_init(&msgDrain); + int err = 0; + while(err >= 0) { + err = zmq_msg_recv(&msgDrain, subscriber, ZMQ_DONTWAIT); + } + + dbc = dbc_lookup(dbc_name); + assert(dbc); + + for (const auto& op : options) { + MessageState state = { + .address = op.address, + // .check_frequency = op.check_frequency, + }; + + // msg is not valid if a message isn't received for 10 consecutive steps + if (op.check_frequency > 0) { + state.check_threshold = (1000000000ULL / op.check_frequency) * 10; + } + + + const Msg* msg = NULL; + for (int i=0; inum_msgs; i++) { + if (dbc->msgs[i].address == op.address) { + msg = &dbc->msgs[i]; + break; + } + } + if (!msg) { + fprintf(stderr, "CANParser: could not find message 0x%X in dnc %s\n", op.address, dbc_name.c_str()); + assert(false); + } + + state.size = msg->size; + + // track checksums and counters for this message + for (int i=0; inum_sigs; i++) { + const Signal *sig = &msg->sigs[i]; + if (sig->type != SignalType::DEFAULT) { + state.parse_sigs.push_back(*sig); + state.vals.push_back(0); + } + } + + // track requested signals for this message + for (const auto& sigop : sigoptions) { + if (sigop.address != op.address) continue; + + for (int i=0; inum_sigs; i++) { + const Signal *sig = &msg->sigs[i]; + if (strcmp(sig->name, sigop.name) == 0 + && sig->type == SignalType::DEFAULT) { + state.parse_sigs.push_back(*sig); + state.vals.push_back(sigop.default_value); + break; + } + } + + } + + message_states[state.address] = state; + } + } + + void UpdateCans(uint64_t sec, const capnp::List::Reader& cans) { + int msg_count = cans.size(); + uint64_t p; + + DEBUG("got %d messages\n", msg_count); + + // parse the messages + for (int i = 0; i < msg_count; i++) { + auto cmsg = cans[i]; + + if (cmsg.getDat().size() > 8) continue; //shouldnt ever happen + uint8_t dat[8] = {0}; + memcpy(dat, cmsg.getDat().begin(), cmsg.getDat().size()); + + if (can_forward_period_ns > 0) raw_can_values[cmsg.getSrc()][cmsg.getAddress()] = read_u64_be(dat); + + //if (((cmsg.getAddress() == 0xe4 or cmsg.getAddress() == 0x33d) and cmsg.getSrc() == bus) or \ + // (cmsg.getSrc() != bus and cmsg.getAddress() != 0x33d and cmsg.getAddress() != 0xe4 and \ + // (cmsg.getAddress() < 0x240 or cmsg.getAddress() > 0x24A))) { + if (cmsg.getSrc() != bus) { + continue; + } + auto state_it = message_states.find(cmsg.getAddress()); + if (state_it == message_states.end()) { + // DEBUG("skip %d: not specified\n", cmsg.getAddress()); + continue; + } + + // Assumes all signals in the message are of the same type (little or big endian) + // TODO: allow signals within the same message to have different endianess + auto& sig = message_states[cmsg.getAddress()].parse_sigs[0]; + if (sig.is_little_endian) { + p = read_u64_le(dat); + } else { + p = read_u64_be(dat); + } + + DEBUG(" proc %X: %llx\n", cmsg.getAddress(), p); + + state_it->second.parse(sec, cmsg.getBusTime(), p); + } + } + + void ForwardCANData(uint64_t sec) { + if (sec > next_can_forward_ns) { + next_can_forward_ns += can_forward_period_ns; + // next_can_forward_ns starts at 0, so it needs to be reset. Also handle delays. + if (sec > next_can_forward_ns) next_can_forward_ns = sec + can_forward_period_ns; + std::string canOut = ""; + for (auto src : raw_can_values) { + for (auto pid : src.second) { + canOut = canOut + std::to_string(src.first) + " " + std::to_string(pid.first) + " " + std::to_string(pid.second) + "|"; + } + } + zmq_send(forwarder, canOut.data(), canOut.size(), 0); + } + } + + void UpdateValid(uint64_t sec) { + can_valid = true; + for (const auto& kv : message_states) { + const auto& state = kv.second; + if (state.check_threshold > 0 && (sec - state.seen) > state.check_threshold) { + if (state.seen > 0) { + DEBUG("%X TIMEOUT\n", state.address); + } + can_valid = false; + } + } + } + + void update(uint64_t sec, bool wait) { + int err; + + // recv from can + zmq_msg_t msg; + zmq_msg_init(&msg); + + // multiple recv is fine + bool first = wait; + while (1) { + if (first) { + err = zmq_msg_recv(&msg, subscriber, 0); + first = false; + } else { + err = zmq_msg_recv(&msg, subscriber, ZMQ_DONTWAIT); + } + if (err < 0) break; + + // format for board, make copy due to alignment issues, will be freed on out of scope + auto amsg = kj::heapArray((zmq_msg_size(&msg) / sizeof(capnp::word)) + 1); + memcpy(amsg.begin(), zmq_msg_data(&msg), zmq_msg_size(&msg)); + + // extract the messages + capnp::FlatArrayMessageReader cmsg(amsg); + cereal::Event::Reader event = cmsg.getRoot(); + + auto cans = event.getCan(); + + UpdateCans(sec, cans); + } + + if (can_forward_period_ns > 0) ForwardCANData(sec); + + UpdateValid(sec); + + zmq_msg_close(&msg); + } + + std::vector query(uint64_t sec) { + std::vector ret; + + for (const auto& kv : message_states) { + const auto& state = kv.second; + if (sec != 0 && state.seen != sec) continue; + + for (int i=0; i> raw_can_values; + + const DBC *dbc = NULL; + std::unordered_map message_states; +}; + +} + +extern "C" { + +void* can_init(int bus, const char* dbc_name, + size_t num_message_options, const MessageParseOptions* message_options, + size_t num_signal_options, const SignalParseOptions* signal_options, + bool sendcan, const char* tcp_addr) { + CANParser* ret = new CANParser(bus, std::string(dbc_name), + (message_options ? std::vector(message_options, message_options+num_message_options) + : std::vector{}), + (signal_options ? std::vector(signal_options, signal_options+num_signal_options) + : std::vector{}), sendcan, std::string(tcp_addr)); + return (void*)ret; +} + +void can_update(void* can, uint64_t sec, bool wait) { + CANParser* cp = (CANParser*)can; + cp->update(sec, wait); +} + +size_t can_query(void* can, uint64_t sec, bool *out_can_valid, size_t out_values_size, SignalValue* out_values) { + CANParser* cp = (CANParser*)can; + + if (out_can_valid) { + *out_can_valid = cp->can_valid; + } + + const std::vector values = cp->query(sec); + if (out_values) { + std::copy(values.begin(), values.begin()+std::min(out_values_size, values.size()), out_values); + } + return values.size(); +}; + +} + +#ifdef TEST + +int main(int argc, char** argv) { + CANParser cp(0, "honda_civic_touring_2016_can", + std::vector{ + // address, check_frequency + {0x14a, 100}, + {0x158, 100}, + {0x17c, 100}, + {0x191, 100}, + {0x1a4, 50}, + {0x326, 10}, + {0x1b0, 50}, + {0x1d0, 50}, + {0x305, 10}, + {0x324, 10}, + {0x405, 3}, + {0x18f, 0}, + {0x130, 0}, + {0x296, 0}, + {0x30c, 0}, + }, + std::vector{ + // sig_name, sig_address, default + {0x158, "XMISSION_SPEED", 0}, + {0x1d0, "WHEEL_SPEED_FL", 0}, + {0x1d0, "WHEEL_SPEED_FR", 0}, + {0x1d0, "WHEEL_SPEED_RL", 0}, + {0x14a, "STEER_ANGLE", 0}, + {0x18f, "STEER_TORQUE_SENSOR", 0}, + {0x191, "GEAR", 0}, + {0x1b0, "WHEELS_MOVING", 1}, + {0x405, "DOOR_OPEN_FL", 1}, + {0x405, "DOOR_OPEN_FR", 1}, + {0x405, "DOOR_OPEN_RL", 1}, + {0x405, "DOOR_OPEN_RR", 1}, + {0x324, "CRUISE_SPEED_PCM", 0}, + {0x305, "SEATBELT_DRIVER_LAMP", 1}, + {0x305, "SEATBELT_DRIVER_LATCHED", 0}, + {0x17c, "BRAKE_PRESSED", 0}, + {0x130, "CAR_GAS", 0}, + {0x296, "CRUISE_BUTTONS", 0}, + {0x1a4, "ESP_DISABLED", 1}, + {0x30c, "HUD_LEAD", 0}, + {0x1a4, "USER_BRAKE", 0}, + {0x18f, "STEER_STATUS", 5}, + {0x1d0, "WHEEL_SPEED_RR", 0}, + {0x1b0, "BRAKE_ERROR_1", 1}, + {0x1b0, "BRAKE_ERROR_2", 1}, + {0x191, "GEAR_SHIFTER", 0}, + {0x326, "MAIN_ON", 0}, + {0x17c, "ACC_STATUS", 0}, + {0x17c, "PEDAL_GAS", 0}, + {0x296, "CRUISE_SETTING", 0}, + {0x326, "LEFT_BLINKER", 0}, + {0x326, "RIGHT_BLINKER", 0}, + {0x324, "COUNTER", 0}, + {0x17c, "ENGINE_RPM", 0}, + }); + + + + const std::string log_fn = "dats.bin"; + + int log_fd = open(log_fn.c_str(), O_RDONLY, 0); + assert(log_fd >= 0); + + off_t log_size = lseek(log_fd, 0, SEEK_END); + lseek(log_fd, 0, SEEK_SET); + + void* log_data = mmap(NULL, log_size, PROT_READ, MAP_PRIVATE, log_fd, 0); + assert(log_data); + + auto words = kj::arrayPtr((const capnp::word*)log_data, log_size/sizeof(capnp::word)); + while (words.size() > 0) { + capnp::FlatArrayMessageReader reader(words); + + auto evt = reader.getRoot(); + auto cans = evt.getCan(); + + cp.UpdateCans(0, cans); + + words = kj::arrayPtr(reader.getEnd(), words.end()); + } + + munmap(log_data, log_size); + + close(log_fd); + + return 0; +} + +#endif diff --git a/selfdrive/can/parser.py b/selfdrive/can/parser.py new file mode 100644 index 00000000000000..165673cea5b6e7 --- /dev/null +++ b/selfdrive/can/parser.py @@ -0,0 +1,246 @@ +import time +from collections import defaultdict +import numbers + +from selfdrive.can.libdbc_py import libdbc, ffi + +class CANParser(object): + def __init__(self, dbc_name, signals, checks=[], bus=0, sendcan=False, tcp_addr="127.0.0.1"): + self.can_valid = True + self.vl = defaultdict(dict) + self.ts = defaultdict(dict) + + self.dbc_name = dbc_name + self.dbc = libdbc.dbc_lookup(dbc_name) + self.msg_name_to_addres = {} + self.address_to_msg_name = {} + + num_msgs = self.dbc[0].num_msgs + for i in range(num_msgs): + msg = self.dbc[0].msgs[i] + + name = ffi.string(msg.name) + address = msg.address + + self.msg_name_to_addres[name] = address + self.address_to_msg_name[address] = name + + # Convert message names into addresses + for i in range(len(signals)): + s = signals[i] + if not isinstance(s[1], numbers.Number): + s = (s[0], self.msg_name_to_addres[s[1]], s[2]) + signals[i] = s + + for i in range(len(checks)): + c = checks[i] + if not isinstance(c[0], numbers.Number): + c = (self.msg_name_to_addres[c[0]], c[1]) + checks[i] = c + + sig_names = dict((name, ffi.new("char[]", name)) for name, _, _ in signals) + + signal_options_c = ffi.new("SignalParseOptions[]", [ + { + 'address': sig_address, + 'name': sig_names[sig_name], + 'default_value': sig_default, + } for sig_name, sig_address, sig_default in signals]) + + message_options = dict((address, 0) for _, address, _ in signals) + message_options.update(dict(checks)) + + message_options_c = ffi.new("MessageParseOptions[]", [ + { + 'address': msg_address, + 'check_frequency': freq, + } for msg_address, freq in message_options.iteritems()]) + + self.can = libdbc.can_init(bus, dbc_name, len(message_options_c), message_options_c, + len(signal_options_c), signal_options_c, sendcan, tcp_addr) + + self.p_can_valid = ffi.new("bool*") + + value_count = libdbc.can_query(self.can, 0, self.p_can_valid, 0, ffi.NULL) + self.can_values = ffi.new("SignalValue[%d]" % value_count) + self.update_vl(0) + # print "===" + + def update_vl(self, sec): + + can_values_len = libdbc.can_query(self.can, sec, self.p_can_valid, len(self.can_values), self.can_values) + assert can_values_len <= len(self.can_values) + + self.can_valid = self.p_can_valid[0] + + # print can_values_len + ret = set() + for i in xrange(can_values_len): + cv = self.can_values[i] + address = cv.address + # print hex(cv.address), ffi.string(cv.name) + name = ffi.string(cv.name) + self.vl[address][name] = cv.value + self.ts[address][name] = cv.ts + + sig_name = self.address_to_msg_name[address] + self.vl[sig_name][name] = cv.value + self.ts[sig_name][name] = cv.ts + ret.add(address) + return ret + + def update(self, sec, wait): + libdbc.can_update(self.can, sec, wait) + return self.update_vl(sec) + +class CANDefine(object): + def __init__(self, dbc_name): + self.dv = defaultdict(dict) + self.dbc_name = dbc_name + self.dbc = libdbc.dbc_lookup(dbc_name) + + num_vals = self.dbc[0].num_vals + + self.address_to_msg_name = {} + num_msgs = self.dbc[0].num_msgs + for i in range(num_msgs): + msg = self.dbc[0].msgs[i] + name = ffi.string(msg.name) + address = msg.address + self.address_to_msg_name[address] = name + + for i in range(num_vals): + val = self.dbc[0].vals[i] + + sgname = ffi.string(val.name) + address = val.address + def_val = ffi.string(val.def_val) + + #separate definition/value pairs + def_val = def_val.split() + values = [int(v) for v in def_val[::2]] + defs = def_val[1::2] + + if address not in self.dv: + self.dv[address] = {} + msgname = self.address_to_msg_name[address] + self.dv[msgname] = {} + + # two ways to lookup: address or msg name + self.dv[address][sgname] = {v: d for v, d in zip(values, defs)} #build dict + self.dv[msgname][sgname] = self.dv[address][sgname] + + +if __name__ == "__main__": + from common.realtime import sec_since_boot + + radar_messages = range(0x430, 0x43A) + range(0x440, 0x446) + # signals = zip(['LONG_DIST'] * 16 + ['NEW_TRACK'] * 16 + ['LAT_DIST'] * 16 + + # ['REL_SPEED'] * 16, radar_messages * 4, + # [255] * 16 + [1] * 16 + [0] * 16 + [0] * 16) + # checks = zip(radar_messages, [20]*16) + + # cp = CANParser("acura_ilx_2016_nidec", signals, checks, 1) + + + # signals = [ + # ("XMISSION_SPEED", 0x158, 0), #sig_name, sig_address, default + # ("WHEEL_SPEED_FL", 0x1d0, 0), + # ("WHEEL_SPEED_FR", 0x1d0, 0), + # ("WHEEL_SPEED_RL", 0x1d0, 0), + # ("STEER_ANGLE", 0x14a, 0), + # ("STEER_TORQUE_SENSOR", 0x18f, 0), + # ("GEAR", 0x191, 0), + # ("WHEELS_MOVING", 0x1b0, 1), + # ("DOOR_OPEN_FL", 0x405, 1), + # ("DOOR_OPEN_FR", 0x405, 1), + # ("DOOR_OPEN_RL", 0x405, 1), + # ("DOOR_OPEN_RR", 0x405, 1), + # ("CRUISE_SPEED_PCM", 0x324, 0), + # ("SEATBELT_DRIVER_LAMP", 0x305, 1), + # ("SEATBELT_DRIVER_LATCHED", 0x305, 0), + # ("BRAKE_PRESSED", 0x17c, 0), + # ("CAR_GAS", 0x130, 0), + # ("CRUISE_BUTTONS", 0x296, 0), + # ("ESP_DISABLED", 0x1a4, 1), + # ("HUD_LEAD", 0x30c, 0), + # ("USER_BRAKE", 0x1a4, 0), + # ("STEER_STATUS", 0x18f, 5), + # ("WHEEL_SPEED_RR", 0x1d0, 0), + # ("BRAKE_ERROR_1", 0x1b0, 1), + # ("BRAKE_ERROR_2", 0x1b0, 1), + # ("GEAR_SHIFTER", 0x191, 0), + # ("MAIN_ON", 0x326, 0), + # ("ACC_STATUS", 0x17c, 0), + # ("PEDAL_GAS", 0x17c, 0), + # ("CRUISE_SETTING", 0x296, 0), + # ("LEFT_BLINKER", 0x326, 0), + # ("RIGHT_BLINKER", 0x326, 0), + # ("COUNTER", 0x324, 0), + # ("ENGINE_RPM", 0x17C, 0) + # ] + # checks = [ + # (0x14a, 100), # address, frequency + # (0x158, 100), + # (0x17c, 100), + # (0x191, 100), + # (0x1a4, 50), + # (0x326, 10), + # (0x1b0, 50), + # (0x1d0, 50), + # (0x305, 10), + # (0x324, 10), + # (0x405, 3), + # ] + + # cp = CANParser("honda_civic_touring_2016_can_generated", signals, checks, 0) + + + signals = [ + # sig_name, sig_address, default + ("GEAR", 956, 0x20), + ("BRAKE_PRESSED", 548, 0), + ("GAS_PEDAL", 705, 0), + + ("WHEEL_SPEED_FL", 170, 0), + ("WHEEL_SPEED_FR", 170, 0), + ("WHEEL_SPEED_RL", 170, 0), + ("WHEEL_SPEED_RR", 170, 0), + ("DOOR_OPEN_FL", 1568, 1), + ("DOOR_OPEN_FR", 1568, 1), + ("DOOR_OPEN_RL", 1568, 1), + ("DOOR_OPEN_RR", 1568, 1), + ("SEATBELT_DRIVER_UNLATCHED", 1568, 1), + ("TC_DISABLED", 951, 1), + ("STEER_ANGLE", 37, 0), + ("STEER_FRACTION", 37, 0), + ("STEER_RATE", 37, 0), + ("GAS_RELEASED", 466, 0), + ("CRUISE_STATE", 466, 0), + ("MAIN_ON", 467, 0), + ("SET_SPEED", 467, 0), + ("STEER_TORQUE_DRIVER", 608, 0), + ("STEER_TORQUE_EPS", 608, 0), + ("TURN_SIGNALS", 1556, 3), # 3 is no blinkers + ("LKA_STATE", 610, 0), + ] + checks = [ + (548, 40), + (705, 33), + + (170, 80), + (37, 80), + (466, 33), + (608, 50), + ] + + cp = CANParser("toyota_rav4_2017_pt_generated", signals, checks, 0) + + # print cp.vl + + while True: + cp.update(int(sec_since_boot()*1e9), True) + # print cp.vl + print(cp.ts) + print(cp.can_valid) + time.sleep(0.01) diff --git a/selfdrive/can/plant_can_parser.py b/selfdrive/can/plant_can_parser.py new file mode 100644 index 00000000000000..44939747cee521 --- /dev/null +++ b/selfdrive/can/plant_can_parser.py @@ -0,0 +1,131 @@ +### old can parser just used by plant.py for regression tests +import os +import opendbc +from collections import defaultdict + +from selfdrive.car.honda.hondacan import fix +from common.realtime import sec_since_boot +from common.dbc import dbc + +class CANParser(object): + def __init__(self, dbc_f, signals, checks=None): + ### input: + # dbc_f : dbc file + # signals : List of tuples (name, address, ival) where + # - name is the signal name. + # - address is the corresponding message address. + # - ival is the initial value. + # checks : List of pairs (address, frequency) where + # - address is the message address of a message for which health should be + # monitored. + # - frequency is the frequency at which health should be monitored. + + checks = [] if checks is None else checks + self.msgs_ck = set([check[0] for check in checks]) + self.frqs = dict(checks) + self.can_valid = False # start with False CAN assumption + # list of received msg we want to monitor counter and checksum for + # read dbc file + self.can_dbc = dbc(os.path.join(opendbc.DBC_PATH, dbc_f)) + # initialize variables to initial values + self.vl = {} # signal values + self.ts = {} # time stamp recorded in log + self.ct = {} # current time stamp + self.ok = {} # valid message? + self.cn = {} # message counter + self.cn_vl = {} # message counter mismatch value + self.ck = {} # message checksum status + + for _, addr, _ in signals: + self.vl[addr] = {} + self.ts[addr] = {} + self.ct[addr] = sec_since_boot() + self.ok[addr] = True + self.cn[addr] = 0 + self.cn_vl[addr] = 0 + self.ck[addr] = False + + for name, addr, ival in signals: + self.vl[addr][name] = ival + self.ts[addr][name] = 0 + + self._msgs = [s[1] for s in signals] + self._sgs = [s[0] for s in signals] + + self._message_indices = defaultdict(list) + for i, x in enumerate(self._msgs): + self._message_indices[x].append(i) + + def update_can(self, can_recv): + msgs_upd = [] + cn_vl_max = 5 # no more than 5 wrong counter checks + + self.sec_since_boot_cached = sec_since_boot() + + # we are subscribing to PID_XXX, else data from USB + for msg, ts, cdat, _ in can_recv: + idxs = self._message_indices[msg] + if idxs: + msgs_upd.append(msg) + # read the entire message + out = self.can_dbc.decode((msg, 0, cdat))[1] + # checksum check + self.ck[msg] = True + if "CHECKSUM" in out.keys() and msg in self.msgs_ck: + # remove checksum (half byte) + ck_portion = cdat[:-1] + chr(ord(cdat[-1]) & 0xF0) + # recalculate checksum + msg_vl = fix(ck_portion, msg) + # compare recalculated vs received checksum + if msg_vl != cdat: + print "CHECKSUM FAIL: " + hex(msg) + self.ck[msg] = False + self.ok[msg] = False + # counter check + cn = 0 + if "COUNTER" in out.keys(): + cn = out["COUNTER"] + # check counter validity if it's a relevant message + if cn != ((self.cn[msg] + 1) % 4) and msg in self.msgs_ck and "COUNTER" in out.keys(): + #print hex(msg), "FAILED COUNTER!" + self.cn_vl[msg] += 1 # counter check failed + else: + self.cn_vl[msg] -= 1 # counter check passed + # message status is invalid if we received too many wrong counter values + if self.cn_vl[msg] >= cn_vl_max: + print "COUNTER WRONG: " + hex(msg) + self.ok[msg] = False + + # update msg time stamps and counter value + self.ct[msg] = self.sec_since_boot_cached + self.cn[msg] = cn + self.cn_vl[msg] = min(max(self.cn_vl[msg], 0), cn_vl_max) + + # set msg valid status if checksum is good and wrong counter counter is zero + if self.ck[msg] and self.cn_vl[msg] == 0: + self.ok[msg] = True + + # update value of signals in the + for ii in idxs: + sg = self._sgs[ii] + self.vl[msg][sg] = out[sg] + self.ts[msg][sg] = ts + + # for each message, check if it's too long since last time we received it + self._check_dead_msgs() + + # assess overall can validity: if there is one relevant message invalid, then set can validity flag to False + self.can_valid = True + + if False in self.ok.values(): + #print "CAN INVALID!" + self.can_valid = False + + return msgs_upd + + def _check_dead_msgs(self): + ### input: + ## simple stuff for now: msg is not valid if a message isn't received for 10 consecutive steps + for msg in set(self._msgs): + if msg in self.msgs_ck and self.sec_since_boot_cached - self.ct[msg] > 10./self.frqs[msg]: + self.ok[msg] = False diff --git a/selfdrive/can/process_dbc.py b/selfdrive/can/process_dbc.py new file mode 100755 index 00000000000000..331e0a3130ca8d --- /dev/null +++ b/selfdrive/can/process_dbc.py @@ -0,0 +1,64 @@ +#!/usr/bin/env python +import os +import sys + +import jinja2 + +from collections import Counter +from common.dbc import dbc + +if len(sys.argv) != 3: + print "usage: %s dbc_path struct_path" % (sys.argv[0],) + sys.exit(0) + +dbc_fn = sys.argv[1] +out_fn = sys.argv[2] + +template_fn = os.path.join(os.path.dirname(__file__), "dbc_template.cc") + +can_dbc = dbc(dbc_fn) + +with open(template_fn, "r") as template_f: + template = jinja2.Template(template_f.read(), trim_blocks=True, lstrip_blocks=True) + +msgs = [(address, msg_name, msg_size, sorted(msg_sigs, key=lambda s: s.name not in ("COUNTER", "CHECKSUM"))) # process counter and checksums first + for address, ((msg_name, msg_size), msg_sigs) in sorted(can_dbc.msgs.iteritems()) if msg_sigs] + +def_vals = {a: set(b) for a,b in can_dbc.def_vals.items()} #remove duplicates +def_vals = [(address, sig) for address, sig in sorted(def_vals.iteritems())] + +if can_dbc.name.startswith("honda") or can_dbc.name.startswith("acura"): + checksum_type = "honda" + checksum_size = 4 +elif can_dbc.name.startswith("toyota") or can_dbc.name.startswith("lexus"): + checksum_type = "toyota" + checksum_size = 8 +else: + checksum_type = None + +for address, msg_name, msg_size, sigs in msgs: + for sig in sigs: + if checksum_type is not None and sig.name == "CHECKSUM": + if sig.size != checksum_size: + sys.exit("CHECKSUM is not %d bits longs %s" % (checksum_size, msg_name)) + if checksum_type == "honda" and sig.start_bit % 8 != 3: + sys.exit("CHECKSUM starts at wrong bit %s" % msg_name) + if checksum_type == "toyota" and sig.start_bit % 8 != 7: + sys.exit("CHECKSUM starts at wrong bit %s" % msg_name) + if checksum_type == "honda" and sig.name == "COUNTER": + if sig.size != 2: + sys.exit("COUNTER is not 2 bits longs %s" % msg_name) + if sig.start_bit % 8 != 5: + sys.exit("COUNTER starts at wrong bit %s" % msg_name) + + +# Fail on duplicate message names +c = Counter([msg_name for address, msg_name, msg_size, sigs in msgs]) +for name, count in c.items(): + if count > 1: + sys.exit("Duplicate message name in DBC file %s" % name) + +parser_code = template.render(dbc=can_dbc, checksum_type=checksum_type, msgs=msgs, def_vals=def_vals, len=len) + +with open(out_fn, "w") as out_f: + out_f.write(parser_code) diff --git a/selfdrive/car/__init__.py b/selfdrive/car/__init__.py new file mode 100644 index 00000000000000..f5c30921a0549b --- /dev/null +++ b/selfdrive/car/__init__.py @@ -0,0 +1,47 @@ +# functions common among cars +from common.numpy_fast import clip + + +def dbc_dict(pt_dbc, radar_dbc, chassis_dbc=None): + return {'pt': pt_dbc, 'radar': radar_dbc, 'chassis': chassis_dbc} + + +def apply_std_steer_torque_limits(apply_torque, apply_torque_last, driver_torque, LIMITS): + + # limits due to driver torque + driver_max_torque = LIMITS.STEER_MAX + (LIMITS.STEER_DRIVER_ALLOWANCE + driver_torque * LIMITS.STEER_DRIVER_FACTOR) * LIMITS.STEER_DRIVER_MULTIPLIER + driver_min_torque = -LIMITS.STEER_MAX + (-LIMITS.STEER_DRIVER_ALLOWANCE + driver_torque * LIMITS.STEER_DRIVER_FACTOR) * LIMITS.STEER_DRIVER_MULTIPLIER + max_steer_allowed = max(min(LIMITS.STEER_MAX, driver_max_torque), 0) + min_steer_allowed = min(max(-LIMITS.STEER_MAX, driver_min_torque), 0) + apply_torque = clip(apply_torque, min_steer_allowed, max_steer_allowed) + + # slow rate if steer torque increases in magnitude + if apply_torque_last > 0: + apply_torque = clip(apply_torque, max(apply_torque_last - LIMITS.STEER_DELTA_DOWN, -LIMITS.STEER_DELTA_UP), + apply_torque_last + LIMITS.STEER_DELTA_UP) + else: + apply_torque = clip(apply_torque, apply_torque_last - LIMITS.STEER_DELTA_UP, + min(apply_torque_last + LIMITS.STEER_DELTA_DOWN, LIMITS.STEER_DELTA_UP)) + + return int(round(apply_torque)) + + +def apply_toyota_steer_torque_limits(apply_torque, apply_torque_last, motor_torque, LIMITS): + + # limits due to comparison of commanded torque VS motor reported torque + max_lim = min(max(motor_torque + LIMITS.STEER_ERROR_MAX, LIMITS.STEER_ERROR_MAX), LIMITS.STEER_MAX) + min_lim = max(min(motor_torque - LIMITS.STEER_ERROR_MAX, -LIMITS.STEER_ERROR_MAX), -LIMITS.STEER_MAX) + + apply_torque = clip(apply_torque, min_lim, max_lim) + + # slow rate if steer torque increases in magnitude + if apply_torque_last > 0: + apply_torque = clip(apply_torque, + max(apply_torque_last - LIMITS.STEER_DELTA_DOWN, -LIMITS.STEER_DELTA_UP), + apply_torque_last + LIMITS.STEER_DELTA_UP) + else: + apply_torque = clip(apply_torque, + apply_torque_last - LIMITS.STEER_DELTA_UP, + min(apply_torque_last + LIMITS.STEER_DELTA_DOWN, LIMITS.STEER_DELTA_UP)) + + return int(round(apply_torque)) diff --git a/selfdrive/car/car_helpers.py b/selfdrive/car/car_helpers.py new file mode 100644 index 00000000000000..58cde11bdf293c --- /dev/null +++ b/selfdrive/car/car_helpers.py @@ -0,0 +1,108 @@ +import os +import time +from common.basedir import BASEDIR +from common.realtime import sec_since_boot +from common.fingerprints import eliminate_incompatible_cars, all_known_cars +from selfdrive.swaglog import cloudlog +import selfdrive.messaging as messaging + +def load_interfaces(x): + ret = {} + for interface in x: + try: + imp = __import__('selfdrive.car.%s.interface' % interface, fromlist=['CarInterface']).CarInterface + except ImportError: + imp = None + for car in x[interface]: + ret[car] = imp + return ret + + +def _get_interface_names(): + # read all the folders in selfdrive/car and return a dict where: + # - keys are all the car names that which we have an interface for + # - values are lists of spefic car models for a given car + interface_names = {} + for car_folder in [x[0] for x in os.walk(BASEDIR + '/selfdrive/car')]: + try: + car_name = car_folder.split('/')[-1] + model_names = __import__('selfdrive.car.%s.values' % car_name, fromlist=['CAR']).CAR + model_names = [getattr(model_names, c) for c in model_names.__dict__.keys() if not c.startswith("__")] + interface_names[car_name] = model_names + except (ImportError, IOError): + pass + + return interface_names + + +# imports from directory selfdrive/car// +interfaces = load_interfaces(_get_interface_names()) + + +# BOUNTY: every added fingerprint in selfdrive/car/*/values.py is a $100 coupon code on shop.comma.ai +# **** for use live only **** +def fingerprint(logcan, timeout): + if os.getenv("SIMULATOR2") is not None: + return ("simulator2", None) + elif os.getenv("SIMULATOR") is not None: + return ("simulator", None) + + cloudlog.warning("waiting for fingerprint...") + candidate_cars = all_known_cars() + finger = {} + st = None + st_passive = sec_since_boot() # only relevant when passive + can_seen = False + while 1: + for a in messaging.drain_sock(logcan): + for can in a.can: + can_seen = True + # ignore everything not on bus 0 and with more than 11 bits, + # which are ussually sporadic and hard to include in fingerprints + if can.src == 0 and can.address < 0x800: + finger[can.address] = len(can.dat) + candidate_cars = eliminate_incompatible_cars(can, candidate_cars) + + if st is None and can_seen: + st = sec_since_boot() # start time + ts = sec_since_boot() + # if we only have one car choice and the time_fingerprint since we got our first + # message has elapsed, exit. Toyota needs higher time_fingerprint, since DSU does not + # broadcast immediately + if len(candidate_cars) == 1 and st is not None: + # TODO: better way to decide to wait more if Toyota + time_fingerprint = 1.0 if ("TOYOTA" in candidate_cars[0] or "LEXUS" in candidate_cars[0]) else 0.1 + if (ts-st) > time_fingerprint: + break + + # bail if no cars left or we've been waiting too long + elif len(candidate_cars) == 0 or (timeout and (ts - st_passive) > timeout): + return None, finger + + time.sleep(0.01) + + cloudlog.warning("fingerprinted %s", candidate_cars[0]) + return (candidate_cars[0], finger) + + +def get_car(logcan, sendcan=None, passive=True): + # TODO: timeout only useful for replays so controlsd can start before unlogger + timeout = 2. if passive else None + candidate, fingerprints = fingerprint(logcan, timeout) + + if candidate is None: + cloudlog.warning("car doesn't match any fingerprints: %r", fingerprints) + if passive: + candidate = "mock" + else: + return None, None + + interface_cls = interfaces[candidate] + + if interface_cls is None: + cloudlog.warning("car matched %s, but interface wasn't available or failed to import" % candidate) + return None, None + + params = interface_cls.get_params(candidate, fingerprints) + + return interface_cls(params, sendcan), params diff --git a/selfdrive/car/chrysler/__init__.py b/selfdrive/car/chrysler/__init__.py new file mode 100644 index 00000000000000..e69de29bb2d1d6 diff --git a/selfdrive/car/chrysler/carcontroller.py b/selfdrive/car/chrysler/carcontroller.py new file mode 100644 index 00000000000000..d6561768cace2f --- /dev/null +++ b/selfdrive/car/chrysler/carcontroller.py @@ -0,0 +1,92 @@ +from cereal import car +from selfdrive.boardd.boardd import can_list_to_can_capnp +from selfdrive.car import apply_toyota_steer_torque_limits +from selfdrive.car.chrysler.chryslercan import create_lkas_hud, create_lkas_command, \ + create_wheel_buttons, create_lkas_heartbit, \ + create_chimes +from selfdrive.car.chrysler.values import ECU +from selfdrive.can.packer import CANPacker + +AudibleAlert = car.CarControl.HUDControl.AudibleAlert +LOUD_ALERTS = [AudibleAlert.chimeWarning1, AudibleAlert.chimeWarning2, AudibleAlert.chimeWarningRepeat] + +class SteerLimitParams: + STEER_MAX = 261 # 262 faults + STEER_DELTA_UP = 3 # 3 is stock. 100 is fine. 200 is too much it seems + STEER_DELTA_DOWN = 3 # no faults on the way down it seems + STEER_ERROR_MAX = 80 + + +class CarController(object): + def __init__(self, dbc_name, car_fingerprint, enable_camera): + self.braking = False + # redundant safety check with the board + self.controls_allowed = True + self.apply_steer_last = 0 + self.ccframe = 0 + self.prev_frame = -1 + self.car_fingerprint = car_fingerprint + self.alert_active = False + self.send_chime = False + + self.fake_ecus = set() + if enable_camera: + self.fake_ecus.add(ECU.CAM) + + self.packer = CANPacker(dbc_name) + + + def update(self, sendcan, enabled, CS, frame, actuators, + pcm_cancel_cmd, hud_alert, audible_alert): + + # this seems needed to avoid steerign faults and to force the sync with the EPS counter + if self.prev_frame == frame: + return + + # *** compute control surfaces *** + # steer torque + apply_steer = actuators.steer * SteerLimitParams.STEER_MAX + apply_steer = apply_toyota_steer_torque_limits(apply_steer, self.apply_steer_last, + CS.steer_torque_motor, SteerLimitParams) + + moving_fast = CS.v_ego > CS.CP.minSteerSpeed # for status message + lkas_active = moving_fast and enabled + + if not lkas_active: + apply_steer = 0 + + self.apply_steer_last = apply_steer + + if audible_alert in LOUD_ALERTS: + self.send_chime = True + + can_sends = [] + + #*** control msgs *** + + if self.send_chime: + new_msg = create_chimes(AudibleAlert) + can_sends.append(new_msg) + if audible_alert not in LOUD_ALERTS: + self.send_chime = False + + if pcm_cancel_cmd: + # TODO: would be better to start from frame_2b3 + new_msg = create_wheel_buttons(self.ccframe) + can_sends.append(new_msg) + + # frame is 100Hz (0.01s period) + if (self.ccframe % 10 == 0): # 0.1s period + new_msg = create_lkas_heartbit(self.car_fingerprint) + can_sends.append(new_msg) + + if (self.ccframe % 25 == 0): # 0.25s period + new_msg = create_lkas_hud(CS.gear_shifter, lkas_active, hud_alert, self.car_fingerprint) + can_sends.append(new_msg) + + new_msg = create_lkas_command(self.packer, int(apply_steer), frame) + can_sends.append(new_msg) + + self.ccframe += 1 + self.prev_frame = frame + sendcan.send(can_list_to_can_capnp(can_sends, msgtype='sendcan').to_bytes()) diff --git a/selfdrive/car/chrysler/carstate.py b/selfdrive/car/chrysler/carstate.py new file mode 100644 index 00000000000000..2a0569edad6c9e --- /dev/null +++ b/selfdrive/car/chrysler/carstate.py @@ -0,0 +1,142 @@ +from selfdrive.can.parser import CANParser +from selfdrive.car.chrysler.values import DBC, STEER_THRESHOLD +from common.kalman.simple_kalman import KF1D +import numpy as np + + +def parse_gear_shifter(can_gear): + if can_gear == 0x1: + return "park" + elif can_gear == 0x2: + return "reverse" + elif can_gear == 0x3: + return "neutral" + elif can_gear == 0x4: + return "drive" + return "unknown" + + +def get_can_parser(CP): + + signals = [ + # sig_name, sig_address, default + ("PRNDL", "GEAR", 0), + ("DOOR_OPEN_FL", "DOORS", 0), + ("DOOR_OPEN_FR", "DOORS", 0), + ("DOOR_OPEN_RL", "DOORS", 0), + ("DOOR_OPEN_RR", "DOORS", 0), + ("BRAKE_PRESSED_2", "BRAKE_2", 0), + ("ACCEL_PEDAL", "ACCEL_PEDAL_MSG", 0), + ("SPEED_LEFT", "SPEED_1", 0), + ("SPEED_RIGHT", "SPEED_1", 0), + ("WHEEL_SPEED_FL", "WHEEL_SPEEDS", 0), + ("WHEEL_SPEED_RR", "WHEEL_SPEEDS", 0), + ("WHEEL_SPEED_RL", "WHEEL_SPEEDS", 0), + ("WHEEL_SPEED_FR", "WHEEL_SPEEDS", 0), + ("STEER_ANGLE", "STEERING", 0), + ("STEERING_RATE", "STEERING", 0), + ("TURN_SIGNALS", "STEERING_LEVERS", 0), + ("ACC_STATUS_2", "ACC_2", 0), + ("HIGH_BEAM_FLASH", "STEERING_LEVERS", 0), + ("ACC_SPEED_CONFIG_KPH", "DASHBOARD", 0), + ("TORQUE_DRIVER", "EPS_STATUS", 0), + ("TORQUE_MOTOR", "EPS_STATUS", 0), + ("LKAS_STATE", "EPS_STATUS", 1), + ("COUNTER", "EPS_STATUS", -1), + ("TRACTION_OFF", "TRACTION_BUTTON", 0), + ("SEATBELT_DRIVER_UNLATCHED", "SEATBELT_STATUS", 0), + ("COUNTER", "WHEEL_BUTTONS", -1), # incrementing counter for 23b + ] + + # It's considered invalid if it is not received for 10x the expected period (1/f). + checks = [ + # sig_address, frequency + ("BRAKE_2", 50), + ("EPS_STATUS", 100), + ("SPEED_1", 100), + ("WHEEL_SPEEDS", 50), + ("STEERING", 100), + ("ACC_2", 50), + ] + + return CANParser(DBC[CP.carFingerprint]['pt'], signals, checks, 0) + + +class CarState(object): + def __init__(self, CP): + + self.CP = CP + self.left_blinker_on = 0 + self.right_blinker_on = 0 + + # initialize can parser + self.car_fingerprint = CP.carFingerprint + + # vEgo kalman filter + dt = 0.01 + # Q = np.matrix([[10.0, 0.0], [0.0, 100.0]]) + # R = 1e3 + self.v_ego_kf = KF1D(x0=np.matrix([[0.0], [0.0]]), + A=np.matrix([[1.0, dt], [0.0, 1.0]]), + C=np.matrix([1.0, 0.0]), + K=np.matrix([[0.12287673], [0.29666309]])) + self.v_ego = 0.0 + + + def update(self, cp): + # copy can_valid + self.can_valid = cp.can_valid + + # update prevs, update must run once per loop + self.prev_left_blinker_on = self.left_blinker_on + self.prev_right_blinker_on = self.right_blinker_on + + self.frame_23b = int(cp.vl["WHEEL_BUTTONS"]['COUNTER']) + self.frame = int(cp.vl["EPS_STATUS"]['COUNTER']) + + self.door_all_closed = not any([cp.vl["DOORS"]['DOOR_OPEN_FL'], + cp.vl["DOORS"]['DOOR_OPEN_FR'], + cp.vl["DOORS"]['DOOR_OPEN_RL'], + cp.vl["DOORS"]['DOOR_OPEN_RR']]) + self.seatbelt = (cp.vl["SEATBELT_STATUS"]['SEATBELT_DRIVER_UNLATCHED'] == 0) + + self.brake_pressed = cp.vl["BRAKE_2"]['BRAKE_PRESSED_2'] == 5 # human-only + self.pedal_gas = cp.vl["ACCEL_PEDAL_MSG"]['ACCEL_PEDAL'] + self.car_gas = self.pedal_gas + self.esp_disabled = (cp.vl["TRACTION_BUTTON"]['TRACTION_OFF'] == 1) + + self.v_wheel_fl = cp.vl['WHEEL_SPEEDS']['WHEEL_SPEED_FL'] + self.v_wheel_rr = cp.vl['WHEEL_SPEEDS']['WHEEL_SPEED_RR'] + self.v_wheel_rl = cp.vl['WHEEL_SPEEDS']['WHEEL_SPEED_RL'] + self.v_wheel_fr = cp.vl['WHEEL_SPEEDS']['WHEEL_SPEED_FR'] + self.v_wheel = (cp.vl['SPEED_1']['SPEED_LEFT'] + cp.vl['SPEED_1']['SPEED_RIGHT']) / 2. + + # Kalman filter + if abs(self.v_wheel - self.v_ego) > 2.0: # Prevent large accelerations when car starts at non zero speed + self.v_ego_x = np.matrix([[self.v_wheel], [0.0]]) + + self.v_ego_raw = self.v_wheel + v_ego_x = self.v_ego_kf.update(self.v_wheel) + self.v_ego = float(v_ego_x[0]) + self.a_ego = float(v_ego_x[1]) + self.standstill = not self.v_wheel > 0.001 + + self.angle_steers = cp.vl["STEERING"]['STEER_ANGLE'] + self.angle_steers_rate = cp.vl["STEERING"]['STEERING_RATE'] + self.gear_shifter = parse_gear_shifter(cp.vl['GEAR']['PRNDL']) + self.main_on = cp.vl["ACC_2"]['ACC_STATUS_2'] == 7 # ACC is green. + self.left_blinker_on = cp.vl["STEERING_LEVERS"]['TURN_SIGNALS'] == 1 + self.right_blinker_on = cp.vl["STEERING_LEVERS"]['TURN_SIGNALS'] == 2 + + self.steer_torque_driver = cp.vl["EPS_STATUS"]["TORQUE_DRIVER"] + self.steer_torque_motor = cp.vl["EPS_STATUS"]["TORQUE_MOTOR"] + self.steer_override = abs(self.steer_torque_driver) > STEER_THRESHOLD + steer_state = cp.vl["EPS_STATUS"]["LKAS_STATE"] + self.steer_error = steer_state == 4 or (steer_state == 0 and self.v_ego > self.CP.minSteerSpeed) + + self.user_brake = 0 + self.brake_lights = self.brake_pressed + self.v_cruise_pcm = cp.vl["DASHBOARD"]['ACC_SPEED_CONFIG_KPH'] + self.pcm_acc_status = self.main_on + + self.generic_toggle = bool(cp.vl["STEERING_LEVERS"]['HIGH_BEAM_FLASH']) diff --git a/selfdrive/car/chrysler/chryslercan.py b/selfdrive/car/chrysler/chryslercan.py new file mode 100644 index 00000000000000..93059001007d00 --- /dev/null +++ b/selfdrive/car/chrysler/chryslercan.py @@ -0,0 +1,121 @@ +from cereal import car +from selfdrive.car.chrysler.values import CAR + + +VisualAlert = car.CarControl.HUDControl.VisualAlert +AudibleAlert = car.CarControl.HUDControl.AudibleAlert + + +def calc_checksum(data): + """This function does not want the checksum byte in the input data. + + jeep chrysler canbus checksum from http://illmatics.com/Remote%20Car%20Hacking.pdf + """ + end_index = len(data) + index = 0 + checksum = 0xFF + temp_chk = 0; + bit_sum = 0; + if(end_index <= index): + return False + for index in range(0, end_index): + shift = 0x80 + curr = data[index] + iterate = 8 + while(iterate > 0): + iterate -= 1 + bit_sum = curr & shift; + temp_chk = checksum & 0x80 + if (bit_sum != 0): + bit_sum = 0x1C + if (temp_chk != 0): + bit_sum = 1 + checksum = checksum << 1 + temp_chk = checksum | 1 + bit_sum ^= temp_chk + else: + if (temp_chk != 0): + bit_sum = 0x1D + checksum = checksum << 1 + bit_sum ^= checksum + checksum = bit_sum + shift = shift >> 1 + return ~checksum & 0xFF + + +def make_can_msg(addr, dat): + return [addr, 0, dat, 0] + +def create_lkas_heartbit(car_fingerprint): + # LKAS_HEARTBIT (729) Lane-keeping heartbeat. + msg = '0000000820'.decode('hex') # 2017 + return make_can_msg(0x2d9, msg) + +def create_lkas_hud(gear, lkas_active, hud_alert, car_fingerprint): + # LKAS_HUD (678) Controls what lane-keeping icon is displayed. + + if hud_alert == VisualAlert.steerRequired: + msg = msg = '0000000300000000'.decode('hex') + return make_can_msg(0x2a6, msg) + + # TODO: use can packer + msg = '0000000000000000'.decode('hex') # park or neutral + if car_fingerprint == CAR.PACIFICA_2018: + msg = '0064000000000000'.decode('hex') # Have not verified 2018 park with a real car. + elif car_fingerprint == CAR.JEEP_CHEROKEE: + msg = '00a4000000000000'.decode('hex') # Have not verified 2018 park with a real car. + elif car_fingerprint == CAR.PACIFICA_2018_HYBRID: + msg = '01a8010000000000'.decode('hex') + if (gear == 'drive' or gear == 'reverse'): + if lkas_active: + msg = '0200060000000000'.decode('hex') # control active, display green. + if car_fingerprint == CAR.PACIFICA_2018: + msg = '0264060000000000'.decode('hex') + elif car_fingerprint == CAR.JEEP_CHEROKEE: + msg = '02a4060000000000'.decode('hex') + elif car_fingerprint == CAR.PACIFICA_2018_HYBRID: + msg = '02a8060000000000'.decode('hex') + else: + msg = '0100010000000000'.decode('hex') # control off, display white. + if car_fingerprint == CAR.PACIFICA_2018: + msg = '0164010000000000'.decode('hex') + elif car_fingerprint == CAR.JEEP_CHEROKEE: + msg = '01a4010000000000'.decode('hex') + elif car_fingerprint == CAR.PACIFICA_2018_HYBRID: + msg = '01a8010000000000'.decode('hex') + + return make_can_msg(0x2a6, msg) + + +def create_lkas_command(packer, apply_steer, frame): + # LKAS_COMMAND (658) Lane-keeping signal to turn the wheel. + values = { + "LKAS_STEERING_TORQUE": apply_steer, + "LKAS_HIGH_TORQUE": 1, + "COUNTER": frame % 0x10, + } + + dat = packer.make_can_msg("LKAS_COMMAND", 0, values)[2] + dat = [ord(i) for i in dat][:-1] + checksum = calc_checksum(dat) + + values["CHECKSUM"] = checksum + return packer.make_can_msg("LKAS_COMMAND", 0, values) + + +def create_chimes(audible_alert): + # '0050' nothing, chime '4f55' + if audible_alert == AudibleAlert.none: + msg = '0050'.decode('hex') + else: + msg = '4f55'.decode('hex') + return make_can_msg(0x339, msg) + + +def create_wheel_buttons(frame): + # WHEEL_BUTTONS (571) Message sent to cancel ACC. + start = [0x01] # acc cancel set + counter = (frame % 10) << 4 + dat = start + [counter] + dat = dat + [calc_checksum(dat)] + return make_can_msg(0x23b, str(bytearray(dat))) diff --git a/selfdrive/car/chrysler/interface.py b/selfdrive/car/chrysler/interface.py new file mode 100755 index 00000000000000..f681a45cbf3d54 --- /dev/null +++ b/selfdrive/car/chrysler/interface.py @@ -0,0 +1,267 @@ +#!/usr/bin/env python +from common.realtime import sec_since_boot +from cereal import car, log +from selfdrive.config import Conversions as CV +from selfdrive.controls.lib.drive_helpers import EventTypes as ET, create_event +from selfdrive.controls.lib.vehicle_model import VehicleModel +from selfdrive.car.chrysler.carstate import CarState, get_can_parser +from selfdrive.car.chrysler.values import ECU, check_ecu_msgs, CAR + +try: + from selfdrive.car.chrysler.carcontroller import CarController +except ImportError: + CarController = None + + +class CarInterface(object): + def __init__(self, CP, sendcan=None): + self.CP = CP + self.VM = VehicleModel(CP) + + self.frame = 0 + self.can_invalid_count = 0 + self.gas_pressed_prev = False + self.brake_pressed_prev = False + self.cruise_enabled_prev = False + self.low_speed_alert = False + + # *** init the major players *** + self.CS = CarState(CP) + + self.cp = get_can_parser(CP) + + # sending if read only is False + if sendcan is not None: + self.sendcan = sendcan + self.CC = CarController(self.cp.dbc_name, CP.carFingerprint, CP.enableCamera) + + @staticmethod + def compute_gb(accel, speed): + return float(accel) / 3.0 + + @staticmethod + def calc_accel_override(a_ego, a_target, v_ego, v_target): + return 1.0 + + @staticmethod + def get_params(candidate, fingerprint): + + # kg of standard extra cargo to count for drive, gas, etc... + std_cargo = 136 + + ret = car.CarParams.new_message() + + ret.carName = "chrysler" + ret.carFingerprint = candidate + + ret.safetyModel = car.CarParams.SafetyModels.chrysler + + # pedal + ret.enableCruise = True + + # FIXME: hardcoding honda civic 2016 touring params so they can be used to + # scale unknown params for other cars + mass_civic = 2923./2.205 + std_cargo + wheelbase_civic = 2.70 + centerToFront_civic = wheelbase_civic * 0.4 + centerToRear_civic = wheelbase_civic - centerToFront_civic + rotationalInertia_civic = 2500 + tireStiffnessFront_civic = 85400 * 2.0 + tireStiffnessRear_civic = 90000 * 2.0 + + # Speed conversion: 20, 45 mph + ret.steerKpBP, ret.steerKiBP = [[9., 20.], [9., 20.]] + ret.wheelbase = 3.089 # in meters for Pacifica Hybrid 2017 + ret.steerRatio = 16.2 # Pacifica Hybrid 2017 + ret.mass = 2858 + std_cargo # kg curb weight Pacifica Hybrid 2017 + ret.steerKpV, ret.steerKiV = [[0.15,0.30], [0.03,0.05]] + ret.steerKf = 0.00006 # full torque for 10 deg at 80mph means 0.00007818594 + ret.steerActuatorDelay = 0.1 + ret.steerRateCost = 0.7 + + if candidate == CAR.JEEP_CHEROKEE: + ret.wheelbase = 2.91 # in meters + + ret.centerToFront = ret.wheelbase * 0.44 + + ret.longPidDeadzoneBP = [0., 9.] + ret.longPidDeadzoneV = [0., .15] + + ret.minSteerSpeed = 3.8 # m/s + ret.minEnableSpeed = -1. # enable is done by stock ACC, so ignore this + + centerToRear = ret.wheelbase - ret.centerToFront + # TODO: get actual value, for now starting with reasonable value for + # civic and scaling by mass and wheelbase + ret.rotationalInertia = rotationalInertia_civic * \ + ret.mass * ret.wheelbase**2 / (mass_civic * wheelbase_civic**2) + + # TODO: start from empirically derived lateral slip stiffness for the civic and scale by + # mass and CG position, so all cars will have approximately similar dyn behaviors + ret.tireStiffnessFront = tireStiffnessFront_civic * \ + ret.mass / mass_civic * \ + (centerToRear / ret.wheelbase) / (centerToRear_civic / wheelbase_civic) + ret.tireStiffnessRear = tireStiffnessRear_civic * \ + ret.mass / mass_civic * \ + (ret.centerToFront / ret.wheelbase) / (centerToFront_civic / wheelbase_civic) + + # no rear steering, at least on the listed cars above + ret.steerRatioRear = 0. + + # steer, gas, brake limitations VS speed + ret.steerMaxBP = [16. * CV.KPH_TO_MS, 45. * CV.KPH_TO_MS] # breakpoints at 1 and 40 kph + ret.steerMaxV = [1., 1.] # 2/3rd torque allowed above 45 kph + ret.gasMaxBP = [0.] + ret.gasMaxV = [0.5] + ret.brakeMaxBP = [5., 20.] + ret.brakeMaxV = [1., 0.8] + + ret.enableCamera = not check_ecu_msgs(fingerprint, ECU.CAM) + print "ECU Camera Simulated: ", ret.enableCamera + ret.openpilotLongitudinalControl = False + + ret.steerLimitAlert = True + ret.stoppingControl = False + ret.startAccel = 0.0 + + ret.longitudinalKpBP = [0., 5., 35.] + ret.longitudinalKpV = [3.6, 2.4, 1.5] + ret.longitudinalKiBP = [0., 35.] + ret.longitudinalKiV = [0.54, 0.36] + + return ret + + # returns a car.CarState + def update(self, c): + # ******************* do can recv ******************* + canMonoTimes = [] + + self.cp.update(int(sec_since_boot() * 1e9), False) + + self.CS.update(self.cp) + + # create message + ret = car.CarState.new_message() + + # speeds + ret.vEgo = self.CS.v_ego + ret.vEgoRaw = self.CS.v_ego_raw + ret.aEgo = self.CS.a_ego + ret.yawRate = self.VM.yaw_rate(self.CS.angle_steers * CV.DEG_TO_RAD, self.CS.v_ego) + ret.standstill = self.CS.standstill + ret.wheelSpeeds.fl = self.CS.v_wheel_fl + ret.wheelSpeeds.fr = self.CS.v_wheel_fr + ret.wheelSpeeds.rl = self.CS.v_wheel_rl + ret.wheelSpeeds.rr = self.CS.v_wheel_rr + + # gear shifter + ret.gearShifter = self.CS.gear_shifter + + # gas pedal + ret.gas = self.CS.car_gas + ret.gasPressed = self.CS.pedal_gas > 0 + + # brake pedal + ret.brake = self.CS.user_brake + ret.brakePressed = self.CS.brake_pressed + ret.brakeLights = self.CS.brake_lights + + # steering wheel + ret.steeringAngle = self.CS.angle_steers + ret.steeringRate = self.CS.angle_steers_rate + + ret.steeringTorque = self.CS.steer_torque_driver + ret.steeringPressed = self.CS.steer_override + + # cruise state + ret.cruiseState.enabled = self.CS.pcm_acc_status # same as main_on + ret.cruiseState.speed = self.CS.v_cruise_pcm * CV.KPH_TO_MS + ret.cruiseState.available = self.CS.main_on + ret.cruiseState.speedOffset = 0. + # ignore standstill in hybrid rav4, since pcm allows to restart without + # receiving any special command + ret.cruiseState.standstill = False + + # TODO: button presses + buttonEvents = [] + + if self.CS.left_blinker_on != self.CS.prev_left_blinker_on: + be = car.CarState.ButtonEvent.new_message() + be.type = 'leftBlinker' + be.pressed = self.CS.left_blinker_on != 0 + buttonEvents.append(be) + + if self.CS.right_blinker_on != self.CS.prev_right_blinker_on: + be = car.CarState.ButtonEvent.new_message() + be.type = 'rightBlinker' + be.pressed = self.CS.right_blinker_on != 0 + buttonEvents.append(be) + + ret.buttonEvents = buttonEvents + ret.leftBlinker = bool(self.CS.left_blinker_on) + ret.rightBlinker = bool(self.CS.right_blinker_on) + + ret.doorOpen = not self.CS.door_all_closed + ret.seatbeltUnlatched = not self.CS.seatbelt + self.low_speed_alert = (ret.vEgo < self.CP.minSteerSpeed) + + ret.genericToggle = self.CS.generic_toggle + + # events + events = [] + if not self.CS.can_valid: + self.can_invalid_count += 1 + if self.can_invalid_count >= 5: + events.append(create_event('commIssue', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE])) + else: + self.can_invalid_count = 0 + if not ret.gearShifter == 'drive': + events.append(create_event('wrongGear', [ET.NO_ENTRY, ET.SOFT_DISABLE])) + if ret.doorOpen: + events.append(create_event('doorOpen', [ET.NO_ENTRY, ET.SOFT_DISABLE])) + if ret.seatbeltUnlatched: + events.append(create_event('seatbeltNotLatched', [ET.NO_ENTRY, ET.SOFT_DISABLE])) + if self.CS.esp_disabled: + events.append(create_event('espDisabled', [ET.NO_ENTRY, ET.SOFT_DISABLE])) + if not self.CS.main_on: + events.append(create_event('wrongCarMode', [ET.NO_ENTRY, ET.USER_DISABLE])) + if ret.gearShifter == 'reverse': + events.append(create_event('reverseGear', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE])) + if self.CS.steer_error: + events.append(create_event('steerUnavailable', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE, ET.PERMANENT])) + + if ret.cruiseState.enabled and not self.cruise_enabled_prev: + events.append(create_event('pcmEnable', [ET.ENABLE])) + elif not ret.cruiseState.enabled: + events.append(create_event('pcmDisable', [ET.USER_DISABLE])) + + # disable on gas pedal and speed isn't zero. Gas pedal is used to resume ACC + # from a 3+ second stop. + if (ret.gasPressed and (not self.gas_pressed_prev) and ret.vEgo > 2.0): + events.append(create_event('pedalPressed', [ET.NO_ENTRY, ET.USER_DISABLE])) + + if self.low_speed_alert: + events.append(create_event('belowSteerSpeed', [ET.WARNING])) + + ret.events = events + ret.canMonoTimes = canMonoTimes + + self.gas_pressed_prev = ret.gasPressed + self.brake_pressed_prev = ret.brakePressed + self.cruise_enabled_prev = ret.cruiseState.enabled + + return ret.as_reader() + + # pass in a car.CarControl + # to be called @ 100hz + def apply(self, c, perception_state=log.Live20Data.new_message()): + + if (self.CS.frame == -1): + return False # if we haven't seen a frame 220, then do not update. + + self.frame = self.CS.frame + self.CC.update(self.sendcan, c.enabled, self.CS, self.frame, + c.actuators, c.cruiseControl.cancel, c.hudControl.visualAlert, + c.hudControl.audibleAlert) + + return False diff --git a/selfdrive/car/chrysler/radar_interface.py b/selfdrive/car/chrysler/radar_interface.py new file mode 100755 index 00000000000000..60eaa4566a8819 --- /dev/null +++ b/selfdrive/car/chrysler/radar_interface.py @@ -0,0 +1,107 @@ +#!/usr/bin/env python +import os +from selfdrive.can.parser import CANParser +from cereal import car +from common.realtime import sec_since_boot +import zmq +from selfdrive.services import service_list +import selfdrive.messaging as messaging + + +RADAR_MSGS_C = range(0x2c2, 0x2d4+2, 2) # c_ messages 706,...,724 +RADAR_MSGS_D = range(0x2a2, 0x2b4+2, 2) # d_ messages +LAST_MSG = max(RADAR_MSGS_C + RADAR_MSGS_D) +NUMBER_MSGS = len(RADAR_MSGS_C) + len(RADAR_MSGS_D) + +def _create_radard_can_parser(): + dbc_f = 'chrysler_pacifica_2017_hybrid_private_fusion.dbc' + msg_n = len(RADAR_MSGS_C) + # list of [(signal name, message name or number, initial values), (...)] + # [('RADAR_STATE', 1024, 0), + # ('LONG_DIST', 1072, 255), + # ('LONG_DIST', 1073, 255), + # ('LONG_DIST', 1074, 255), + # ('LONG_DIST', 1075, 255), + + # The factor and offset are applied by the dbc parsing library, so the + # default values should be after the factor/offset are applied. + signals = zip(['LONG_DIST'] * msg_n + + ['LAT_DIST'] * msg_n + + ['REL_SPEED'] * msg_n, + RADAR_MSGS_C * 2 + # LONG_DIST, LAT_DIST + RADAR_MSGS_D, # REL_SPEED + [0] * msg_n + # LONG_DIST + [-1000] * msg_n + # LAT_DIST + [-146.278] * msg_n) # REL_SPEED set to 0, factor/offset to this + # TODO what are the checks actually used for? + # honda only checks the last message, + # toyota checks all the messages. Which do we want? + checks = zip(RADAR_MSGS_C + + RADAR_MSGS_D, + [20]*msg_n + # 20Hz (0.05s) + [20]*msg_n) # 20Hz (0.05s) + + return CANParser(os.path.splitext(dbc_f)[0], signals, checks, 1) + +def _address_to_track(address): + if address in RADAR_MSGS_C: + return (address - RADAR_MSGS_C[0]) / 2 + if address in RADAR_MSGS_D: + return (address - RADAR_MSGS_D[0]) / 2 + raise ValueError("radar received unexpected address %d" % address) + +class RadarInterface(object): + def __init__(self, CP): + self.pts = {} + self.delay = 0.0 # Delay of radar #TUNE + self.rcp = _create_radard_can_parser() + context = zmq.Context() + self.logcan = messaging.sub_sock(context, service_list['can'].port) + + def update(self): + canMonoTimes = [] + + updated_messages = set() # set of message IDs (sig_addresses) we've seen + + while 1: + tm = int(sec_since_boot() * 1e9) + updated_messages.update(self.rcp.update(tm, True)) + if LAST_MSG in updated_messages: + break + + ret = car.RadarState.new_message() + errors = [] + if not self.rcp.can_valid: + errors.append("commIssue") + ret.errors = errors + ret.canMonoTimes = canMonoTimes + + for ii in updated_messages: # ii should be the message ID as a number + cpt = self.rcp.vl[ii] + trackId = _address_to_track(ii) + + if trackId not in self.pts: + self.pts[trackId] = car.RadarState.RadarPoint.new_message() + self.pts[trackId].trackId = trackId + self.pts[trackId].aRel = float('nan') + self.pts[trackId].yvRel = float('nan') + self.pts[trackId].measured = True + + if 'LONG_DIST' in cpt: # c_* message + self.pts[trackId].dRel = cpt['LONG_DIST'] # from front of car + # our lat_dist is positive to the right in car's frame. + # TODO what does yRel want? + self.pts[trackId].yRel = cpt['LAT_DIST'] # in car frame's y axis, left is positive + else: # d_* message + self.pts[trackId].vRel = cpt['REL_SPEED'] + + # We want a list, not a dictionary. Filter out LONG_DIST==0 because that means it's not valid. + ret.points = [x for x in self.pts.values() if x.dRel != 0] + return ret + +if __name__ == "__main__": + RI = RadarInterface(None) + while 1: + ret = RI.update() + print(chr(27) + "[2J") # clear screen + print ret diff --git a/selfdrive/car/chrysler/values.py b/selfdrive/car/chrysler/values.py new file mode 100644 index 00000000000000..8f89924dfc6211 --- /dev/null +++ b/selfdrive/car/chrysler/values.py @@ -0,0 +1,77 @@ +from selfdrive.car import dbc_dict + +class CAR: + PACIFICA_2017_HYBRID = "CHRYSLER PACIFICA HYBRID 2017" + PACIFICA_2018_HYBRID = "CHRYSLER PACIFICA HYBRID 2018" # Also covers Pacifica 2019 Hybrid. + PACIFICA_2018 = "CHRYSLER PACIFICA 2018" + JEEP_CHEROKEE = "JEEP GRAND CHEROKEE V6 2018" # Also covers Tailhawk 2017. + +# Unique can messages: +# Only the hybrids have 270: 8 +# Only the gas have 55: 8, 416: 7 +# For 564, Pacifica 2017 has length 4, whereas Pacifica 2018-19 have length 8. +# For 924, Pacifica 2017 has length 3, whereas all 2018-19 have length 8. +# For 560, Pacifica 2019 Hybrid has length 8, whereas all 2017-18 have length 4. + +# Jeep Grand Cherokee unique messages: +# 2017 Trailhawk: 618: 8 +# For 924, Trailhawk 2017 has length 3, whereas 2018 V6 has length 8. + +# TODO: verify everything is ok for cars that have commented fingerprint, then upstream them + +FINGERPRINTS = { + CAR.PACIFICA_2017_HYBRID: [ + {168: 8, 257: 5, 258: 8, 264: 8, 268: 8, 270: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 291: 8, 292: 8, 294: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 368: 8, 376: 3, 384: 8, 388: 4, 448: 6, 456: 4, 464: 8, 469: 8, 480: 8, 500: 8, 501: 8, 512: 8, 514: 8, 515: 7, 516: 7, 517: 7, 518: 7, 520: 8, 528: 8, 532: 8, 542: 8, 544: 8, 557: 8, 559: 8, 560: 4, 564: 4, 571: 3, 584: 8, 608: 8, 624: 8, 625: 8, 632: 8, 639: 8, 653: 8, 654: 8, 655: 8, 658: 6, 660: 8, 669: 3, 671: 8, 672: 8, 678: 8, 680: 8, 701: 8, 704: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 729: 5, 736: 8, 737: 8, 746: 5, 760: 8, 764: 8, 766: 8, 770: 8, 773: 8, 779: 8, 782: 8, 784: 8, 792: 8, 799: 8, 800: 8, 804: 8, 808: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 832: 8, 838: 2, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 878: 8, 882: 8, 897: 8, 908: 8, 924: 3, 926: 3, 929: 8, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 956: 8, 958: 8, 959: 8, 969: 4, 974: 5, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1082: 8, 1083: 8, 1098: 8, 1100: 8, 1216: 8, 1218: 8, 1220: 8, 1225: 8, 1235: 8, 1242: 8, 1246: 8, 1250: 8, 1284: 8, 1537: 8, 1538: 8, 1562: 8, 1568: 8, 1856: 8, 1858: 8, 1860: 8, 1865: 8, 1875: 8, 1882: 8, 1886: 8, 1890: 8, 1892: 8, 2016: 8, 2024: 8}, + ], + CAR.PACIFICA_2018: [{}], + #CAR.PACIFICA_2018: [ + # {170: 8, 171: 8, 189: 7, 190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 209: 7, 211: 2, 241: 6, 288: 5, 298: 8, 304: 1, 308: 4, 309: 8, 311: 8, 313: 8, 320: 3, 328: 1, 352: 5, 381: 6, 384: 4, 386: 8, 388: 8, 389: 2, 390: 7, 417: 7, 419: 1, 426: 7, 451: 8, 452: 8, 453: 6, 454: 8, 456: 8, 479: 3, 481: 7, 485: 8, 489: 8, 493: 8, 495: 4, 497: 8, 499: 3, 500: 6, 501: 8, 508: 8, 528: 4, 532: 6, 546: 7, 550: 8, 554: 3, 558: 8, 560: 8, 562: 8, 563: 5, 564: 5, 565: 5, 566: 5, 567: 3, 568: 1, 573: 1, 577: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 3, 707: 8, 711: 6, 715: 8, 717: 5, 761: 7, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 869: 4, 880: 6, 961: 8, 967: 4, 969: 8, 977: 8, 979: 7, 988: 6, 989: 8, 995: 7, 1001: 8, 1005: 6, 1009: 8, 1017: 8, 1019: 2, 1020: 8, 1033: 7, 1034: 7, 1105: 6, 1187: 4, 1217: 8, 1221: 5, 1223: 3, 1225: 7, 1227: 4, 1233: 8, 1249: 8, 1257: 6, 1265: 8, 1267: 1, 1273: 3, 1275: 3, 1280: 4, 1296: 4, 1300: 8, 1322: 6, 1323: 4, 1328: 4, 1417: 8, 1601: 8, 1905: 7, 1906: 7, 1907: 7, 1910: 7, 1912: 7, 1922: 7, 1927: 7, 1930: 7, 2016: 8, 2020: 8, 2024: 8, 2028: 8}, + # {55: 8, 257: 5, 258: 8, 264: 8, 268: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 292: 8, 294: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 368: 8, 376: 3, 384: 8, 388: 4, 416: 7, 448: 6, 456: 4, 464: 8, 469: 8, 480: 8, 500: 8, 501: 8, 512: 8, 514: 8, 520: 8, 528: 8, 532: 8, 544: 8, 557: 8, 559: 8, 560: 4, 564: 8, 571: 3, 579: 8, 584: 8, 608: 8, 624: 8, 625: 8, 632: 8, 639: 8, 660: 8, 669: 3, 671: 8, 672: 8, 680: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 736: 8, 746: 5, 752: 2, 760: 8, 764: 8, 766: 8, 770: 8, 773: 8, 779: 8, 784: 8, 792: 8, 799: 8, 800: 8, 804: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 832: 8, 838: 2, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 882: 8, 897: 8, 924: 8, 926: 3, 937: 8, 947: 8, 948: 8, 969: 4, 974: 5, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1098: 8, 1100: 8} + #], + CAR.PACIFICA_2018_HYBRID: [{}], + #CAR.PACIFICA_2018_HYBRID: [ + # {68: 8, 257: 5, 258: 8, 264: 8, 268: 8, 270: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 291: 8, 292: 8, 294: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 368: 8, 376: 3, 384: 8, 388: 4, 448: 6, 456: 4, 464: 8, 469: 8, 480: 8, 500: 8, 501: 8, 512: 8, 514: 8, 520: 8, 528: 8, 532: 8, 544: 8, 557: 8, 559: 8, 560: 4, 564: 8, 571: 3, 579: 8, 584: 8, 608: 8, 624: 8, 625: 8, 632: 8, 639: 8, 653: 8, 654: 8, 655: 8, 660: 8, 669: 3, 671: 8, 672: 8, 680: 8, 701: 8, 704: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 736: 8, 737: 8, 746: 5, 760: 8, 764: 8, 766: 8, 770: 8, 773: 8, 779: 8, 782: 8, 784: 8, 792: 8, 799: 8, 800: 8, 804: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 832: 8, 838: 2, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 878: 8, 882: 8, 897: 8, 908: 8, 924: 8, 926: 3, 929: 8, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 958: 8, 959: 8, 969: 4, 974: 5, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1082: 8, 1083: 8, 1098: 8, 1100: 8}, + # {168: 8, 257: 5, 258: 8, 264: 8, 268: 8, 270: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 291: 8, 292: 8, 294: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 368: 8, 376: 3, 384: 8, 388: 4, 448: 6, 456: 4, 464: 8, 469: 8, 480: 8, 500: 8, 501: 8, 512: 8, 514: 8, 520: 8, 528: 8, 532: 8, 544: 8, 557: 8, 559: 8, 560: 4, 564: 8, 571: 3, 579: 8, 584: 8, 608: 8, 624: 8, 625: 8, 632: 8, 639: 8, 653: 8, 654: 8, 655: 8, 660: 8, 669: 3, 671: 8, 672: 8, 680: 8, 701: 8, 704: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 736: 8, 737: 8, 746: 5, 760: 8, 764: 8, 766: 8, 770: 8, 773: 8, 779: 8, 782: 8, 784: 8, 792: 8, 799: 8, 800: 8, 804: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 832: 8, 838: 2, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 878: 8, 882: 8, 897: 8, 908: 8, 924: 8, 926: 3, 929: 8, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 958: 8, 959: 8, 969: 4, 974: 5, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1082: 8, 1083: 8, 1098: 8, 1100: 8}, + # # Pacifica 2019 Hybrid + # { 168: 8, 257: 5, 258: 8, 264: 8, 268: 8, 270: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 291: 8, 292: 8, 294: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 368: 8, 376: 3, 384: 8, 388: 4, 448: 6, 456: 4, 464: 8, 469: 8, 480: 8, 500: 8, 501: 8, 512: 8, 514: 8, 515: 7, 516: 7, 517: 7, 518: 7, 520: 8, 528: 8, 532: 8, 542: 8, 544: 8, 557: 8, 559: 8, 560: 8, 564: 8, 571: 3, 579: 8, 584: 8, 608: 8, 624: 8, 625: 8, 632: 8, 639: 8, 653: 8, 654: 8, 655: 8, 660: 8, 669: 3, 671: 8, 672: 8, 680: 8, 701: 8, 703: 8, 704: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 736: 8, 737: 8, 746: 5, 752: 2, 754: 8, 760: 8, 764: 8, 766: 8, 770:8, 773: 8, 779: 8, 782: 8, 784: 8, 792: 8, 799: 8, 800: 8, 804: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 832: 8, 838: 2, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 878: 8, 882: 8, 897: 8, 906: 8, 908: 8, 924: 8, 926: 3, 929: 8, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 958: 8, 959: 8, 962: 8, 969: 4, 973: 8, 974: 5, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1082: 8, 1083: 8, 1098: 8, 1100: 8, 1538: 8} + #], + CAR.JEEP_CHEROKEE: [{}], + #CAR.JEEP_CHEROKEE: [ + # # JEEP GRAND CHEROKEE V6 2018 + # {55: 8, 168: 8, 181: 8, 256: 4, 257: 5, 258: 8, 264: 8, 268: 8, 272: 6, 273: 6, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 292: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 352: 8, 362: 8, 368: 8, 376: 3, 384: 8, 388: 4, 416: 7, 448: 6, 456: 4, 464: 8, 500: 8, 501: 8, 512: 8, 514: 8, 520: 8, 532: 8, 544: 8, 557: 8, 559: 8, 560: 4, 564: 4, 571: 3, 579: 8, 584: 8, 608: 8, 624: 8, 625: 8, 632: 8, 639: 8, 656: 4, 658: 6, 660: 8, 671: 8, 672: 8, 676: 8, 678: 8, 680: 8, 683: 8, 684: 8, 703: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 729: 5, 736: 8, 737: 8, 738: 8, 746: 5, 752: 2, 754: 8, 760: 8, 761: 8, 764: 8, 766: 8, 773: 8, 776: 8, 779: 8, 782: 8, 783: 8, 784: 8, 785: 8, 788: 3, 792: 8, 799: 8, 800: 8, 804: 8, 806: 2, 808: 8, 810: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 831: 6, 832: 8, 838: 2, 844: 5, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 882: 8, 897: 8, 906: 8, 924: 8, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 968: 8, 969: 4, 970: 8, 973: 8, 974: 5, 976: 8, 977: 4, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1062: 8, 1098: 8, 1100: 8}, + # # Jeep Grand Cherokee 2017 Trailhawk + # {257: 5, 258: 8, 264: 8, 268: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 292: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 352: 8, 362: 8, 368: 8, 376: 3, 384: 8, 388: 4, 416: 7, 448: 6, 456: 4, 464: 8, 500: 8, 501: 8, 512: 8, 514: 8, 520: 8, 532: 8, 544: 8, 557: 8, 559: 8, 560: 4, 564: 4, 571: 3, 584: 8, 608: 8, 618: 8, 624: 8, 625: 8, 632: 8, 639: 8, 660: 8, 671: 8, 672: 8, 680: 8, 684: 8, 703: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 736: 8, 737: 8, 746: 5, 752: 2, 760: 8, 761: 8, 764: 8, 766: 8, 773: 8, 776: 8, 779: 8, 783: 8, 784: 8, 792: 8, 799: 8, 800: 8, 804: 8, 806: 2, 808: 8, 810: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 831: 6, 832: 8, 838: 2, 844: 5, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 882: 8, 897: 8, 924: 3, 937: 8, 947: 8, 948: 8, 969: 4, 974: 5, 977: 4, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1062: 8, 1098: 8, 1100: 8} + #], +} + + +DBC = { + CAR.PACIFICA_2017_HYBRID: dbc_dict( + 'chrysler_pacifica_2017_hybrid', # 'pt' + 'chrysler_pacifica_2017_hybrid_private_fusion'), # 'radar' + CAR.PACIFICA_2018: dbc_dict( # Same DBC file works. + 'chrysler_pacifica_2017_hybrid', # 'pt' + 'chrysler_pacifica_2017_hybrid_private_fusion'), # 'radar' + CAR.PACIFICA_2018_HYBRID: dbc_dict( # Same DBC file works. + 'chrysler_pacifica_2017_hybrid', # 'pt' + 'chrysler_pacifica_2017_hybrid_private_fusion'), # 'radar' + CAR.JEEP_CHEROKEE: dbc_dict( # Same DBC file works. + 'chrysler_pacifica_2017_hybrid', # 'pt' + 'chrysler_pacifica_2017_hybrid_private_fusion'), # 'radar' +} + +STEER_THRESHOLD = 120 + + +class ECU: + CAM = 0 # LKAS camera + + +ECU_FINGERPRINT = { + ECU.CAM: 0x2d9, # steer torque cmd +} + + +def check_ecu_msgs(fingerprint, ecu): + # return True if fingerprint contains messages normally sent by a given ecu + return ECU_FINGERPRINT[ecu] in fingerprint diff --git a/selfdrive/car/ford/__init__.py b/selfdrive/car/ford/__init__.py new file mode 100644 index 00000000000000..e69de29bb2d1d6 diff --git a/selfdrive/car/ford/carstate.py b/selfdrive/car/ford/carstate.py new file mode 100644 index 00000000000000..c860cfdee4e353 --- /dev/null +++ b/selfdrive/car/ford/carstate.py @@ -0,0 +1,90 @@ +from selfdrive.can.parser import CANParser +from selfdrive.config import Conversions as CV +from selfdrive.car.ford.values import DBC +from common.kalman.simple_kalman import KF1D +import numpy as np + +WHEEL_RADIUS = 0.33 + +def get_can_parser(CP): + + signals = [ + # sig_name, sig_address, default + ("WhlRr_W_Meas", "WheelSpeed_CG1", 0.), + ("WhlRl_W_Meas", "WheelSpeed_CG1", 0.), + ("WhlFr_W_Meas", "WheelSpeed_CG1", 0.), + ("WhlFl_W_Meas", "WheelSpeed_CG1", 0.), + ("SteWhlRelInit_An_Sns", "Steering_Wheel_Data_CG1", 0.), + ("Cruise_State", "Cruise_Status", 0.), + ("Set_Speed", "Cruise_Status", 0.), + ("LaActAvail_D_Actl", "Lane_Keep_Assist_Status", 0), + ("LaHandsOff_B_Actl", "Lane_Keep_Assist_Status", 0), + ("LaActDeny_B_Actl", "Lane_Keep_Assist_Status", 0), + ("ApedPosScal_Pc_Actl", "EngineData_14", 0.), + ("Dist_Incr", "Steering_Buttons", 0.), + ("Brake_Drv_Appl", "Cruise_Status", 0.), + ("Brake_Lights", "BCM_to_HS_Body", 0.), + ] + + checks = [ + ] + + return CANParser(DBC[CP.carFingerprint]['pt'], signals, checks, 0) + + +class CarState(object): + def __init__(self, CP): + + self.CP = CP + self.left_blinker_on = 0 + self.right_blinker_on = 0 + + # initialize can parser + self.car_fingerprint = CP.carFingerprint + + # vEgo kalman filter + dt = 0.01 + # Q = np.matrix([[10.0, 0.0], [0.0, 100.0]]) + # R = 1e3 + self.v_ego_kf = KF1D(x0=np.matrix([[0.0], [0.0]]), + A=np.matrix([[1.0, dt], [0.0, 1.0]]), + C=np.matrix([1.0, 0.0]), + K=np.matrix([[0.12287673], [0.29666309]])) + self.v_ego = 0.0 + + def update(self, cp): + # copy can_valid + self.can_valid = cp.can_valid + + # update prevs, update must run once per loop + self.prev_left_blinker_on = self.left_blinker_on + self.prev_right_blinker_on = self.right_blinker_on + + # calc best v_ego estimate, by averaging two opposite corners + self.v_wheel_fl = cp.vl["WheelSpeed_CG1"]['WhlRr_W_Meas'] * WHEEL_RADIUS + self.v_wheel_fr = cp.vl["WheelSpeed_CG1"]['WhlRl_W_Meas'] * WHEEL_RADIUS + self.v_wheel_rl = cp.vl["WheelSpeed_CG1"]['WhlFr_W_Meas'] * WHEEL_RADIUS + self.v_wheel_rr = cp.vl["WheelSpeed_CG1"]['WhlFl_W_Meas'] * WHEEL_RADIUS + self.v_wheel = float(np.mean([self.v_wheel_fl, self.v_wheel_fr, self.v_wheel_rl, self.v_wheel_rr])) + + # Kalman filter + if abs(self.v_wheel - self.v_ego) > 2.0: # Prevent large accelerations when car starts at non zero speed + self.v_ego_x = np.matrix([[self.v_wheel], [0.0]]) + + self.v_ego_raw = self.v_wheel + v_ego_x = self.v_ego_kf.update(self.v_wheel) + self.v_ego = float(v_ego_x[0]) + self.a_ego = float(v_ego_x[1]) + self.standstill = not self.v_wheel > 0.001 + + self.angle_steers = cp.vl["Steering_Wheel_Data_CG1"]['SteWhlRelInit_An_Sns'] + self.v_cruise_pcm = cp.vl["Cruise_Status"]['Set_Speed'] * CV.MPH_TO_MS + self.pcm_acc_status = cp.vl["Cruise_Status"]['Cruise_State'] + self.main_on = cp.vl["Cruise_Status"]['Cruise_State'] != 0 + self.lkas_state = cp.vl["Lane_Keep_Assist_Status"]['LaActAvail_D_Actl'] + self.steer_override = not cp.vl["Lane_Keep_Assist_Status"]['LaHandsOff_B_Actl'] + self.steer_error = cp.vl["Lane_Keep_Assist_Status"]['LaActDeny_B_Actl'] + self.user_gas = cp.vl["EngineData_14"]['ApedPosScal_Pc_Actl'] + self.brake_pressed = bool(cp.vl["Cruise_Status"]["Brake_Drv_Appl"]) + self.brake_lights = bool(cp.vl["BCM_to_HS_Body"]["Brake_Lights"]) + self.generic_toggle = bool(cp.vl["Steering_Buttons"]["Dist_Incr"]) diff --git a/selfdrive/car/ford/interface.py b/selfdrive/car/ford/interface.py new file mode 100755 index 00000000000000..633ce4b8ae0458 --- /dev/null +++ b/selfdrive/car/ford/interface.py @@ -0,0 +1,219 @@ +#!/usr/bin/env python +from common.realtime import sec_since_boot +from cereal import car, log +from selfdrive.swaglog import cloudlog +from selfdrive.config import Conversions as CV +from selfdrive.controls.lib.drive_helpers import EventTypes as ET, create_event +from selfdrive.controls.lib.vehicle_model import VehicleModel +from selfdrive.car.ford.carstate import CarState, get_can_parser +from selfdrive.car.ford.fordcan import MAX_ANGLE + +try: + from selfdrive.car.ford.carcontroller import CarController +except ImportError: + CarController = None + + +class CarInterface(object): + def __init__(self, CP, sendcan=None): + self.CP = CP + self.VM = VehicleModel(CP) + + self.frame = 0 + self.can_invalid_count = 0 + self.gas_pressed_prev = False + self.brake_pressed_prev = False + self.cruise_enabled_prev = False + + # *** init the major players *** + self.CS = CarState(CP) + + self.cp = get_can_parser(CP) + + # sending if read only is False + if sendcan is not None: + self.sendcan = sendcan + self.CC = CarController(self.cp.dbc_name, CP.enableCamera, self.VM) + + @staticmethod + def compute_gb(accel, speed): + return float(accel) / 3.0 + + @staticmethod + def calc_accel_override(a_ego, a_target, v_ego, v_target): + return 1.0 + + @staticmethod + def get_params(candidate, fingerprint): + + # kg of standard extra cargo to count for drive, gas, etc... + std_cargo = 136 + + ret = car.CarParams.new_message() + + ret.carName = "ford" + ret.carFingerprint = candidate + + ret.safetyModel = car.CarParams.SafetyModels.ford + + # pedal + ret.enableCruise = True + + # FIXME: hardcoding honda civic 2016 touring params so they can be used to + # scale unknown params for other cars + mass_civic = 2923. * CV.LB_TO_KG + std_cargo + wheelbase_civic = 2.70 + centerToFront_civic = wheelbase_civic * 0.4 + centerToRear_civic = wheelbase_civic - centerToFront_civic + rotationalInertia_civic = 2500 + tireStiffnessFront_civic = 85400 + tireStiffnessRear_civic = 90000 + + ret.steerKiBP, ret.steerKpBP = [[0.], [0.]] + ret.wheelbase = 2.85 + ret.steerRatio = 14.8 + ret.mass = 3045. * CV.LB_TO_KG + std_cargo + ret.steerKpV, ret.steerKiV = [[0.01], [0.005]] # TODO: tune this + ret.steerKf = 1. / MAX_ANGLE # MAX Steer angle to normalize FF + ret.steerActuatorDelay = 0.1 # Default delay, not measured yet + ret.steerRateCost = 1.0 + + f = 1.2 + tireStiffnessFront_civic *= f + tireStiffnessRear_civic *= f + + ret.centerToFront = ret.wheelbase * 0.44 + + ret.longPidDeadzoneBP = [0., 9.] + ret.longPidDeadzoneV = [0., .15] + + # min speed to enable ACC. if car can do stop and go, then set enabling speed + # to a negative value, so it won't matter. + ret.minEnableSpeed = -1. + + centerToRear = ret.wheelbase - ret.centerToFront + # TODO: get actual value, for now starting with reasonable value for + # civic and scaling by mass and wheelbase + ret.rotationalInertia = rotationalInertia_civic * \ + ret.mass * ret.wheelbase**2 / (mass_civic * wheelbase_civic**2) + + # TODO: start from empirically derived lateral slip stiffness for the civic and scale by + # mass and CG position, so all cars will have approximately similar dyn behaviors + ret.tireStiffnessFront = tireStiffnessFront_civic * \ + ret.mass / mass_civic * \ + (centerToRear / ret.wheelbase) / (centerToRear_civic / wheelbase_civic) + ret.tireStiffnessRear = tireStiffnessRear_civic * \ + ret.mass / mass_civic * \ + (ret.centerToFront / ret.wheelbase) / (centerToFront_civic / wheelbase_civic) + + # no rear steering, at least on the listed cars above + ret.steerRatioRear = 0. + ret.steerControlType = car.CarParams.SteerControlType.angle + + # steer, gas, brake limitations VS speed + ret.steerMaxBP = [0.] # breakpoints at 1 and 40 kph + ret.steerMaxV = [1.0] # 2/3rd torque allowed above 45 kph + ret.gasMaxBP = [0.] + ret.gasMaxV = [0.5] + ret.brakeMaxBP = [5., 20.] + ret.brakeMaxV = [1., 0.8] + + ret.enableCamera = not any(x for x in [970, 973, 984] if x in fingerprint) + ret.openpilotLongitudinalControl = False + cloudlog.warn("ECU Camera Simulated: %r", ret.enableCamera) + + ret.steerLimitAlert = False + ret.stoppingControl = False + ret.startAccel = 0.0 + + ret.longitudinalKpBP = [0., 5., 35.] + ret.longitudinalKpV = [3.6, 2.4, 1.5] + ret.longitudinalKiBP = [0., 35.] + ret.longitudinalKiV = [0.54, 0.36] + + return ret + + # returns a car.CarState + def update(self, c): + # ******************* do can recv ******************* + canMonoTimes = [] + + self.cp.update(int(sec_since_boot() * 1e9), False) + + self.CS.update(self.cp) + + # create message + ret = car.CarState.new_message() + + # speeds + ret.vEgo = self.CS.v_ego + ret.vEgoRaw = self.CS.v_ego_raw + ret.standstill = self.CS.standstill + ret.wheelSpeeds.fl = self.CS.v_wheel_fl + ret.wheelSpeeds.fr = self.CS.v_wheel_fr + ret.wheelSpeeds.rl = self.CS.v_wheel_rl + ret.wheelSpeeds.rr = self.CS.v_wheel_rr + + # steering wheel + ret.steeringAngle = self.CS.angle_steers + ret.steeringPressed = self.CS.steer_override + + # gas pedal + ret.gas = self.CS.user_gas / 100. + ret.gasPressed = self.CS.user_gas > 0.0001 + ret.brakePressed = self.CS.brake_pressed + ret.brakeLights = self.CS.brake_lights + + ret.cruiseState.enabled = not (self.CS.pcm_acc_status in [0, 3]) + ret.cruiseState.speed = self.CS.v_cruise_pcm + ret.cruiseState.available = self.CS.pcm_acc_status != 0 + + ret.genericToggle = self.CS.generic_toggle + + # events + events = [] + if not self.CS.can_valid: + self.can_invalid_count += 1 + if self.can_invalid_count >= 5: + events.append(create_event('commIssue', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE])) + else: + self.can_invalid_count = 0 + + if self.CS.steer_error: + events.append(create_event('steerUnavailable', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE, ET.PERMANENT])) + + # enable request in prius is simple, as we activate when Toyota is active (rising edge) + if ret.cruiseState.enabled and not self.cruise_enabled_prev: + events.append(create_event('pcmEnable', [ET.ENABLE])) + elif not ret.cruiseState.enabled: + events.append(create_event('pcmDisable', [ET.USER_DISABLE])) + + # disable on pedals rising edge or when brake is pressed and speed isn't zero + if (ret.gasPressed and not self.gas_pressed_prev) or \ + (ret.brakePressed and (not self.brake_pressed_prev or ret.vEgo > 0.001)): + events.append(create_event('pedalPressed', [ET.NO_ENTRY, ET.USER_DISABLE])) + + if ret.gasPressed: + events.append(create_event('pedalPressed', [ET.PRE_ENABLE])) + + if self.CS.lkas_state not in [2, 3] and ret.vEgo > 13.* CV.MPH_TO_MS and ret.cruiseState.enabled: + events.append(create_event('steerTempUnavailableMute', [ET.WARNING])) + + ret.events = events + ret.canMonoTimes = canMonoTimes + + self.gas_pressed_prev = ret.gasPressed + self.brake_pressed_prev = ret.brakePressed + self.cruise_enabled_prev = ret.cruiseState.enabled + + return ret.as_reader() + + # pass in a car.CarControl + # to be called @ 100hz + def apply(self, c, perception_state=log.Live20Data.new_message()): + + self.CC.update(self.sendcan, c.enabled, self.CS, self.frame, c.actuators, + c.hudControl.visualAlert, c.cruiseControl.cancel) + + self.frame += 1 + return False diff --git a/selfdrive/car/ford/radar_interface.py b/selfdrive/car/ford/radar_interface.py new file mode 100755 index 00000000000000..2acea9d7084949 --- /dev/null +++ b/selfdrive/car/ford/radar_interface.py @@ -0,0 +1,93 @@ +#!/usr/bin/env python +import os +import numpy as np +from selfdrive.can.parser import CANParser +from cereal import car +from common.realtime import sec_since_boot +import zmq +from selfdrive.services import service_list +import selfdrive.messaging as messaging + + +RADAR_MSGS = range(0x500, 0x540) + +def _create_radard_can_parser(): + dbc_f = 'ford_fusion_2018_adas.dbc' + msg_n = len(RADAR_MSGS) + signals = zip(['X_Rel'] * msg_n + ['Angle'] * msg_n + ['V_Rel'] * msg_n, + RADAR_MSGS * 3, + [0] * msg_n + [0] * msg_n + [0] * msg_n) + checks = zip(RADAR_MSGS, [20]*msg_n) + + return CANParser(os.path.splitext(dbc_f)[0], signals, checks, 1) + +class RadarInterface(object): + def __init__(self, CP): + # radar + self.pts = {} + self.validCnt = {key: 0 for key in RADAR_MSGS} + self.track_id = 0 + + self.delay = 0.0 # Delay of radar + + # Nidec + self.rcp = _create_radard_can_parser() + + context = zmq.Context() + self.logcan = messaging.sub_sock(context, service_list['can'].port) + + def update(self): + canMonoTimes = [] + + updated_messages = set() + while 1: + tm = int(sec_since_boot() * 1e9) + updated_messages.update(self.rcp.update(tm, True)) + # TODO: do not hardcode last msg + if 0x53f in updated_messages: + break + + ret = car.RadarState.new_message() + errors = [] + if not self.rcp.can_valid: + errors.append("commIssue") + ret.errors = errors + ret.canMonoTimes = canMonoTimes + + for ii in updated_messages: + cpt = self.rcp.vl[ii] + + if cpt['X_Rel'] > 0.00001: + self.validCnt[ii] = 0 # reset counter + + if cpt['X_Rel'] > 0.00001: + self.validCnt[ii] += 1 + else: + self.validCnt[ii] = max(self.validCnt[ii] -1, 0) + #print ii, self.validCnt[ii], cpt['VALID'], cpt['X_Rel'], cpt['Angle'] + + # radar point only valid if there have been enough valid measurements + if self.validCnt[ii] > 0: + if ii not in self.pts: + self.pts[ii] = car.RadarState.RadarPoint.new_message() + self.pts[ii].trackId = self.track_id + self.track_id += 1 + self.pts[ii].dRel = cpt['X_Rel'] # from front of car + self.pts[ii].yRel = cpt['X_Rel'] * cpt['Angle'] * np.pi / 180. # in car frame's y axis, left is positive + self.pts[ii].vRel = cpt['V_Rel'] + self.pts[ii].aRel = float('nan') + self.pts[ii].yvRel = float('nan') + self.pts[ii].measured = True + else: + if ii in self.pts: + del self.pts[ii] + + ret.points = self.pts.values() + return ret + +if __name__ == "__main__": + RI = RadarInterface(None) + while 1: + ret = RI.update() + print(chr(27) + "[2J") + print ret diff --git a/selfdrive/car/ford/values.py b/selfdrive/car/ford/values.py new file mode 100644 index 00000000000000..b8890107fcc52b --- /dev/null +++ b/selfdrive/car/ford/values.py @@ -0,0 +1,14 @@ +from selfdrive.car import dbc_dict + +class CAR: + FUSION = "FORD FUSION 2018" + +FINGERPRINTS = { + CAR.FUSION: [{ + 71: 8, 74: 8, 75: 8, 76: 8, 90: 8, 92: 8, 93: 8, 118: 8, 119: 8, 120: 8, 125: 8, 129: 8, 130: 8, 131: 8, 132: 8, 133: 8, 145: 8, 146: 8, 357: 8, 359: 8, 360: 8, 361: 8, 376: 8, 390: 8, 391: 8, 392: 8, 394: 8, 512: 8, 514: 8, 516: 8, 531: 8, 532: 8, 534: 8, 535: 8, 560: 8, 578: 8, 604: 8, 613: 8, 673: 8, 827: 8, 848: 8, 934: 8, 935: 8, 936: 8, 947: 8, 963: 8, 970: 8, 972: 8, 973: 8, 984: 8, 992: 8, 994: 8, 997: 8, 998: 8, 1003: 8, 1034: 8, 1045: 8, 1046: 8, 1053: 8, 1054: 8, 1058: 8, 1059: 8, 1068: 8, 1072: 8, 1073: 8, 1082: 8, 1107: 8, 1108: 8, 1109: 8, 1110: 8, 1200: 8, 1427: 8, 1430: 8, 1438: 8, 1459: 8 + }], +} + +DBC = { + CAR.FUSION: dbc_dict('ford_fusion_2018_pt', 'ford_fusion_2018_adas'), +} diff --git a/selfdrive/car/gm/__init__.py b/selfdrive/car/gm/__init__.py new file mode 100644 index 00000000000000..e69de29bb2d1d6 diff --git a/selfdrive/car/gm/carcontroller.py b/selfdrive/car/gm/carcontroller.py new file mode 100644 index 00000000000000..fd90ffd4dcf0ca --- /dev/null +++ b/selfdrive/car/gm/carcontroller.py @@ -0,0 +1,196 @@ +from common.numpy_fast import interp +from common.realtime import sec_since_boot +from selfdrive.config import Conversions as CV +from selfdrive.boardd.boardd import can_list_to_can_capnp +from selfdrive.car import apply_std_steer_torque_limits +from selfdrive.car.gm import gmcan +from selfdrive.car.gm.values import CAR, DBC +from selfdrive.can.packer import CANPacker + + +class CarControllerParams(): + def __init__(self, car_fingerprint): + if car_fingerprint in (CAR.VOLT, CAR.MALIBU, CAR.HOLDEN_ASTRA, CAR.ACADIA, CAR.CADILLAC_ATS): + self.STEER_MAX = 300 + self.STEER_STEP = 2 # how often we update the steer cmd + self.STEER_DELTA_UP = 7 # ~0.75s time to peak torque (255/50hz/0.75s) + self.STEER_DELTA_DOWN = 17 # ~0.3s from peak torque to zero + elif car_fingerprint == CAR.CADILLAC_CT6: + self.STEER_MAX = 150 + self.STEER_STEP = 1 # how often we update the steer cmd + self.STEER_DELTA_UP = 2 # 0.75s time to peak torque + self.STEER_DELTA_DOWN = 5 # 0.3s from peak torque to zero + + self.STEER_DRIVER_ALLOWANCE = 50 # allowed driver torque before start limiting + self.STEER_DRIVER_MULTIPLIER = 4 # weight driver torque heavily + self.STEER_DRIVER_FACTOR = 100 # from dbc + self.NEAR_STOP_BRAKE_PHASE = 0.5 # m/s, more aggressive braking near full stop + + # Takes case of "Service Adaptive Cruise" and "Service Front Camera" + # dashboard messages. + self.ADAS_KEEPALIVE_STEP = 100 + self.CAMERA_KEEPALIVE_STEP = 100 + + # pedal lookups, only for Volt + MAX_GAS = 3072 # Only a safety limit + ZERO_GAS = 2048 + MAX_BRAKE = 350 # Should be around 3.5m/s^2, including regen + self.MAX_ACC_REGEN = 1404 # ACC Regen braking is slightly less powerful than max regen paddle + self.GAS_LOOKUP_BP = [-0.25, 0., 0.5] + self.GAS_LOOKUP_V = [self.MAX_ACC_REGEN, ZERO_GAS, MAX_GAS] + self.BRAKE_LOOKUP_BP = [-1., -0.25] + self.BRAKE_LOOKUP_V = [MAX_BRAKE, 0] + + +def actuator_hystereses(final_pedal, pedal_steady): + # hyst params... TODO: move these to VehicleParams + pedal_hyst_gap = 0.01 # don't change pedal command for small oscilalitons within this value + + # for small pedal oscillations within pedal_hyst_gap, don't change the pedal command + if final_pedal == 0.: + pedal_steady = 0. + elif final_pedal > pedal_steady + pedal_hyst_gap: + pedal_steady = final_pedal - pedal_hyst_gap + elif final_pedal < pedal_steady - pedal_hyst_gap: + pedal_steady = final_pedal + pedal_hyst_gap + final_pedal = pedal_steady + + return final_pedal, pedal_steady + + +class CarController(object): + def __init__(self, canbus, car_fingerprint, allow_controls): + self.pedal_steady = 0. + self.start_time = sec_since_boot() + self.chime = 0 + self.steer_idx = 0 + self.apply_steer_last = 0 + self.car_fingerprint = car_fingerprint + self.allow_controls = allow_controls + self.lka_icon_status_last = (False, False) + + # Setup detection helper. Routes commands to + # an appropriate CAN bus number. + self.canbus = canbus + self.params = CarControllerParams(car_fingerprint) + + self.packer_pt = CANPacker(DBC[car_fingerprint]['pt']) + self.packer_ch = CANPacker(DBC[car_fingerprint]['chassis']) + + def update(self, sendcan, enabled, CS, frame, actuators, \ + hud_v_cruise, hud_show_lanes, hud_show_car, chime, chime_cnt): + """ Controls thread """ + + # Sanity check. + if not self.allow_controls: + return + + P = self.params + + # Send CAN commands. + can_sends = [] + canbus = self.canbus + + ### STEER ### + + if (frame % P.STEER_STEP) == 0: + lkas_enabled = enabled and not CS.steer_not_allowed and CS.v_ego > 3. + if lkas_enabled: + apply_steer = actuators.steer * P.STEER_MAX + apply_steer = apply_std_steer_torque_limits(apply_steer, self.apply_steer_last, CS.steer_torque_driver, P) + else: + apply_steer = 0 + + self.apply_steer_last = apply_steer + idx = (frame / P.STEER_STEP) % 4 + + if self.car_fingerprint in (CAR.VOLT, CAR.MALIBU, CAR.HOLDEN_ASTRA, CAR.ACADIA, CAR.CADILLAC_ATS): + can_sends.append(gmcan.create_steering_control(self.packer_pt, + canbus.powertrain, apply_steer, idx, lkas_enabled)) + if self.car_fingerprint == CAR.CADILLAC_CT6: + can_sends += gmcan.create_steering_control_ct6(self.packer_pt, + canbus, apply_steer, CS.v_ego, idx, lkas_enabled) + + ### GAS/BRAKE ### + + if self.car_fingerprint in (CAR.VOLT, CAR.MALIBU, CAR.HOLDEN_ASTRA, CAR.ACADIA, CAR.CADILLAC_ATS): + # no output if not enabled, but keep sending keepalive messages + # treat pedals as one + final_pedal = actuators.gas - actuators.brake + + # *** apply pedal hysteresis *** + final_brake, self.brake_steady = actuator_hystereses( + final_pedal, self.pedal_steady) + + if not enabled: + # Stock ECU sends max regen when not enabled. + apply_gas = P.MAX_ACC_REGEN + apply_brake = 0 + else: + apply_gas = int(round(interp(final_pedal, P.GAS_LOOKUP_BP, P.GAS_LOOKUP_V))) + apply_brake = int(round(interp(final_pedal, P.BRAKE_LOOKUP_BP, P.BRAKE_LOOKUP_V))) + + # Gas/regen and brakes - all at 25Hz + if (frame % 4) == 0: + idx = (frame / 4) % 4 + + at_full_stop = enabled and CS.standstill + near_stop = enabled and (CS.v_ego < P.NEAR_STOP_BRAKE_PHASE) + can_sends.append(gmcan.create_friction_brake_command(self.packer_ch, canbus.chassis, apply_brake, idx, near_stop, at_full_stop)) + + at_full_stop = enabled and CS.standstill + can_sends.append(gmcan.create_gas_regen_command(self.packer_pt, canbus.powertrain, apply_gas, idx, enabled, at_full_stop)) + + # Send dashboard UI commands (ACC status), 25hz + if (frame % 4) == 0: + can_sends.append(gmcan.create_acc_dashboard_command(self.packer_pt, canbus.powertrain, enabled, hud_v_cruise * CV.MS_TO_KPH, hud_show_car)) + + # Radar needs to know current speed and yaw rate (50hz), + # and that ADAS is alive (10hz) + time_and_headlights_step = 10 + tt = sec_since_boot() + + if frame % time_and_headlights_step == 0: + idx = (frame / time_and_headlights_step) % 4 + can_sends.append(gmcan.create_adas_time_status(canbus.obstacle, int((tt - self.start_time) * 60), idx)) + can_sends.append(gmcan.create_adas_headlights_status(canbus.obstacle)) + + speed_and_accelerometer_step = 2 + if frame % speed_and_accelerometer_step == 0: + idx = (frame / speed_and_accelerometer_step) % 4 + can_sends.append(gmcan.create_adas_steering_status(canbus.obstacle, idx)) + can_sends.append(gmcan.create_adas_accelerometer_speed_status(canbus.obstacle, CS.v_ego, idx)) + + if frame % P.ADAS_KEEPALIVE_STEP == 0: + can_sends += gmcan.create_adas_keepalive(canbus.powertrain) + + # Show green icon when LKA torque is applied, and + # alarming orange icon when approaching torque limit. + # If not sent again, LKA icon disappears in about 5 seconds. + # Conveniently, sending camera message periodically also works as a keepalive. + lka_active = CS.lkas_status == 1 + lka_critical = lka_active and abs(actuators.steer) > 0.9 + lka_icon_status = (lka_active, lka_critical) + if frame % P.CAMERA_KEEPALIVE_STEP == 0 \ + or lka_icon_status != self.lka_icon_status_last: + can_sends.append(gmcan.create_lka_icon_command(canbus.sw_gmlan, lka_active, lka_critical)) + self.lka_icon_status_last = lka_icon_status + + # Send chimes + if self.chime != chime: + duration = 0x3c + + # There is no 'repeat forever' chime command + # TODO: Manage periodic re-issuing of chime command + # and chime cancellation + if chime_cnt == -1: + chime_cnt = 10 + + if chime != 0: + can_sends.append(gmcan.create_chime_command(canbus.sw_gmlan, chime, duration, chime_cnt)) + + # If canceling a repeated chime, cancel command must be + # issued for the same chime type and duration + self.chime = chime + + sendcan.send(can_list_to_can_capnp(can_sends, msgtype='sendcan').to_bytes()) diff --git a/selfdrive/car/gm/carstate.py b/selfdrive/car/gm/carstate.py new file mode 100644 index 00000000000000..24c73a3079b23a --- /dev/null +++ b/selfdrive/car/gm/carstate.py @@ -0,0 +1,150 @@ +import numpy as np +from cereal import car +from common.kalman.simple_kalman import KF1D +from selfdrive.config import Conversions as CV +from selfdrive.can.parser import CANParser +from selfdrive.car.gm.values import DBC, CAR, parse_gear_shifter, \ + CruiseButtons, is_eps_status_ok, \ + STEER_THRESHOLD + +def get_powertrain_can_parser(CP, canbus): + # this function generates lists for signal, messages and initial values + signals = [ + # sig_name, sig_address, default + ("BrakePedalPosition", "EBCMBrakePedalPosition", 0), + ("FrontLeftDoor", "BCMDoorBeltStatus", 0), + ("FrontRightDoor", "BCMDoorBeltStatus", 0), + ("RearLeftDoor", "BCMDoorBeltStatus", 0), + ("RearRightDoor", "BCMDoorBeltStatus", 0), + ("LeftSeatBelt", "BCMDoorBeltStatus", 0), + ("RightSeatBelt", "BCMDoorBeltStatus", 0), + ("TurnSignals", "BCMTurnSignals", 0), + ("AcceleratorPedal", "AcceleratorPedal", 0), + ("ACCButtons", "ASCMSteeringButton", CruiseButtons.UNPRESS), + ("SteeringWheelAngle", "PSCMSteeringAngle", 0), + ("FLWheelSpd", "EBCMWheelSpdFront", 0), + ("FRWheelSpd", "EBCMWheelSpdFront", 0), + ("RLWheelSpd", "EBCMWheelSpdRear", 0), + ("RRWheelSpd", "EBCMWheelSpdRear", 0), + ("PRNDL", "ECMPRDNL", 0), + ("LKADriverAppldTrq", "PSCMStatus", 0), + ("LKATorqueDeliveredStatus", "PSCMStatus", 0), + ] + + if CP.carFingerprint == CAR.VOLT: + signals += [ + ("RegenPaddle", "EBCMRegenPaddle", 0), + ] + if CP.carFingerprint in (CAR.VOLT, CAR.MALIBU, CAR.HOLDEN_ASTRA, CAR.ACADIA, CAR.CADILLAC_ATS): + signals += [ + ("TractionControlOn", "ESPStatus", 0), + ("EPBClosed", "EPBStatus", 0), + ("CruiseMainOn", "ECMEngineStatus", 0), + ("CruiseState", "AcceleratorPedal2", 0), + ] + if CP.carFingerprint == CAR.CADILLAC_CT6: + signals += [ + ("ACCCmdActive", "ASCMActiveCruiseControlStatus", 0) + ] + + return CANParser(DBC[CP.carFingerprint]['pt'], signals, [], canbus.powertrain) + +class CarState(object): + def __init__(self, CP, canbus): + self.CP = CP + # initialize can parser + + self.car_fingerprint = CP.carFingerprint + self.cruise_buttons = CruiseButtons.UNPRESS + self.left_blinker_on = False + self.prev_left_blinker_on = False + self.right_blinker_on = False + self.prev_right_blinker_on = False + + # vEgo kalman filter + dt = 0.01 + self.v_ego_kf = KF1D(x0=np.matrix([[0.], [0.]]), + A=np.matrix([[1., dt], [0., 1.]]), + C=np.matrix([1., 0.]), + K=np.matrix([[0.12287673], [0.29666309]])) + self.v_ego = 0. + + def update(self, pt_cp): + + self.can_valid = pt_cp.can_valid + self.prev_cruise_buttons = self.cruise_buttons + self.cruise_buttons = pt_cp.vl["ASCMSteeringButton"]['ACCButtons'] + + self.v_wheel_fl = pt_cp.vl["EBCMWheelSpdFront"]['FLWheelSpd'] * CV.KPH_TO_MS + self.v_wheel_fr = pt_cp.vl["EBCMWheelSpdFront"]['FRWheelSpd'] * CV.KPH_TO_MS + self.v_wheel_rl = pt_cp.vl["EBCMWheelSpdRear"]['RLWheelSpd'] * CV.KPH_TO_MS + self.v_wheel_rr = pt_cp.vl["EBCMWheelSpdRear"]['RRWheelSpd'] * CV.KPH_TO_MS + speed_estimate = float(np.mean([self.v_wheel_fl, self.v_wheel_fr, self.v_wheel_rl, self.v_wheel_rr])) + + self.v_ego_raw = speed_estimate + v_ego_x = self.v_ego_kf.update(speed_estimate) + self.v_ego = float(v_ego_x[0]) + self.a_ego = float(v_ego_x[1]) + + self.standstill = self.v_ego_raw < 0.01 + + self.angle_steers = pt_cp.vl["PSCMSteeringAngle"]['SteeringWheelAngle'] + self.gear_shifter = parse_gear_shifter(pt_cp.vl["ECMPRDNL"]['PRNDL']) + self.user_brake = pt_cp.vl["EBCMBrakePedalPosition"]['BrakePedalPosition'] + + self.pedal_gas = pt_cp.vl["AcceleratorPedal"]['AcceleratorPedal'] + self.user_gas_pressed = self.pedal_gas > 0 + + self.steer_torque_driver = pt_cp.vl["PSCMStatus"]['LKADriverAppldTrq'] + self.steer_override = abs(self.steer_torque_driver) > STEER_THRESHOLD + + # 0 - inactive, 1 - active, 2 - temporary limited, 3 - failed + self.lkas_status = pt_cp.vl["PSCMStatus"]['LKATorqueDeliveredStatus'] + self.steer_not_allowed = not is_eps_status_ok(self.lkas_status, self.car_fingerprint) + + # 1 - open, 0 - closed + self.door_all_closed = (pt_cp.vl["BCMDoorBeltStatus"]['FrontLeftDoor'] == 0 and + pt_cp.vl["BCMDoorBeltStatus"]['FrontRightDoor'] == 0 and + pt_cp.vl["BCMDoorBeltStatus"]['RearLeftDoor'] == 0 and + pt_cp.vl["BCMDoorBeltStatus"]['RearRightDoor'] == 0) + + # 1 - latched + self.seatbelt = pt_cp.vl["BCMDoorBeltStatus"]['LeftSeatBelt'] == 1 + + self.steer_error = False + + self.brake_error = False + self.can_valid = True + + self.prev_left_blinker_on = self.left_blinker_on + self.prev_right_blinker_on = self.right_blinker_on + self.left_blinker_on = pt_cp.vl["BCMTurnSignals"]['TurnSignals'] == 1 + self.right_blinker_on = pt_cp.vl["BCMTurnSignals"]['TurnSignals'] == 2 + + if self.car_fingerprint in (CAR.VOLT, CAR.MALIBU, CAR.HOLDEN_ASTRA, CAR.ACADIA, CAR.CADILLAC_ATS): + self.park_brake = pt_cp.vl["EPBStatus"]['EPBClosed'] + self.main_on = pt_cp.vl["ECMEngineStatus"]['CruiseMainOn'] + self.acc_active = False + self.esp_disabled = pt_cp.vl["ESPStatus"]['TractionControlOn'] != 1 + self.pcm_acc_status = pt_cp.vl["AcceleratorPedal2"]['CruiseState'] + if self.car_fingerprint == CAR.VOLT: + self.regen_pressed = bool(pt_cp.vl["EBCMRegenPaddle"]['RegenPaddle']) + else: + self.regen_pressed = False + if self.car_fingerprint == CAR.CADILLAC_CT6: + self.park_brake = False + self.main_on = False + self.acc_active = pt_cp.vl["ASCMActiveCruiseControlStatus"]['ACCCmdActive'] + self.esp_disabled = False + self.regen_pressed = False + self.pcm_acc_status = int(self.acc_active) + + # Brake pedal's potentiometer returns near-zero reading + # even when pedal is not pressed. + if self.user_brake < 10: + self.user_brake = 0 + + # Regen braking is braking + self.brake_pressed = self.user_brake > 10 or self.regen_pressed + + self.gear_shifter_valid = self.gear_shifter == car.CarState.GearShifter.drive diff --git a/selfdrive/car/gm/gmcan.py b/selfdrive/car/gm/gmcan.py new file mode 100644 index 00000000000000..910cb1d95604ce --- /dev/null +++ b/selfdrive/car/gm/gmcan.py @@ -0,0 +1,190 @@ +def create_steering_control(packer, bus, apply_steer, idx, lkas_active): + + values = { + "LKASteeringCmdActive": lkas_active, + "LKASteeringCmd": apply_steer, + "RollingCounter": idx, + "LKASteeringCmdChecksum": 0x1000 - (lkas_active << 11) - (apply_steer & 0x7ff) - idx + } + + return packer.make_can_msg("ASCMLKASteeringCmd", bus, values) + +def create_steering_control_ct6(packer, canbus, apply_steer, v_ego, idx, enabled): + + values = { + "LKASteeringCmdActive": 1 if enabled else 0, + "LKASteeringCmd": apply_steer, + "RollingCounter": idx, + "SetMe1": 1, + "LKASVehicleSpeed": abs(v_ego * 3.6), + "LKASMode": 2 if enabled else 0, + "LKASteeringCmdChecksum": 0 # assume zero and then manually compute it + } + + dat = packer.make_can_msg("ASCMLKASteeringCmd", 0, values)[2] + # the checksum logic is weird + values['LKASteeringCmdChecksum'] = (0x2a + + sum([ord(i) for i in dat][:4]) + + values['LKASMode']) & 0x3ff + # pack again with checksum + dat = packer.make_can_msg("ASCMLKASteeringCmd", 0, values)[2] + + return [0x152, 0, dat, canbus.powertrain], \ + [0x154, 0, dat, canbus.powertrain], \ + [0x151, 0, dat, canbus.chassis], \ + [0x153, 0, dat, canbus.chassis] + + +def create_adas_keepalive(bus): + dat = "\x00\x00\x00\x00\x00\x00\x00" + return [[0x409, 0, dat, bus], [0x40a, 0, dat, bus]] + +def create_gas_regen_command(packer, bus, throttle, idx, acc_engaged, at_full_stop): + values = { + "GasRegenCmdActive": acc_engaged, + "RollingCounter": idx, + "GasRegenCmdActiveInv": 1 - acc_engaged, + "GasRegenCmd": throttle, + "GasRegenFullStopActive": at_full_stop, + "GasRegenAlwaysOne": 1, + "GasRegenAlwaysOne2": 1, + "GasRegenAlwaysOne3": 1, + } + + dat = packer.make_can_msg("ASCMGasRegenCmd", bus, values)[2] + values["GasRegenChecksum"] = (((0xff - ord(dat[1])) & 0xff) << 16) | \ + (((0xff - ord(dat[2])) & 0xff) << 8) | \ + ((0x100 - ord(dat[3]) - idx) & 0xff) + + return packer.make_can_msg("ASCMGasRegenCmd", bus, values) + +def create_friction_brake_command(packer, bus, apply_brake, idx, near_stop, at_full_stop): + + if apply_brake == 0: + mode = 0x1 + else: + mode = 0xa + + if at_full_stop: + mode = 0xd + # TODO: this is to have GM bringing the car to complete stop, + # but currently it conflicts with OP controls, so turned off. + #elif near_stop: + # mode = 0xb + + brake = (0x1000 - apply_brake) & 0xfff + checksum = (0x10000 - (mode << 12) - brake - idx) & 0xffff + + values = { + "RollingCounter" : idx, + "FrictionBrakeMode" : mode, + "FrictionBrakeChecksum": checksum, + "FrictionBrakeCmd" : -apply_brake + } + + return packer.make_can_msg("EBCMFrictionBrakeCmd", bus, values) + +def create_acc_dashboard_command(packer, bus, acc_engaged, target_speed_kph, lead_car_in_sight): + # Not a bit shift, dash can round up based on low 4 bits. + target_speed = int(target_speed_kph * 16) & 0xfff + + values = { + "ACCAlwaysOne" : 1, + "ACCResumeButton" : 0, + "ACCSpeedSetpoint" : target_speed, + "ACCGapLevel" : 3 * acc_engaged, # 3 "far", 0 "inactive" + "ACCCmdActive" : acc_engaged, + "ACCAlwaysOne2" : 1, + "ACCLeadCar" : lead_car_in_sight + } + + return packer.make_can_msg("ASCMActiveCruiseControlStatus", bus, values) + +def create_adas_time_status(bus, tt, idx): + dat = [(tt >> 20) & 0xff, (tt >> 12) & 0xff, (tt >> 4) & 0xff, + ((tt & 0xf) << 4) + (idx << 2)] + chksum = 0x1000 - dat[0] - dat[1] - dat[2] - dat[3] + chksum = chksum & 0xfff + dat += [0x40 + (chksum >> 8), chksum & 0xff, 0x12] + return [0xa1, 0, "".join(map(chr, dat)), bus] + +def create_adas_steering_status(bus, idx): + dat = [idx << 6, 0xf0, 0x20, 0, 0, 0] + chksum = 0x60 + sum(dat) + dat += [chksum >> 8, chksum & 0xff] + return [0x306, 0, "".join(map(chr, dat)), bus] + +def create_adas_accelerometer_speed_status(bus, speed_ms, idx): + spd = int(speed_ms * 16) & 0xfff + accel = 0 & 0xfff + # 0 if in park/neutral, 0x10 if in reverse, 0x08 for D/L + #stick = 0x08 + near_range_cutoff = 0x27 + near_range_mode = 1 if spd <= near_range_cutoff else 0 + far_range_mode = 1 - near_range_mode + dat = [0x08, spd >> 4, ((spd & 0xf) << 4) | (accel >> 8), accel & 0xff, 0] + chksum = 0x62 + far_range_mode + (idx << 2) + dat[0] + dat[1] + dat[2] + dat[3] + dat[4] + dat += [(idx << 5) + (far_range_mode << 4) + (near_range_mode << 3) + (chksum >> 8), chksum & 0xff] + return [0x308, 0, "".join(map(chr, dat)), bus] + +def create_adas_headlights_status(bus): + return [0x310, 0, "\x42\x04", bus] + +def create_chime_command(bus, chime_type, duration, repeat_cnt): + dat = [chime_type, duration, repeat_cnt, 0xff, 0] + return [0x10400060, 0, "".join(map(chr, dat)), bus] + +def create_lka_icon_command(bus, active, critical): + if active: + if critical: + dat = "\x40\xc0\x14" + else: + dat = "\x40\x40\x18" + else: + dat = "\x00\x00\x00" + return [0x104c006c, 0, dat, bus] + +# TODO: WIP +''' +def create_friction_brake_command_ct6(packer, bus, apply_brake, idx, near_stop, at_full_stop): + + # counters loops across [0, 29, 42, 55] but checksum only considers 0, 1, 2, 3 + cntrs = [0, 29, 42, 55] + if apply_brake == 0: + mode = 0x1 + else: + mode = 0xa + + if at_full_stop: + mode = 0xd + elif near_stop: + mode = 0xb + + brake = (0x1000 - apply_brake) & 0xfff + checksum = (0x10000 - (mode << 12) - brake - idx) & 0xffff + + values = { + "RollingCounter" : cntrs[idx], + "FrictionBrakeMode" : mode, + "FrictionBrakeChecksum": checksum, + "FrictionBrakeCmd" : -apply_brake + } + + dat = packer.make_can_msg("EBCMFrictionBrakeCmd", 0, values)[2] + # msg is 0x315 but we are doing the panda forwarding + return [0x314, 0, dat, 2] + +def create_gas_regen_command_ct6(bus, throttle, idx, acc_engaged, at_full_stop): + cntrs = [0, 7, 10, 13] + eng_bit = 1 if acc_engaged else 0 + gas_high = (throttle >> 8) | 0x80 + gas_low = (throttle) & 0xff + full_stop = 0x20 if at_full_stop else 0 + + chk1 = (0x100 - gas_high - 1) & 0xff + chk2 = (0x100 - gas_low - idx) & 0xff + dat = [(idx << 6) | eng_bit, 0xc2 | full_stop, gas_high, gas_low, + (1 - eng_bit) | (cntrs[idx] << 1), 0x5d - full_stop, chk1, chk2] + return [0x2cb, 0, "".join(map(chr, dat)), bus] + +''' diff --git a/selfdrive/car/gm/interface.py b/selfdrive/car/gm/interface.py new file mode 100755 index 00000000000000..9ec1b9e5d0e12c --- /dev/null +++ b/selfdrive/car/gm/interface.py @@ -0,0 +1,357 @@ +#!/usr/bin/env python +from cereal import car, log +from common.realtime import sec_since_boot +from selfdrive.config import Conversions as CV +from selfdrive.controls.lib.drive_helpers import create_event, EventTypes as ET +from selfdrive.controls.lib.vehicle_model import VehicleModel +from selfdrive.car.gm.values import DBC, CAR, STOCK_CONTROL_MSGS, AUDIO_HUD +from selfdrive.car.gm.carstate import CarState, CruiseButtons, get_powertrain_can_parser + +try: + from selfdrive.car.gm.carcontroller import CarController +except ImportError: + CarController = None + +class CanBus(object): + def __init__(self): + self.powertrain = 0 + self.obstacle = 1 + self.chassis = 2 + self.sw_gmlan = 3 + +class CarInterface(object): + def __init__(self, CP, sendcan=None): + self.CP = CP + + self.frame = 0 + self.gas_pressed_prev = False + self.brake_pressed_prev = False + self.can_invalid_count = 0 + self.acc_active_prev = 0 + + # *** init the major players *** + canbus = CanBus() + self.CS = CarState(CP, canbus) + self.VM = VehicleModel(CP) + self.pt_cp = get_powertrain_can_parser(CP, canbus) + self.ch_cp_dbc_name = DBC[CP.carFingerprint]['chassis'] + + # sending if read only is False + if sendcan is not None: + self.sendcan = sendcan + self.CC = CarController(canbus, CP.carFingerprint, CP.enableCamera) + + @staticmethod + def compute_gb(accel, speed): + return float(accel) / 4.0 + + @staticmethod + def calc_accel_override(a_ego, a_target, v_ego, v_target): + return 1.0 + + @staticmethod + def get_params(candidate, fingerprint): + ret = car.CarParams.new_message() + + ret.carName = "gm" + ret.carFingerprint = candidate + + ret.enableCruise = False + + # Presence of a camera on the object bus is ok. + # Have to go passive if ASCM is online (ACC-enabled cars), + # or camera is on powertrain bus (LKA cars without ACC). + ret.enableCamera = not any(x for x in STOCK_CONTROL_MSGS[candidate] if x in fingerprint) + ret.openpilotLongitudinalControl = ret.enableCamera + + std_cargo = 136 + + if candidate == CAR.VOLT: + # supports stop and go, but initial engage must be above 18mph (which include conservatism) + ret.minEnableSpeed = 18 * CV.MPH_TO_MS + # kg of standard extra cargo to count for driver, gas, etc... + ret.mass = 1607 + std_cargo + ret.safetyModel = car.CarParams.SafetyModels.gm + ret.wheelbase = 2.69 + ret.steerRatio = 15.7 + ret.steerRatioRear = 0. + ret.centerToFront = ret.wheelbase * 0.4 # wild guess + + elif candidate == CAR.MALIBU: + # supports stop and go, but initial engage must be above 18mph (which include conservatism) + ret.minEnableSpeed = 18 * CV.MPH_TO_MS + ret.mass = 1496 + std_cargo + ret.safetyModel = car.CarParams.SafetyModels.gm + ret.wheelbase = 2.83 + ret.steerRatio = 15.8 + ret.steerRatioRear = 0. + ret.centerToFront = ret.wheelbase * 0.4 # wild guess + + elif candidate == CAR.HOLDEN_ASTRA: + # kg of standard extra cargo to count for driver, gas, etc... + ret.mass = 1363 + std_cargo + ret.wheelbase = 2.662 + # Remaining parameters copied from Volt for now + ret.centerToFront = ret.wheelbase * 0.4 + ret.minEnableSpeed = 18 * CV.MPH_TO_MS + ret.safetyModel = car.CarParams.SafetyModels.gm + ret.steerRatio = 15.7 + ret.steerRatioRear = 0. + + elif candidate == CAR.ACADIA: + ret.minEnableSpeed = -1 # engage speed is decided by pcm + ret.mass = 4353. * CV.LB_TO_KG + std_cargo + ret.safetyModel = car.CarParams.SafetyModels.gm + ret.wheelbase = 2.86 + ret.steerRatio = 14.4 #end to end is 13.46 + ret.steerRatioRear = 0. + ret.centerToFront = ret.wheelbase * 0.4 + + elif candidate == CAR.CADILLAC_ATS: + ret.minEnableSpeed = 18 * CV.MPH_TO_MS + ret.mass = 1601 + std_cargo + ret.safetyModel = car.CarParams.SafetyModels.gm + ret.wheelbase = 2.78 + ret.steerRatio = 15.3 + ret.steerRatioRear = 0. + ret.centerToFront = ret.wheelbase * 0.49 + + elif candidate == CAR.CADILLAC_CT6: + # engage speed is decided by pcm + ret.minEnableSpeed = -1 + # kg of standard extra cargo to count for driver, gas, etc... + ret.mass = 4016. * CV.LB_TO_KG + std_cargo + ret.safetyModel = car.CarParams.SafetyModels.cadillac + ret.wheelbase = 3.11 + ret.steerRatio = 14.6 # it's 16.3 without rear active steering + ret.steerRatioRear = 0. # TODO: there is RAS on this car! + ret.centerToFront = ret.wheelbase * 0.465 + + + # hardcoding honda civic 2016 touring params so they can be used to + # scale unknown params for other cars + mass_civic = 2923. * CV.LB_TO_KG + std_cargo + wheelbase_civic = 2.70 + centerToFront_civic = wheelbase_civic * 0.4 + centerToRear_civic = wheelbase_civic - centerToFront_civic + rotationalInertia_civic = 2500 + tireStiffnessFront_civic = 85400 + tireStiffnessRear_civic = 90000 + + centerToRear = ret.wheelbase - ret.centerToFront + # TODO: get actual value, for now starting with reasonable value for + # civic and scaling by mass and wheelbase + ret.rotationalInertia = rotationalInertia_civic * \ + ret.mass * ret.wheelbase**2 / (mass_civic * wheelbase_civic**2) + + # TODO: start from empirically derived lateral slip stiffness for the civic and scale by + # mass and CG position, so all cars will have approximately similar dyn behaviors + ret.tireStiffnessFront = tireStiffnessFront_civic * \ + ret.mass / mass_civic * \ + (centerToRear / ret.wheelbase) / (centerToRear_civic / wheelbase_civic) + ret.tireStiffnessRear = tireStiffnessRear_civic * \ + ret.mass / mass_civic * \ + (ret.centerToFront / ret.wheelbase) / (centerToFront_civic / wheelbase_civic) + + + # same tuning for Volt and CT6 for now + ret.steerKiBP, ret.steerKpBP = [[0.], [0.]] + ret.steerKpV, ret.steerKiV = [[0.2], [0.00]] + ret.steerKf = 0.00004 # full torque for 20 deg at 80mph means 0.00007818594 + + ret.steerMaxBP = [0.] # m/s + ret.steerMaxV = [1.] + ret.gasMaxBP = [0.] + ret.gasMaxV = [.5] + ret.brakeMaxBP = [0.] + ret.brakeMaxV = [1.] + ret.longPidDeadzoneBP = [0.] + ret.longPidDeadzoneV = [0.] + + ret.longitudinalKpBP = [5., 35.] + ret.longitudinalKpV = [2.4, 1.5] + ret.longitudinalKiBP = [0.] + ret.longitudinalKiV = [0.36] + + ret.steerLimitAlert = True + + ret.stoppingControl = True + ret.startAccel = 0.8 + + ret.steerActuatorDelay = 0.1 # Default delay, not measured yet + ret.steerRateCost = 1.0 + ret.steerControlType = car.CarParams.SteerControlType.torque + + return ret + + # returns a car.CarState + def update(self, c): + + self.pt_cp.update(int(sec_since_boot() * 1e9), False) + self.CS.update(self.pt_cp) + + # create message + ret = car.CarState.new_message() + + # speeds + ret.vEgo = self.CS.v_ego + ret.aEgo = self.CS.a_ego + ret.vEgoRaw = self.CS.v_ego_raw + ret.yawRate = self.VM.yaw_rate(self.CS.angle_steers * CV.DEG_TO_RAD, self.CS.v_ego) + ret.standstill = self.CS.standstill + ret.wheelSpeeds.fl = self.CS.v_wheel_fl + ret.wheelSpeeds.fr = self.CS.v_wheel_fr + ret.wheelSpeeds.rl = self.CS.v_wheel_rl + ret.wheelSpeeds.rr = self.CS.v_wheel_rr + + # gas pedal information. + ret.gas = self.CS.pedal_gas / 254.0 + ret.gasPressed = self.CS.user_gas_pressed + + # brake pedal + ret.brake = self.CS.user_brake / 0xd0 + ret.brakePressed = self.CS.brake_pressed + + # steering wheel + ret.steeringAngle = self.CS.angle_steers + + # torque and user override. Driver awareness + # timer resets when the user uses the steering wheel. + ret.steeringPressed = self.CS.steer_override + ret.steeringTorque = self.CS.steer_torque_driver + + # cruise state + ret.cruiseState.available = bool(self.CS.main_on) + cruiseEnabled = self.CS.pcm_acc_status != 0 + ret.cruiseState.enabled = cruiseEnabled + ret.cruiseState.standstill = self.CS.pcm_acc_status == 4 + + ret.leftBlinker = self.CS.left_blinker_on + ret.rightBlinker = self.CS.right_blinker_on + ret.doorOpen = not self.CS.door_all_closed + ret.seatbeltUnlatched = not self.CS.seatbelt + ret.gearShifter = self.CS.gear_shifter + + buttonEvents = [] + + # blinkers + if self.CS.left_blinker_on != self.CS.prev_left_blinker_on: + be = car.CarState.ButtonEvent.new_message() + be.type = 'leftBlinker' + be.pressed = self.CS.left_blinker_on + buttonEvents.append(be) + + if self.CS.right_blinker_on != self.CS.prev_right_blinker_on: + be = car.CarState.ButtonEvent.new_message() + be.type = 'rightBlinker' + be.pressed = self.CS.right_blinker_on + buttonEvents.append(be) + + if self.CS.cruise_buttons != self.CS.prev_cruise_buttons: + be = car.CarState.ButtonEvent.new_message() + be.type = 'unknown' + if self.CS.cruise_buttons != CruiseButtons.UNPRESS: + be.pressed = True + but = self.CS.cruise_buttons + else: + be.pressed = False + but = self.CS.prev_cruise_buttons + if but == CruiseButtons.RES_ACCEL: + if not (cruiseEnabled and self.CS.standstill): + be.type = 'accelCruise' # Suppress resume button if we're resuming from stop so we don't adjust speed. + elif but == CruiseButtons.DECEL_SET: + be.type = 'decelCruise' + elif but == CruiseButtons.CANCEL: + be.type = 'cancel' + elif but == CruiseButtons.MAIN: + be.type = 'altButton3' + buttonEvents.append(be) + + ret.buttonEvents = buttonEvents + + events = [] + if not self.CS.can_valid: + self.can_invalid_count += 1 + if self.can_invalid_count >= 5: + events.append(create_event('commIssue', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE])) + else: + self.can_invalid_count = 0 + if self.CS.steer_error: + events.append(create_event('steerUnavailable', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE, ET.PERMANENT])) + if self.CS.steer_not_allowed: + events.append(create_event('steerTempUnavailable', [ET.NO_ENTRY, ET.WARNING])) + if ret.doorOpen: + events.append(create_event('doorOpen', [ET.NO_ENTRY, ET.SOFT_DISABLE])) + if ret.seatbeltUnlatched: + events.append(create_event('seatbeltNotLatched', [ET.NO_ENTRY, ET.SOFT_DISABLE])) + + if self.CS.car_fingerprint in (CAR.VOLT, CAR.MALIBU, CAR.HOLDEN_ASTRA, CAR.ACADIA, CAR.CADILLAC_ATS): + if self.CS.brake_error: + events.append(create_event('brakeUnavailable', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE, ET.PERMANENT])) + if not self.CS.gear_shifter_valid: + events.append(create_event('wrongGear', [ET.NO_ENTRY, ET.SOFT_DISABLE])) + if self.CS.esp_disabled: + events.append(create_event('espDisabled', [ET.NO_ENTRY, ET.SOFT_DISABLE])) + if not self.CS.main_on: + events.append(create_event('wrongCarMode', [ET.NO_ENTRY, ET.USER_DISABLE])) + if self.CS.gear_shifter == 3: + events.append(create_event('reverseGear', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE])) + if ret.vEgo < self.CP.minEnableSpeed: + events.append(create_event('speedTooLow', [ET.NO_ENTRY])) + if self.CS.park_brake: + events.append(create_event('parkBrake', [ET.NO_ENTRY, ET.USER_DISABLE])) + # disable on pedals rising edge or when brake is pressed and speed isn't zero + if (ret.gasPressed and not self.gas_pressed_prev) or \ + (ret.brakePressed): # and (not self.brake_pressed_prev or ret.vEgo > 0.001)): + events.append(create_event('pedalPressed', [ET.NO_ENTRY, ET.USER_DISABLE])) + if ret.gasPressed: + events.append(create_event('pedalPressed', [ET.PRE_ENABLE])) + if ret.cruiseState.standstill: + events.append(create_event('resumeRequired', [ET.WARNING])) + + # handle button presses + for b in ret.buttonEvents: + # do enable on both accel and decel buttons + if b.type in ["accelCruise", "decelCruise"] and not b.pressed: + events.append(create_event('buttonEnable', [ET.ENABLE])) + # do disable on button down + if b.type == "cancel" and b.pressed: + events.append(create_event('buttonCancel', [ET.USER_DISABLE])) + + if self.CS.car_fingerprint == CAR.CADILLAC_CT6: + + if self.CS.acc_active and not self.acc_active_prev: + events.append(create_event('pcmEnable', [ET.ENABLE])) + if not self.CS.acc_active: + events.append(create_event('pcmDisable', [ET.USER_DISABLE])) + + ret.events = events + + # update previous brake/gas pressed + self.acc_active_prev = self.CS.acc_active + self.gas_pressed_prev = ret.gasPressed + self.brake_pressed_prev = ret.brakePressed + + # cast to reader so it can't be modified + return ret.as_reader() + + # pass in a car.CarControl + # to be called @ 100hz + def apply(self, c, perception_state=log.Live20Data.new_message()): + hud_v_cruise = c.hudControl.setSpeed + if hud_v_cruise > 70: + hud_v_cruise = 0 + + chime, chime_count = AUDIO_HUD[c.hudControl.audibleAlert.raw] + + # For Openpilot, "enabled" includes pre-enable. + # In GM, PCM faults out if ACC command overlaps user gas. + enabled = c.enabled and not self.CS.user_gas_pressed + + self.CC.update(self.sendcan, enabled, self.CS, self.frame, \ + c.actuators, + hud_v_cruise, c.hudControl.lanesVisible, \ + c.hudControl.leadVisible, \ + chime, chime_count) + + self.frame += 1 diff --git a/selfdrive/car/gm/radar_interface.py b/selfdrive/car/gm/radar_interface.py new file mode 100755 index 00000000000000..6af0d3f8fae843 --- /dev/null +++ b/selfdrive/car/gm/radar_interface.py @@ -0,0 +1,127 @@ +#!/usr/bin/env python +import zmq +import math +import time +import numpy as np +from cereal import car +from selfdrive.can.parser import CANParser +from selfdrive.car.gm.interface import CanBus +from selfdrive.car.gm.values import DBC, CAR +from common.realtime import sec_since_boot +from selfdrive.services import service_list +import selfdrive.messaging as messaging + +RADAR_HEADER_MSG = 1120 +SLOT_1_MSG = RADAR_HEADER_MSG + 1 +NUM_SLOTS = 20 + +# Actually it's 0x47f, but can parser only reports +# messages that are present in DBC +LAST_RADAR_MSG = RADAR_HEADER_MSG + NUM_SLOTS + +def create_radard_can_parser(canbus, car_fingerprint): + + dbc_f = DBC[car_fingerprint]['radar'] + if car_fingerprint in (CAR.VOLT, CAR.MALIBU, CAR.HOLDEN_ASTRA, CAR.ACADIA, CAR.CADILLAC_ATS): + # C1A-ARS3-A by Continental + radar_targets = range(SLOT_1_MSG, SLOT_1_MSG + NUM_SLOTS) + signals = zip(['FLRRNumValidTargets', + 'FLRRSnsrBlckd', 'FLRRYawRtPlsblityFlt', + 'FLRRHWFltPrsntInt', 'FLRRAntTngFltPrsnt', + 'FLRRAlgnFltPrsnt', 'FLRRSnstvFltPrsntInt'] + + ['TrkRange'] * NUM_SLOTS + ['TrkRangeRate'] * NUM_SLOTS + + ['TrkRangeAccel'] * NUM_SLOTS + ['TrkAzimuth'] * NUM_SLOTS + + ['TrkWidth'] * NUM_SLOTS + ['TrkObjectID'] * NUM_SLOTS, + [RADAR_HEADER_MSG] * 7 + radar_targets * 6, + [0] * 7 + + [0.0] * NUM_SLOTS + [0.0] * NUM_SLOTS + + [0.0] * NUM_SLOTS + [0.0] * NUM_SLOTS + + [0.0] * NUM_SLOTS + [0] * NUM_SLOTS) + + checks = [] + + return CANParser(dbc_f, signals, checks, canbus.obstacle) + else: + return None + +class RadarInterface(object): + def __init__(self, CP): + # radar + self.pts = {} + + self.delay = 0.0 # Delay of radar + + canbus = CanBus() + print "Using %d as obstacle CAN bus ID" % canbus.obstacle + self.rcp = create_radard_can_parser(canbus, CP.carFingerprint) + + context = zmq.Context() + self.logcan = messaging.sub_sock(context, service_list['can'].port) + + def update(self): + updated_messages = set() + ret = car.RadarState.new_message() + while 1: + + if self.rcp is None: + time.sleep(0.05) # nothing to do + return ret + + tm = int(sec_since_boot() * 1e9) + updated_messages.update(self.rcp.update(tm, True)) + if LAST_RADAR_MSG in updated_messages: + break + + header = self.rcp.vl[RADAR_HEADER_MSG] + fault = header['FLRRSnsrBlckd'] or header['FLRRSnstvFltPrsntInt'] or \ + header['FLRRYawRtPlsblityFlt'] or header['FLRRHWFltPrsntInt'] or \ + header['FLRRAntTngFltPrsnt'] or header['FLRRAlgnFltPrsnt'] + errors = [] + if not self.rcp.can_valid: + errors.append("commIssue") + if fault: + errors.append("fault") + ret.errors = errors + + currentTargets = set() + num_targets = header['FLRRNumValidTargets'] + + # Not all radar messages describe targets, + # no need to monitor all of the self.rcp.msgs_upd + for ii in updated_messages: + if ii == RADAR_HEADER_MSG: + continue + + if num_targets == 0: + break + + cpt = self.rcp.vl[ii] + # Zero distance means it's an empty target slot + if cpt['TrkRange'] > 0.0: + targetId = cpt['TrkObjectID'] + currentTargets.add(targetId) + if targetId not in self.pts: + self.pts[targetId] = car.RadarState.RadarPoint.new_message() + self.pts[targetId].trackId = targetId + distance = cpt['TrkRange'] + self.pts[targetId].dRel = distance # from front of car + # From driver's pov, left is positive + deg_to_rad = np.pi/180. + self.pts[targetId].yRel = math.sin(deg_to_rad * cpt['TrkAzimuth']) * distance + self.pts[targetId].vRel = cpt['TrkRangeRate'] + self.pts[targetId].aRel = float('nan') + self.pts[targetId].yvRel = float('nan') + + for oldTarget in self.pts.keys(): + if not oldTarget in currentTargets: + del self.pts[oldTarget] + + ret.points = self.pts.values() + return ret + +if __name__ == "__main__": + RI = RadarInterface(None) + while 1: + ret = RI.update() + print(chr(27) + "[2J") + print ret diff --git a/selfdrive/car/gm/values.py b/selfdrive/car/gm/values.py new file mode 100644 index 00000000000000..17260fe27b3897 --- /dev/null +++ b/selfdrive/car/gm/values.py @@ -0,0 +1,112 @@ +from cereal import car +from selfdrive.car import dbc_dict + +AudibleAlert = car.CarControl.HUDControl.AudibleAlert + +class CAR: + HOLDEN_ASTRA = "HOLDEN ASTRA RS-V BK 2017" + VOLT = "CHEVROLET VOLT PREMIER 2017" + CADILLAC_ATS = "CADILLAC ATS Premium Performance 2018" + CADILLAC_CT6 = "CADILLAC CT6 SUPERCRUISE 2018" + MALIBU = "CHEVROLET MALIBU PREMIER 2017" + ACADIA = "GMC ACADIA DENALI 2018" + +class CruiseButtons: + UNPRESS = 1 + RES_ACCEL = 2 + DECEL_SET = 3 + MAIN = 5 + CANCEL = 6 + +# Car chimes, beeps, blinker sounds etc +class CM: + TOCK = 0x81 + TICK = 0x82 + LOW_BEEP = 0x84 + HIGH_BEEP = 0x85 + LOW_CHIME = 0x86 + HIGH_CHIME = 0x87 + +AUDIO_HUD = { + AudibleAlert.none: (0, 0), + AudibleAlert.chimeEngage: (CM.HIGH_CHIME, 1), + AudibleAlert.chimeDisengage: (CM.HIGH_CHIME, 1), + AudibleAlert.chimeError: (CM.LOW_CHIME, 2), + AudibleAlert.chimePrompt: (CM.LOW_CHIME, 1), + AudibleAlert.chimeWarning1: (CM.LOW_CHIME, 2), + AudibleAlert.chimeWarning2: (CM.LOW_CHIME, -1), + AudibleAlert.chimeWarningRepeat: (CM.LOW_CHIME, -1)} + +def is_eps_status_ok(eps_status, car_fingerprint): + valid_eps_status = [] + if car_fingerprint in (CAR.VOLT, CAR.MALIBU, CAR.HOLDEN_ASTRA, CAR.ACADIA, CAR.CADILLAC_ATS): + valid_eps_status += [0, 1] + elif car_fingerprint == CAR.CADILLAC_CT6: + valid_eps_status += [0, 1, 4, 5, 6] + return eps_status in valid_eps_status + +def parse_gear_shifter(can_gear): + if can_gear == 0: + return car.CarState.GearShifter.park + elif can_gear == 1: + return car.CarState.GearShifter.neutral + elif can_gear == 2: + return car.CarState.GearShifter.drive + elif can_gear == 3: + return car.CarState.GearShifter.reverse + else: + return car.CarState.GearShifter.unknown + +FINGERPRINTS = { + # Astra BK MY17, ASCM unplugged + CAR.HOLDEN_ASTRA: [{ + 190: 8, 193: 8, 197: 8, 199: 4, 201: 8, 209: 7, 211: 8, 241: 6, 249: 8, 288: 5, 298: 8, 304: 1, 309: 8, 311: 8, 313: 8, 320: 3, 328: 1, 352: 5, 381: 6, 386: 8, 388: 8, 393: 8, 398: 8, 401: 8, 413: 8, 417: 8, 419: 8, 422: 1, 426: 7, 431: 8, 442: 8, 451: 8, 452: 8, 453: 8, 455: 7, 456: 8, 458: 5, 479: 8, 481: 7, 485: 8, 489: 8, 497: 8, 499: 3, 500: 8, 501: 8, 508: 8, 528: 5, 532: 6, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 565: 5, 567: 5, 647: 5, 707: 8, 723: 8, 753: 5, 761: 7, 806: 1, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 961: 8, 969: 8, 977: 8, 979: 8, 985: 5, 1001: 8, 1009: 8, 1011: 6, 1017: 8, 1019: 3, 1020: 8, 1105: 6, 1217: 8, 1221: 5, 1225: 8, 1233: 8, 1249: 8, 1257: 6, 1259: 8, 1261: 7, 1263: 4, 1265: 8, 1267: 8, 1280: 4, 1300: 8, 1328: 4, 1417: 8, 1906: 7, 1907: 7, 1908: 7, 1912: 7, 1919: 7, + }], + CAR.VOLT: [ + # Volt Premier w/ ACC 2017 + { + 170: 8, 171: 8, 189: 7, 190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 209: 7, 211: 2, 241: 6, 288: 5, 289: 8, 298: 8, 304: 1, 308: 4, 309: 8, 311: 8, 313: 8, 320: 3, 328: 1, 352: 5, 381: 6, 386: 8, 388: 8, 389: 2, 390: 7, 417: 7, 419: 1, 426: 7, 451: 8, 452: 8, 453: 6, 454: 8, 456: 8, 479: 3, 481: 7, 485: 8, 489: 8, 493: 8, 495: 4, 497: 8, 499: 3, 500: 6, 501: 8, 508: 8, 528: 4, 532: 6, 546: 7, 550: 8, 554: 3, 558: 8, 560: 8, 562: 8, 563: 5, 564: 5, 565: 5, 566: 5, 567: 3, 568: 1, 573: 1, 577: 8, 647: 3, 707: 8, 711: 6, 761: 7, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 961: 8, 969: 8, 977: 8, 979: 7, 988: 6, 989: 8, 995: 7, 1001: 8, 1005: 6, 1009: 8, 1017: 8, 1019: 2, 1020: 8, 1105: 6, 1187: 4, 1217: 8, 1221: 5, 1223: 3, 1225: 7, 1227: 4, 1233: 8, 1249: 8, 1257: 6, 1265: 8, 1267: 1, 1273: 3, 1275: 3, 1280: 4, 1300: 8, 1322: 6, 1323: 4, 1328: 4, 1417: 8, 1601: 8, 1905: 7, 1906: 7, 1907: 7, 1910: 7, 1912: 7, 1922: 7, 1927: 7, 1928: 7, 2016: 8, 2020: 8, 2024: 8, 2028: 8 + }, + # Volt Premier w/ ACC 2018 + { + 170: 8, 171: 8, 189: 7, 190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 209: 7, 211: 2, 241: 6, 288: 5, 298: 8, 304: 1, 308: 4, 309: 8, 311: 8, 313: 8, 320: 3, 328: 1, 352: 5, 381: 6, 384: 4, 386: 8, 388: 8, 389: 2, 390: 7, 417: 7, 419: 1, 426: 7, 451: 8, 452: 8, 453: 6, 454: 8, 456: 8, 479: 3, 481: 7, 485: 8, 489: 8, 493: 8, 495: 4, 497: 8, 499: 3, 500: 6, 501: 8, 508: 8, 528: 4, 532: 6, 546: 7, 550: 8, 554: 3, 558: 8, 560: 8, 562: 8, 563: 5, 564: 5, 565: 5, 566: 5, 567: 3, 568: 1, 573: 1, 577: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 3, 707: 8, 711: 6, 715: 8, 717: 5, 761: 7, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 869: 4, 880: 6, 961: 8, 967: 4, 969: 8, 977: 8, 979: 7, 988: 6, 989: 8, 995: 7, 1001: 8, 1005: 6, 1009: 8, 1017: 8, 1019: 2, 1020: 8, 1033: 7, 1034: 7, 1105: 6, 1187: 4, 1217: 8, 1221: 5, 1223: 3, 1225: 7, 1227: 4, 1233: 8, 1249: 8, 1257: 6, 1265: 8, 1267: 1, 1273: 3, 1275: 3, 1280: 4, 1296: 4, 1300: 8, 1322: 6, 1323: 4, 1328: 4, 1417: 8, 1601: 8, 1905: 7, 1906: 7, 1907: 7, 1910: 7, 1912: 7, 1922: 7, 1927: 7, 1930: 7, 2016: 8, 2020: 8, 2024: 8, 2028: 8 + }], + CAR.CADILLAC_ATS: [ + # Cadillac ATS Coupe Premium Performance 3.6L RWD w/ ACC 2018 + { + 190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 209: 7, 211: 2, 241: 6, 249: 8, 288: 5, 298: 8, 304: 1, 309: 8, 311: 8, 313: 8, 320: 3, 322: 7, 328: 1, 352: 5, 368: 3, 381: 6, 384: 4, 386: 8, 388: 8, 393: 7, 398: 8, 401: 8, 407: 7, 413: 8, 417: 7, 419: 1, 422: 4, 426: 7, 431: 8, 442: 8, 451: 8, 452: 8, 453: 6, 455: 7, 456: 8, 462: 4, 479: 3, 481: 7, 485: 8, 487: 8, 489: 8, 491: 2, 493: 8, 497: 8, 499: 3, 500: 6, 501: 8, 508: 8, 510: 8, 528: 5, 532: 6, 534: 2, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 565: 5, 567: 5, 573: 1, 577: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 6, 707: 8, 715: 8, 717: 5, 719: 5, 723: 2, 753: 5, 761: 7, 801: 8, 804: 3, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 869: 4, 880: 6, 882: 8, 890: 1, 892: 2, 893: 2, 894: 1, 961: 8, 967: 4, 969: 8, 977: 8, 979: 8, 985: 5, 1001: 8, 1005: 6, 1009: 8, 1011: 6, 1013: 3, 1017: 8, 1019: 2, 1020: 8, 1033: 7, 1034: 7, 1105: 6, 1217: 8, 1221: 5, 1223: 3, 1225: 7, 1233: 8, 1241: 3, 1249: 8, 1257: 6, 1259: 8, 1261: 7, 1263: 4, 1265: 8, 1267: 1, 1271: 8, 1280: 4, 1296: 4, 1300: 8, 1322: 6, 1323: 4, 1328: 4, 1417: 8, 1601: 8, 1904: 7, 1906: 7, 1907: 7, 1912: 7, 1916: 7, 1917: 7, 1918: 7, 1919: 7, 1920: 7, 1930: 7, 2016: 8, 2024: 8 + }], + CAR.CADILLAC_CT6: [{ + 190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 209: 7, 211: 2, 241: 6, 249: 8, 288: 5, 298: 8, 304: 1, 309: 8, 313: 8, 320: 3, 322: 7, 328: 1, 336: 1, 338: 6, 340: 6, 352: 5, 354: 5, 356: 8, 368: 3, 372: 5, 381: 8, 386: 8, 393: 7, 398: 8, 407: 7, 413: 8, 417: 7, 419: 1, 422: 4, 426: 7, 431: 8, 442: 8, 451: 8, 452: 8, 453: 6, 455: 7, 456: 8, 458: 5, 460: 5, 462: 4, 463: 3, 479: 3, 481: 7, 485: 8, 487: 8, 489: 8, 495: 4, 497: 8, 499: 3, 500: 6, 501: 8, 508: 8, 528: 5, 532: 6, 534: 2, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 565: 5, 567: 5, 569: 3, 573: 1, 577: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 6, 707: 8, 715: 8, 717: 5, 719: 5, 723: 2, 753: 5, 761: 7, 800: 6, 801: 8, 804: 3, 810: 8, 832: 8, 833: 8, 834: 8, 835: 6, 836: 5, 837: 8, 838: 8, 839: 8, 840: 5, 842: 5, 844: 8, 866: 4, 869: 4, 880: 6, 884: 8, 961: 8, 969: 8, 977: 8, 979: 8, 985: 5, 1001: 8, 1005: 6, 1009: 8, 1011: 6, 1013: 1, 1017: 8, 1019: 2, 1020: 8, 1105: 6, 1217: 8, 1221: 5, 1223: 3, 1225: 7, 1233: 8, 1249: 8, 1257: 6, 1259: 8, 1261: 7, 1263: 4, 1265: 8, 1267: 1, 1280: 4, 1296: 4, 1300: 8, 1322: 6, 1417: 8, 1601: 8, 1906: 7, 1907: 7, 1912: 7, 1914: 7, 1918: 7, 1919: 7, 1934: 7, 2016: 8, 2024: 8 + }], + CAR.MALIBU: [ + # Malibu Premier w/ ACC 2017 + { + 190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 209: 7, 211: 2, 241: 6, 249: 8, 288: 5, 298: 8, 304: 1, 309: 8, 311: 8, 313: 8, 320: 3, 328: 1, 352: 5, 381: 6, 384: 4, 386: 8, 388: 8, 393: 7, 398: 8, 407: 7, 413: 8, 417: 7, 419: 1, 422: 4, 426: 7, 431: 8, 442: 8, 451: 8, 452: 8, 453: 6, 455: 7, 456: 8, 479: 3, 481: 7, 485: 8, 487: 8, 489: 8, 495: 4, 497: 8, 499: 3, 500: 6, 501: 8, 508: 8, 510: 8, 528: 5, 532: 6, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 565: 5, 567: 5, 573: 1, 577: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 6, 707: 8, 715: 8, 717: 5, 753: 5, 761: 7, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 869: 4, 880: 6, 961: 8, 969: 8, 977: 8, 979: 8, 985: 5, 1001: 8, 1005: 6, 1009: 8, 1013: 3, 1017: 8, 1019: 2, 1020: 8, 1033: 7, 1034: 7, 1105: 6, 1217: 8, 1221: 5, 1223: 2, 1225: 7, 1233: 8, 1249: 8, 1257: 6, 1265: 8, 1267: 1, 1280: 4, 1296: 4, 1300: 8, 1322: 6, 1323: 4, 1328: 4, 1417: 8, 1601: 8, 1906: 7, 1907: 7, 1912: 7, 1919: 7, 1930: 7, 2016: 8, 2024: 8, + }], + CAR.ACADIA: [ + # Acadia Denali w/ /ACC 2018 + { + 190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 208: 8, 209: 7, 211: 2, 241: 6, 249: 8, 288: 5, 289: 8, 298: 8, 304: 1, 309: 8, 313: 8, 320: 3, 322: 7, 328: 1, 338: 6, 340: 6, 352: 5, 381: 8, 384: 4, 386: 8, 388: 8, 393: 8, 398: 8, 413: 8, 417: 7, 419: 1, 422: 4, 426: 7, 431: 8, 442: 8, 451: 8, 452: 8, 453: 6, 454: 8, 455: 7, 462: 4, 463: 3, 479: 3, 481: 7, 485: 8, 489: 8, 497: 8, 499: 3, 500: 6, 501: 8, 508: 8, 510: 8, 532: 6, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 567: 5, 573: 1, 577: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 6, 707: 8, 715: 8, 717: 5, 753: 5, 761: 7, 840: 5, 842: 5, 844: 8, 866: 4, 869: 4, 880: 6, 961: 8, 969: 8, 977: 8, 979: 8, 985: 5, 1001: 8, 1005: 6, 1009: 8, 1017: 8, 1020: 8, 1033: 7, 1034: 7, 1105: 6, 1217: 8, 1221: 5, 1225: 8, 1233: 8, 1249: 8, 1257: 6, 1265: 8, 1267: 1, 1280: 4, 1296: 4, 1300: 8, 1322: 6, 1328: 4, 1417: 8, 1601: 8, 1906: 7, 1907: 7, 1912: 7, 1914: 7, 1919: 7, 1920: 7, 1930: 7, 2016: 8, 2024: 8 + }], +} + +STEER_THRESHOLD = 1.0 + +STOCK_CONTROL_MSGS = { + CAR.HOLDEN_ASTRA: [384, 715], + CAR.VOLT: [384, 715], # 384 = "ASCMLKASteeringCmd", 715 = "ASCMGasRegenCmd" + CAR.MALIBU: [384, 715], # 384 = "ASCMLKASteeringCmd", 715 = "ASCMGasRegenCmd" + CAR.ACADIA: [384, 715], # 384 = "ASCMLKASteeringCmd", 715 = "ASCMGasRegenCmd" + CAR.CADILLAC_ATS: [384, 715], # 384 = "ASCMLKASteeringCmd", 715 = "ASCMGasRegenCmd" + CAR.CADILLAC_CT6: [], # CT6 does not require ASCMs to be disconnected +} + +DBC = { + CAR.HOLDEN_ASTRA: dbc_dict('gm_global_a_powertrain', 'gm_global_a_object', chassis_dbc='gm_global_a_chassis'), + CAR.VOLT: dbc_dict('gm_global_a_powertrain', 'gm_global_a_object', chassis_dbc='gm_global_a_chassis'), + CAR.MALIBU: dbc_dict('gm_global_a_powertrain', 'gm_global_a_object', chassis_dbc='gm_global_a_chassis'), + CAR.ACADIA: dbc_dict('gm_global_a_powertrain', 'gm_global_a_object', chassis_dbc='gm_global_a_chassis'), + CAR.CADILLAC_ATS: dbc_dict('gm_global_a_powertrain', 'gm_global_a_object', chassis_dbc='gm_global_a_chassis'), + CAR.CADILLAC_CT6: dbc_dict('cadillac_ct6_powertrain', 'cadillac_ct6_object', chassis_dbc='cadillac_ct6_chassis'), +} diff --git a/selfdrive/car/honda/__init__.py b/selfdrive/car/honda/__init__.py new file mode 100644 index 00000000000000..e69de29bb2d1d6 diff --git a/selfdrive/car/honda/carcontroller.py b/selfdrive/car/honda/carcontroller.py new file mode 100644 index 00000000000000..fb29a21e447427 --- /dev/null +++ b/selfdrive/car/honda/carcontroller.py @@ -0,0 +1,198 @@ +from collections import namedtuple +from common.realtime import sec_since_boot +from selfdrive.boardd.boardd import can_list_to_can_capnp +from selfdrive.controls.lib.drive_helpers import rate_limit +from common.numpy_fast import clip +from selfdrive.car.honda import hondacan +from selfdrive.car.honda.values import AH, CruiseButtons, CAR +from selfdrive.can.packer import CANPacker +from common.params import Params + +def actuator_hystereses(brake, braking, brake_steady, v_ego, car_fingerprint): + # hyst params + brake_hyst_on = 0.02 # to activate brakes exceed this value + brake_hyst_off = 0.005 # to deactivate brakes below this value + brake_hyst_gap = 0.01 # don't change brake command for small ocilalitons within this value + + #*** histeresis logic to avoid brake blinking. go above 0.1 to trigger + if (brake < brake_hyst_on and not braking) or brake < brake_hyst_off: + brake = 0. + braking = brake > 0. + + # for small brake oscillations within brake_hyst_gap, don't change the brake command + if brake == 0.: + brake_steady = 0. + elif brake > brake_steady + brake_hyst_gap: + brake_steady = brake - brake_hyst_gap + elif brake < brake_steady - brake_hyst_gap: + brake_steady = brake + brake_hyst_gap + brake = brake_steady + + if (car_fingerprint in (CAR.ACURA_ILX, CAR.CRV)) and brake > 0.0: + brake += 0.15 + + return brake, braking, brake_steady + + +def brake_pump_hysteresys(apply_brake, apply_brake_last, last_pump_ts): + ts = sec_since_boot() + pump_on = False + + # reset pump timer if: + # - there is an increment in brake request + # - we are applying steady state brakes and we haven't been running the pump + # for more than 20s (to prevent pressure bleeding) + if apply_brake > apply_brake_last or (ts - last_pump_ts > 20 and apply_brake > 0): + last_pump_ts = ts + + # once the pump is on, run it for at least 0.2s + if ts - last_pump_ts < 0.2 and apply_brake > 0: + pump_on = True + + return pump_on, last_pump_ts + + +def process_hud_alert(hud_alert): + # initialize to no alert + fcw_display = 0 + steer_required = 0 + acc_alert = 0 + + if hud_alert == AH.NONE: # no alert + pass + elif hud_alert == AH.FCW: # FCW + fcw_display = hud_alert[1] + elif hud_alert == AH.STEER: # STEER + steer_required = hud_alert[1] + else: # any other ACC alert + acc_alert = hud_alert[1] + + return fcw_display, steer_required, acc_alert + + +HUDData = namedtuple("HUDData", + ["pcm_accel", "v_cruise", "mini_car", "car", "X4", + "lanes", "beep", "chime", "fcw", "acc_alert", "steer_required", "dist_lines", "dashed_lanes", "speed_units"]) + + +class CarController(object): + def __init__(self, dbc_name, enable_camera=True): + self.braking = False + self.brake_steady = 0. + self.brake_last = 0. + self.apply_brake_last = 0 + self.last_pump_ts = 0 + self.enable_camera = enable_camera + self.packer = CANPacker(dbc_name) + self.new_radar_config = False + #self.params = Params() + self.is_metric = Params().get("IsMetric") == "1" + if self.is_metric: + self.speed_units = 2 + else: + self.speed_units = 3 + + + + def update(self, sendcan, enabled, CS, frame, actuators, \ + pcm_speed, pcm_override, pcm_cancel_cmd, pcm_accel, \ + radar_error, hud_v_cruise, hud_show_lanes, hud_show_car, \ + hud_alert, snd_beep, snd_chime): + + """ Controls thread """ + + if not self.enable_camera: + return + + # *** apply brake hysteresis *** + brake, self.braking, self.brake_steady = actuator_hystereses(actuators.brake, self.braking, self.brake_steady, CS.v_ego, CS.CP.carFingerprint) + + # *** no output if not enabled *** + if not enabled and CS.pcm_acc_status: + # send pcm acc cancel cmd if drive is disabled but pcm is still on, or if the system can't be activated + pcm_cancel_cmd = True + + # *** rate limit after the enable check *** + self.brake_last = rate_limit(brake, self.brake_last, -2., 1./100) + + # vehicle hud display, wait for one update from 10Hz 0x304 msg + if hud_show_lanes and CS.lkMode and not CS.left_blinker_on and not CS.right_blinker_on: + hud_lanes = 1 + else: + hud_lanes = 0 + + if enabled: + if hud_show_car: + hud_car = 2 + else: + hud_car = 1 + else: + hud_car = 0 + + # For lateral control-only, send chimes as a beep since we don't send 0x1fa + if CS.CP.radarOffCan: + snd_beep = snd_beep if snd_beep is not 0 else snd_chime + + # Do not send audible alert when steering is disabled or blinkers on + #if not CS.lkMode or CS.left_blinker_on or CS.right_blinker_on: + # snd_chime = 0 + + #print chime, alert_id, hud_alert + fcw_display, steer_required, acc_alert = process_hud_alert(hud_alert) + + hud = HUDData(int(pcm_accel), int(round(hud_v_cruise)), 1, hud_car, + 0xc1, hud_lanes, int(snd_beep), snd_chime, fcw_display, acc_alert, steer_required, CS.read_distance_lines, CS.lkMode, self.speed_units) + + # **** process the car messages **** + + # *** compute control surfaces *** + BRAKE_MAX = 1024/4 + if CS.CP.carFingerprint in (CAR.ACURA_ILX): + STEER_MAX = 0xF00 + elif CS.CP.carFingerprint in (CAR.CRV, CAR.ACURA_RDX): + STEER_MAX = 0x3e8 # CR-V only uses 12-bits and requires a lower value (max value from energee) + else: + STEER_MAX = 0x1000 + + # steer torque is converted back to CAN reference (positive when steering right) + apply_gas = clip(actuators.gas, 0., 1.) + apply_brake = int(clip(self.brake_last * BRAKE_MAX, 0, BRAKE_MAX - 1)) + apply_steer = int(clip(-actuators.steer * STEER_MAX, -STEER_MAX, STEER_MAX)) + + lkas_active = enabled and not CS.steer_not_allowed and CS.lkMode and not CS.left_blinker_on and not CS.right_blinker_on # add LKAS button to toggle steering + + # Send CAN commands. + can_sends = [] + + # Send steering command. + idx = frame % 4 + can_sends.append(hondacan.create_steering_control(self.packer, apply_steer, + lkas_active, CS.CP.carFingerprint, idx)) + + # Send dashboard UI commands. + if (frame % 10) == 0: + idx = (frame/10) % 4 + can_sends.extend(hondacan.create_ui_commands(self.packer, pcm_speed, hud, CS.CP.carFingerprint, idx)) + + if CS.CP.radarOffCan: + # If using stock ACC, spam cancel command to kill gas when OP disengages. + if pcm_cancel_cmd: + can_sends.append(hondacan.spam_buttons_command(self.packer, CruiseButtons.CANCEL, idx)) + elif CS.stopped: + can_sends.append(hondacan.spam_buttons_command(self.packer, CruiseButtons.RES_ACCEL, idx)) + + else: + # Send gas and brake commands. + if (frame % 2) == 0: + idx = (frame / 2) % 4 + pump_on, self.last_pump_ts = brake_pump_hysteresys(apply_brake, self.apply_brake_last, self.last_pump_ts) + can_sends.append(hondacan.create_brake_command(self.packer, apply_brake, pump_on, + pcm_override, pcm_cancel_cmd, hud.chime, hud.fcw, idx)) + self.apply_brake_last = apply_brake + + if CS.CP.enableGasInterceptor: + # send exactly zero if apply_gas is zero. Interceptor will send the max between read value and apply_gas. + # This prevents unexpected pedal range rescaling + can_sends.append(hondacan.create_gas_command(self.packer, apply_gas, idx)) + + sendcan.send(can_list_to_can_capnp(can_sends, msgtype='sendcan').to_bytes()) diff --git a/selfdrive/car/honda/carstate.py b/selfdrive/car/honda/carstate.py new file mode 100644 index 00000000000000..8d6e0c882850dd --- /dev/null +++ b/selfdrive/car/honda/carstate.py @@ -0,0 +1,357 @@ +from common.numpy_fast import interp +from common.kalman.simple_kalman import KF1D +from selfdrive.can.parser import CANParser, CANDefine +from selfdrive.config import Conversions as CV +from selfdrive.car.honda.values import CAR, DBC, STEER_THRESHOLD, SPEED_FACTOR, HONDA_BOSCH +from selfdrive.kegman_conf import kegman_conf + +def parse_gear_shifter(gear, vals): + + val_to_capnp = {'P': 'park', 'R': 'reverse', 'N': 'neutral', + 'D': 'drive', 'S': 'sport', 'L': 'low'} + try: + return val_to_capnp[vals[gear]] + except KeyError: + return "unknown" + + +def calc_cruise_offset(offset, speed): + # euristic formula so that speed is controlled to ~ 0.3m/s below pid_speed + # constraints to solve for _K0, _K1, _K2 are: + # - speed = 0m/s, out = -0.3 + # - speed = 34m/s, offset = 20, out = -0.25 + # - speed = 34m/s, offset = -2.5, out = -1.8 + _K0 = -0.3 + _K1 = -0.01879 + _K2 = 0.01013 + return min(_K0 + _K1 * speed + _K2 * speed * offset, 0.) + + +def get_can_signals(CP): +# this function generates lists for signal, messages and initial values + signals = [ + ("XMISSION_SPEED", "ENGINE_DATA", 0), + ("WHEEL_SPEED_FL", "WHEEL_SPEEDS", 0), + ("WHEEL_SPEED_FR", "WHEEL_SPEEDS", 0), + ("WHEEL_SPEED_RL", "WHEEL_SPEEDS", 0), + ("WHEEL_SPEED_RR", "WHEEL_SPEEDS", 0), + ("STEER_ANGLE", "STEERING_SENSORS", 0), + ("STEER_ANGLE_RATE", "STEERING_SENSORS", 0), + ("STEER_ANGLE_OFFSET", "STEERING_SENSORS", 0), + ("STEER_TORQUE_SENSOR", "STEER_STATUS", 0), + ("LEFT_BLINKER", "SCM_FEEDBACK", 0), + ("RIGHT_BLINKER", "SCM_FEEDBACK", 0), + ("GEAR", "GEARBOX", 0), + ("SEATBELT_DRIVER_LAMP", "SEATBELT_STATUS", 1), + ("SEATBELT_DRIVER_LATCHED", "SEATBELT_STATUS", 0), + ("BRAKE_PRESSED", "POWERTRAIN_DATA", 0), + ("BRAKE_SWITCH", "POWERTRAIN_DATA", 0), + ("CRUISE_BUTTONS", "SCM_BUTTONS", 0), + ("ESP_DISABLED", "VSA_STATUS", 1), + ("HUD_LEAD", "ACC_HUD", 0), + ("USER_BRAKE", "VSA_STATUS", 0), + ("STEER_STATUS", "STEER_STATUS", 5), + ("GEAR_SHIFTER", "GEARBOX", 0), + ("PEDAL_GAS", "POWERTRAIN_DATA", 0), + ("CRUISE_SETTING", "SCM_BUTTONS", 0), + ("ACC_STATUS", "POWERTRAIN_DATA", 0), + ] + + checks = [ + ("ENGINE_DATA", 100), + ("WHEEL_SPEEDS", 50), + ("STEERING_SENSORS", 100), + ("SCM_FEEDBACK", 10), + ("GEARBOX", 100), + ("SEATBELT_STATUS", 10), + ("CRUISE", 10), + ("POWERTRAIN_DATA", 100), + ("VSA_STATUS", 50), + ("SCM_BUTTONS", 25), + ] + + if CP.radarOffCan: + # Civic is only bosch to use the same brake message as other hondas. + if CP.carFingerprint not in (CAR.ACCORDH, CAR.CIVIC_BOSCH): + signals += [("BRAKE_PRESSED", "BRAKE_MODULE", 0)] + checks += [("BRAKE_MODULE", 50)] + signals += [("CAR_GAS", "GAS_PEDAL_2", 0), + ("MAIN_ON", "SCM_FEEDBACK", 0), + ("EPB_STATE", "EPB_STATUS", 0), + ("BRAKE_HOLD_ACTIVE", "VSA_STATUS", 0), + ("CRUISE_SPEED", "ACC_HUD", 0)] + checks += [("GAS_PEDAL_2", 100)] + else: + # Nidec signals. + signals += [("BRAKE_ERROR_1", "STANDSTILL", 1), + ("BRAKE_ERROR_2", "STANDSTILL", 1), + ("CRUISE_SPEED_PCM", "CRUISE", 0), + ("CRUISE_SPEED_OFFSET", "CRUISE_PARAMS", 0)] + checks += [("CRUISE_PARAMS", 50), + ("STANDSTILL", 50)] + + if CP.carFingerprint in (CAR.ACCORD, CAR.ACCORD_15, CAR.ACCORDH, CAR.CIVIC_BOSCH): + signals += [("DRIVERS_DOOR_OPEN", "SCM_FEEDBACK", 1)] + else: + signals += [("DOOR_OPEN_FL", "DOORS_STATUS", 1), + ("DOOR_OPEN_FR", "DOORS_STATUS", 1), + ("DOOR_OPEN_RL", "DOORS_STATUS", 1), + ("DOOR_OPEN_RR", "DOORS_STATUS", 1), + ("WHEELS_MOVING", "STANDSTILL", 1)] + checks += [("DOORS_STATUS", 3)] + + if CP.carFingerprint == CAR.CIVIC: + signals += [("CAR_GAS", "GAS_PEDAL_2", 0), + ("MAIN_ON", "SCM_FEEDBACK", 0), + ("EPB_STATE", "EPB_STATUS", 0), + ("BRAKE_HOLD_ACTIVE", "VSA_STATUS", 0)] + elif CP.carFingerprint == CAR.ACURA_ILX: + signals += [("CAR_GAS", "GAS_PEDAL_2", 0), + ("MAIN_ON", "SCM_BUTTONS", 0)] + elif CP.carFingerprint in (CAR.CRV, CAR.ACURA_RDX, CAR.PILOT_2019, CAR.RIDGELINE): + signals += [("MAIN_ON", "SCM_BUTTONS", 0)] + elif CP.carFingerprint == CAR.ODYSSEY: + signals += [("MAIN_ON", "SCM_FEEDBACK", 0), + ("EPB_STATE", "EPB_STATUS", 0), + ("BRAKE_HOLD_ACTIVE", "VSA_STATUS", 0)] + checks += [("EPB_STATUS", 50)] + elif CP.carFingerprint == CAR.PILOT: + signals += [("MAIN_ON", "SCM_BUTTONS", 0), + ("CAR_GAS", "GAS_PEDAL_2", 0)] + + # add gas interceptor reading if we are using it + if CP.enableGasInterceptor: + signals.append(("INTERCEPTOR_GAS", "GAS_SENSOR", 0)) + checks.append(("GAS_SENSOR", 50)) + + return signals, checks + + +def get_can_parser(CP): + signals, checks = get_can_signals(CP) + return CANParser(DBC[CP.carFingerprint]['pt'], signals, checks, 0) + +def get_cam_can_parser(CP): + signals = [] + + # all hondas except CRV and RDX use 0xe4 for steering + checks = [(0xe4, 100)] + if CP.carFingerprint in [CAR.CRV, CAR.ACURA_RDX]: + checks = [(0x194, 100)] + + cam_bus = 1 if CP.carFingerprint in HONDA_BOSCH else 2 + + return CANParser(DBC[CP.carFingerprint]['pt'], signals, checks, cam_bus) + +class CarState(object): + def __init__(self, CP): + self.k = kegman_conf() + self.trMode = int(self.k.conf['lastTrMode']) # default to last distance interval on startup + self.lkMode = True + self.read_distance_lines_prev = 4 + self.CP = CP + self.can_define = CANDefine(DBC[CP.carFingerprint]['pt']) + self.shifter_values = self.can_define.dv["GEARBOX"]["GEAR_SHIFTER"] + + self.user_gas, self.user_gas_pressed = 0., 0 + self.brake_switch_prev = 0 + self.brake_switch_ts = 0 + + self.cruise_buttons = 0 + self.cruise_setting = 0 + self.v_cruise_pcm_prev = 0 + self.blinker_on = 0 + + self.left_blinker_on = 0 + self.right_blinker_on = 0 + + self.stopped = 0 + + # vEgo kalman filter + dt = 0.01 + # Q = np.matrix([[10.0, 0.0], [0.0, 100.0]]) + # R = 1e3 + self.v_ego_kf = KF1D(x0=[[0.0], [0.0]], + A=[[1.0, dt], [0.0, 1.0]], + C=[[1.0, 0.0]], + K=[[0.12287673], [0.29666309]]) + self.v_ego = 0.0 + + def update(self, cp, cp_cam): + + # copy can_valid on buses 0 and 2 + self.can_valid = cp.can_valid + self.cam_can_valid = cp_cam.can_valid + + # car params + v_weight_v = [0., 1.] # don't trust smooth speed at low values to avoid premature zero snapping + v_weight_bp = [1., 6.] # smooth blending, below ~0.6m/s the smooth speed snaps to zero + + # update prevs, update must run once per loop + self.prev_cruise_buttons = self.cruise_buttons + self.prev_blinker_on = self.blinker_on + + self.prev_left_blinker_on = self.left_blinker_on + self.prev_right_blinker_on = self.right_blinker_on + + # ******************* parse out can ******************* + + if self.CP.carFingerprint in (CAR.ACCORD, CAR.ACCORD_15, CAR.ACCORDH, CAR.CIVIC_BOSCH): # TODO: find wheels moving bit in dbc + self.standstill = cp.vl["ENGINE_DATA"]['XMISSION_SPEED'] < 0.1 + self.door_all_closed = not cp.vl["SCM_FEEDBACK"]['DRIVERS_DOOR_OPEN'] + else: + self.standstill = not cp.vl["STANDSTILL"]['WHEELS_MOVING'] + self.door_all_closed = not any([cp.vl["DOORS_STATUS"]['DOOR_OPEN_FL'], cp.vl["DOORS_STATUS"]['DOOR_OPEN_FR'], + cp.vl["DOORS_STATUS"]['DOOR_OPEN_RL'], cp.vl["DOORS_STATUS"]['DOOR_OPEN_RR']]) + self.seatbelt = not cp.vl["SEATBELT_STATUS"]['SEATBELT_DRIVER_LAMP'] and cp.vl["SEATBELT_STATUS"]['SEATBELT_DRIVER_LATCHED'] + + # 2 = temporary; 3 = TBD; 4 = temporary, hit a bump; 5 = (permanent); 6 = temporary; 7 = (permanent) + # TODO: Use values from DBC to parse this field + self.steer_error = cp.vl["STEER_STATUS"]['STEER_STATUS'] not in [0, 2, 3, 4, 6] + self.steer_not_allowed = cp.vl["STEER_STATUS"]['STEER_STATUS'] != 0 + self.steer_warning = cp.vl["STEER_STATUS"]['STEER_STATUS'] not in [0, 3] # 3 is low speed lockout, not worth a warning + if self.CP.radarOffCan: + self.brake_error = 0 + else: + self.brake_error = cp.vl["STANDSTILL"]['BRAKE_ERROR_1'] or cp.vl["STANDSTILL"]['BRAKE_ERROR_2'] + self.esp_disabled = cp.vl["VSA_STATUS"]['ESP_DISABLED'] + + # calc best v_ego estimate, by averaging two opposite corners + speed_factor = SPEED_FACTOR[self.CP.carFingerprint] + self.v_wheel_fl = cp.vl["WHEEL_SPEEDS"]['WHEEL_SPEED_FL'] * CV.KPH_TO_MS * speed_factor + self.v_wheel_fr = cp.vl["WHEEL_SPEEDS"]['WHEEL_SPEED_FR'] * CV.KPH_TO_MS * speed_factor + self.v_wheel_rl = cp.vl["WHEEL_SPEEDS"]['WHEEL_SPEED_RL'] * CV.KPH_TO_MS * speed_factor + self.v_wheel_rr = cp.vl["WHEEL_SPEEDS"]['WHEEL_SPEED_RR'] * CV.KPH_TO_MS * speed_factor + self.v_wheel = (self.v_wheel_fl+self.v_wheel_fr+self.v_wheel_rl+self.v_wheel_rr)/4. + + # blend in transmission speed at low speed, since it has more low speed accuracy + self.v_weight = interp(self.v_wheel, v_weight_bp, v_weight_v) + speed = (1. - self.v_weight) * cp.vl["ENGINE_DATA"]['XMISSION_SPEED'] * CV.KPH_TO_MS * speed_factor + \ + self.v_weight * self.v_wheel + + if abs(speed - self.v_ego) > 2.0: # Prevent large accelerations when car starts at non zero speed + self.v_ego_x = [[speed], [0.0]] + + self.v_ego_raw = speed + v_ego_x = self.v_ego_kf.update(speed) + self.v_ego = float(v_ego_x[0]) + self.a_ego = float(v_ego_x[1]) + + # this is a hack for the interceptor. This is now only used in the simulation + # TODO: Replace tests by toyota so this can go away + if self.CP.enableGasInterceptor: + self.user_gas = cp.vl["GAS_SENSOR"]['INTERCEPTOR_GAS'] + self.user_gas_pressed = self.user_gas > 0 # this works because interceptor read < 0 when pedal position is 0. Once calibrated, this will change + + self.gear = 0 if self.CP.carFingerprint == CAR.CIVIC else cp.vl["GEARBOX"]['GEAR'] + if self.CP.carFingerprint in HONDA_BOSCH: + self.angle_steers = cp.vl["STEERING_SENSORS"]['STEER_ANGLE'] + cp.vl["STEERING_SENSORS"]['STEER_ANGLE_OFFSET'] + else: + self.angle_steers = cp.vl["STEERING_SENSORS"]['STEER_ANGLE'] + + self.angle_steers_rate = cp.vl["STEERING_SENSORS"]['STEER_ANGLE_RATE'] + + #self.cruise_setting = cp.vl["SCM_BUTTONS"]['CRUISE_SETTING'] + self.cruise_buttons = cp.vl["SCM_BUTTONS"]['CRUISE_BUTTONS'] + + self.blinker_on = cp.vl["SCM_FEEDBACK"]['LEFT_BLINKER'] or cp.vl["SCM_FEEDBACK"]['RIGHT_BLINKER'] + self.left_blinker_on = cp.vl["SCM_FEEDBACK"]['LEFT_BLINKER'] + self.right_blinker_on = cp.vl["SCM_FEEDBACK"]['RIGHT_BLINKER'] + + if self.CP.carFingerprint in (CAR.CIVIC, CAR.ODYSSEY, CAR.CRV_5G, CAR.ACCORD, CAR.ACCORD_15, CAR.ACCORDH, CAR.CIVIC_BOSCH): + self.park_brake = cp.vl["EPB_STATUS"]['EPB_STATE'] != 0 + self.brake_hold = cp.vl["VSA_STATUS"]['BRAKE_HOLD_ACTIVE'] + self.main_on = cp.vl["SCM_FEEDBACK"]['MAIN_ON'] + else: + self.park_brake = 0 # TODO + self.brake_hold = 0 # TODO + self.main_on = cp.vl["SCM_BUTTONS"]['MAIN_ON'] + + can_gear_shifter = int(cp.vl["GEARBOX"]['GEAR_SHIFTER']) + self.gear_shifter = parse_gear_shifter(can_gear_shifter, self.shifter_values) + + self.pedal_gas = cp.vl["POWERTRAIN_DATA"]['PEDAL_GAS'] + # crv doesn't include cruise control + if self.CP.carFingerprint in (CAR.CRV, CAR.ODYSSEY, CAR.ACURA_RDX, CAR.RIDGELINE, CAR.PILOT_2019): + self.car_gas = self.pedal_gas + else: + self.car_gas = cp.vl["GAS_PEDAL_2"]['CAR_GAS'] + + self.steer_torque_driver = cp.vl["STEER_STATUS"]['STEER_TORQUE_SENSOR'] + self.steer_override = abs(self.steer_torque_driver) > STEER_THRESHOLD[self.CP.carFingerprint] + self.brake_switch = cp.vl["POWERTRAIN_DATA"]['BRAKE_SWITCH'] + + if self.CP.radarOffCan: + self.stopped = cp.vl["ACC_HUD"]['CRUISE_SPEED'] == 252. + self.cruise_speed_offset = calc_cruise_offset(0, self.v_ego) + if self.CP.carFingerprint in (CAR.CIVIC_BOSCH, CAR.ACCORDH): + self.brake_switch = cp.vl["POWERTRAIN_DATA"]['BRAKE_SWITCH'] + self.brake_pressed = cp.vl["POWERTRAIN_DATA"]['BRAKE_PRESSED'] or \ + (self.brake_switch and self.brake_switch_prev and \ + cp.ts["POWERTRAIN_DATA"]['BRAKE_SWITCH'] != self.brake_switch_ts) + self.brake_switch_prev = self.brake_switch + self.brake_switch_ts = cp.ts["POWERTRAIN_DATA"]['BRAKE_SWITCH'] + else: + self.brake_pressed = cp.vl["BRAKE_MODULE"]['BRAKE_PRESSED'] + # On set, cruise set speed pulses between 254~255 and the set speed prev is set to avoid this. + self.v_cruise_pcm = self.v_cruise_pcm_prev if cp.vl["ACC_HUD"]['CRUISE_SPEED'] > 160.0 else cp.vl["ACC_HUD"]['CRUISE_SPEED'] + self.v_cruise_pcm_prev = self.v_cruise_pcm + else: + self.brake_switch = cp.vl["POWERTRAIN_DATA"]['BRAKE_SWITCH'] + self.cruise_speed_offset = calc_cruise_offset(cp.vl["CRUISE_PARAMS"]['CRUISE_SPEED_OFFSET'], self.v_ego) + self.v_cruise_pcm = cp.vl["CRUISE"]['CRUISE_SPEED_PCM'] + # brake switch has shown some single time step noise, so only considered when + # switch is on for at least 2 consecutive CAN samples + self.brake_pressed = cp.vl["POWERTRAIN_DATA"]['BRAKE_PRESSED'] or \ + (self.brake_switch and self.brake_switch_prev and \ + cp.ts["POWERTRAIN_DATA"]['BRAKE_SWITCH'] != self.brake_switch_ts) + + self.brake_switch_prev = self.brake_switch + self.brake_switch_ts = cp.ts["POWERTRAIN_DATA"]['BRAKE_SWITCH'] + + self.user_brake = cp.vl["VSA_STATUS"]['USER_BRAKE'] + self.pcm_acc_status = cp.vl["POWERTRAIN_DATA"]['ACC_STATUS'] + self.hud_lead = cp.vl["ACC_HUD"]['HUD_LEAD'] + + # gets rid of Pedal Grinding noise for certain models + if self.CP.carFingerprint in (CAR.PILOT, CAR.PILOT_2019, CAR.RIDGELINE): + if self.user_brake > 0.05: + self.brake_pressed = 1 + + # when user presses distance button on steering wheel + if self.cruise_setting == 3: + if cp.vl["SCM_BUTTONS"]["CRUISE_SETTING"] == 0: + self.trMode = (self.trMode + 1 ) % 4 + self.k.conf['lastTrMode'] = str(self.trMode) # write last distance bar setting to file + self.k.write_config(self.k.conf) + + # when user presses LKAS button on steering wheel + if self.cruise_setting == 1: + if cp.vl["SCM_BUTTONS"]["CRUISE_SETTING"] == 0: + if self.lkMode: + self.lkMode = False + else: + self.lkMode = True + + self.prev_cruise_setting = self.cruise_setting + self.cruise_setting = cp.vl["SCM_BUTTONS"]['CRUISE_SETTING'] + self.read_distance_lines = self.trMode + 1 + + if self.read_distance_lines <> self.read_distance_lines_prev: + self.read_distance_lines_prev = self.read_distance_lines + +# carstate standalone tester +if __name__ == '__main__': + import zmq + context = zmq.Context() + + class CarParams(object): + def __init__(self): + self.carFingerprint = "HONDA CIVIC 2016 TOURING" + self.enableGasInterceptor = 0 + CP = CarParams() + CS = CarState(CP) + + # while 1: + # CS.update() + # time.sleep(0.01) diff --git a/selfdrive/car/honda/hondacan.py b/selfdrive/car/honda/hondacan.py new file mode 100644 index 00000000000000..88768bbec11e93 --- /dev/null +++ b/selfdrive/car/honda/hondacan.py @@ -0,0 +1,114 @@ +import struct +from selfdrive.config import Conversions as CV +from selfdrive.car.honda.values import CAR, HONDA_BOSCH + +# *** Honda specific *** +def can_cksum(mm): + s = 0 + for c in mm: + c = ord(c) + s += (c>>4) + s += c & 0xF + s = 8-s + s %= 0x10 + return s + + +def fix(msg, addr): + msg2 = msg[0:-1] + chr(ord(msg[-1]) | can_cksum(struct.pack("I", addr)+msg)) + return msg2 + + +def create_brake_command(packer, apply_brake, pump_on, pcm_override, pcm_cancel_cmd, chime, fcw, idx): + # TODO: do we loose pressure if we keep pump off for long? + brakelights = apply_brake > 0 + brake_rq = apply_brake > 0 + pcm_fault_cmd = False + + values = { + "COMPUTER_BRAKE": apply_brake, + "BRAKE_PUMP_REQUEST": pump_on, + "CRUISE_OVERRIDE": pcm_override, + "CRUISE_FAULT_CMD": pcm_fault_cmd, + "CRUISE_CANCEL_CMD": pcm_cancel_cmd, + "COMPUTER_BRAKE_REQUEST": brake_rq, + "SET_ME_0X80": 0x80, + "BRAKE_LIGHTS": brakelights, + "CHIME": chime, + # TODO: Why are there two bits for fcw? According to dbc file the first bit should also work + "FCW": fcw << 1, + } + return packer.make_can_msg("BRAKE_COMMAND", 0, values, idx) + + +def create_gas_command(packer, gas_amount, idx): + enable = gas_amount > 0.001 + + values = {"ENABLE": enable} + + if enable: + values["GAS_COMMAND"] = gas_amount * 255. + values["GAS_COMMAND2"] = gas_amount * 255. + + return packer.make_can_msg("GAS_COMMAND", 0, values, idx) + + +def create_steering_control(packer, apply_steer, lkas_active, car_fingerprint, idx): + values = { + "STEER_TORQUE": apply_steer if lkas_active else 0, + "STEER_TORQUE_REQUEST": lkas_active, + } + # Set bus 2 for accord and new crv. + bus = 2 if car_fingerprint in HONDA_BOSCH else 0 + return packer.make_can_msg("STEERING_CONTROL", bus, values, idx) + + +def create_ui_commands(packer, pcm_speed, hud, car_fingerprint, idx): + commands = [] + bus = 0 + + # Bosch sends commands to bus 2. + if car_fingerprint in HONDA_BOSCH: + bus = 2 + else: + acc_hud_values = { + 'PCM_SPEED': pcm_speed * CV.MS_TO_KPH, + 'PCM_GAS': hud.pcm_accel, + 'CRUISE_SPEED': hud.v_cruise, + 'ENABLE_MINI_CAR': hud.mini_car, + 'HUD_LEAD': hud.car, + 'SET_ME_X03': hud.dist_lines, + 'SET_ME_X03_2': hud.speed_units, + 'SET_ME_X01': 0x01, + 'HUD_DISTANCE_3': 1, + } + commands.append(packer.make_can_msg("ACC_HUD", 0, acc_hud_values, idx)) + + lkas_hud_values = { + 'SET_ME_X41': 0x41, + 'SET_ME_X48': 0x48, + 'STEERING_REQUIRED': hud.steer_required, + 'SOLID_LANES': hud.lanes, + 'DASHED_LANES': hud.dashed_lanes, + 'BEEP': hud.beep, + } + commands.append(packer.make_can_msg('LKAS_HUD', bus, lkas_hud_values, idx)) + + if car_fingerprint in (CAR.CIVIC, CAR.ODYSSEY): + + radar_hud_values = { + 'ACC_ALERTS': hud.acc_alert, + 'LEAD_SPEED': 0x1fe, # What are these magic values + 'LEAD_STATE': 0x7, + 'LEAD_DISTANCE': 0x1e, + } + commands.append(packer.make_can_msg('RADAR_HUD', 0, radar_hud_values, idx)) + return commands + + +def spam_buttons_command(packer, button_val, idx): + values = { + 'CRUISE_BUTTONS': button_val, + 'CRUISE_SETTING': 0, + } + return packer.make_can_msg("SCM_BUTTONS", 0, values, idx) diff --git a/selfdrive/car/honda/interface.py b/selfdrive/car/honda/interface.py new file mode 100755 index 00000000000000..bbb205bac0d635 --- /dev/null +++ b/selfdrive/car/honda/interface.py @@ -0,0 +1,623 @@ +#!/usr/bin/env python +import os +import numpy as np +from cereal import car, log +from common.numpy_fast import clip, interp +from common.realtime import sec_since_boot +from selfdrive.swaglog import cloudlog +from selfdrive.config import Conversions as CV +from selfdrive.controls.lib.drive_helpers import create_event, EventTypes as ET, get_events +from selfdrive.controls.lib.vehicle_model import VehicleModel +from selfdrive.car.honda.carstate import CarState, get_can_parser, get_cam_can_parser +from selfdrive.car.honda.values import CruiseButtons, CAR, HONDA_BOSCH, AUDIO_HUD, VISUAL_HUD +from selfdrive.controls.lib.planner import _A_CRUISE_MAX_V_FOLLOWING + +try: + from selfdrive.car.honda.carcontroller import CarController +except ImportError: + CarController = None + + +# msgs sent for steering controller by camera module on can 0. +# those messages are mutually exclusive on CRV and non-CRV cars +CAMERA_MSGS = [0xe4, 0x194] + +A_ACC_MAX = max(_A_CRUISE_MAX_V_FOLLOWING) + + +def compute_gb_honda(accel, speed): + creep_brake = 0.0 + creep_speed = 2.3 + creep_brake_value = 0.15 + if speed < creep_speed: + creep_brake = (creep_speed - speed) / creep_speed * creep_brake_value + return float(accel) / 4.8 - creep_brake + + +def get_compute_gb_acura(): + # generate a function that takes in [desired_accel, current_speed] -> [-1.0, 1.0] + # where -1.0 is max brake and 1.0 is max gas + # see debug/dump_accel_from_fiber.py to see how those parameters were generated + w0 = np.array([[ 1.22056961, -0.39625418, 0.67952657], + [ 1.03691769, 0.78210306, -0.41343188]]) + b0 = np.array([ 0.01536703, -0.14335321, -0.26932889]) + w2 = np.array([[-0.59124422, 0.42899439, 0.38660881], + [ 0.79973811, 0.13178682, 0.08550351], + [-0.15651935, -0.44360259, 0.76910877]]) + b2 = np.array([ 0.15624429, 0.02294923, -0.0341086 ]) + w4 = np.array([[-0.31521443], + [-0.38626176], + [ 0.52667892]]) + b4 = np.array([-0.02922216]) + + def compute_output(dat, w0, b0, w2, b2, w4, b4): + m0 = np.dot(dat, w0) + b0 + m0 = leakyrelu(m0, 0.1) + m2 = np.dot(m0, w2) + b2 + m2 = leakyrelu(m2, 0.1) + m4 = np.dot(m2, w4) + b4 + return m4 + + def leakyrelu(x, alpha): + return np.maximum(x, alpha * x) + + def _compute_gb_acura(accel, speed): + # linearly extrap below v1 using v1 and v2 data + v1 = 5. + v2 = 10. + dat = np.array([accel, speed]) + if speed > 5.: + m4 = compute_output(dat, w0, b0, w2, b2, w4, b4) + else: + dat[1] = v1 + m4v1 = compute_output(dat, w0, b0, w2, b2, w4, b4) + dat[1] = v2 + m4v2 = compute_output(dat, w0, b0, w2, b2, w4, b4) + m4 = (speed - v1) * (m4v2 - m4v1) / (v2 - v1) + m4v1 + return float(m4) + + return _compute_gb_acura + + +class CarInterface(object): + def __init__(self, CP, sendcan=None): + self.CP = CP + + self.frame = 0 + self.last_enable_pressed = 0 + self.last_enable_sent = 0 + self.gas_pressed_prev = False + self.brake_pressed_prev = False + self.can_invalid_count = 0 + self.cam_can_invalid_count = 0 + + self.cp = get_can_parser(CP) + self.cp_cam = get_cam_can_parser(CP) + + # *** init the major players *** + self.CS = CarState(CP) + self.VM = VehicleModel(CP) + + # sending if read only is False + if sendcan is not None: + self.sendcan = sendcan + self.CC = CarController(self.cp.dbc_name, CP.enableCamera) + + if self.CS.CP.carFingerprint == CAR.ACURA_ILX: + self.compute_gb = get_compute_gb_acura() + else: + self.compute_gb = compute_gb_honda + + @staticmethod + def calc_accel_override(a_ego, a_target, v_ego, v_target): + + # normalized max accel. Allowing max accel at low speed causes speed overshoots + max_accel_bp = [10, 20] # m/s + max_accel_v = [0.714, 1.0] # unit of max accel + max_accel = interp(v_ego, max_accel_bp, max_accel_v) + + # limit the pcm accel cmd if: + # - v_ego exceeds v_target, or + # - a_ego exceeds a_target and v_ego is close to v_target + + eA = a_ego - a_target + valuesA = [1.0, 0.1] + bpA = [0.3, 1.1] + + eV = v_ego - v_target + valuesV = [1.0, 0.1] + bpV = [0.0, 0.5] + + valuesRangeV = [1., 0.] + bpRangeV = [-1., 0.] + + # only limit if v_ego is close to v_target + speedLimiter = interp(eV, bpV, valuesV) + accelLimiter = max(interp(eA, bpA, valuesA), interp(eV, bpRangeV, valuesRangeV)) + + # accelOverride is more or less the max throttle allowed to pcm: usually set to a constant + # unless aTargetMax is very high and then we scale with it; this help in quicker restart + + return float(max(max_accel, a_target / A_ACC_MAX)) * min(speedLimiter, accelLimiter) + + @staticmethod + def get_params(candidate, fingerprint): + + ret = car.CarParams.new_message() + ret.carName = "honda" + ret.carFingerprint = candidate + + if candidate in HONDA_BOSCH: + ret.safetyModel = car.CarParams.SafetyModels.hondaBosch + ret.enableCamera = True + ret.radarOffCan = True + ret.openpilotLongitudinalControl = False + else: + ret.safetyModel = car.CarParams.SafetyModels.honda + ret.enableCamera = not any(x for x in CAMERA_MSGS if x in fingerprint) + ret.enableGasInterceptor = 0x201 in fingerprint + ret.openpilotLongitudinalControl = ret.enableCamera + + cloudlog.warn("ECU Camera Simulated: %r", ret.enableCamera) + cloudlog.warn("ECU Gas Interceptor: %r", ret.enableGasInterceptor) + + ret.enableCruise = not ret.enableGasInterceptor + + # kg of standard extra cargo to count for drive, gas, etc... + std_cargo = 136 + + # FIXME: hardcoding honda civic 2016 touring params so they can be used to + # scale unknown params for other cars + mass_civic = 2923 * CV.LB_TO_KG + std_cargo + wheelbase_civic = 2.70 + centerToFront_civic = wheelbase_civic * 0.4 + centerToRear_civic = wheelbase_civic - centerToFront_civic + rotationalInertia_civic = 2500 + tireStiffnessFront_civic = 192150 + tireStiffnessRear_civic = 202500 + + # Optimized car params: tire_stiffness_factor and steerRatio are a result of a vehicle + # model optimization process. Certain Hondas have an extra steering sensor at the bottom + # of the steering rack, which improves controls quality as it removes the steering column + # torsion from feedback. + # Tire stiffness factor fictitiously lower if it includes the steering column torsion effect. + # For modeling details, see p.198-200 in "The Science of Vehicle Dynamics (2014), M. Guiggiani" + + ret.steerKiBP, ret.steerKpBP = [[0.], [0.]] + + ret.steerKf = 0.00006 # conservative feed-forward + + if candidate in [CAR.CIVIC, CAR.CIVIC_BOSCH]: + stop_and_go = True + ret.mass = mass_civic + ret.wheelbase = wheelbase_civic + ret.centerToFront = centerToFront_civic + ret.steerRatio = 14.63 # 10.93 is end-to-end spec + tire_stiffness_factor = 1. + # Civic at comma has modified steering FW, so different tuning for the Neo in that car + is_fw_modified = os.getenv("DONGLE_ID") in ['99c94dc769b5d96e'] + ret.steerKpV, ret.steerKiV = [[0.4], [0.12]] if is_fw_modified else [[0.8], [0.24]] + if is_fw_modified: + tire_stiffness_factor = 0.9 + ret.steerKf = 0.00004 + ret.longitudinalKpBP = [0., 5., 35.] + ret.longitudinalKpV = [3.6, 2.4, 1.5] + ret.longitudinalKiBP = [0., 35.] + ret.longitudinalKiV = [0.54, 0.36] + + elif candidate in (CAR.ACCORD, CAR.ACCORD_15, CAR.ACCORDH): + stop_and_go = True + if not candidate == CAR.ACCORDH: # Hybrid uses same brake msg as hatch + ret.safetyParam = 1 # Accord and CRV 5G use an alternate user brake msg + ret.mass = 3279. * CV.LB_TO_KG + std_cargo + ret.wheelbase = 2.83 + ret.centerToFront = ret.wheelbase * 0.39 + ret.steerRatio = 15.96 # 11.82 is spec end-to-end + tire_stiffness_factor = 0.8467 + ret.steerKpV, ret.steerKiV = [[0.6], [0.18]] + ret.longitudinalKpBP = [0., 5., 35.] + ret.longitudinalKpV = [1.2, 0.8, 0.5] + ret.longitudinalKiBP = [0., 35.] + ret.longitudinalKiV = [0.18, 0.12] + + elif candidate == CAR.ACURA_ILX: + stop_and_go = False + ret.mass = 3095 * CV.LB_TO_KG + std_cargo + ret.wheelbase = 2.67 + ret.centerToFront = ret.wheelbase * 0.37 + ret.steerRatio = 18.61 # 15.3 is spec end-to-end + tire_stiffness_factor = 0.72 + ret.steerKpV, ret.steerKiV = [[0.8], [0.24]] + ret.longitudinalKpBP = [0., 5., 35.] + ret.longitudinalKpV = [1.2, 0.8, 0.5] + ret.longitudinalKiBP = [0., 35.] + ret.longitudinalKiV = [0.18, 0.12] + + elif candidate == CAR.CRV: + stop_and_go = False + ret.mass = 3572 * CV.LB_TO_KG + std_cargo + ret.wheelbase = 2.62 + ret.centerToFront = ret.wheelbase * 0.41 + ret.steerRatio = 15.3 # as spec + tire_stiffness_factor = 0.444 # not optimized yet + ret.steerKpV, ret.steerKiV = [[0.6], [0.18]] + ret.longitudinalKpBP = [0., 5., 35.] + ret.longitudinalKpV = [1.2, 0.8, 0.5] + ret.longitudinalKiBP = [0., 35.] + ret.longitudinalKiV = [0.18, 0.12] + + elif candidate == CAR.CRV_5G: + stop_and_go = True + ret.safetyParam = 1 # Accord and CRV 5G use an alternate user brake msg + ret.mass = 3410. * CV.LB_TO_KG + std_cargo + ret.wheelbase = 2.66 + ret.centerToFront = ret.wheelbase * 0.41 + ret.steerRatio = 16.0 # 12.3 is spec end-to-end + tire_stiffness_factor = 0.677 + ret.steerKpV, ret.steerKiV = [[0.6], [0.18]] + ret.longitudinalKpBP = [0., 5., 35.] + ret.longitudinalKpV = [1.2, 0.8, 0.5] + ret.longitudinalKiBP = [0., 35.] + ret.longitudinalKiV = [0.18, 0.12] + + elif candidate == CAR.ACURA_RDX: + stop_and_go = False + ret.mass = 3935 * CV.LB_TO_KG + std_cargo + ret.wheelbase = 2.68 + ret.centerToFront = ret.wheelbase * 0.38 + ret.steerRatio = 15.0 # as spec + tire_stiffness_factor = 0.444 # not optimized yet + ret.steerKpV, ret.steerKiV = [[0.6], [0.18]] + ret.longitudinalKpBP = [0., 5., 35.] + ret.longitudinalKpV = [1.2, 0.8, 0.5] + ret.longitudinalKiBP = [0., 35.] + ret.longitudinalKiV = [0.18, 0.12] + + elif candidate == CAR.ODYSSEY: + stop_and_go = False + ret.mass = 4471 * CV.LB_TO_KG + std_cargo + ret.wheelbase = 3.00 + ret.centerToFront = ret.wheelbase * 0.41 + ret.steerRatio = 14.35 # as spec + tire_stiffness_factor = 0.82 + ret.steerKpV, ret.steerKiV = [[0.45], [0.135]] + ret.longitudinalKpBP = [0., 5., 35.] + ret.longitudinalKpV = [1.2, 0.8, 0.5] + ret.longitudinalKiBP = [0., 35.] + ret.longitudinalKiV = [0.18, 0.12] + + elif candidate in (CAR.PILOT, CAR.PILOT_2019): + stop_and_go = False + ret.mass = 4303 * CV.LB_TO_KG + std_cargo + ret.wheelbase = 2.81 + ret.centerToFront = ret.wheelbase * 0.41 + ret.steerRatio = 16.0 # as spec + tire_stiffness_factor = 0.82 + ret.steerKpV, ret.steerKiV = [[0.5], [0.22]] + ret.steerKf = 0.000078 + ret.longitudinalKpBP = [0., 5., 35.] + ret.longitudinalKpV = [1.2, 0.8, 0.5] + ret.longitudinalKiBP = [0., 35.] + ret.longitudinalKiV = [0.18, 0.12] + + elif candidate == CAR.RIDGELINE: + stop_and_go = False + ret.mass = 4515 * CV.LB_TO_KG + std_cargo + ret.wheelbase = 3.18 + ret.centerToFront = ret.wheelbase * 0.41 + ret.steerRatio = 15.59 # as spec + tire_stiffness_factor = 0.82 + ret.steerKpV, ret.steerKiV = [[0.5], [0.22]] + ret.longitudinalKpBP = [0., 5., 35.] + ret.longitudinalKpV = [1.2, 0.8, 0.5] + ret.longitudinalKiBP = [0., 35.] + ret.longitudinalKiV = [0.18, 0.12] + + else: + raise ValueError("unsupported car %s" % candidate) + + ret.steerControlType = car.CarParams.SteerControlType.torque + + # min speed to enable ACC. if car can do stop and go, then set enabling speed + # to a negative value, so it won't matter. Otherwise, add 0.5 mph margin to not + # conflict with PCM acc + ret.minEnableSpeed = -1. if (stop_and_go or ret.enableGasInterceptor) else 25.5 * CV.MPH_TO_MS + + centerToRear = ret.wheelbase - ret.centerToFront + # TODO: get actual value, for now starting with reasonable value for + # civic and scaling by mass and wheelbase + ret.rotationalInertia = rotationalInertia_civic * \ + ret.mass * ret.wheelbase**2 / (mass_civic * wheelbase_civic**2) + + # TODO: start from empirically derived lateral slip stiffness for the civic and scale by + # mass and CG position, so all cars will have approximately similar dyn behaviors + ret.tireStiffnessFront = (tireStiffnessFront_civic * tire_stiffness_factor) * \ + ret.mass / mass_civic * \ + (centerToRear / ret.wheelbase) / (centerToRear_civic / wheelbase_civic) + ret.tireStiffnessRear = (tireStiffnessRear_civic * tire_stiffness_factor) * \ + ret.mass / mass_civic * \ + (ret.centerToFront / ret.wheelbase) / (centerToFront_civic / wheelbase_civic) + + # no rear steering, at least on the listed cars above + ret.steerRatioRear = 0. + + # no max steer limit VS speed + ret.steerMaxBP = [0.] # m/s + ret.steerMaxV = [1.] # max steer allowed + + # prevent lurching when resuming + if ret.enableGasInterceptor: + ret.gasMaxBP = [0., 8, 35] + ret.gasMaxV = [0.2, 0.6, 0.6] + ret.longitudinalKpBP = [0., 5., 35.] + ret.longitudinalKpV = [1.2, 0.8, 0.5] + else: + ret.gasMaxBP = [0.] # m/s + ret.gasMaxV = [0.] # max gas allowed + + #ret.gasMaxBP = [0.] # m/s + #ret.gasMaxV = [0.6] if ret.enableGasInterceptor else [0.] # max gas allowed + ret.brakeMaxBP = [5., 20.] # m/s + ret.brakeMaxV = [1., 0.8] # max brake allowed + + ret.longPidDeadzoneBP = [0.] + ret.longPidDeadzoneV = [0.] + + ret.stoppingControl = True + ret.steerLimitAlert = True + ret.startAccel = 0.5 + + ret.steerActuatorDelay = 0.1 + ret.steerRateCost = 0.35 + + return ret + + # returns a car.CarState + def update(self, c): + # ******************* do can recv ******************* + canMonoTimes = [] + + self.cp.update(int(sec_since_boot() * 1e9), False) + self.cp_cam.update(int(sec_since_boot() * 1e9), False) + + self.CS.update(self.cp, self.cp_cam) + + # create message + ret = car.CarState.new_message() + + # speeds + ret.vEgo = self.CS.v_ego + ret.aEgo = self.CS.a_ego + ret.vEgoRaw = self.CS.v_ego_raw + ret.yawRate = self.VM.yaw_rate(self.CS.angle_steers * CV.DEG_TO_RAD, self.CS.v_ego) + ret.standstill = self.CS.standstill + ret.wheelSpeeds.fl = self.CS.v_wheel_fl + ret.wheelSpeeds.fr = self.CS.v_wheel_fr + ret.wheelSpeeds.rl = self.CS.v_wheel_rl + ret.wheelSpeeds.rr = self.CS.v_wheel_rr + + # gas pedal + ret.gas = self.CS.car_gas / 256.0 + if not self.CP.enableGasInterceptor: + ret.gasPressed = self.CS.pedal_gas > 0 + else: + ret.gasPressed = self.CS.user_gas_pressed + + # brake pedal + ret.brake = self.CS.user_brake + ret.brakePressed = self.CS.brake_pressed != 0 + # FIXME: read sendcan for brakelights + brakelights_threshold = 0.02 if self.CS.CP.carFingerprint == CAR.CIVIC else 0.1 + ret.brakeLights = bool(self.CS.brake_switch or + c.actuators.brake > brakelights_threshold) + + # steering wheel + ret.steeringAngle = self.CS.angle_steers + ret.steeringRate = self.CS.angle_steers_rate + + # gear shifter lever + ret.gearShifter = self.CS.gear_shifter + + ret.steeringTorque = self.CS.steer_torque_driver + ret.steeringPressed = self.CS.steer_override + + # cruise state + ret.cruiseState.enabled = self.CS.pcm_acc_status != 0 + ret.cruiseState.speed = self.CS.v_cruise_pcm * CV.KPH_TO_MS + ret.cruiseState.available = bool(self.CS.main_on) + ret.cruiseState.speedOffset = self.CS.cruise_speed_offset + ret.cruiseState.standstill = False + + ret.readdistancelines = self.CS.read_distance_lines + ret.lkMode = self.CS.lkMode + + # TODO: button presses + buttonEvents = [] + ret.leftBlinker = bool(self.CS.left_blinker_on) + ret.rightBlinker = bool(self.CS.right_blinker_on) + + ret.doorOpen = not self.CS.door_all_closed + ret.seatbeltUnlatched = not self.CS.seatbelt + + if self.CS.left_blinker_on != self.CS.prev_left_blinker_on: + be = car.CarState.ButtonEvent.new_message() + be.type = 'leftBlinker' + be.pressed = self.CS.left_blinker_on != 0 + buttonEvents.append(be) + + if self.CS.right_blinker_on != self.CS.prev_right_blinker_on: + be = car.CarState.ButtonEvent.new_message() + be.type = 'rightBlinker' + be.pressed = self.CS.right_blinker_on != 0 + buttonEvents.append(be) + + if self.CS.cruise_buttons != self.CS.prev_cruise_buttons: + be = car.CarState.ButtonEvent.new_message() + be.type = 'unknown' + if self.CS.cruise_buttons != 0: + be.pressed = True + but = self.CS.cruise_buttons + else: + be.pressed = False + but = self.CS.prev_cruise_buttons + if but == CruiseButtons.RES_ACCEL: + be.type = 'accelCruise' + elif but == CruiseButtons.DECEL_SET: + be.type = 'decelCruise' + elif but == CruiseButtons.CANCEL: + be.type = 'cancel' + elif but == CruiseButtons.MAIN: + be.type = 'altButton3' + buttonEvents.append(be) + + if self.CS.cruise_setting != self.CS.prev_cruise_setting: + be = car.CarState.ButtonEvent.new_message() + be.type = 'unknown' + if self.CS.cruise_setting != 0: + be.pressed = True + but = self.CS.cruise_setting + else: + be.pressed = False + but = self.CS.prev_cruise_setting + if but == 1: + be.type = 'altButton1' + # TODO: more buttons? + buttonEvents.append(be) + ret.buttonEvents = buttonEvents + + # events + # TODO: event names aren't checked at compile time. + # Maybe there is a way to use capnp enums directly + events = [] + if not self.CS.can_valid: + self.can_invalid_count += 1 + if self.can_invalid_count >= 5: + events.append(create_event('commIssue', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE])) + else: + self.can_invalid_count = 0 + + if not self.CS.cam_can_valid and self.CP.enableCamera: + self.cam_can_invalid_count += 1 + # wait 1.0s before throwing the alert to avoid it popping when you turn off the car + if self.cam_can_invalid_count >= 100 and self.CS.CP.carFingerprint not in HONDA_BOSCH: + events.append(create_event('invalidGiraffeHonda', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE, ET.PERMANENT])) + else: + self.cam_can_invalid_count = 0 + + if not self.CS.lkMode: + events.append(create_event('manualSteeringRequired', [ET.WARNING])) + elif self.CS.lkMode and self.CS.left_blinker_on: + events.append(create_event('manualSteeringRequiredBlinkerOnLeft', [ET.WARNING])) + elif self.CS.lkMode and self.CS.right_blinker_on: + events.append(create_event('manualSteeringRequiredBlinkerOnRight', [ET.WARNING])) + elif self.CS.steer_error: + events.append(create_event('steerUnavailable', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE, ET.PERMANENT])) + elif self.CS.steer_warning: + events.append(create_event('steerTempUnavailable', [ET.WARNING])) + if self.CS.brake_error: + events.append(create_event('brakeUnavailable', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE, ET.PERMANENT])) + if not ret.gearShifter == 'drive': + events.append(create_event('wrongGear', [ET.NO_ENTRY, ET.SOFT_DISABLE])) + if ret.doorOpen: + events.append(create_event('doorOpen', [ET.NO_ENTRY, ET.SOFT_DISABLE])) + if ret.seatbeltUnlatched: + events.append(create_event('seatbeltNotLatched', [ET.NO_ENTRY, ET.SOFT_DISABLE])) + if self.CS.esp_disabled: + events.append(create_event('espDisabled', [ET.NO_ENTRY, ET.SOFT_DISABLE])) + if not self.CS.main_on: + events.append(create_event('wrongCarMode', [ET.NO_ENTRY, ET.USER_DISABLE])) + if ret.gearShifter == 'reverse': + events.append(create_event('reverseGear', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE])) + if self.CS.brake_hold and self.CS.CP.carFingerprint not in HONDA_BOSCH: + events.append(create_event('brakeHold', [ET.NO_ENTRY, ET.USER_DISABLE])) + if self.CS.park_brake: + events.append(create_event('parkBrake', [ET.NO_ENTRY, ET.USER_DISABLE])) + + if self.CP.enableCruise and ret.vEgo < self.CP.minEnableSpeed: + events.append(create_event('speedTooLow', [ET.NO_ENTRY])) + + # disable on pedals rising edge or when brake is pressed and speed isn't zero + if (ret.gasPressed and not self.gas_pressed_prev) or \ + (ret.brakePressed and (not self.brake_pressed_prev or ret.vEgo > 0.001)): + events.append(create_event('pedalPressed', [ET.NO_ENTRY, ET.USER_DISABLE])) + + if ret.gasPressed: + events.append(create_event('pedalPressed', [ET.PRE_ENABLE])) + + # it can happen that car cruise disables while comma system is enabled: need to + # keep braking if needed or if the speed is very low + if self.CP.enableCruise and not ret.cruiseState.enabled and c.actuators.brake <= 0.: + # non loud alert if cruise disbales below 25mph as expected (+ a little margin) + if ret.vEgo < self.CP.minEnableSpeed + 2.: + # events.append(create_event('speedTooLow', [ET.IMMEDIATE_DISABLE])) + #else: + events.append(create_event("cruiseDisabled", [ET.IMMEDIATE_DISABLE])) # send loud alert if slow and cruise disables during braking + + if self.CS.CP.minEnableSpeed > 0 and ret.vEgo < 0.001: + events.append(create_event('manualRestart', [ET.WARNING])) + + cur_time = sec_since_boot() + enable_pressed = False + # handle button presses + for b in ret.buttonEvents: + + # do enable on both accel and decel buttons + if b.type in ["accelCruise", "decelCruise"] and not b.pressed: + self.last_enable_pressed = cur_time + enable_pressed = True + + # do disable on button down + if b.type == "cancel" and b.pressed: + events.append(create_event('buttonCancel', [ET.USER_DISABLE])) + + if self.CP.enableCruise: + # KEEP THIS EVENT LAST! send enable event if button is pressed and there are + # NO_ENTRY events, so controlsd will display alerts. Also not send enable events + # too close in time, so a no_entry will not be followed by another one. + # TODO: button press should be the only thing that triggers enble + if ((cur_time - self.last_enable_pressed) < 0.2 and + (cur_time - self.last_enable_sent) > 0.2 and + ret.cruiseState.enabled) or \ + (enable_pressed and get_events(events, [ET.NO_ENTRY])): + events.append(create_event('buttonEnable', [ET.ENABLE])) + self.last_enable_sent = cur_time + elif enable_pressed: + events.append(create_event('buttonEnable', [ET.ENABLE])) + + ret.events = events + ret.canMonoTimes = canMonoTimes + + # update previous brake/gas pressed + self.gas_pressed_prev = ret.gasPressed + self.brake_pressed_prev = ret.brakePressed + + # cast to reader so it can't be modified + return ret.as_reader() + + # pass in a car.CarControl + # to be called @ 100hz + def apply(self, c, perception_state=log.Live20Data.new_message()): + if c.hudControl.speedVisible: + hud_v_cruise = c.hudControl.setSpeed * CV.MS_TO_KPH + else: + hud_v_cruise = 255 + + hud_alert = VISUAL_HUD[c.hudControl.visualAlert.raw] + snd_beep, snd_chime = AUDIO_HUD[c.hudControl.audibleAlert.raw] + + pcm_accel = int(clip(c.cruiseControl.accelOverride,0,1)*0xc6) + + self.CC.update(self.sendcan, c.enabled, self.CS, self.frame, \ + c.actuators, \ + c.cruiseControl.speedOverride, \ + c.cruiseControl.override, \ + c.cruiseControl.cancel, \ + pcm_accel, \ + perception_state.radarErrors, \ + hud_v_cruise, c.hudControl.lanesVisible, \ + hud_show_car = c.hudControl.leadVisible, \ + hud_alert = hud_alert, \ + snd_beep = snd_beep, \ + snd_chime = snd_chime) + + self.frame += 1 diff --git a/selfdrive/car/honda/radar_interface.py b/selfdrive/car/honda/radar_interface.py new file mode 100755 index 00000000000000..7d30265c2f471e --- /dev/null +++ b/selfdrive/car/honda/radar_interface.py @@ -0,0 +1,104 @@ +#!/usr/bin/env python +import os +import zmq +import time +from cereal import car +from selfdrive.can.parser import CANParser +from common.realtime import sec_since_boot +from selfdrive.services import service_list +import selfdrive.messaging as messaging + + +def _create_nidec_can_parser(): + dbc_f = 'acura_ilx_2016_nidec.dbc' + radar_messages = [0x400] + range(0x430, 0x43A) + range(0x440, 0x446) + signals = zip(['RADAR_STATE'] + + ['LONG_DIST'] * 16 + ['NEW_TRACK'] * 16 + ['LAT_DIST'] * 16 + + ['REL_SPEED'] * 16, + [0x400] + radar_messages[1:] * 4, + [0] + [255] * 16 + [1] * 16 + [0] * 16 + [0] * 16) + checks = zip([0x445], [20]) + + return CANParser(os.path.splitext(dbc_f)[0], signals, checks, 1) + + +class RadarInterface(object): + def __init__(self, CP): + # radar + self.pts = {} + self.track_id = 0 + self.radar_fault = False + self.radar_wrong_config = False + self.radar_off_can = CP.radarOffCan + + self.delay = 0.1 # Delay of radar + + # Nidec + self.rcp = _create_nidec_can_parser() + + context = zmq.Context() + self.logcan = messaging.sub_sock(context, service_list['can'].port) + + def update(self): + canMonoTimes = [] + + updated_messages = set() + ret = car.RadarState.new_message() + + # in Bosch radar and we are only steering for now, so sleep 0.05s to keep + # radard at 20Hz and return no points + if self.radar_off_can: + time.sleep(0.05) + return ret + + while 1: + tm = int(sec_since_boot() * 1e9) + updated_messages.update(self.rcp.update(tm, True)) + if 0x445 in updated_messages: + break + + for ii in updated_messages: + cpt = self.rcp.vl[ii] + if ii == 0x400: + # check for radar faults + self.radar_fault = cpt['RADAR_STATE'] != 0x79 + self.radar_wrong_config = cpt['RADAR_STATE'] == 0x69 + elif cpt['LONG_DIST'] < 255: + if ii not in self.pts or cpt['NEW_TRACK']: + self.pts[ii] = car.RadarState.RadarPoint.new_message() + self.pts[ii].trackId = self.track_id + self.track_id += 1 + self.pts[ii].dRel = cpt['LONG_DIST'] # from front of car + self.pts[ii].yRel = -cpt['LAT_DIST'] # in car frame's y axis, left is positive + self.pts[ii].vRel = cpt['REL_SPEED'] + self.pts[ii].aRel = float('nan') + self.pts[ii].yvRel = float('nan') + self.pts[ii].measured = True + else: + if ii in self.pts: + del self.pts[ii] + + errors = [] + if not self.rcp.can_valid: + errors.append("commIssue") + if self.radar_fault: + errors.append("fault") + if self.radar_wrong_config: + errors.append("wrongConfig") + ret.errors = errors + ret.canMonoTimes = canMonoTimes + + ret.points = self.pts.values() + + return ret + + +if __name__ == "__main__": + class CarParams: + radarOffCan = False + + RI = RadarInterface(CarParams) + while 1: + ret = RI.update() + print(chr(27) + "[2J") + print ret diff --git a/selfdrive/car/honda/values.py b/selfdrive/car/honda/values.py new file mode 100644 index 00000000000000..9a7974d2d9e3b8 --- /dev/null +++ b/selfdrive/car/honda/values.py @@ -0,0 +1,182 @@ +from cereal import car +from selfdrive.car import dbc_dict + +AudibleAlert = car.CarControl.HUDControl.AudibleAlert +VisualAlert = car.CarControl.HUDControl.VisualAlert + +# Car button codes +class CruiseButtons: + RES_ACCEL = 4 + DECEL_SET = 3 + CANCEL = 2 + MAIN = 1 + +#car chimes: enumeration from dbc file. Chimes are for alerts and warnings +class CM: + MUTE = 0 + SINGLE = 3 + DOUBLE = 4 + REPEATED = 1 + CONTINUOUS = 2 + +#car beeps: enumeration from dbc file. Beeps are for engage and disengage +class BP: + MUTE = 0 + SINGLE = 3 + TRIPLE = 2 + REPEATED = 1 + +AUDIO_HUD = { + AudibleAlert.none: (BP.MUTE, CM.MUTE), + AudibleAlert.chimeEngage: (BP.SINGLE, CM.MUTE), + AudibleAlert.chimeDisengage: (BP.SINGLE, CM.MUTE), + AudibleAlert.chimeError: (BP.MUTE, CM.DOUBLE), + AudibleAlert.chimePrompt: (BP.MUTE, CM.SINGLE), + AudibleAlert.chimeWarning1: (BP.MUTE, CM.DOUBLE), + AudibleAlert.chimeWarning2: (BP.MUTE, CM.REPEATED), + AudibleAlert.chimeWarningRepeat: (BP.MUTE, CM.REPEATED)} + +class AH: + #[alert_idx, value] + # See dbc files for info on values" + NONE = [0, 0] + FCW = [1, 1] + STEER = [2, 1] + BRAKE_PRESSED = [3, 10] + GEAR_NOT_D = [4, 6] + SEATBELT = [5, 5] + SPEED_TOO_HIGH = [6, 8] + +VISUAL_HUD = { + VisualAlert.none: AH.NONE, + VisualAlert.fcw: AH.FCW, + VisualAlert.steerRequired: AH.STEER, + VisualAlert.brakePressed: AH.BRAKE_PRESSED, + VisualAlert.wrongGear: AH.GEAR_NOT_D, + VisualAlert.seatbeltUnbuckled: AH.SEATBELT, + VisualAlert.speedTooHigh: AH.SPEED_TOO_HIGH} + +class CAR: + ACCORD = "HONDA ACCORD 2018 SPORT 2T" + ACCORD_15 = "HONDA ACCORD 2018 LX 1.5T" + ACCORDH = "HONDA ACCORD 2018 HYBRID TOURING" + CIVIC = "HONDA CIVIC 2016 TOURING" + CIVIC_BOSCH = "HONDA CIVIC HATCHBACK 2017 SEDAN/COUPE 2019" + ACURA_ILX = "ACURA ILX 2016 ACURAWATCH PLUS" + CRV = "HONDA CR-V 2016 TOURING" + CRV_5G = "HONDA CR-V 2017 EX" + ODYSSEY = "HONDA ODYSSEY 2018 EX-L" + ACURA_RDX = "ACURA RDX 2018 ACURAWATCH PLUS" + PILOT = "HONDA PILOT 2017 TOURING" + PILOT_2019 = "HONDA PILOT 2019 ELITE" + RIDGELINE = "HONDA RIDGELINE 2017 BLACK EDITION" + +FINGERPRINTS = { + CAR.ACCORD: [{ + 148: 8, 228: 5, 304: 8, 330: 8, 344: 8, 380: 8, 399: 7, 419: 8, 420: 8, 427: 3, 432: 7, 441: 5, 446: 3, 450: 8, 464: 8, 477: 8, 479: 8, 495: 8, 545: 6, 662: 4, 773: 7, 777: 8, 780: 8, 804: 8, 806: 8, 808: 8, 829: 5, 862: 8, 884: 8, 891: 8, 927: 8, 929: 8, 1302: 8, 1600: 5, 1601: 8, 1652: 8 + }], + CAR.ACCORD_15: [{ + 148: 8, 228: 5, 304: 8, 330: 8, 344: 8, 380: 8, 399: 7, 401: 8, 420: 8, 427: 3, 432: 7, 441: 5, 446: 3, 450: 8, 464: 8, 477: 8, 479: 8, 495: 8, 545: 6, 662: 4, 773: 7, 777: 8, 780: 8, 804: 8, 806: 8, 808: 8, 829: 5, 862: 8, 884: 8, 891: 8, 927: 8, 929: 8, 1302: 8, 1600: 5, 1601: 8, 1652: 8 + }], + CAR.ACCORDH: [{ + 148: 8, 228: 5, 304: 8, 330: 8, 344: 8, 380: 8, 387: 8, 388: 8, 399: 7, 419: 8, 420: 8, 427: 3, 432: 7, 441: 5, 450: 8, 464: 8, 477: 8, 479: 8, 495: 8, 525: 8, 545: 6, 662: 4, 773: 7, 777: 8, 780: 8, 804: 8, 806: 8, 808: 8, 829: 5, 862: 8, 884: 8, 891: 8, 927: 8, 929: 8, 1302: 8, 1600: 5, 1601: 8, 1652: 8 + }], + CAR.ACURA_ILX: [{ + 57: 3, 145: 8, 228: 5, 304: 8, 316: 8, 342: 6, 344: 8, 380: 8, 398: 3, 399: 7, 419: 8, 420: 8, 422: 8, 428: 8, 432: 7, 464: 8, 476: 4, 490: 8, 506: 8, 512: 6, 513: 6, 542: 7, 545: 4, 597: 8, 660: 8, 773: 7, 777: 8, 780: 8, 800: 8, 804: 8, 808: 8, 819: 7, 821: 5, 829: 5, 882: 2, 884: 7, 887: 8, 888: 8, 892: 8, 923: 2, 929: 4, 983: 8, 985: 3, 1024: 5, 1027: 5, 1029: 8, 1030: 5, 1034: 5, 1036: 8, 1039: 8, 1057: 5, 1064: 7, 1108: 8, 1365: 5, + }], + # Acura RDX w/ Added Comma Pedal Support (512L & 513L) + CAR.ACURA_RDX: [{ + 57: 3, 145: 8, 229: 4, 308: 5, 316: 8, 342: 6, 344: 8, 380: 8, 392: 6, 398: 3, 399: 6, 404: 4, 420: 8, 422: 8, 426: 8, 432: 7, 464: 8, 474: 5, 476: 4, 487: 4, 490: 8, 506: 8, 512: 6, 513: 6, 542: 7, 545: 4, 597: 8, 660: 8, 773: 7, 777: 8, 780: 8, 800: 8, 804: 8, 808: 8, 819: 7, 821: 5, 829: 5, 882: 2, 884: 7, 887: 8, 888: 8, 892: 8, 923: 2, 929: 4, 963: 8, 965: 8, 966: 8, 967: 8, 983: 8, 985: 3, 1024: 5, 1027: 5, 1029: 8, 1033: 5, 1034: 5, 1036: 8, 1039: 8, 1057: 5, 1064: 7, 1108: 8, 1365: 5, 1424: 5, 1729: 1 + }], + CAR.CIVIC: [{ + 57: 3, 148: 8, 228: 5, 304: 8, 330: 8, 344: 8, 380: 8, 399: 7, 401: 8, 420: 8, 427: 3, 428: 8, 432: 7, 450: 8, 464: 8, 470: 2, 476: 7, 487: 4, 490: 8, 493: 5, 506: 8, 512: 6, 513: 6, 545: 6, 597: 8, 662: 4, 773: 7, 777: 8, 780: 8, 795: 8, 800: 8, 804: 8, 806: 8, 808: 8, 829: 5, 862: 8, 884: 8, 891: 8, 892: 8, 927: 8, 929: 8, 985: 3, 1024: 5, 1027: 5, 1029: 8, 1036: 8, 1039: 8, 1108: 8, 1302: 8, 1322: 5, 1361: 5, 1365: 5, 1424: 5, 1633: 8, + }], + CAR.CIVIC_BOSCH: [{ + # 2017 Civic Hatchback EX and 2019 Civic Sedan Touring Canadian + 57: 3, 148: 8, 228: 5, 304: 8, 330: 8, 344: 8, 380: 8, 399: 7, 401: 8, 420: 8, 427: 3, 428: 8, 432: 7, 441: 5, 450: 8, 464: 8, 470: 2, 476: 7, 477: 8, 479: 8, 490: 8, 493: 5, 495: 8, 506: 8, 545: 6, 597: 8, 662: 4, 773: 7, 777: 8, 780: 8, 795: 8, 800: 8, 804: 8, 806: 8, 808: 8, 829: 5, 862: 8, 884: 8, 891: 8, 892: 8, 927: 8, 929: 8, 985: 3, 1024: 5, 1027: 5, 1029: 8, 1036: 8, 1039: 8, 1108: 8, 1302: 8, 1322: 5, 1361: 5, 1365: 5, 1424: 5, 1600: 5, 1601: 8, 1633: 8, + }], + CAR.CRV: [{ + 57: 3, 145: 8, 316: 8, 340: 8, 342: 6, 344: 8, 380: 8, 398: 3, 399: 6, 401: 8, 404: 4, 420: 8, 422: 8, 426: 8, 432: 7, 464: 8, 474: 5, 476: 4, 487: 4, 490: 8, 493: 3, 506: 8, 507: 1, 512: 6, 513: 6, 542: 7, 545: 4, 597: 8, 660: 8, 661: 4, 773: 7, 777: 8, 780: 8, 800: 8, 804: 8, 808: 8, 829: 5, 882: 2, 884: 7, 888: 8, 891: 8, 892: 8, 923: 2, 929: 8, 983: 8, 985: 3, 1024: 5, 1027: 5, 1029: 8, 1033: 5, 1036: 8, 1039: 8, 1057: 5, 1064: 7, 1108: 8, 1125: 8, 1296: 8, 1365: 5, 1424: 5, 1600: 5, 1601: 8, + }], + CAR.CRV_5G: [{ + 57: 3, 148: 8, 199: 4, 228: 5, 231: 5, 232: 7, 304: 8, 330: 8, 340: 8, 344: 8, 380: 8, 399: 7, 401: 8, 420: 8, 423: 2, 427: 3, 428: 8, 432: 7, 441: 5, 446: 3, 450: 8, 464: 8, 467: 2, 469: 3, 470: 2, 474: 8, 476: 7, 477: 8, 479: 8, 490: 8, 493: 5, 495: 8, 507: 1, 545: 6, 597: 8, 661: 4, 662: 4, 773: 7, 777: 8, 780: 8, 795: 8, 800: 8, 804: 8, 806: 8, 808: 8, 814: 4, 815: 8, 817: 4, 825: 4, 829: 5, 862: 8, 881: 8, 882: 4, 884: 8, 888: 8, 891: 8, 927: 8, 918: 7, 929: 8, 983: 8, 985: 3, 1024: 5, 1027: 5, 1029: 8, 1036: 8, 1039: 8, 1064: 7, 1108: 8, 1092: 1, 1115: 4, 1125: 8, 1127: 2, 1296: 8, 1302: 8, 1322: 5, 1361: 5, 1365: 5, 1424: 5, 1600: 5, 1601: 8, 1618: 5, 1633: 8, 1670: 5 + }], + # 2018 Odyssey w/ Added Comma Pedal Support (512L & 513L) + CAR.ODYSSEY: [{ + 57: 3, 148: 8, 228: 5, 229: 4, 316: 8, 342: 6, 344: 8, 380: 8, 399: 7, 411: 5, 419: 8, 420: 8, 427: 3, 432: 7, 450: 8, 463: 8, 464: 8, 476: 4, 490: 8, 506: 8, 512: 6, 513: 6, 542: 7, 545: 6, 597: 8, 662: 4, 773: 7, 777: 8, 780: 8, 795: 8, 800: 8, 804: 8, 806: 8, 808: 8, 817: 4, 819: 7, 821: 5, 825: 4, 829: 5, 837: 5, 856: 7, 862: 8, 871: 8, 881: 8, 882: 4, 884: 8, 891: 8, 892: 8, 905: 8, 923: 2, 927: 8, 929: 8, 963: 8, 965: 8, 966: 8, 967: 8, 983: 8, 985: 3, 1029: 8, 1036: 8, 1052: 8, 1064: 7, 1088: 8, 1089: 8, 1092: 1, 1108: 8, 1110: 8, 1125: 8, 1296: 8, 1302: 8, 1600: 5, 1601: 8, 1612: 5, 1613: 5, 1614: 5, 1615: 8, 1616: 5, 1619: 5, 1623: 5, 1668: 5 + }, + # 2018 Odyssey Elite w/ Added Comma Pedal Support (512L & 513L) + { + 57: 3, 148: 8, 228: 5, 229: 4, 304: 8, 342: 6, 344: 8, 380: 8, 399: 7, 411: 5, 419: 8, 420: 8, 427: 3, 432: 7, 440: 8, 450: 8, 463: 8, 464: 8, 476: 4, 490: 8, 506: 8, 507: 1, 542: 7, 545: 6, 597: 8, 662: 4, 773: 7, 777: 8, 780: 8, 795: 8, 800: 8, 804: 8, 806: 8, 808: 8, 817: 4, 819: 7, 821: 5, 825: 4, 829: 5, 837: 5, 856: 7, 862: 8, 871: 8, 881: 8, 882: 4, 884: 8, 891: 8, 892: 8, 905: 8, 923: 2, 927: 8, 929: 8, 963: 8, 965: 8, 966: 8, 967: 8, 983: 8, 985: 3, 1029: 8, 1036: 8, 1052: 8, 1064: 7, 1088: 8, 1089: 8, 1092: 1, 1108: 8, 1110: 8, 1125: 8, 1296: 8, 1302: 8, 1600: 5, 1601: 8, 1612: 5, 1613: 5, 1614: 5, 1616: 5, 1619: 5, 1623: 5, 1668: 5 + }], + # 2017 Pilot Touring AND 2016 Pilot EX-L w/ Added Comma Pedal Support (512L & 513L) + CAR.PILOT: [{ + 57: 3, 145: 8, 228: 5, 229: 4, 308: 5, 316: 8, 334: 8, 339: 7, 342: 6, 344: 8, 379: 8, 380: 8, 392: 6, 399: 7, 419: 8, 420: 8, 422: 8, 425: 8, 426: 8, 427: 3, 432: 7, 463: 8, 464: 8, 476: 4, 490: 8, 506: 8, 507: 1, 512: 6, 513: 6, 538: 3, 542: 7, 545: 5, 546: 3, 597: 8, 660: 8, 773: 7, 777: 8, 780: 8, 795: 8, 800: 8, 804: 8, 808: 8, 819: 7, 821: 5, 829: 5, 837: 5, 856: 7, 871: 8, 882: 2, 884: 7, 891: 8, 892: 8, 923: 2, 929: 8, 963: 8, 965: 8, 966: 8, 967: 8, 983: 8, 985: 3, 1027: 5, 1029: 8, 1036: 8, 1039: 8, 1064: 7, 1088: 8, 1089: 8, 1108: 8, 1125: 8, 1296: 8, 1424: 5, 1600: 5, 1601: 8, 1612: 5, 1613: 5, 1616: 5, 1618: 5, 1668: 5 + }], + CAR.PILOT_2019: [{ + 57: 3, 145: 8, 228: 5, 308: 5, 316: 8, 334: 8, 342: 6, 344: 8, 379: 8, 380: 8, 399: 7, 411: 5, 419: 8, 420: 8, 422: 8, 425: 8, 426: 8, 427: 3, 432: 7, 463: 8, 464: 8, 476: 4, 490: 8, 506: 8, 512: 6, 513: 6, 538: 3, 542: 7, 545: 5, 546: 3, 597: 8, 660: 8, 773: 7, 777: 8, 780: 8, 795: 8, 800: 8, 804: 8, 808: 8, 817: 4, 819: 7, 821: 5, 825: 4, 829: 5, 837: 5, 856: 7, 871: 8, 881: 8, 882: 2, 884: 7, 891: 8, 892: 8, 923: 2, 927: 8, 929: 8, 983: 8, 985: 3, 1029: 8, 1052: 8, 1064: 7, 1088: 8, 1089: 8, 1092: 1, 1108: 8, 1110: 8, 1125: 8, 1296: 8, 1424: 5, 1445: 8, 1600: 5, 1601: 8, 1612: 5, 1613: 5, 1614: 5, 1615: 8, 1616: 5, 1617: 8, 1618: 5, 1623: 5, 1668: 5 + }, + # 2019 Pilot EX-L + { + 57: 3, 145: 8, 228: 5, 229: 4, 308: 5, 316: 8, 339: 7, 342: 6, 344: 8, 380: 8, 392: 6, 399: 7, 411: 5, 419: 8, 420: 8, 422: 8, 425: 8, 426: 8, 427: 3, 432: 7, 464: 8, 476: 4, 490: 8, 506: 8, 542: 7, 545: 5, 546: 3, 597: 8, 660: 8, 773: 7, 777: 8, 780: 8, 795: 8, 800: 8, 804: 8, 808: 8, 817: 4, 819: 7, 821: 5, 829: 5, 871: 8, 881: 8, 882: 2, 884: 7, 891: 8, 892: 8, 923: 2, 927: 8, 929: 8, 963: 8, 965: 8, 966: 8, 967: 8, 983: 8, 985: 3, 1027: 5, 1029: 8, 1039: 8, 1064: 7, 1088: 8, 1089: 8, 1092: 1, 1108: 8, 1125: 8, 1296: 8, 1424: 5, 1445: 8, 1600: 5, 1601: 8, 1612: 5, 1613: 5, 1616: 5, 1617: 8, 1618: 5, 1623: 5, 1668: 5 + }], + # Ridgeline w/ Added Comma Pedal Support (512L & 513L) + CAR.RIDGELINE: [{ + 57: 3, 145: 8, 228: 5, 229: 4, 308: 5, 316: 8, 339: 7, 342: 6, 344: 8, 380: 8, 392: 6, 399: 7, 419: 8, 420: 8, 422: 8, 425: 8, 426: 8, 427: 3, 432: 7, 464: 8, 471: 3, 476: 4, 490: 8, 506: 8, 512: 6, 513: 6, 545: 5, 546: 3, 597: 8, 660: 8, 773: 7, 777: 8, 780: 8, 795: 8, 800: 8, 804: 8, 808: 8, 819: 7, 821: 5, 829: 5, 871: 8, 882: 2, 884: 7, 892: 8, 923: 2, 927: 8, 929: 8, 963: 8, 965: 8, 966: 8, 967: 8, 983: 8, 985: 3, 1027: 5, 1029: 8, 1036: 8, 1039: 8, 1064: 7, 1088: 8, 1089: 8, 1108: 8, 1125: 8, 1296: 8, 1365: 5, 1424: 5, 1600: 5, 1601: 8, 1613: 5, 1616: 5, 1618: 5, 1668: 5, 2015: 3 + }, + # 2019 Ridgeline + { + 57: 3, 145: 8, 229: 4, 308: 5, 316: 8, 339: 7, 342: 6, 344: 8, 380: 8, 392: 6, 399: 7, 419: 8, 420: 8, 422:8, 425: 8, 426: 8, 427: 3, 432: 7, 464: 8, 476: 4, 490: 8, 545: 5, 546: 3, 597: 8, 660: 8, 773: 7, 777: 8, 795: 8, 800: 8, 804: 8, 808: 8, 819: 7, 821: 5, 871: 8, 882: 2, 884: 7, 892: 8, 923: 2, 929: 8, 963: 8, 965: 8, 966: 8, 967: 8, 983: 8, 985: 3, 1027: 5, 1029: 8, 1036: 8, 1039: 8, 1064: 7, 1088: 8, 1089: 8, 1092: 1, 1108: 8, 1125: 8, 1296: 8, 1365: 5, 424: 5, 1613: 5, 1616: 5, 1618: 5, 1623: 5, 1668: 5 + }] +} + +DBC = { + CAR.ACCORD: dbc_dict('honda_accord_s2t_2018_can_generated', None), + CAR.ACCORD_15: dbc_dict('honda_accord_lx15t_2018_can_generated', None), + CAR.ACCORDH: dbc_dict('honda_accord_s2t_2018_can_generated', None), + CAR.ACURA_ILX: dbc_dict('acura_ilx_2016_can_generated', 'acura_ilx_2016_nidec'), + CAR.ACURA_RDX: dbc_dict('acura_rdx_2018_can_generated', 'acura_ilx_2016_nidec'), + CAR.CIVIC: dbc_dict('honda_civic_touring_2016_can_generated', 'acura_ilx_2016_nidec'), + CAR.CIVIC_BOSCH: dbc_dict('honda_civic_hatchback_ex_2017_can_generated', None), + CAR.CRV: dbc_dict('honda_crv_touring_2016_can_generated', 'acura_ilx_2016_nidec'), + CAR.CRV_5G: dbc_dict('honda_crv_ex_2017_can_generated', None), + CAR.ODYSSEY: dbc_dict('honda_odyssey_exl_2018_generated', 'acura_ilx_2016_nidec'), + CAR.PILOT: dbc_dict('honda_pilot_touring_2017_can_generated', 'acura_ilx_2016_nidec'), + CAR.PILOT_2019: dbc_dict('honda_pilot_touring_2017_can_generated', 'acura_ilx_2016_nidec'), + CAR.RIDGELINE: dbc_dict('honda_ridgeline_black_edition_2017_can_generated', 'acura_ilx_2016_nidec'), +} + +STEER_THRESHOLD = { + CAR.ACCORD: 1200, + CAR.ACCORD_15: 1200, + CAR.ACCORDH: 1200, + CAR.ACURA_ILX: 1200, + CAR.ACURA_RDX: 400, + CAR.CIVIC: 1200, + CAR.CIVIC_BOSCH: 1200, + CAR.CRV: 1200, + CAR.CRV_5G: 1200, + CAR.ODYSSEY: 1200, + CAR.PILOT: 1200, + CAR.PILOT_2019: 1200, + CAR.RIDGELINE: 1200, +} + +SPEED_FACTOR = { + CAR.ACCORD: 1., + CAR.ACCORD_15: 1., + CAR.ACCORDH: 1., + CAR.ACURA_ILX: 1., + CAR.ACURA_RDX: 1., + CAR.CIVIC: 1., + CAR.CIVIC_BOSCH: 1., + CAR.CRV: 1.025, + CAR.CRV_5G: 1.025, + CAR.ODYSSEY: 1., + CAR.PILOT: 1., + CAR.PILOT_2019: 1., + CAR.RIDGELINE: 1., +} + +# TODO: get these from dbc file +HONDA_BOSCH = [CAR.ACCORD, CAR.ACCORD_15, CAR.ACCORDH, CAR.CIVIC_BOSCH, CAR.CRV_5G] diff --git a/selfdrive/car/hyundai/__init__.py b/selfdrive/car/hyundai/__init__.py new file mode 100644 index 00000000000000..e69de29bb2d1d6 diff --git a/selfdrive/car/hyundai/carcontroller.py b/selfdrive/car/hyundai/carcontroller.py new file mode 100644 index 00000000000000..3cd8d136ff8a27 --- /dev/null +++ b/selfdrive/car/hyundai/carcontroller.py @@ -0,0 +1,76 @@ +from selfdrive.car import apply_std_steer_torque_limits +from selfdrive.boardd.boardd import can_list_to_can_capnp +from selfdrive.car.hyundai.hyundaican import create_lkas11, create_lkas12, \ + create_1191, create_1156, \ + create_clu11 +from selfdrive.car.hyundai.values import Buttons +from selfdrive.can.packer import CANPacker + + +# Steer torque limits + +class SteerLimitParams: + STEER_MAX = 250 # 409 is the max + STEER_DELTA_UP = 3 + STEER_DELTA_DOWN = 7 + STEER_DRIVER_ALLOWANCE = 50 + STEER_DRIVER_MULTIPLIER = 2 + STEER_DRIVER_FACTOR = 1 + +class CarController(object): + def __init__(self, dbc_name, car_fingerprint, enable_camera): + self.apply_steer_last = 0 + self.car_fingerprint = car_fingerprint + self.lkas11_cnt = 0 + self.cnt = 0 + self.last_resume_cnt = 0 + self.enable_camera = enable_camera + # True when giraffe switch 2 is low and we need to replace all the camera messages + # otherwise we forward the camera msgs and we just replace the lkas cmd signals + self.camera_disconnected = False + + self.packer = CANPacker(dbc_name) + + def update(self, sendcan, enabled, CS, actuators, pcm_cancel_cmd, hud_alert): + + if not self.enable_camera: + return + + ### Steering Torque + apply_steer = actuators.steer * SteerLimitParams.STEER_MAX + + apply_steer = apply_std_steer_torque_limits(apply_steer, self.apply_steer_last, CS.steer_torque_driver, SteerLimitParams) + + if not enabled: + apply_steer = 0 + + steer_req = 1 if enabled else 0 + + self.apply_steer_last = apply_steer + + can_sends = [] + + self.lkas11_cnt = self.cnt % 0x10 + self.clu11_cnt = self.cnt % 0x10 + + if self.camera_disconnected: + if (self.cnt % 10) == 0: + can_sends.append(create_lkas12()) + if (self.cnt % 50) == 0: + can_sends.append(create_1191()) + if (self.cnt % 7) == 0: + can_sends.append(create_1156()) + + can_sends.append(create_lkas11(self.packer, self.car_fingerprint, apply_steer, steer_req, self.lkas11_cnt, + enabled, CS.lkas11, hud_alert, keep_stock=(not self.camera_disconnected))) + + if pcm_cancel_cmd: + can_sends.append(create_clu11(self.packer, CS.clu11, Buttons.CANCEL)) + elif CS.stopped and (self.cnt - self.last_resume_cnt) > 5: + self.last_resume_cnt = self.cnt + can_sends.append(create_clu11(self.packer, CS.clu11, Buttons.RES_ACCEL)) + + ### Send messages to canbus + sendcan.send(can_list_to_can_capnp(can_sends, msgtype='sendcan').to_bytes()) + + self.cnt += 1 diff --git a/selfdrive/car/hyundai/carstate.py b/selfdrive/car/hyundai/carstate.py new file mode 100644 index 00000000000000..01fd28a5876d79 --- /dev/null +++ b/selfdrive/car/hyundai/carstate.py @@ -0,0 +1,239 @@ +from selfdrive.car.hyundai.values import DBC, STEER_THRESHOLD +from selfdrive.can.parser import CANParser +from selfdrive.config import Conversions as CV +from common.kalman.simple_kalman import KF1D +import numpy as np + + +def get_can_parser(CP): + + signals = [ + # sig_name, sig_address, default + ("WHL_SPD_FL", "WHL_SPD11", 0), + ("WHL_SPD_FR", "WHL_SPD11", 0), + ("WHL_SPD_RL", "WHL_SPD11", 0), + ("WHL_SPD_RR", "WHL_SPD11", 0), + + ("YAW_RATE", "ESP12", 0), + + ("CF_Gway_DrvSeatBeltInd", "CGW4", 1), + + ("CF_Gway_DrvSeatBeltSw", "CGW1", 0), + ("CF_Gway_TSigLHSw", "CGW1", 0), + ("CF_Gway_TurnSigLh", "CGW1", 0), + ("CF_Gway_TSigRHSw", "CGW1", 0), + ("CF_Gway_TurnSigRh", "CGW1", 0), + ("CF_Gway_ParkBrakeSw", "CGW1", 0), + + ("BRAKE_ACT", "EMS12", 0), + ("PV_AV_CAN", "EMS12", 0), + ("TPS", "EMS12", 0), + + ("CYL_PRES", "ESP12", 0), + + ("CF_Clu_CruiseSwState", "CLU11", 0), + ("CF_Clu_CruiseSwMain" , "CLU11", 0), + ("CF_Clu_SldMainSW", "CLU11", 0), + ("CF_Clu_ParityBit1", "CLU11", 0), + ("CF_Clu_VanzDecimal" , "CLU11", 0), + ("CF_Clu_Vanz", "CLU11", 0), + ("CF_Clu_SPEED_UNIT", "CLU11", 0), + ("CF_Clu_DetentOut", "CLU11", 0), + ("CF_Clu_RheostatLevel", "CLU11", 0), + ("CF_Clu_CluInfo", "CLU11", 0), + ("CF_Clu_AmpInfo", "CLU11", 0), + ("CF_Clu_AliveCnt1", "CLU11", 0), + + ("CF_Clu_InhibitD", "CLU15", 0), + ("CF_Clu_InhibitP", "CLU15", 0), + ("CF_Clu_InhibitN", "CLU15", 0), + ("CF_Clu_InhibitR", "CLU15", 0), + + ("CF_Lvr_Gear","LVR12",0), + + ("ACCEnable", "TCS13", 0), + ("ACC_REQ", "TCS13", 0), + ("DriverBraking", "TCS13", 0), + ("DriverOverride", "TCS13", 0), + + ("ESC_Off_Step", "TCS15", 0), + + ("CF_Lvr_GearInf", "LVR11", 0), #Transmission Gear (0 = N or P, 1-8 = Fwd, 14 = Rev) + + ("CR_Mdps_DrvTq", "MDPS11", 0), + + ("CR_Mdps_StrColTq", "MDPS12", 0), + ("CF_Mdps_ToiActive", "MDPS12", 0), + ("CF_Mdps_ToiUnavail", "MDPS12", 0), + ("CF_Mdps_FailStat", "MDPS12", 0), + ("CR_Mdps_OutTq", "MDPS12", 0), + + ("VSetDis", "SCC11", 0), + ("SCCInfoDisplay", "SCC11", 0), + ("ACCMode", "SCC12", 1), + + ("SAS_Angle", "SAS11", 0), + ("SAS_Speed", "SAS11", 0), + ] + + checks = [ + # address, frequency + ("MDPS12", 50), + ("MDPS11", 100), + ("TCS15", 10), + ("TCS13", 50), + ("CLU11", 50), + ("ESP12", 100), + ("EMS12", 100), + ("CGW1", 10), + ("CGW4", 5), + ("WHL_SPD11", 50), + ("SCC11", 50), + ("SCC12", 50), + ("SAS11", 100) + ] + + return CANParser(DBC[CP.carFingerprint]['pt'], signals, checks, 0) + +def get_camera_parser(CP): + + signals = [ + # sig_name, sig_address, default + ("CF_Lkas_LdwsSysState", "LKAS11", 0), + ("CF_Lkas_SysWarning", "LKAS11", 0), + ("CF_Lkas_LdwsLHWarning", "LKAS11", 0), + ("CF_Lkas_LdwsRHWarning", "LKAS11", 0), + ("CF_Lkas_HbaLamp", "LKAS11", 0), + ("CF_Lkas_FcwBasReq", "LKAS11", 0), + ("CF_Lkas_ToiFlt", "LKAS11", 0), + ("CF_Lkas_HbaSysState", "LKAS11", 0), + ("CF_Lkas_FcwOpt", "LKAS11", 0), + ("CF_Lkas_HbaOpt", "LKAS11", 0), + ("CF_Lkas_FcwSysState", "LKAS11", 0), + ("CF_Lkas_FcwCollisionWarning", "LKAS11", 0), + ("CF_Lkas_FusionState", "LKAS11", 0), + ("CF_Lkas_FcwOpt_USM", "LKAS11", 0), + ("CF_Lkas_LdwsOpt_USM", "LKAS11", 0) + ] + + checks = [] + + return CANParser(DBC[CP.carFingerprint]['pt'], signals, checks, 2) + +class CarState(object): + def __init__(self, CP): + + self.CP = CP + + # initialize can parser + self.car_fingerprint = CP.carFingerprint + + # vEgo kalman filter + dt = 0.01 + # Q = np.matrix([[10.0, 0.0], [0.0, 100.0]]) + # R = 1e3 + self.v_ego_kf = KF1D(x0=np.matrix([[0.0], [0.0]]), + A=np.matrix([[1.0, dt], [0.0, 1.0]]), + C=np.matrix([1.0, 0.0]), + K=np.matrix([[0.12287673], [0.29666309]])) + self.v_ego = 0.0 + self.left_blinker_on = 0 + self.left_blinker_flash = 0 + self.right_blinker_on = 0 + self.right_blinker_flash = 0 + + def update(self, cp, cp_cam): + # copy can_valid + self.can_valid = cp.can_valid + + # update prevs, update must run once per Loop + self.prev_left_blinker_on = self.left_blinker_on + self.prev_right_blinker_on = self.right_blinker_on + + self.door_all_closed = True + self.seatbelt = cp.vl["CGW1"]['CF_Gway_DrvSeatBeltSw'] + + self.brake_pressed = cp.vl["TCS13"]['DriverBraking'] + self.esp_disabled = cp.vl["TCS15"]['ESC_Off_Step'] + + self.park_brake = cp.vl["CGW1"]['CF_Gway_ParkBrakeSw'] + self.main_on = True + self.acc_active = cp.vl["SCC12"]['ACCMode'] != 0 + self.pcm_acc_status = int(self.acc_active) + + # calc best v_ego estimate, by averaging two opposite corners + self.v_wheel_fl = cp.vl["WHL_SPD11"]['WHL_SPD_FL'] * CV.KPH_TO_MS + self.v_wheel_fr = cp.vl["WHL_SPD11"]['WHL_SPD_FR'] * CV.KPH_TO_MS + self.v_wheel_rl = cp.vl["WHL_SPD11"]['WHL_SPD_RL'] * CV.KPH_TO_MS + self.v_wheel_rr = cp.vl["WHL_SPD11"]['WHL_SPD_RR'] * CV.KPH_TO_MS + self.v_wheel = (self.v_wheel_fl + self.v_wheel_fr + self.v_wheel_rl + self.v_wheel_rr) / 4. + + self.low_speed_lockout = self.v_wheel < 1.0 + + # Kalman filter, even though Hyundai raw wheel speed is heaviliy filtered by default + if abs(self.v_wheel - self.v_ego) > 2.0: # Prevent large accelerations when car starts at non zero speed + self.v_ego_x = np.matrix([[self.v_wheel], [0.0]]) + + self.v_ego_raw = self.v_wheel + v_ego_x = self.v_ego_kf.update(self.v_wheel) + self.v_ego = float(v_ego_x[0]) + self.a_ego = float(v_ego_x[1]) + is_set_speed_in_mph = int(cp.vl["CLU11"]["CF_Clu_SPEED_UNIT"]) + speed_conv = CV.MPH_TO_MS if is_set_speed_in_mph else CV.KPH_TO_MS + self.cruise_set_speed = cp.vl["SCC11"]['VSetDis'] * speed_conv + self.standstill = not self.v_wheel > 0.1 + + self.angle_steers = cp.vl["SAS11"]['SAS_Angle'] + self.angle_steers_rate = cp.vl["SAS11"]['SAS_Speed'] + self.yaw_rate = cp.vl["ESP12"]['YAW_RATE'] + self.main_on = True + self.left_blinker_on = cp.vl["CGW1"]['CF_Gway_TSigLHSw'] + self.left_blinker_flash = cp.vl["CGW1"]['CF_Gway_TurnSigLh'] + self.right_blinker_on = cp.vl["CGW1"]['CF_Gway_TSigRHSw'] + self.right_blinker_flash = cp.vl["CGW1"]['CF_Gway_TurnSigRh'] + self.steer_override = abs(cp.vl["MDPS11"]['CR_Mdps_DrvTq']) > STEER_THRESHOLD + self.steer_state = cp.vl["MDPS12"]['CF_Mdps_ToiActive'] #0 NOT ACTIVE, 1 ACTIVE + self.steer_error = cp.vl["MDPS12"]['CF_Mdps_ToiUnavail'] + self.brake_error = 0 + self.steer_torque_driver = cp.vl["MDPS11"]['CR_Mdps_DrvTq'] + self.steer_torque_motor = cp.vl["MDPS12"]['CR_Mdps_OutTq'] + self.stopped = cp.vl["SCC11"]['SCCInfoDisplay'] == 4. + + self.user_brake = 0 + + self.brake_pressed = cp.vl["TCS13"]['DriverBraking'] + self.brake_lights = bool(self.brake_pressed) + if (cp.vl["TCS13"]["DriverOverride"] == 0 and cp.vl["TCS13"]['ACC_REQ'] == 1): + self.pedal_gas = 0 + else: + self.pedal_gas = cp.vl["EMS12"]['TPS'] + self.car_gas = cp.vl["EMS12"]['TPS'] + + # Gear Selecton - This is not compatible with all Kia/Hyundai's, But is the best way for those it is compatible with + gear = cp.vl["LVR12"]["CF_Lvr_Gear"] + if gear == 5: + self.gear_shifter = "drive" + elif gear == 6: + self.gear_shifter = "neutral" + elif gear == 0: + self.gear_shifter = "park" + elif gear == 7: + self.gear_shifter = "reverse" + else: + self.gear_shifter = "unknown" + + # Gear Selection via Cluster - For those Kia/Hyundai which are not fully discovered, we can use the Cluster Indicator for Gear Selection, as this seems to be standard over all cars, but is not the preferred method. + if cp.vl["CLU15"]["CF_Clu_InhibitD"] == 1: + self.gear_shifter_cluster = "drive" + elif cp.vl["CLU15"]["CF_Clu_InhibitN"] == 1: + self.gear_shifter_cluster = "neutral" + elif cp.vl["CLU15"]["CF_Clu_InhibitP"] == 1: + self.gear_shifter_cluster = "park" + elif cp.vl["CLU15"]["CF_Clu_InhibitR"] == 1: + self.gear_shifter_cluster = "reverse" + else: + self.gear_shifter_cluster = "unknown" + + # save the entire LKAS11 and CLU11 + self.lkas11 = cp_cam.vl["LKAS11"] + self.clu11 = cp.vl["CLU11"] diff --git a/selfdrive/car/hyundai/hyundaican.py b/selfdrive/car/hyundai/hyundaican.py new file mode 100644 index 00000000000000..5a895497a1865f --- /dev/null +++ b/selfdrive/car/hyundai/hyundaican.py @@ -0,0 +1,79 @@ +import crcmod +from selfdrive.car.hyundai.values import CHECKSUM + +hyundai_checksum = crcmod.mkCrcFun(0x11D, initCrc=0xFD, rev=False, xorOut=0xdf) + +def make_can_msg(addr, dat, alt): + return [addr, 0, dat, alt] + +def create_lkas11(packer, car_fingerprint, apply_steer, steer_req, cnt, enabled, lkas11, hud_alert, keep_stock=False): + values = { + "CF_Lkas_Icon": 3 if enabled else 0, + "CF_Lkas_LdwsSysState": 3 if steer_req else 1, + "CF_Lkas_SysWarning": hud_alert, + "CF_Lkas_LdwsLHWarning": lkas11["CF_Lkas_LdwsLHWarning"] if keep_stock else 0, + "CF_Lkas_LdwsRHWarning": lkas11["CF_Lkas_LdwsRHWarning"] if keep_stock else 0, + "CF_Lkas_HbaLamp": lkas11["CF_Lkas_HbaLamp"] if keep_stock else 0, + "CF_Lkas_FcwBasReq": lkas11["CF_Lkas_FcwBasReq"] if keep_stock else 0, + "CR_Lkas_StrToqReq": apply_steer, + "CF_Lkas_ActToi": steer_req, + "CF_Lkas_ToiFlt": 0, + "CF_Lkas_HbaSysState": lkas11["CF_Lkas_HbaSysState"] if keep_stock else 1, + "CF_Lkas_FcwOpt": lkas11["CF_Lkas_FcwOpt"] if keep_stock else 0, + "CF_Lkas_HbaOpt": lkas11["CF_Lkas_HbaOpt"] if keep_stock else 3, + "CF_Lkas_MsgCount": cnt, + "CF_Lkas_FcwSysState": lkas11["CF_Lkas_FcwSysState"] if keep_stock else 0, + "CF_Lkas_FcwCollisionWarning": lkas11["CF_Lkas_FcwCollisionWarning"] if keep_stock else 0, + "CF_Lkas_FusionState": lkas11["CF_Lkas_FusionState"] if keep_stock else 0, + "CF_Lkas_Chksum": 0, + "CF_Lkas_FcwOpt_USM": 2 if enabled else 1, + "CF_Lkas_LdwsOpt_USM": lkas11["CF_Lkas_LdwsOpt_USM"] if keep_stock else 3, + } + + dat = packer.make_can_msg("LKAS11", 0, values)[2] + + if car_fingerprint in CHECKSUM["crc8"]: + # CRC Checksum as seen on 2019 Hyundai Santa Fe + dat = dat[:6] + dat[7] + checksum = hyundai_checksum(dat) + elif car_fingerprint in CHECKSUM["6B"]: + # Checksum of first 6 Bytes, as seen on 2018 Kia Sorento + dat = [ord(i) for i in dat] + checksum = sum(dat[:6]) % 256 + elif car_fingerprint in CHECKSUM["7B"]: + # Checksum of first 6 Bytes and last Byte as seen on 2018 Kia Stinger + dat = [ord(i) for i in dat] + checksum = (sum(dat[:6]) + dat[7]) % 256 + + values["CF_Lkas_Chksum"] = checksum + + return packer.make_can_msg("LKAS11", 0, values) + +def create_lkas12(): + return make_can_msg(1342, "\x00\x00\x00\x00\x60\x05", 0) + + +def create_1191(): + return make_can_msg(1191, "\x01\x00", 0) + + +def create_1156(): + return make_can_msg(1156, "\x08\x20\xfe\x3f\x00\xe0\xfd\x3f", 0) + +def create_clu11(packer, clu11, button): + values = { + "CF_Clu_CruiseSwState": button, + "CF_Clu_CruiseSwMain": clu11["CF_Clu_CruiseSwMain"], + "CF_Clu_SldMainSW": clu11["CF_Clu_SldMainSW"], + "CF_Clu_ParityBit1": clu11["CF_Clu_ParityBit1"], + "CF_Clu_VanzDecimal": clu11["CF_Clu_VanzDecimal"], + "CF_Clu_Vanz": clu11["CF_Clu_Vanz"], + "CF_Clu_SPEED_UNIT": clu11["CF_Clu_SPEED_UNIT"], + "CF_Clu_DetentOut": clu11["CF_Clu_DetentOut"], + "CF_Clu_RheostatLevel": clu11["CF_Clu_RheostatLevel"], + "CF_Clu_CluInfo": clu11["CF_Clu_CluInfo"], + "CF_Clu_AmpInfo": clu11["CF_Clu_AmpInfo"], + "CF_Clu_AliveCnt1": 0, + } + + return packer.make_can_msg("CLU11", 0, values) diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py new file mode 100644 index 00000000000000..5399d827610896 --- /dev/null +++ b/selfdrive/car/hyundai/interface.py @@ -0,0 +1,310 @@ +#!/usr/bin/env python +from cereal import car, log +from common.realtime import sec_since_boot +from selfdrive.config import Conversions as CV +from selfdrive.controls.lib.drive_helpers import EventTypes as ET, create_event +from selfdrive.controls.lib.vehicle_model import VehicleModel +from selfdrive.car.hyundai.carstate import CarState, get_can_parser, get_camera_parser +from selfdrive.car.hyundai.values import CAMERA_MSGS, CAR, get_hud_alerts + +try: + from selfdrive.car.hyundai.carcontroller import CarController +except ImportError: + CarController = None + + +class CarInterface(object): + def __init__(self, CP, sendcan=None): + self.CP = CP + self.VM = VehicleModel(CP) + self.idx = 0 + self.lanes = 0 + self.lkas_request = 0 + + self.gas_pressed_prev = False + self.brake_pressed_prev = False + self.can_invalid_count = 0 + self.cruise_enabled_prev = False + self.low_speed_alert = False + + # *** init the major players *** + self.CS = CarState(CP) + self.cp = get_can_parser(CP) + self.cp_cam = get_camera_parser(CP) + + # sending if read only is False + if sendcan is not None: + self.sendcan = sendcan + self.CC = CarController(self.cp.dbc_name, CP.carFingerprint, CP.enableCamera) + + @staticmethod + def compute_gb(accel, speed): + return float(accel) / 3.0 + + @staticmethod + def calc_accel_override(a_ego, a_target, v_ego, v_target): + return 1.0 + + @staticmethod + def get_params(candidate, fingerprint): + + # kg of standard extra cargo to count for drive, gas, etc... + std_cargo = 136 + + ret = car.CarParams.new_message() + + ret.carName = "hyundai" + ret.carFingerprint = candidate + ret.radarOffCan = True + ret.safetyModel = car.CarParams.SafetyModels.hyundai + ret.enableCruise = True # stock acc + + # FIXME: hardcoding honda civic 2016 touring params so they can be used to + # scale unknown params for other cars + mass_civic = 2923 * CV.LB_TO_KG + std_cargo + wheelbase_civic = 2.70 + centerToFront_civic = wheelbase_civic * 0.4 + centerToRear_civic = wheelbase_civic - centerToFront_civic + rotationalInertia_civic = 2500 + tireStiffnessFront_civic = 192150 + tireStiffnessRear_civic = 202500 + + ret.steerActuatorDelay = 0.1 # Default delay + tire_stiffness_factor = 1. + + if candidate == CAR.SANTA_FE: + ret.steerKf = 0.00005 + ret.steerRateCost = 0.5 + ret.mass = 3982 * CV.LB_TO_KG + std_cargo + ret.wheelbase = 2.766 + + # Values from optimizer + ret.steerRatio = 16.55 # 13.8 is spec end-to-end + tire_stiffness_factor = 0.82 + + ret.steerKiBP, ret.steerKpBP = [[9., 22.], [9., 22.]] + ret.steerKpV, ret.steerKiV = [[0.2, 0.35], [0.05, 0.09]] + ret.minSteerSpeed = 0. + elif candidate == CAR.KIA_SORENTO: + ret.steerKf = 0.00005 + ret.steerRateCost = 0.5 + ret.mass = 1985 + std_cargo + ret.wheelbase = 2.78 + ret.steerRatio = 14.4 * 1.1 # 10% higher at the center seems reasonable + ret.steerKiBP, ret.steerKpBP = [[0.], [0.]] + ret.steerKpV, ret.steerKiV = [[0.25], [0.05]] + ret.minSteerSpeed = 0. + elif candidate == CAR.ELANTRA: + ret.steerKf = 0.00006 + ret.steerRateCost = 0.5 + ret.mass = 1275 + std_cargo + ret.wheelbase = 2.7 + ret.steerRatio = 13.73 #Spec + tire_stiffness_factor = 0.385 + ret.steerKiBP, ret.steerKpBP = [[0.], [0.]] + ret.steerKpV, ret.steerKiV = [[0.25], [0.05]] + ret.minSteerSpeed = 32 * CV.MPH_TO_MS + elif candidate == CAR.GENESIS: + ret.steerKf = 0.00005 + ret.steerRateCost = 0.5 + ret.mass = 2060 + std_cargo + ret.wheelbase = 3.01 + ret.steerRatio = 16.5 + ret.steerKiBP, ret.steerKpBP = [[0.], [0.]] + ret.steerKpV, ret.steerKiV = [[0.16], [0.01]] + ret.minSteerSpeed = 35 * CV.MPH_TO_MS + elif candidate == CAR.KIA_STINGER: + ret.steerKf = 0.00005 + ret.steerRateCost = 0.5 + ret.mass = 1825 + std_cargo + ret.wheelbase = 2.78 + ret.steerRatio = 14.4 * 1.15 # 15% higher at the center seems reasonable + ret.steerKiBP, ret.steerKpBP = [[0.], [0.]] + ret.steerKpV, ret.steerKiV = [[0.25], [0.05]] + ret.minSteerSpeed = 0. + + ret.minEnableSpeed = -1. # enable is done by stock ACC, so ignore this + ret.longitudinalKpBP = [0.] + ret.longitudinalKpV = [0.] + ret.longitudinalKiBP = [0.] + ret.longitudinalKiV = [0.] + + ret.centerToFront = ret.wheelbase * 0.4 + + centerToRear = ret.wheelbase - ret.centerToFront + + # TODO: get actual value, for now starting with reasonable value for + # civic and scaling by mass and wheelbase + ret.rotationalInertia = rotationalInertia_civic * \ + ret.mass * ret.wheelbase**2 / (mass_civic * wheelbase_civic**2) + + # TODO: start from empirically derived lateral slip stiffness for the civic and scale by + # mass and CG position, so all cars will have approximately similar dyn behaviors + ret.tireStiffnessFront = (tireStiffnessFront_civic * tire_stiffness_factor) * \ + ret.mass / mass_civic * \ + (centerToRear / ret.wheelbase) / (centerToRear_civic / wheelbase_civic) + ret.tireStiffnessRear = (tireStiffnessRear_civic * tire_stiffness_factor) * \ + ret.mass / mass_civic * \ + (ret.centerToFront / ret.wheelbase) / (centerToFront_civic / wheelbase_civic) + + + # no rear steering, at least on the listed cars above + ret.steerRatioRear = 0. + ret.steerControlType = car.CarParams.SteerControlType.torque + + # steer, gas, brake limitations VS speed + ret.steerMaxBP = [0.] + ret.steerMaxV = [1.0] + ret.gasMaxBP = [0.] + ret.gasMaxV = [1.] + ret.brakeMaxBP = [0.] + ret.brakeMaxV = [1.] + ret.longPidDeadzoneBP = [0.] + ret.longPidDeadzoneV = [0.] + + ret.enableCamera = not any(x for x in CAMERA_MSGS if x in fingerprint) + ret.openpilotLongitudinalControl = False + + ret.steerLimitAlert = False + ret.stoppingControl = False + ret.startAccel = 0.0 + + return ret + + # returns a car.CarState + def update(self, c): + # ******************* do can recv ******************* + canMonoTimes = [] + self.cp.update(int(sec_since_boot() * 1e9), False) + self.cp_cam.update(int(sec_since_boot() * 1e9), False) + self.CS.update(self.cp, self.cp_cam) + # create message + ret = car.CarState.new_message() + # speeds + ret.vEgo = self.CS.v_ego + ret.vEgoRaw = self.CS.v_ego_raw + ret.aEgo = self.CS.a_ego + ret.yawRate = self.CS.yaw_rate + ret.standstill = self.CS.standstill + ret.wheelSpeeds.fl = self.CS.v_wheel_fl + ret.wheelSpeeds.fr = self.CS.v_wheel_fr + ret.wheelSpeeds.rl = self.CS.v_wheel_rl + ret.wheelSpeeds.rr = self.CS.v_wheel_rr + + # gear shifter + if self.CP.carFingerprint == CAR.ELANTRA: + ret.gearShifter = self.CS.gear_shifter_cluster + else: + ret.gearShifter = self.CS.gear_shifter + + # gas pedal + ret.gas = self.CS.car_gas + ret.gasPressed = self.CS.pedal_gas > 1e-3 # tolerance to avoid false press reading + + # brake pedal + ret.brake = self.CS.user_brake + ret.brakePressed = self.CS.brake_pressed != 0 + ret.brakeLights = self.CS.brake_lights + + # steering wheel + ret.steeringAngle = self.CS.angle_steers + ret.steeringRate = self.CS.angle_steers_rate # it's unsigned + + ret.steeringTorque = self.CS.steer_torque_driver + ret.steeringPressed = self.CS.steer_override + + # cruise state + ret.cruiseState.enabled = self.CS.pcm_acc_status != 0 + if self.CS.pcm_acc_status != 0: + ret.cruiseState.speed = self.CS.cruise_set_speed + else: + ret.cruiseState.speed = 0 + ret.cruiseState.available = bool(self.CS.main_on) + ret.cruiseState.standstill = False + + # TODO: button presses + buttonEvents = [] + + if self.CS.left_blinker_on != self.CS.prev_left_blinker_on: + be = car.CarState.ButtonEvent.new_message() + be.type = 'leftBlinker' + be.pressed = self.CS.left_blinker_on != 0 + buttonEvents.append(be) + + if self.CS.right_blinker_on != self.CS.prev_right_blinker_on: + be = car.CarState.ButtonEvent.new_message() + be.type = 'rightBlinker' + be.pressed = self.CS.right_blinker_on != 0 + buttonEvents.append(be) + + ret.buttonEvents = buttonEvents + ret.leftBlinker = bool(self.CS.left_blinker_on) + ret.rightBlinker = bool(self.CS.right_blinker_on) + + ret.doorOpen = not self.CS.door_all_closed + ret.seatbeltUnlatched = not self.CS.seatbelt + + + # low speed steer alert hysteresis logic (only for cars with steer cut off above 10 m/s) + if ret.vEgo < (self.CP.minSteerSpeed + 2.) and self.CP.minSteerSpeed > 10.: + self.low_speed_alert = True + if ret.vEgo > (self.CP.minSteerSpeed + 4.): + self.low_speed_alert = False + + # events + events = [] + if not self.CS.can_valid: + self.can_invalid_count += 1 + if self.can_invalid_count >= 5: + events.append(create_event('commIssue', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE])) + else: + self.can_invalid_count = 0 + if not ret.gearShifter == 'drive': + events.append(create_event('wrongGear', [ET.NO_ENTRY, ET.SOFT_DISABLE])) + if ret.doorOpen: + events.append(create_event('doorOpen', [ET.NO_ENTRY, ET.SOFT_DISABLE])) + if ret.seatbeltUnlatched: + events.append(create_event('seatbeltNotLatched', [ET.NO_ENTRY, ET.SOFT_DISABLE])) + if self.CS.esp_disabled: + events.append(create_event('espDisabled', [ET.NO_ENTRY, ET.SOFT_DISABLE])) + if not self.CS.main_on: + events.append(create_event('wrongCarMode', [ET.NO_ENTRY, ET.USER_DISABLE])) + if ret.gearShifter == 'reverse': + events.append(create_event('reverseGear', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE])) + if self.CS.steer_error: + events.append(create_event('steerTempUnavailable', [ET.NO_ENTRY, ET.WARNING])) + + # enable request in prius is simple, as we activate when Toyota is active (rising edge) + if ret.cruiseState.enabled and not self.cruise_enabled_prev: + events.append(create_event('pcmEnable', [ET.ENABLE])) + elif not ret.cruiseState.enabled: + events.append(create_event('pcmDisable', [ET.USER_DISABLE])) + + # disable on pedals rising edge or when brake is pressed and speed isn't zero + if (ret.gasPressed and not self.gas_pressed_prev) or \ + (ret.brakePressed and (not self.brake_pressed_prev or ret.vEgoRaw > 0.1)): + events.append(create_event('pedalPressed', [ET.NO_ENTRY, ET.USER_DISABLE])) + + if ret.gasPressed: + events.append(create_event('pedalPressed', [ET.PRE_ENABLE])) + + if self.low_speed_alert: + events.append(create_event('belowSteerSpeed', [ET.WARNING])) + + ret.events = events + ret.canMonoTimes = canMonoTimes + + self.gas_pressed_prev = ret.gasPressed + self.brake_pressed_prev = ret.brakePressed + self.cruise_enabled_prev = ret.cruiseState.enabled + + return ret.as_reader() + + def apply(self, c, perception_state=log.Live20Data.new_message()): + + hud_alert = get_hud_alerts(c.hudControl.visualAlert, c.hudControl.audibleAlert) + + self.CC.update(self.sendcan, c.enabled, self.CS, c.actuators, + c.cruiseControl.cancel, hud_alert) + + return False diff --git a/selfdrive/car/hyundai/radar_interface.py b/selfdrive/car/hyundai/radar_interface.py new file mode 100644 index 00000000000000..96159fd87d9535 --- /dev/null +++ b/selfdrive/car/hyundai/radar_interface.py @@ -0,0 +1,24 @@ +#!/usr/bin/env python +from cereal import car +import time + + +class RadarInterface(object): + def __init__(self, CP): + # radar + self.pts = {} + self.delay = 0.1 + + def update(self): + + ret = car.RadarState.new_message() + time.sleep(0.05) # radard runs on RI updates + + return ret + +if __name__ == "__main__": + RI = RadarInterface(None) + while 1: + ret = RI.update() + print(chr(27) + "[2J") + print ret diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py new file mode 100644 index 00000000000000..56b6e605361b5e --- /dev/null +++ b/selfdrive/car/hyundai/values.py @@ -0,0 +1,67 @@ +from cereal import car +from selfdrive.car import dbc_dict + +VisualAlert = car.CarControl.HUDControl.VisualAlert +AudibleAlert = car.CarControl.HUDControl.AudibleAlert + +def get_hud_alerts(visual_alert, audible_alert): + if visual_alert == VisualAlert.steerRequired: + return 4 if audible_alert != AudibleAlert.none else 5 + else: + return 0 + +class CAR: + ELANTRA = "HYUNDAI ELANTRA LIMITED ULTIMATE 2017" + GENESIS = "HYUNDAI GENESIS 2018" + KIA_SORENTO = "KIA SORENTO GT LINE 2018" + KIA_STINGER = "KIA STINGER GT2 2018" + SANTA_FE = "HYUNDAI SANTA FE LIMITED 2019" + +class Buttons: + NONE = 0 + RES_ACCEL = 1 + SET_DECEL = 2 + CANCEL = 4 + +FINGERPRINTS = { + CAR.ELANTRA: [{ + 66: 8, 67: 8, 68: 8, 127: 8, 273: 8, 274: 8, 275: 8, 339: 8, 356: 4, 399: 8, 512: 6, 544: 8, 593: 8, 608: 8, 688: 5, 790: 8, 809: 8, 897: 8, 899: 8, 902: 8, 903: 8, 905: 8, 909: 8, 916: 8, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1170: 8, 1265: 4, 1280: 1, 1282: 4, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1314: 8, 1322: 8, 1345: 8, 1349: 8, 1351: 8, 1353: 8, 1363: 8, 1366: 8, 1367: 8, 1369: 8, 1407: 8, 1415: 8, 1419: 8, 1425: 2, 1427: 6, 1440: 8, 1456: 4, 1472: 8, 1486: 8, 1487: 8, 1491: 8, 1530: 8, 1532: 5, 2001: 8, 2003: 8, 2004: 8, 2009: 8, 2012: 8, 2016: 8, 2017: 8, 2024: 8, 2025: 8 + }], + CAR.GENESIS: [{ + 67: 8, 68: 8, 304: 8, 320: 8, 339: 8, 356: 4, 544: 7, 593: 8, 608: 8, 688: 5, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 5, 897: 8, 902: 8, 903: 6, 916: 8, 1024: 2, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1168: 7, 1170: 8, 1173: 8, 1184: 8, 1265: 4, 1280: 1, 1287: 4, 1292: 8, 1312: 8, 1322: 8, 1331: 8, 1332: 8, 1333: 8, 1334: 8, 1335: 8, 1342: 6, 1345: 8, 1363: 8, 1369: 8, 1370: 8, 1371: 8, 1378: 4, 1384: 5, 1407: 8, 1419: 8, 1427: 6, 1434: 2, 1456: 4 + }, + { + 67: 8, 68: 8, 304: 8, 320: 8, 339: 8, 356: 4, 544: 7, 593: 8, 608: 8, 688: 5, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 5, 897: 8, 902: 8, 903: 6, 916: 8, 1024: 2, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1168: 7, 1170: 8, 1173: 8, 1184: 8, 1265: 4, 1280: 1, 1281: 3, 1287: 4, 1292: 8, 1312: 8, 1322: 8, 1331: 8, 1332: 8, 1333: 8, 1334: 8, 1335: 8, 1345: 8, 1363: 8, 1369: 8, 1370: 8, 1378: 4, 1379: 8, 1384: 5, 1407: 8, 1419: 8, 1427: 6, 1434: 2, 1456: 4 + }], + CAR.KIA_SORENTO: [{ + 67: 8, 68: 8, 127: 8, 304: 8, 320: 8, 339: 8, 356: 4, 544: 8, 593: 8, 608: 8, 688: 5, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 903: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1064: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1168: 7, 1170: 8, 1173: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1331: 8, 1332: 8, 1333: 8, 1342: 6, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1370: 8, 1371: 8, 1384: 8, 1407: 8, 1411: 8, 1419: 8, 1425: 2, 1427: 6, 1444: 8, 1456: 4, 1470: 8, 1489: 1 + }], + CAR.KIA_STINGER: [{ + 67: 8, 127: 8, 304: 8, 320: 8, 339: 8, 356: 4, 358: 6, 359: 8, 544: 8, 576: 8, 593: 8, 608: 8, 688: 5, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 909: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1064: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1168: 7, 1170: 8, 1173: 8, 1184: 8, 1265: 4, 1280: 1, 1281: 4, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1378: 4, 1379: 8, 1384: 8, 1407: 8, 1419: 8, 1425: 2, 1427: 6, 1456: 4, 1470: 8 + }], + CAR.SANTA_FE: [{ + 67: 8, 127: 8, 304: 8, 320: 8, 339: 8, 356: 4, 544: 8, 593: 8, 608: 8, 688: 6, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 903: 8, 905: 8, 909: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1155: 8, 1156: 8, 1162: 8, 1164: 8, 1168: 7, 1170: 8, 1173: 8, 1183: 8, 1186: 2, 1191: 2, 1227: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1379: 8, 1384: 8, 1407: 8, 1414: 3, 1419: 8, 1427: 6, 1456: 4, 1470: 8 + }, + { + 67: 8, 127: 8, 304: 8, 320: 8, 339: 8, 356: 4, 544: 8, 593: 8, 608: 8, 688: 6, 764: 8, 809: 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 903: 8, 905: 8, 909: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1064: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1155: 8, 1162: 8, 1164: 8, 1168: 7, 1170: 8, 1173: 8, 1180: 8, 1183: 8, 1186: 2, 1227: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1371: 8, 1378: 8, 1384: 8, 1407: 8, 1414: 3, 1419: 8, 1427: 6, 1456: 4, 1470: 8, 1988: 8, 2000: 8, 2004: 8, 2008: 8, 2012: 8 + } + ], +} + +CAMERA_MSGS = [832, 1156, 1191, 1342] + +CHECKSUM = { + "crc8": [CAR.SANTA_FE], + "6B": [CAR.KIA_SORENTO, CAR.GENESIS], + "7B": [CAR.KIA_STINGER, CAR.ELANTRA], +} + +DBC = { + CAR.ELANTRA: dbc_dict('hyundai_kia_generic', None), + CAR.GENESIS: dbc_dict('hyundai_kia_generic', None), + CAR.KIA_SORENTO: dbc_dict('hyundai_kia_generic', None), + CAR.KIA_STINGER: dbc_dict('hyundai_kia_generic', None), + CAR.SANTA_FE: dbc_dict('hyundai_kia_generic', None), +} + +STEER_THRESHOLD = 100 diff --git a/selfdrive/car/mock/__init__.py b/selfdrive/car/mock/__init__.py new file mode 100644 index 00000000000000..e69de29bb2d1d6 diff --git a/selfdrive/car/mock/interface.py b/selfdrive/car/mock/interface.py new file mode 100755 index 00000000000000..b7d60a4257bfee --- /dev/null +++ b/selfdrive/car/mock/interface.py @@ -0,0 +1,123 @@ +#!/usr/bin/env python +import zmq +from cereal import car, log +from selfdrive.config import Conversions as CV +from selfdrive.services import service_list +from selfdrive.swaglog import cloudlog +import selfdrive.messaging as messaging + +# mocked car interface to work with chffrplus +TS = 0.01 # 100Hz +YAW_FR = 0.2 # ~0.8s time constant on yaw rate filter +# low pass gain +LPG = 2 * 3.1415 * YAW_FR * TS / (1 + 2 * 3.1415 * YAW_FR * TS) + + +class CarInterface(object): + def __init__(self, CP, sendcan=None): + + self.CP = CP + + cloudlog.debug("Using Mock Car Interface") + context = zmq.Context() + + # TODO: subscribe to phone sensor + self.sensor = messaging.sub_sock(context, service_list['sensorEvents'].port) + self.gps = messaging.sub_sock(context, service_list['gpsLocation'].port) + + self.speed = 0. + self.prev_speed = 0. + self.yaw_rate = 0. + self.yaw_rate_meas = 0. + + @staticmethod + def compute_gb(accel, speed): + return accel + + @staticmethod + def calc_accel_override(a_ego, a_target, v_ego, v_target): + return 1.0 + + @staticmethod + def get_params(candidate, fingerprint): + + ret = car.CarParams.new_message() + + ret.carName = "mock" + ret.carFingerprint = candidate + + ret.safetyModel = car.CarParams.SafetyModels.noOutput + ret.openpilotLongitudinalControl = False + + # FIXME: hardcoding honda civic 2016 touring params so they can be used to + # scale unknown params for other cars + ret.mass = 1700. + ret.rotationalInertia = 2500. + ret.wheelbase = 2.70 + ret.centerToFront = ret.wheelbase * 0.5 + ret.steerRatio = 13. # reasonable + ret.longPidDeadzoneBP = [0.] + ret.longPidDeadzoneV = [0.] + ret.tireStiffnessFront = 1e6 # very stiff to neglect slip + ret.tireStiffnessRear = 1e6 # very stiff to neglect slip + ret.steerRatioRear = 0. + + ret.steerMaxBP = [0.] + ret.steerMaxV = [0.] # 2/3rd torque allowed above 45 kph + ret.gasMaxBP = [0.] + ret.gasMaxV = [0.] + ret.brakeMaxBP = [0.] + ret.brakeMaxV = [0.] + + ret.longitudinalKpBP = [0.] + ret.longitudinalKpV = [0.] + ret.longitudinalKiBP = [0.] + ret.longitudinalKiV = [0.] + ret.steerActuatorDelay = 0. + + return ret + + # returns a car.CarState + def update(self, c): + + # get basic data from phone and gps since CAN isn't connected + sensors = messaging.recv_sock(self.sensor) + if sensors is not None: + for sensor in sensors.sensorEvents: + if sensor.type == 4: # gyro + self.yaw_rate_meas = -sensor.gyro.v[0] + + gps = messaging.recv_sock(self.gps) + if gps is not None: + self.prev_speed = self.speed + self.speed = gps.gpsLocation.speed + + # create message + ret = car.CarState.new_message() + + # speeds + ret.vEgo = self.speed + ret.vEgoRaw = self.speed + a = self.speed - self.prev_speed + + ret.aEgo = a + ret.brakePressed = a < -0.5 + + self.yawRate = LPG * self.yaw_rate_meas + (1. - LPG) * self.yaw_rate + ret.yawRate = self.yaw_rate + ret.standstill = self.speed < 0.01 + ret.wheelSpeeds.fl = self.speed + ret.wheelSpeeds.fr = self.speed + ret.wheelSpeeds.rl = self.speed + ret.wheelSpeeds.rr = self.speed + curvature = self.yaw_rate / max(self.speed, 1.) + ret.steeringAngle = curvature * self.CP.steerRatio * self.CP.wheelbase * CV.RAD_TO_DEG + + events = [] + ret.events = events + + return ret.as_reader() + + def apply(self, c, perception_state=log.Live20Data.new_message()): + # in mock no carcontrols + return False diff --git a/selfdrive/car/mock/radar_interface.py b/selfdrive/car/mock/radar_interface.py new file mode 100755 index 00000000000000..ec042d1794a7ec --- /dev/null +++ b/selfdrive/car/mock/radar_interface.py @@ -0,0 +1,24 @@ +#!/usr/bin/env python +from cereal import car +import time + + +class RadarInterface(object): + def __init__(self, CP): + # radar + self.pts = {} + self.delay = 0.1 + + def update(self): + + ret = car.RadarState.new_message() + time.sleep(0.05) # radard runs on RI updates + + return ret + +if __name__ == "__main__": + RI = RadarInterface(None) + while 1: + ret = RI.update() + print(chr(27) + "[2J") + print ret diff --git a/selfdrive/car/mock/values.py b/selfdrive/car/mock/values.py new file mode 100644 index 00000000000000..0dd91565bde856 --- /dev/null +++ b/selfdrive/car/mock/values.py @@ -0,0 +1,2 @@ +class CAR: + MOCK = 'mock' diff --git a/selfdrive/car/toyota/__init__.py b/selfdrive/car/toyota/__init__.py new file mode 100644 index 00000000000000..e69de29bb2d1d6 diff --git a/selfdrive/car/toyota/carcontroller.py b/selfdrive/car/toyota/carcontroller.py new file mode 100644 index 00000000000000..620c9a2ddf81c7 --- /dev/null +++ b/selfdrive/car/toyota/carcontroller.py @@ -0,0 +1,258 @@ +from cereal import car +from common.numpy_fast import clip, interp +from selfdrive.boardd.boardd import can_list_to_can_capnp +from selfdrive.car import apply_toyota_steer_torque_limits +from selfdrive.car.toyota.toyotacan import make_can_msg, create_video_target,\ + create_steer_command, create_ui_command, \ + create_ipas_steer_command, create_accel_command, \ + create_fcw_command +from selfdrive.car.toyota.values import ECU, STATIC_MSGS +from selfdrive.can.packer import CANPacker + +VisualAlert = car.CarControl.HUDControl.VisualAlert +AudibleAlert = car.CarControl.HUDControl.AudibleAlert + +# Accel limits +ACCEL_HYST_GAP = 0.02 # don't change accel command for small oscilalitons within this value +ACCEL_MAX = 1.5 # 1.5 m/s2 +ACCEL_MIN = -3.0 # 3 m/s2 +ACCEL_SCALE = max(ACCEL_MAX, -ACCEL_MIN) + +# Steer torque limits +class SteerLimitParams: + STEER_MAX = 1500 + STEER_DELTA_UP = 10 # 1.5s time to peak torque + STEER_DELTA_DOWN = 25 # always lower than 45 otherwise the Rav4 faults (Prius seems ok with 50) + STEER_ERROR_MAX = 350 # max delta between torque cmd and torque motor + +# Steer angle limits (tested at the Crows Landing track and considered ok) +ANGLE_MAX_BP = [0., 5.] +ANGLE_MAX_V = [510., 300.] +ANGLE_DELTA_BP = [0., 5., 15.] +ANGLE_DELTA_V = [5., .8, .15] # windup limit +ANGLE_DELTA_VU = [5., 3.5, 0.4] # unwind limit + +TARGET_IDS = [0x340, 0x341, 0x342, 0x343, 0x344, 0x345, + 0x363, 0x364, 0x365, 0x370, 0x371, 0x372, + 0x373, 0x374, 0x375, 0x380, 0x381, 0x382, + 0x383] + + +def accel_hysteresis(accel, accel_steady, enabled): + + # for small accel oscillations within ACCEL_HYST_GAP, don't change the accel command + if not enabled: + # send 0 when disabled, otherwise acc faults + accel_steady = 0. + elif accel > accel_steady + ACCEL_HYST_GAP: + accel_steady = accel - ACCEL_HYST_GAP + elif accel < accel_steady - ACCEL_HYST_GAP: + accel_steady = accel + ACCEL_HYST_GAP + accel = accel_steady + + return accel, accel_steady + + +def process_hud_alert(hud_alert, audible_alert): + # initialize to no alert + steer = 0 + fcw = 0 + sound1 = 0 + sound2 = 0 + + if hud_alert == VisualAlert.fcw: + fcw = 1 + elif hud_alert == VisualAlert.steerRequired: + steer = 1 + + if audible_alert == AudibleAlert.chimeWarningRepeat: + sound1 = 1 + elif audible_alert != AudibleAlert.none: + # TODO: find a way to send single chimes + sound2 = 1 + + return steer, fcw, sound1, sound2 + + +def ipas_state_transition(steer_angle_enabled, enabled, ipas_active, ipas_reset_counter): + + if enabled and not steer_angle_enabled: + #ipas_reset_counter = max(0, ipas_reset_counter - 1) + #if ipas_reset_counter == 0: + # steer_angle_enabled = True + #else: + # steer_angle_enabled = False + #return steer_angle_enabled, ipas_reset_counter + return True, 0 + + elif enabled and steer_angle_enabled: + if steer_angle_enabled and not ipas_active: + ipas_reset_counter += 1 + else: + ipas_reset_counter = 0 + if ipas_reset_counter > 10: # try every 0.1s + steer_angle_enabled = False + return steer_angle_enabled, ipas_reset_counter + + else: + return False, 0 + + +class CarController(object): + def __init__(self, dbc_name, car_fingerprint, enable_camera, enable_dsu, enable_apg): + self.braking = False + # redundant safety check with the board + self.controls_allowed = True + self.last_steer = 0 + self.last_angle = 0 + self.accel_steady = 0. + self.car_fingerprint = car_fingerprint + self.alert_active = False + self.last_standstill = False + self.standstill_req = False + self.angle_control = False + + self.steer_angle_enabled = False + self.ipas_reset_counter = 0 + self.last_fault_frame = -200 + + self.fake_ecus = set() + if enable_camera: self.fake_ecus.add(ECU.CAM) + if enable_dsu: self.fake_ecus.add(ECU.DSU) + if enable_apg: self.fake_ecus.add(ECU.APGS) + + self.packer = CANPacker(dbc_name) + + def update(self, sendcan, enabled, CS, frame, actuators, + pcm_cancel_cmd, hud_alert, audible_alert, forwarding_camera, left_line, right_line, lead): + + # *** compute control surfaces *** + + # gas and brake + apply_accel = actuators.gas - actuators.brake + apply_accel, self.accel_steady = accel_hysteresis(apply_accel, self.accel_steady, enabled) + apply_accel = clip(apply_accel * ACCEL_SCALE, ACCEL_MIN, ACCEL_MAX) + + # steer torque + apply_steer = int(round(actuators.steer * SteerLimitParams.STEER_MAX)) + + apply_steer = apply_toyota_steer_torque_limits(apply_steer, self.last_steer, CS.steer_torque_motor, SteerLimitParams) + + # only cut torque when steer state is a known fault + if CS.steer_state in [9, 25]: + self.last_fault_frame = frame + + # Cut steering for 2s after fault + if not enabled or (frame - self.last_fault_frame < 200): + apply_steer = 0 + apply_steer_req = 0 + else: + apply_steer_req = 1 + + self.steer_angle_enabled, self.ipas_reset_counter = \ + ipas_state_transition(self.steer_angle_enabled, enabled, CS.ipas_active, self.ipas_reset_counter) + #print self.steer_angle_enabled, self.ipas_reset_counter, CS.ipas_active + + # steer angle + if self.steer_angle_enabled and CS.ipas_active: + apply_angle = actuators.steerAngle + angle_lim = interp(CS.v_ego, ANGLE_MAX_BP, ANGLE_MAX_V) + apply_angle = clip(apply_angle, -angle_lim, angle_lim) + + # windup slower + if self.last_angle * apply_angle > 0. and abs(apply_angle) > abs(self.last_angle): + angle_rate_lim = interp(CS.v_ego, ANGLE_DELTA_BP, ANGLE_DELTA_V) + else: + angle_rate_lim = interp(CS.v_ego, ANGLE_DELTA_BP, ANGLE_DELTA_VU) + + apply_angle = clip(apply_angle, self.last_angle - angle_rate_lim, self.last_angle + angle_rate_lim) + else: + apply_angle = CS.angle_steers + + if not enabled and CS.pcm_acc_status: + # send pcm acc cancel cmd if drive is disabled but pcm is still on, or if the system can't be activated + pcm_cancel_cmd = 1 + + # on entering standstill, send standstill request + if CS.standstill and not self.last_standstill: + self.standstill_req = True + if CS.pcm_acc_status != 8: + # pcm entered standstill or it's disabled + self.standstill_req = False + + self.last_steer = apply_steer + self.last_angle = apply_angle + self.last_accel = apply_accel + self.last_standstill = CS.standstill + + can_sends = [] + + #*** control msgs *** + #print "steer", apply_steer, min_lim, max_lim, CS.steer_torque_motor + + # toyota can trace shows this message at 42Hz, with counter adding alternatively 1 and 2; + # sending it at 100Hz seem to allow a higher rate limit, as the rate limit seems imposed + # on consecutive messages + if ECU.CAM in self.fake_ecus: + if self.angle_control: + can_sends.append(create_steer_command(self.packer, 0., 0, frame)) + else: + can_sends.append(create_steer_command(self.packer, apply_steer, apply_steer_req, frame)) + + if self.angle_control: + can_sends.append(create_ipas_steer_command(self.packer, apply_angle, self.steer_angle_enabled, + ECU.APGS in self.fake_ecus)) + elif ECU.APGS in self.fake_ecus: + can_sends.append(create_ipas_steer_command(self.packer, 0, 0, True)) + + # accel cmd comes from DSU, but we can spam can to cancel the system even if we are using lat only control + if (frame % 3 == 0 and ECU.DSU in self.fake_ecus) or (pcm_cancel_cmd and ECU.CAM in self.fake_ecus): + lead = lead or CS.v_ego < 12. # at low speed we always assume the lead is present do ACC can be engaged + if ECU.DSU in self.fake_ecus: + can_sends.append(create_accel_command(self.packer, apply_accel, pcm_cancel_cmd, self.standstill_req, lead)) + else: + can_sends.append(create_accel_command(self.packer, 0, pcm_cancel_cmd, False, lead)) + + if frame % 10 == 0 and ECU.CAM in self.fake_ecus and not forwarding_camera: + for addr in TARGET_IDS: + can_sends.append(create_video_target(frame/10, addr)) + + # ui mesg is at 100Hz but we send asap if: + # - there is something to display + # - there is something to stop displaying + alert_out = process_hud_alert(hud_alert, audible_alert) + steer, fcw, sound1, sound2 = alert_out + + if (any(alert_out) and not self.alert_active) or \ + (not any(alert_out) and self.alert_active): + send_ui = True + self.alert_active = not self.alert_active + else: + send_ui = False + + if (frame % 100 == 0 or send_ui) and ECU.CAM in self.fake_ecus: + can_sends.append(create_ui_command(self.packer, steer, sound1, sound2, left_line, right_line)) + + if frame % 100 == 0 and ECU.DSU in self.fake_ecus: + can_sends.append(create_fcw_command(self.packer, fcw)) + + #*** static msgs *** + + for (addr, ecu, cars, bus, fr_step, vl) in STATIC_MSGS: + if frame % fr_step == 0 and ecu in self.fake_ecus and self.car_fingerprint in cars and not (ecu == ECU.CAM and forwarding_camera): + # special cases + if fr_step == 5 and ecu == ECU.CAM and bus == 1: + cnt = (((frame / 5) % 7) + 1) << 5 + vl = chr(cnt) + vl + elif addr in (0x489, 0x48a) and bus == 0: + # add counter for those 2 messages (last 4 bits) + cnt = ((frame/100)%0xf) + 1 + if addr == 0x48a: + # 0x48a has a 8 preceding the counter + cnt += 1 << 7 + vl += chr(cnt) + + can_sends.append(make_can_msg(addr, vl, bus, False)) + + + sendcan.send(can_list_to_can_capnp(can_sends, msgtype='sendcan').to_bytes()) diff --git a/selfdrive/car/toyota/carstate.py b/selfdrive/car/toyota/carstate.py new file mode 100644 index 00000000000000..71d33b0ab7c2a2 --- /dev/null +++ b/selfdrive/car/toyota/carstate.py @@ -0,0 +1,164 @@ +import numpy as np +from common.kalman.simple_kalman import KF1D +from selfdrive.can.parser import CANParser, CANDefine +from selfdrive.config import Conversions as CV +from selfdrive.car.toyota.values import CAR, DBC, STEER_THRESHOLD + +def parse_gear_shifter(gear, vals): + + val_to_capnp = {'P': 'park', 'R': 'reverse', 'N': 'neutral', + 'D': 'drive', 'B': 'brake'} + try: + return val_to_capnp[vals[gear]] + except KeyError: + return "unknown" + + +def get_can_parser(CP): + + signals = [ + # sig_name, sig_address, default + ("GEAR", "GEAR_PACKET", 0), + ("BRAKE_PRESSED", "BRAKE_MODULE", 0), + ("GAS_PEDAL", "GAS_PEDAL", 0), + ("WHEEL_SPEED_FL", "WHEEL_SPEEDS", 0), + ("WHEEL_SPEED_FR", "WHEEL_SPEEDS", 0), + ("WHEEL_SPEED_RL", "WHEEL_SPEEDS", 0), + ("WHEEL_SPEED_RR", "WHEEL_SPEEDS", 0), + ("DOOR_OPEN_FL", "SEATS_DOORS", 1), + ("DOOR_OPEN_FR", "SEATS_DOORS", 1), + ("DOOR_OPEN_RL", "SEATS_DOORS", 1), + ("DOOR_OPEN_RR", "SEATS_DOORS", 1), + ("SEATBELT_DRIVER_UNLATCHED", "SEATS_DOORS", 1), + ("TC_DISABLED", "ESP_CONTROL", 1), + ("STEER_ANGLE", "STEER_ANGLE_SENSOR", 0), + ("STEER_FRACTION", "STEER_ANGLE_SENSOR", 0), + ("STEER_RATE", "STEER_ANGLE_SENSOR", 0), + ("GAS_RELEASED", "PCM_CRUISE", 0), + ("CRUISE_ACTIVE", "PCM_CRUISE", 0), + ("CRUISE_STATE", "PCM_CRUISE", 0), + ("MAIN_ON", "PCM_CRUISE_2", 0), + ("SET_SPEED", "PCM_CRUISE_2", 0), + ("LOW_SPEED_LOCKOUT", "PCM_CRUISE_2", 0), + ("STEER_TORQUE_DRIVER", "STEER_TORQUE_SENSOR", 0), + ("STEER_TORQUE_EPS", "STEER_TORQUE_SENSOR", 0), + ("TURN_SIGNALS", "STEERING_LEVERS", 3), # 3 is no blinkers + ("LKA_STATE", "EPS_STATUS", 0), + ("IPAS_STATE", "EPS_STATUS", 1), + ("BRAKE_LIGHTS_ACC", "ESP_CONTROL", 0), + ("AUTO_HIGH_BEAM", "LIGHT_STALK", 0), + ] + + checks = [ + ("BRAKE_MODULE", 40), + ("GAS_PEDAL", 33), + ("WHEEL_SPEEDS", 80), + ("STEER_ANGLE_SENSOR", 80), + ("PCM_CRUISE", 33), + ("PCM_CRUISE_2", 33), + ("STEER_TORQUE_SENSOR", 50), + ("EPS_STATUS", 25), + ] + + if CP.carFingerprint == CAR.PRIUS: + signals += [("STATE", "AUTOPARK_STATUS", 0)] + + return CANParser(DBC[CP.carFingerprint]['pt'], signals, checks, 0) + + +def get_cam_can_parser(CP): + + signals = [] + + # use steering message to check if panda is connected to frc + checks = [("STEERING_LKA", 42)] + + return CANParser(DBC[CP.carFingerprint]['pt'], signals, checks, 2) + + +class CarState(object): + def __init__(self, CP): + + self.CP = CP + self.can_define = CANDefine(DBC[CP.carFingerprint]['pt']) + self.shifter_values = self.can_define.dv["GEAR_PACKET"]['GEAR'] + self.left_blinker_on = 0 + self.right_blinker_on = 0 + + # initialize can parser + self.car_fingerprint = CP.carFingerprint + + # vEgo kalman filter + dt = 0.01 + # Q = np.matrix([[10.0, 0.0], [0.0, 100.0]]) + # R = 1e3 + self.v_ego_kf = KF1D(x0=np.matrix([[0.0], [0.0]]), + A=np.matrix([[1.0, dt], [0.0, 1.0]]), + C=np.matrix([1.0, 0.0]), + K=np.matrix([[0.12287673], [0.29666309]])) + self.v_ego = 0.0 + + def update(self, cp, cp_cam): + # copy can_valid + self.can_valid = cp.can_valid + self.cam_can_valid = cp_cam.can_valid + + # update prevs, update must run once per loop + self.prev_left_blinker_on = self.left_blinker_on + self.prev_right_blinker_on = self.right_blinker_on + + self.door_all_closed = not any([cp.vl["SEATS_DOORS"]['DOOR_OPEN_FL'], cp.vl["SEATS_DOORS"]['DOOR_OPEN_FR'], + cp.vl["SEATS_DOORS"]['DOOR_OPEN_RL'], cp.vl["SEATS_DOORS"]['DOOR_OPEN_RR']]) + self.seatbelt = not cp.vl["SEATS_DOORS"]['SEATBELT_DRIVER_UNLATCHED'] + + self.brake_pressed = cp.vl["BRAKE_MODULE"]['BRAKE_PRESSED'] + self.pedal_gas = cp.vl["GAS_PEDAL"]['GAS_PEDAL'] + self.car_gas = self.pedal_gas + self.esp_disabled = cp.vl["ESP_CONTROL"]['TC_DISABLED'] + + # calc best v_ego estimate, by averaging two opposite corners + self.v_wheel_fl = cp.vl["WHEEL_SPEEDS"]['WHEEL_SPEED_FL'] * CV.KPH_TO_MS + self.v_wheel_fr = cp.vl["WHEEL_SPEEDS"]['WHEEL_SPEED_FR'] * CV.KPH_TO_MS + self.v_wheel_rl = cp.vl["WHEEL_SPEEDS"]['WHEEL_SPEED_RL'] * CV.KPH_TO_MS + self.v_wheel_rr = cp.vl["WHEEL_SPEEDS"]['WHEEL_SPEED_RR'] * CV.KPH_TO_MS + self.v_wheel = float(np.mean([self.v_wheel_fl, self.v_wheel_fr, self.v_wheel_rl, self.v_wheel_rr])) + + # Kalman filter + if abs(self.v_wheel - self.v_ego) > 2.0: # Prevent large accelerations when car starts at non zero speed + self.v_ego_x = np.matrix([[self.v_wheel], [0.0]]) + + self.v_ego_raw = self.v_wheel + v_ego_x = self.v_ego_kf.update(self.v_wheel) + self.v_ego = float(v_ego_x[0]) + self.a_ego = float(v_ego_x[1]) + self.standstill = not self.v_wheel > 0.001 + + self.angle_steers = cp.vl["STEER_ANGLE_SENSOR"]['STEER_ANGLE'] + cp.vl["STEER_ANGLE_SENSOR"]['STEER_FRACTION'] + self.angle_steers_rate = cp.vl["STEER_ANGLE_SENSOR"]['STEER_RATE'] + can_gear = int(cp.vl["GEAR_PACKET"]['GEAR']) + self.gear_shifter = parse_gear_shifter(can_gear, self.shifter_values) + self.main_on = cp.vl["PCM_CRUISE_2"]['MAIN_ON'] + self.left_blinker_on = cp.vl["STEERING_LEVERS"]['TURN_SIGNALS'] == 1 + self.right_blinker_on = cp.vl["STEERING_LEVERS"]['TURN_SIGNALS'] == 2 + + # 2 is standby, 10 is active. TODO: check that everything else is really a faulty state + self.steer_state = cp.vl["EPS_STATUS"]['LKA_STATE'] + self.steer_error = cp.vl["EPS_STATUS"]['LKA_STATE'] not in [1, 5] + self.ipas_active = cp.vl['EPS_STATUS']['IPAS_STATE'] == 3 + self.brake_error = 0 + self.steer_torque_driver = cp.vl["STEER_TORQUE_SENSOR"]['STEER_TORQUE_DRIVER'] + self.steer_torque_motor = cp.vl["STEER_TORQUE_SENSOR"]['STEER_TORQUE_EPS'] + # we could use the override bit from dbc, but it's triggered at too high torque values + self.steer_override = abs(self.steer_torque_driver) > STEER_THRESHOLD + + self.user_brake = 0 + self.v_cruise_pcm = cp.vl["PCM_CRUISE_2"]['SET_SPEED'] + self.pcm_acc_status = cp.vl["PCM_CRUISE"]['CRUISE_STATE'] + self.pcm_acc_active = bool(cp.vl["PCM_CRUISE"]['CRUISE_ACTIVE']) + self.gas_pressed = not cp.vl["PCM_CRUISE"]['GAS_RELEASED'] + self.low_speed_lockout = cp.vl["PCM_CRUISE_2"]['LOW_SPEED_LOCKOUT'] == 2 + self.brake_lights = bool(cp.vl["ESP_CONTROL"]['BRAKE_LIGHTS_ACC'] or self.brake_pressed) + if self.CP.carFingerprint == CAR.PRIUS: + self.generic_toggle = cp.vl["AUTOPARK_STATUS"]['STATE'] != 0 + else: + self.generic_toggle = bool(cp.vl["LIGHT_STALK"]['AUTO_HIGH_BEAM']) diff --git a/selfdrive/car/toyota/interface.py b/selfdrive/car/toyota/interface.py new file mode 100755 index 00000000000000..03a19b8a288efa --- /dev/null +++ b/selfdrive/car/toyota/interface.py @@ -0,0 +1,357 @@ +#!/usr/bin/env python +from common.realtime import sec_since_boot +from cereal import car, log +from selfdrive.config import Conversions as CV +from selfdrive.controls.lib.drive_helpers import EventTypes as ET, create_event +from selfdrive.controls.lib.vehicle_model import VehicleModel +from selfdrive.car.toyota.carstate import CarState, get_can_parser, get_cam_can_parser +from selfdrive.car.toyota.values import ECU, check_ecu_msgs, CAR +from selfdrive.swaglog import cloudlog + +try: + from selfdrive.car.toyota.carcontroller import CarController +except ImportError: + CarController = None + + +class CarInterface(object): + def __init__(self, CP, sendcan=None): + self.CP = CP + self.VM = VehicleModel(CP) + + self.frame = 0 + self.gas_pressed_prev = False + self.brake_pressed_prev = False + self.can_invalid_count = 0 + self.cam_can_valid_count = 0 + self.cruise_enabled_prev = False + + # *** init the major players *** + self.CS = CarState(CP) + + self.cp = get_can_parser(CP) + self.cp_cam = get_cam_can_parser(CP) + + self.forwarding_camera = False + + # sending if read only is False + if sendcan is not None: + self.sendcan = sendcan + self.CC = CarController(self.cp.dbc_name, CP.carFingerprint, CP.enableCamera, CP.enableDsu, CP.enableApgs) + + @staticmethod + def compute_gb(accel, speed): + return float(accel) / 3.0 + + @staticmethod + def calc_accel_override(a_ego, a_target, v_ego, v_target): + return 1.0 + + @staticmethod + def get_params(candidate, fingerprint): + + # kg of standard extra cargo to count for drive, gas, etc... + std_cargo = 136 + + ret = car.CarParams.new_message() + + ret.carName = "toyota" + ret.carFingerprint = candidate + + ret.safetyModel = car.CarParams.SafetyModels.toyota + + # pedal + ret.enableCruise = True + + # FIXME: hardcoding honda civic 2016 touring params so they can be used to + # scale unknown params for other cars + mass_civic = 2923 * CV.LB_TO_KG + std_cargo + wheelbase_civic = 2.70 + centerToFront_civic = wheelbase_civic * 0.4 + centerToRear_civic = wheelbase_civic - centerToFront_civic + rotationalInertia_civic = 2500 + tireStiffnessFront_civic = 192150 + tireStiffnessRear_civic = 202500 + + ret.steerKiBP, ret.steerKpBP = [[0.], [0.]] + ret.steerActuatorDelay = 0.12 # Default delay, Prius has larger delay + + if candidate == CAR.PRIUS: + ret.safetyParam = 66 # see conversion factor for STEER_TORQUE_EPS in dbc file + ret.wheelbase = 2.70 + ret.steerRatio = 15.00 # unknown end-to-end spec + tire_stiffness_factor = 0.6371 # hand-tune + ret.mass = 3045 * CV.LB_TO_KG + std_cargo + ret.steerKpV, ret.steerKiV = [[0.4], [0.01]] + ret.steerKf = 0.00006 # full torque for 10 deg at 80mph means 0.00007818594 + # TODO: Prius seem to have very laggy actuators. Understand if it is lag or hysteresis + ret.steerActuatorDelay = 0.25 + + elif candidate in [CAR.RAV4, CAR.RAV4H]: + ret.safetyParam = 73 # see conversion factor for STEER_TORQUE_EPS in dbc file + ret.wheelbase = 2.65 + ret.steerRatio = 16.30 # 14.5 is spec end-to-end + tire_stiffness_factor = 0.5533 + ret.mass = 3650 * CV.LB_TO_KG + std_cargo # mean between normal and hybrid + ret.steerKpV, ret.steerKiV = [[0.6], [0.05]] + ret.steerKf = 0.00006 # full torque for 10 deg at 80mph means 0.00007818594 + + elif candidate == CAR.COROLLA: + ret.safetyParam = 100 # see conversion factor for STEER_TORQUE_EPS in dbc file + ret.wheelbase = 2.70 + ret.steerRatio = 17.8 + tire_stiffness_factor = 0.444 + ret.mass = 2860 * CV.LB_TO_KG + std_cargo # mean between normal and hybrid + ret.steerKpV, ret.steerKiV = [[0.2], [0.05]] + ret.steerKf = 0.00003 # full torque for 20 deg at 80mph means 0.00007818594 + + elif candidate == CAR.LEXUS_RXH: + ret.safetyParam = 100 # see conversion factor for STEER_TORQUE_EPS in dbc file + ret.wheelbase = 2.79 + ret.steerRatio = 16. # 14.8 is spec end-to-end + tire_stiffness_factor = 0.444 # not optimized yet + ret.mass = 4481 * CV.LB_TO_KG + std_cargo # mean between min and max + ret.steerKpV, ret.steerKiV = [[0.6], [0.1]] + ret.steerKf = 0.00006 # full torque for 10 deg at 80mph means 0.00007818594 + + elif candidate in [CAR.CHR, CAR.CHRH]: + ret.safetyParam = 100 + ret.wheelbase = 2.63906 + ret.steerRatio = 13.6 + tire_stiffness_factor = 0.7933 + ret.mass = 3300. * CV.LB_TO_KG + std_cargo + ret.steerKpV, ret.steerKiV = [[0.723], [0.0428]] + ret.steerKf = 0.00006 + + elif candidate in [CAR.CAMRY, CAR.CAMRYH]: + ret.safetyParam = 100 + ret.wheelbase = 2.82448 + ret.steerRatio = 13.7 + tire_stiffness_factor = 0.7933 + ret.mass = 3400 * CV.LB_TO_KG + std_cargo #mean between normal and hybrid + ret.steerKpV, ret.steerKiV = [[0.6], [0.1]] + ret.steerKf = 0.00006 + + elif candidate in [CAR.HIGHLANDER, CAR.HIGHLANDERH]: + ret.safetyParam = 100 + ret.wheelbase = 2.78 + ret.steerRatio = 16.0 + tire_stiffness_factor = 0.444 # not optimized yet + ret.mass = 4607 * CV.LB_TO_KG + std_cargo #mean between normal and hybrid limited + ret.steerKpV, ret.steerKiV = [[0.6], [0.05]] + ret.steerKf = 0.00006 + + ret.steerRateCost = 1. + ret.centerToFront = ret.wheelbase * 0.44 + + ret.longPidDeadzoneBP = [0., 9.] + ret.longPidDeadzoneV = [0., .15] + + # min speed to enable ACC. if car can do stop and go, then set enabling speed + # to a negative value, so it won't matter. + # hybrid models can't do stop and go even though the stock ACC can't + if candidate in [CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.CHR, + CAR.CHRH, CAR.CAMRY, CAR.CAMRYH, CAR.HIGHLANDERH, CAR.HIGHLANDER]: + ret.minEnableSpeed = -1. + elif candidate in [CAR.RAV4, CAR.COROLLA]: # TODO: hack ICE to do stop and go + ret.minEnableSpeed = 19. * CV.MPH_TO_MS + + centerToRear = ret.wheelbase - ret.centerToFront + # TODO: get actual value, for now starting with reasonable value for + # civic and scaling by mass and wheelbase + ret.rotationalInertia = rotationalInertia_civic * \ + ret.mass * ret.wheelbase**2 / (mass_civic * wheelbase_civic**2) + + # TODO: start from empirically derived lateral slip stiffness for the civic and scale by + # mass and CG position, so all cars will have approximately similar dyn behaviors + ret.tireStiffnessFront = (tireStiffnessFront_civic * tire_stiffness_factor) * \ + ret.mass / mass_civic * \ + (centerToRear / ret.wheelbase) / (centerToRear_civic / wheelbase_civic) + ret.tireStiffnessRear = (tireStiffnessRear_civic * tire_stiffness_factor) * \ + ret.mass / mass_civic * \ + (ret.centerToFront / ret.wheelbase) / (centerToFront_civic / wheelbase_civic) + + # no rear steering, at least on the listed cars above + ret.steerRatioRear = 0. + ret.steerControlType = car.CarParams.SteerControlType.torque + + # steer, gas, brake limitations VS speed + ret.steerMaxBP = [16. * CV.KPH_TO_MS, 45. * CV.KPH_TO_MS] # breakpoints at 1 and 40 kph + ret.steerMaxV = [1., 1.] # 2/3rd torque allowed above 45 kph + ret.gasMaxBP = [0.] + ret.gasMaxV = [0.5] + ret.brakeMaxBP = [5., 20.] + ret.brakeMaxV = [1., 0.8] + + ret.enableCamera = not check_ecu_msgs(fingerprint, ECU.CAM) + ret.enableDsu = not check_ecu_msgs(fingerprint, ECU.DSU) + ret.enableApgs = False #not check_ecu_msgs(fingerprint, ECU.APGS) + ret.openpilotLongitudinalControl = ret.enableCamera and ret.enableDsu + cloudlog.warn("ECU Camera Simulated: %r", ret.enableCamera) + cloudlog.warn("ECU DSU Simulated: %r", ret.enableDsu) + cloudlog.warn("ECU APGS Simulated: %r", ret.enableApgs) + + ret.steerLimitAlert = False + ret.stoppingControl = False + ret.startAccel = 0.0 + + ret.longitudinalKpBP = [0., 5., 35.] + ret.longitudinalKpV = [3.6, 2.4, 1.5] + ret.longitudinalKiBP = [0., 35.] + ret.longitudinalKiV = [0.54, 0.36] + + return ret + + # returns a car.CarState + def update(self, c): + # ******************* do can recv ******************* + canMonoTimes = [] + + self.cp.update(int(sec_since_boot() * 1e9), False) + + # run the cam can update for 10s as we just need to know if the camera is alive + if self.frame < 1000: + self.cp_cam.update(int(sec_since_boot() * 1e9), False) + + self.CS.update(self.cp, self.cp_cam) + + # create message + ret = car.CarState.new_message() + + # speeds + ret.vEgo = self.CS.v_ego + ret.vEgoRaw = self.CS.v_ego_raw + ret.aEgo = self.CS.a_ego + ret.yawRate = self.VM.yaw_rate(self.CS.angle_steers * CV.DEG_TO_RAD, self.CS.v_ego) + ret.standstill = self.CS.standstill + ret.wheelSpeeds.fl = self.CS.v_wheel_fl + ret.wheelSpeeds.fr = self.CS.v_wheel_fr + ret.wheelSpeeds.rl = self.CS.v_wheel_rl + ret.wheelSpeeds.rr = self.CS.v_wheel_rr + + # gear shifter + ret.gearShifter = self.CS.gear_shifter + + # gas pedal + ret.gas = self.CS.car_gas + ret.gasPressed = self.CS.pedal_gas > 0 + + # brake pedal + ret.brake = self.CS.user_brake + ret.brakePressed = self.CS.brake_pressed != 0 + ret.brakeLights = self.CS.brake_lights + + # steering wheel + ret.steeringAngle = self.CS.angle_steers + ret.steeringRate = self.CS.angle_steers_rate + + ret.steeringTorque = self.CS.steer_torque_driver + ret.steeringPressed = self.CS.steer_override + + # cruise state + ret.cruiseState.enabled = self.CS.pcm_acc_active + ret.cruiseState.speed = self.CS.v_cruise_pcm * CV.KPH_TO_MS + ret.cruiseState.available = bool(self.CS.main_on) + ret.cruiseState.speedOffset = 0. + if self.CP.carFingerprint in [CAR.RAV4H, CAR.HIGHLANDERH, CAR.HIGHLANDER]: + # ignore standstill in hybrid vehicles, since pcm allows to restart without + # receiving any special command + ret.cruiseState.standstill = False + else: + ret.cruiseState.standstill = self.CS.pcm_acc_status == 7 + + buttonEvents = [] + if self.CS.left_blinker_on != self.CS.prev_left_blinker_on: + be = car.CarState.ButtonEvent.new_message() + be.type = 'leftBlinker' + be.pressed = self.CS.left_blinker_on != 0 + buttonEvents.append(be) + + if self.CS.right_blinker_on != self.CS.prev_right_blinker_on: + be = car.CarState.ButtonEvent.new_message() + be.type = 'rightBlinker' + be.pressed = self.CS.right_blinker_on != 0 + buttonEvents.append(be) + + ret.buttonEvents = buttonEvents + ret.leftBlinker = bool(self.CS.left_blinker_on) + ret.rightBlinker = bool(self.CS.right_blinker_on) + + ret.doorOpen = not self.CS.door_all_closed + ret.seatbeltUnlatched = not self.CS.seatbelt + + ret.genericToggle = self.CS.generic_toggle + + # events + events = [] + if not self.CS.can_valid: + self.can_invalid_count += 1 + if self.can_invalid_count >= 5: + events.append(create_event('commIssue', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE])) + else: + self.can_invalid_count = 0 + + if self.CS.cam_can_valid: + self.cam_can_valid_count += 1 + if self.cam_can_valid_count >= 5: + self.forwarding_camera = True + + if not ret.gearShifter == 'drive' and self.CP.enableDsu: + events.append(create_event('wrongGear', [ET.NO_ENTRY, ET.SOFT_DISABLE])) + if ret.doorOpen: + events.append(create_event('doorOpen', [ET.NO_ENTRY, ET.SOFT_DISABLE])) + if ret.seatbeltUnlatched: + events.append(create_event('seatbeltNotLatched', [ET.NO_ENTRY, ET.SOFT_DISABLE])) + if self.CS.esp_disabled and self.CP.enableDsu: + events.append(create_event('espDisabled', [ET.NO_ENTRY, ET.SOFT_DISABLE])) + if not self.CS.main_on and self.CP.enableDsu: + events.append(create_event('wrongCarMode', [ET.NO_ENTRY, ET.USER_DISABLE])) + if ret.gearShifter == 'reverse' and self.CP.enableDsu: + events.append(create_event('reverseGear', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE])) + if self.CS.steer_error: + events.append(create_event('steerTempUnavailable', [ET.NO_ENTRY, ET.WARNING])) + if self.CS.low_speed_lockout and self.CP.enableDsu: + events.append(create_event('lowSpeedLockout', [ET.NO_ENTRY, ET.PERMANENT])) + if ret.vEgo < self.CP.minEnableSpeed and self.CP.enableDsu: + events.append(create_event('speedTooLow', [ET.NO_ENTRY])) + if c.actuators.gas > 0.1: + # some margin on the actuator to not false trigger cancellation while stopping + events.append(create_event('speedTooLow', [ET.IMMEDIATE_DISABLE])) + if ret.vEgo < 0.001: + # while in standstill, send a user alert + events.append(create_event('manualRestart', [ET.WARNING])) + + # enable request in prius is simple, as we activate when Toyota is active (rising edge) + if ret.cruiseState.enabled and not self.cruise_enabled_prev: + events.append(create_event('pcmEnable', [ET.ENABLE])) + elif not ret.cruiseState.enabled: + events.append(create_event('pcmDisable', [ET.USER_DISABLE])) + + # disable on pedals rising edge or when brake is pressed and speed isn't zero + if (ret.gasPressed and not self.gas_pressed_prev) or \ + (ret.brakePressed and (not self.brake_pressed_prev or ret.vEgo > 0.001)): + events.append(create_event('pedalPressed', [ET.NO_ENTRY, ET.USER_DISABLE])) + + if ret.gasPressed: + events.append(create_event('pedalPressed', [ET.PRE_ENABLE])) + + ret.events = events + ret.canMonoTimes = canMonoTimes + + self.gas_pressed_prev = ret.gasPressed + self.brake_pressed_prev = ret.brakePressed + self.cruise_enabled_prev = ret.cruiseState.enabled + + return ret.as_reader() + + # pass in a car.CarControl + # to be called @ 100hz + def apply(self, c, perception_state=log.Live20Data.new_message()): + + self.CC.update(self.sendcan, c.enabled, self.CS, self.frame, + c.actuators, c.cruiseControl.cancel, c.hudControl.visualAlert, + c.hudControl.audibleAlert, self.forwarding_camera, + c.hudControl.leftLaneVisible, c.hudControl.rightLaneVisible, c.hudControl.leadVisible) + + self.frame += 1 + return False diff --git a/selfdrive/car/toyota/radar_interface.py b/selfdrive/car/toyota/radar_interface.py new file mode 100755 index 00000000000000..9711f1393ff566 --- /dev/null +++ b/selfdrive/car/toyota/radar_interface.py @@ -0,0 +1,107 @@ +#!/usr/bin/env python +import os +import zmq +import time +from selfdrive.can.parser import CANParser +from cereal import car +from common.realtime import sec_since_boot +from selfdrive.services import service_list +import selfdrive.messaging as messaging +from selfdrive.car.toyota.values import NO_DSU_CAR + + +RADAR_A_MSGS = list(range(0x210, 0x220)) +RADAR_B_MSGS = list(range(0x220, 0x230)) + +def _create_radard_can_parser(): + dbc_f = 'toyota_prius_2017_adas.dbc' + + msg_a_n = len(RADAR_A_MSGS) + msg_b_n = len(RADAR_B_MSGS) + + signals = zip(['LONG_DIST'] * msg_a_n + ['NEW_TRACK'] * msg_a_n + ['LAT_DIST'] * msg_a_n + + ['REL_SPEED'] * msg_a_n + ['VALID'] * msg_a_n + ['SCORE'] * msg_b_n, + RADAR_A_MSGS * 5 + RADAR_B_MSGS, + [255] * msg_a_n + [1] * msg_a_n + [0] * msg_a_n + [0] * msg_a_n + [0] * msg_a_n + [0] * msg_b_n) + + checks = zip(RADAR_A_MSGS + RADAR_B_MSGS, [20]*(msg_a_n + msg_b_n)) + + return CANParser(os.path.splitext(dbc_f)[0], signals, checks, 1) + + +class RadarInterface(object): + def __init__(self, CP): + # radar + self.pts = {} + self.valid_cnt = {key: 0 for key in RADAR_A_MSGS} + self.track_id = 0 + + self.delay = 0.0 # Delay of radar + + self.rcp = _create_radard_can_parser() + self.no_dsu_car = CP.carFingerprint in NO_DSU_CAR + + context = zmq.Context() + self.logcan = messaging.sub_sock(context, service_list['can'].port) + + def update(self): + + ret = car.RadarState.new_message() + if self.no_dsu_car: + # TODO: make a adas dbc file for dsu-less models + time.sleep(0.05) + return ret + + canMonoTimes = [] + updated_messages = set() + while 1: + tm = int(sec_since_boot() * 1e9) + updated_messages.update(self.rcp.update(tm, True)) + if RADAR_B_MSGS[-1] in updated_messages: + break + + errors = [] + if not self.rcp.can_valid: + errors.append("commIssue") + ret.errors = errors + ret.canMonoTimes = canMonoTimes + + for ii in updated_messages: + if ii in RADAR_A_MSGS: + cpt = self.rcp.vl[ii] + + if cpt['LONG_DIST'] >=255 or cpt['NEW_TRACK']: + self.valid_cnt[ii] = 0 # reset counter + if cpt['VALID'] and cpt['LONG_DIST'] < 255: + self.valid_cnt[ii] += 1 + else: + self.valid_cnt[ii] = max(self.valid_cnt[ii] -1, 0) + + score = self.rcp.vl[ii+16]['SCORE'] + # print ii, self.valid_cnt[ii], score, cpt['VALID'], cpt['LONG_DIST'], cpt['LAT_DIST'] + + # radar point only valid if it's a valid measurement and score is above 50 + if cpt['VALID'] or (score > 50 and cpt['LONG_DIST'] < 255 and self.valid_cnt[ii] > 0): + if ii not in self.pts or cpt['NEW_TRACK']: + self.pts[ii] = car.RadarState.RadarPoint.new_message() + self.pts[ii].trackId = self.track_id + self.track_id += 1 + self.pts[ii].dRel = cpt['LONG_DIST'] # from front of car + self.pts[ii].yRel = -cpt['LAT_DIST'] # in car frame's y axis, left is positive + self.pts[ii].vRel = cpt['REL_SPEED'] + self.pts[ii].aRel = float('nan') + self.pts[ii].yvRel = float('nan') + self.pts[ii].measured = bool(cpt['VALID']) + else: + if ii in self.pts: + del self.pts[ii] + + ret.points = self.pts.values() + return ret + +if __name__ == "__main__": + RI = RadarInterface(None) + while 1: + ret = RI.update() + print(chr(27) + "[2J") + print(ret) diff --git a/selfdrive/car/toyota/toyotacan.py b/selfdrive/car/toyota/toyotacan.py new file mode 100644 index 00000000000000..720c0ef60a8a25 --- /dev/null +++ b/selfdrive/car/toyota/toyotacan.py @@ -0,0 +1,106 @@ +import struct + + +# *** Toyota specific *** + +def fix(msg, addr): + checksum = 0 + idh = (addr & 0xff00) >> 8 + idl = (addr & 0xff) + + checksum = idh + idl + len(msg) + 1 + for d_byte in msg: + checksum += ord(d_byte) + + #return msg + chr(checksum & 0xFF) + return msg + struct.pack("B", checksum & 0xFF) + + +def make_can_msg(addr, dat, alt, cks=False): + if cks: + dat = fix(dat, addr) + return [addr, 0, dat, alt] + + +def create_video_target(frame, addr): + counter = frame & 0xff + msg = struct.pack("!BBBBBBB", counter, 0x03, 0xff, 0x00, 0x00, 0x00, 0x00) + return make_can_msg(addr, msg, 1, True) + + +def create_ipas_steer_command(packer, steer, enabled, apgs_enabled): + """Creates a CAN message for the Toyota Steer Command.""" + if steer < 0: + direction = 3 + elif steer > 0: + direction = 1 + else: + direction = 2 + + mode = 3 if enabled else 1 + + values = { + "STATE": mode, + "DIRECTION_CMD": direction, + "ANGLE": steer, + "SET_ME_X10": 0x10, + "SET_ME_X40": 0x40 + } + if apgs_enabled: + return packer.make_can_msg("STEERING_IPAS", 0, values) + else: + return packer.make_can_msg("STEERING_IPAS_COMMA", 0, values) + + +def create_steer_command(packer, steer, steer_req, raw_cnt): + """Creates a CAN message for the Toyota Steer Command.""" + + values = { + "STEER_REQUEST": steer_req, + "STEER_TORQUE_CMD": steer, + "COUNTER": raw_cnt, + "SET_ME_1": 1, + } + return packer.make_can_msg("STEERING_LKA", 0, values) + + +def create_accel_command(packer, accel, pcm_cancel, standstill_req, lead): + # TODO: find the exact canceling bit that does not create a chime + values = { + "ACCEL_CMD": accel, + "SET_ME_X01": 1, + "DISTANCE": 0, + "MINI_CAR": lead, + "SET_ME_X3": 3, + "SET_ME_1": 1, + "RELEASE_STANDSTILL": not standstill_req, + "CANCEL_REQ": pcm_cancel, + } + return packer.make_can_msg("ACC_CONTROL", 0, values) + + +def create_fcw_command(packer, fcw): + values = { + "FCW": fcw, + "SET_ME_X20": 0x20, + "SET_ME_X10": 0x10, + "SET_ME_X80": 0x80, + } + return packer.make_can_msg("ACC_HUD", 0, values) + + +def create_ui_command(packer, steer, sound1, sound2, left_line, right_line): + values = { + "RIGHT_LINE": 1 if right_line else 2, + "LEFT_LINE": 1 if left_line else 2, + "SET_ME_X0C": 0x0c, + "SET_ME_X2C": 0x2c, + "SET_ME_X38": 0x38, + "SET_ME_X02": 0x02, + "SET_ME_X01": 1, + "SET_ME_X01_2": 1, + "REPEATED_BEEPS": sound1, + "TWO_BEEPS": sound2, + "LDA_ALERT": steer, + } + return packer.make_can_msg("LKAS_HUD", 0, values) diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py new file mode 100644 index 00000000000000..e6dd026b03aae6 --- /dev/null +++ b/selfdrive/car/toyota/values.py @@ -0,0 +1,164 @@ +from selfdrive.car import dbc_dict + +class CAR: + PRIUS = "TOYOTA PRIUS 2017" + RAV4H = "TOYOTA RAV4 HYBRID 2017" + RAV4 = "TOYOTA RAV4 2017" + COROLLA = "TOYOTA COROLLA 2017" + LEXUS_RXH = "LEXUS RX HYBRID 2017" + CHR = "TOYOTA C-HR 2018" + CHRH = "TOYOTA C-HR HYBRID 2018" + CAMRY = "TOYOTA CAMRY 2018" + CAMRYH = "TOYOTA CAMRY HYBRID 2018" + HIGHLANDER = "TOYOTA HIGHLANDER 2017" + HIGHLANDERH = "TOYOTA HIGHLANDER HYBRID 2018" + + +class ECU: + CAM = 0 # camera + DSU = 1 # driving support unit + APGS = 2 # advanced parking guidance system + + +# addr: (ecu, cars, bus, 1/freq*100, vl) +STATIC_MSGS = [ + (0x130, ECU.CAM, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.HIGHLANDERH), 1, 100, '\x00\x00\x00\x00\x00\x00\x38'), + (0x240, ECU.CAM, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.HIGHLANDERH), 1, 5, '\x00\x10\x01\x00\x10\x01\x00'), + (0x241, ECU.CAM, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.HIGHLANDERH), 1, 5, '\x00\x10\x01\x00\x10\x01\x00'), + (0x244, ECU.CAM, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.HIGHLANDERH), 1, 5, '\x00\x10\x01\x00\x10\x01\x00'), + (0x245, ECU.CAM, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.HIGHLANDERH), 1, 5, '\x00\x10\x01\x00\x10\x01\x00'), + (0x248, ECU.CAM, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.HIGHLANDERH), 1, 5, '\x00\x00\x00\x00\x00\x00\x01'), + (0x367, ECU.CAM, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.HIGHLANDERH), 0, 40, '\x06\x00'), + (0x414, ECU.CAM, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.HIGHLANDERH), 0, 100, '\x00\x00\x00\x00\x00\x00\x17\x00'), + (0x466, ECU.CAM, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.RAV4, CAR.HIGHLANDER, CAR.HIGHLANDERH), 1, 100, '\x20\x20\xAD'), + (0x466, ECU.CAM, (CAR.COROLLA), 1, 100, '\x24\x20\xB1'), + (0x489, ECU.CAM, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.HIGHLANDERH), 0, 100, '\x00\x00\x00\x00\x00\x00\x00'), + (0x48a, ECU.CAM, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.HIGHLANDERH), 0, 100, '\x00\x00\x00\x00\x00\x00\x00'), + (0x48b, ECU.CAM, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.HIGHLANDERH), 0, 100, '\x66\x06\x08\x0a\x02\x00\x00\x00'), + (0x4d3, ECU.CAM, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.RAV4, CAR.COROLLA), 0, 100, '\x1C\x00\x00\x01\x00\x00\x00\x00'), + + (0x128, ECU.DSU, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.RAV4, CAR.COROLLA), 1, 3, '\xf4\x01\x90\x83\x00\x37'), + (0x128, ECU.DSU, (CAR.HIGHLANDER, CAR.HIGHLANDERH), 1, 3, '\x03\x00\x20\x00\x00\x52'), + (0x141, ECU.DSU, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.HIGHLANDERH), 1, 2, '\x00\x00\x00\x46'), + (0x160, ECU.DSU, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.HIGHLANDERH), 1, 7, '\x00\x00\x08\x12\x01\x31\x9c\x51'), + (0x161, ECU.DSU, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.RAV4, CAR.COROLLA), 1, 7, '\x00\x1e\x00\x00\x00\x80\x07'), + (0X161, ECU.DSU, (CAR.HIGHLANDERH, CAR.HIGHLANDER), 1, 7, '\x00\x1e\x00\xd4\x00\x00\x5b'), + (0x283, ECU.DSU, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.HIGHLANDERH), 0, 3, '\x00\x00\x00\x00\x00\x00\x8c'), + (0x2E6, ECU.DSU, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH), 0, 3, '\xff\xf8\x00\x08\x7f\xe0\x00\x4e'), + (0x2E7, ECU.DSU, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH), 0, 3, '\xa8\x9c\x31\x9c\x00\x00\x00\x02'), + (0x33E, ECU.DSU, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH), 0, 20, '\x0f\xff\x26\x40\x00\x1f\x00'), + (0x344, ECU.DSU, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.HIGHLANDERH), 0, 5, '\x00\x00\x01\x00\x00\x00\x00\x50'), + (0x365, ECU.DSU, (CAR.PRIUS, CAR.LEXUS_RXH, CAR.HIGHLANDERH), 0, 20, '\x00\x00\x00\x80\x03\x00\x08'), + (0x365, ECU.DSU, (CAR.RAV4, CAR.RAV4H, CAR.COROLLA, CAR.HIGHLANDER), 0, 20, '\x00\x00\x00\x80\xfc\x00\x08'), + (0x366, ECU.DSU, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.HIGHLANDERH), 0, 20, '\x00\x00\x4d\x82\x40\x02\x00'), + (0x366, ECU.DSU, (CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER), 0, 20, '\x00\x72\x07\xff\x09\xfe\x00'), + (0x470, ECU.DSU, (CAR.PRIUS, CAR.LEXUS_RXH), 1, 100, '\x00\x00\x02\x7a'), + (0x470, ECU.DSU, (CAR.HIGHLANDER, CAR.HIGHLANDERH, CAR.RAV4H), 1, 100, '\x00\x00\x01\x79'), + (0x4CB, ECU.DSU, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDERH, CAR.HIGHLANDER), 0, 100, '\x0c\x00\x00\x00\x00\x00\x00\x00'), + + (0x292, ECU.APGS, (CAR.PRIUS), 0, 3, '\x00\x00\x00\x00\x00\x00\x00\x9e'), + (0x32E, ECU.APGS, (CAR.PRIUS), 0, 20, '\x00\x00\x00\x00\x00\x00\x00\x00'), + (0x396, ECU.APGS, (CAR.PRIUS), 0, 100, '\xBD\x00\x00\x00\x60\x0F\x02\x00'), + (0x43A, ECU.APGS, (CAR.PRIUS), 0, 100, '\x84\x00\x00\x00\x00\x00\x00\x00'), + (0x43B, ECU.APGS, (CAR.PRIUS), 0, 100, '\x00\x00\x00\x00\x00\x00\x00\x00'), + (0x497, ECU.APGS, (CAR.PRIUS), 0, 100, '\x00\x00\x00\x00\x00\x00\x00\x00'), + (0x4CC, ECU.APGS, (CAR.PRIUS), 0, 100, '\x0D\x00\x00\x00\x00\x00\x00\x00'), +] + +ECU_FINGERPRINT = { + ECU.CAM: 0x2e4, # steer torque cmd + ECU.DSU: 0x343, # accel cmd + ECU.APGS: 0x835, # angle cmd +} + + +def check_ecu_msgs(fingerprint, ecu): + # return True if fingerprint contains messages normally sent by a given ecu + return ECU_FINGERPRINT[ecu] in fingerprint + + +FINGERPRINTS = { + CAR.RAV4: [{ + 36: 8, 37: 8, 170: 8, 180: 8, 186: 4, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 547: 8, 548: 8, 552: 4, 562: 4, 608: 8, 610: 5, 643: 7, 705: 8, 725: 2, 740: 5, 800: 8, 835: 8, 836: 8, 849: 4, 869: 7, 870: 7, 871: 2, 896: 8, 897: 8, 900: 6, 902: 6, 905: 8, 911: 8, 916: 3, 918: 7, 921: 8, 933: 8, 944: 8, 945: 8, 951: 8, 955: 4, 956: 8, 979: 2, 998: 5, 999: 7, 1000: 8, 1001: 8, 1005: 2, 1008: 2, 1014: 8, 1017: 8, 1041: 8, 1042: 8, 1043: 8, 1044: 8, 1056: 8, 1059: 1, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1176: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1181: 8, 1190: 8, 1191: 8, 1192: 8, 1196: 8, 1227: 8, 1228: 8, 1235: 8, 1237: 8, 1263: 8, 1264: 8, 1279: 8, 1408: 8, 1409: 8, 1410: 8, 1552: 8, 1553: 8, 1554: 8, 1555: 8, 1556: 8, 1557: 8, 1561: 8, 1562: 8, 1568: 8, 1569: 8, 1570: 8, 1571: 8, 1572: 8, 1584: 8, 1589: 8, 1592: 8, 1593: 8, 1595: 8, 1596: 8, 1597: 8, 1600: 8, 1656: 8, 1664: 8, 1728: 8, 1745: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 + }], + CAR.RAV4H: [{ + 36: 8, 37: 8, 170: 8, 180: 8, 186: 4, 296: 8, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 547: 8, 548: 8, 550: 8, 552: 4, 560: 7, 562: 4, 581: 5, 608: 8, 610: 5, 643: 7, 705: 8, 713: 8, 725: 2, 740: 5, 800: 8, 835: 8, 836: 8, 849: 4, 869: 7, 870: 7, 871: 2, 896: 8, 897: 8, 900: 6, 902: 6, 905: 8, 911: 8, 916: 3, 918: 7, 921: 8, 933: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 3, 955: 8, 956: 8, 979: 2, 998: 5, 999: 7, 1000: 8, 1001: 8, 1005: 2, 1008: 2, 1014: 8, 1017: 8, 1041: 8, 1042: 8, 1043: 8, 1044: 8, 1056: 8, 1059: 1, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1176: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1181: 8, 1184: 8, 1185: 8, 1186: 8, 1190: 8, 1191: 8, 1192: 8, 1196: 8, 1197: 8, 1198: 8, 1199: 8, 1212: 8, 1227: 8, 1228: 8, 1232: 8, 1235: 8, 1237: 8, 1263: 8, 1264: 8, 1279: 8, 1408: 8, 1409: 8, 1410: 8, 1552: 8, 1553: 8, 1554: 8, 1555: 8, 1556: 8, 1557: 8, 1561: 8, 1562: 8, 1568: 8, 1569: 8, 1570: 8, 1571: 8, 1572: 8, 1584: 8, 1589: 8, 1592: 8, 1593: 8, 1595: 8, 1596: 8, 1597: 8, 1600: 8, 1656: 8, 1664: 8, 1728: 8, 1745: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 + }, + # Chinese RAV4 + { + 36: 8, 37: 8, 170: 8, 180: 8, 186: 4, 355: 5, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 547: 8, 548: 8, 552: 4, 562: 4, 608: 8, 610: 5, 643: 7, 705: 8, 725: 2, 740: 5, 742: 8, 743: 8, 800: 8, 830: 7, 835: 8, 836: 8, 849: 4, 869: 7, 870: 7, 871: 2, 896: 8, 897: 8, 900: 6, 902: 6, 905: 8, 911: 8, 916: 3, 921: 8, 922: 8, 933: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 979: 2, 998: 5, 999: 7, 1000: 8, 1001: 8, 1008: 2, 1017: 8, 1041: 8, 1042: 8, 1043: 8, 1044: 8, 1056: 8, 1059: 1, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1176: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1181: 8, 1190: 8, 1191: 8, 1192: 8, 1196: 8, 1207: 8, 1227: 8, 1235: 8, 1263: 8, 1279: 8, 1552: 8, 1553: 8, 1554: 8, 1555: 8, 1556: 8, 1557: 8, 1561: 8, 1562: 8, 1568: 8, 1569: 8, 1570: 8, 1571: 8, 1572: 8, 1584: 8, 1589: 8, 1592: 8, 1593: 8, 1595: 8, 1596: 8, 1597: 8, 1600: 8, 1664: 8, 1728: 8, 1745: 8, 1779: 8 + }], + CAR.PRIUS: [{ + 36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 8, 614: 8, 643: 7, 658: 8, 713: 8, 740: 5, 742: 8, 743: 8, 800: 8, 810: 2, 814: 8, 829: 2, 830: 7, 835: 8, 836: 8, 863: 8, 869: 7, 870: 7, 871: 2, 898: 8, 900: 6, 902: 6, 905: 8, 918: 8, 921: 8, 933: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 975: 5, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1057: 8, 1059: 1, 1071: 8, 1077: 8, 1082: 8, 1083: 8, 1084: 8, 1085: 8, 1086: 8, 1114: 8, 1132: 8, 1161: 8, 1162: 8, 1163: 8, 1175: 8, 1227: 8, 1228: 8, 1235: 8, 1237: 8, 1279: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1595: 8, 1777: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 + }, + # Prius Prime + { + 36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 8, 614: 8, 643: 7, 658: 8, 713: 8, 740: 5, 742: 8, 743: 8, 800: 8, 810: 2, 814: 8, 824: 2, 829: 2, 830: 7, 835: 8, 836: 8, 863: 8, 869: 7, 870: 7, 871: 2,898: 8, 900: 6, 902: 6, 905: 8, 913: 8, 918: 8, 921: 8, 933: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 974: 8, 975: 5, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1057: 8, 1059: 1, 1071: 8, 1076: 8, 1077: 8, 1082: 8, 1083: 8, 1084: 8, 1085: 8, 1086: 8, 1114: 8, 1132: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1175: 8, 1227: 8, 1228: 8, 1235: 8, 1237: 8, 1279: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1595: 8, 1777: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 + }, + # Taiwanese Prius Prime + { + 36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 8, 614: 8, 643: 7, 658: 8, 713: 8, 740: 5, 742: 8, 743: 8, 800: 8, 810: 2, 814: 8, 824: 2, 829: 2, 830: 7, 835: 8, 836: 8, 845: 5, 863: 8, 869: 7, 870: 7, 871: 2,898: 8, 900: 6, 902: 6, 905: 8, 913: 8, 918: 8, 921: 8, 933: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 974: 8, 975: 5, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1005: 2, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1057: 8, 1059: 1, 1071: 8, 1076: 8, 1077: 8, 1082: 8, 1083: 8, 1084: 8, 1085: 8, 1086: 8, 1114: 8, 1132: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1175: 8, 1227: 8, 1228: 8, 1235: 8, 1237: 8, 1264: 8, 1279: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1595: 8, 1777: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 + }], + CAR.COROLLA: [{ + 36: 8, 37: 8, 170: 8, 180: 8, 186: 4, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 547: 8, 548: 8, 552: 4, 608: 8, 610: 5, 643: 7, 705: 8, 740: 5, 800: 8, 835: 8, 836: 8, 849: 4, 869: 7, 870: 7, 871: 2, 896: 8, 897: 8, 900: 6, 902: 6, 905: 8, 911: 8, 916: 2, 921: 8, 933: 8, 944: 8, 945: 8, 951: 8, 955: 4, 956: 8, 979: 2, 992: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1017: 8, 1041: 8, 1042: 8, 1043: 8, 1044: 8, 1056: 8, 1059: 1, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1196: 8, 1227: 8, 1235: 8, 1279: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1561: 8, 1562: 8, 1568: 8, 1569: 8, 1570: 8, 1571: 8, 1572: 8, 1584: 8, 1589: 8, 1592: 8, 1596: 8, 1597: 8, 1600: 8, 1664: 8, 1728: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 + }, + # Corolla LE 2017 + { + 36: 8, 37: 8, 170: 8, 180: 8, 186: 4, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 547: 8, 548: 8, 552: 4, 608: 8, 610: 5, 643: 7, 705: 8, 740: 5, 800: 8, 835: 8, 836: 8, 849: 4, 869: 7, 870: 7, 871: 2, 896: 8, 897: 8, 900: 6, 902: 6, 905: 8, 911: 8, 916: 2, 921: 8, 933: 8, 944: 8, 945: 8, 951: 8, 955: 4, 956: 8, 979: 2, 998: 5, 999: 7, 1000: 8, 1001: 8, 1017: 8, 1041: 8, 1042: 8, 1043: 8, 1044: 8, 1056: 8, 1059: 1, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1196: 8, 1227: 8, 1235: 8, 1279: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1561: 8, 1562: 8, 1568: 8, 1569: 8, 1570: 8, 1571: 8, 1572: 8, 1592: 8, 1596: 8, 1597: 8, 1600: 8, 1664: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8, 2016: 8, 2017: 8, 2018: 8, 2019: 8, 2020: 8, 2021: 8, 2022: 8, 2023: 8, 2024: 8 + }], + CAR.LEXUS_RXH: [{ + 36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 5, 643: 7, 658: 8, 713: 8, 740: 5, 742: 8, 743: 8, 800: 8, 810: 2, 812: 3, 814: 8, 830: 7, 835: 8, 836: 8, 845: 5, 863: 8, 869: 7, 870: 7, 871: 2, 898: 8, 900: 6, 902: 6, 905: 8, 913: 8, 918: 8, 921: 8, 933: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 975: 6, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1005: 2, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1059: 1, 1063: 8, 1071: 8, 1077: 8, 1082: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1227: 8, 1228: 8, 1235: 8, 1237: 8, 1264: 8, 1279: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1575: 8, 1595: 8, 1777: 8, 1779: 8, 1808: 8, 1810: 8, 1816: 8, 1818: 8, 1840: 8, 1848: 8, 1904: 8, 1912: 8, 1940: 8, 1941: 8, 1948: 8, 1949: 8, 1952: 8, 1956: 8, 1960: 8, 1964: 8, 1986: 8, 1990: 8, 1994: 8, 1998: 8, 2004: 8, 2012: 8 + }, + # RX450HL + { + 36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 5, 643: 7, 658: 8, 713: 8, 742: 8, 743: 8, 800: 8, 810: 2, 812: 3, 814: 8, 830: 7, 835: 8, 836: 8, 863: 8, 865: 8, 869: 7, 870: 7, 898: 8, 900: 6, 902: 6, 905: 8, 918: 8, 921: 8, 933: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 975: 6, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1005: 2, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1056: 8, 1057: 8, 1059: 1, 1063: 8, 1071: 8, 1076: 8, 1077: 8, 1082: 8, 1114: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1227: 8, 1228: 8, 1237: 8, 1264: 8, 1279: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1575: 8, 1592: 8, 1594: 8, 1595: 8, 1649: 8, 1777: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 + }], + CAR.CHR: [{ + 36: 8, 37: 8, 170: 8, 180: 8, 186: 4, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 550: 8, 552: 4, 562: 6, 608: 8, 610: 8, 614: 8, 643: 7, 658: 8, 705: 8, 740: 5, 800: 8, 810: 2, 812: 8, 814: 8, 830: 7, 835: 8, 836: 8, 845: 5, 869: 7, 870: 7, 871: 2, 898: 8, 913: 8, 918: 8, 921: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 976: 1, 1014: 8, 1017: 8, 1020: 8, 1021: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1059: 1, 1082: 8, 1083: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1175: 8, 1228: 8, 1235: 8, 1237: 8, 1279: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1595: 8, 1745: 8, 1779: 8 + }], + CAR.CHRH: [{ + 36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 8, 614: 8, 643: 7, 658: 8, 713: 8, 740: 5, 800: 8, 810: 2, 812: 8, 814: 8, 829: 2, 830: 7, 835: 8, 836: 8, 845: 5, 869: 7, 870: 7, 871: 2, 898: 8, 900: 6, 902: 6, 905: 8, 913: 8, 918: 8, 921: 8, 933: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 975: 5, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1014: 8, 1017: 8, 1020: 8, 1021: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1057: 8, 1059: 1, 1071: 8, 1076: 8, 1077: 8, 1082: 8, 1083: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1175: 8, 1228: 8, 1235: 8, 1237: 8, 1279: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1595: 8, 1745: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 + }], + CAR.CAMRY: [ + #XLE and LE + { + 36: 8, 37: 8, 119: 6, 170: 8, 180: 8, 186: 4, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 550: 8, 552: 4, 562: 6, 608: 8, 610: 8, 643: 7, 658: 8, 705: 8, 728: 8, 740: 5, 761: 8, 764: 8, 800: 8, 810: 2, 812: 8, 814: 8, 818: 8, 822: 8, 824: 8, 830: 7, 835: 8, 836: 8, 869: 7, 870: 7, 871: 2, 888: 8, 889: 8, 891: 8, 898: 8, 900: 6, 902: 6, 905: 8, 918: 8, 921: 8, 933: 8, 934: 8, 935: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 976: 1, 983: 8, 984: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1002: 8, 1011: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1059: 1, 1076: 8, 1077: 8, 1082: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1228: 8, 1235: 8, 1237: 8, 1263: 8, 1264: 8, 1279: 8, 1412: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1595: 8, 1745: 8, 1779: 8, 1786: 8, 1787: 8, 1788: 8, 1789: 8, 1808: 8, 1816: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 + }, + #XSE and SE + { + 36: 8, 37: 8, 114: 5, 119: 6, 120: 4, 170: 8, 180: 8, 186: 4, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 550: 8, 552: 4, 562: 6, 608: 8, 610: 8, 643: 7, 658: 8, 705: 8, 728: 8, 761: 8, 764: 8, 800: 8, 810: 2, 812: 8, 814: 8, 818: 8, 822: 8, 824: 8, 830: 7, 835: 8, 836: 8, 869: 7, 870: 7, 888: 8, 889: 8, 891: 8, 898: 8, 900: 6, 902: 6, 905: 8, 918: 8, 921: 8, 933: 8, 934: 8, 935: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 976: 1, 983: 8, 984: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1002: 8, 1011: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1056: 8, 1059: 1, 1076: 8, 1077: 8, 1082: 8, 1114: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1228: 8, 1237: 8, 1263: 8, 1264: 8, 1279: 8, 1412: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1595: 8, 1745: 8, 1779: 8, 1786: 8, 1787: 8, 1788: 8, 1789: 8, 1808: 8, 1816: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 + }], + CAR.CAMRYH: [ + #LE + { + 36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 8, 643: 7, 713: 8, 728: 8, 740: 5, 761: 8, 764: 8, 800: 8, 810: 2, 812: 8, 824: 8, 829: 2, 830: 7, 835: 8, 836: 8, 869: 7, 870: 7, 871: 2, 898: 8, 900: 6, 902: 6, 905: 8, 921: 8, 933: 8, 934: 8, 935: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 975: 5, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1002: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1057: 8, 1059: 1, 1071: 8, 1076: 8, 1077: 8, 1084: 8, 1085: 8, 1086: 8, 1114: 8, 1132: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1235: 8, 1279: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572:8, 1595: 8, 1745: 8, 1779: 8, 1786: 8, 1787: 8, 1788: 8, 1789: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 + }], + CAR.HIGHLANDER: [{ + 36: 8, 37: 8, 114: 5, 119: 6, 120: 4, 170: 8, 180: 8, 186: 4, 238: 4, 355: 5, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 545: 5, 550: 8, 552: 4, 608: 8, 610: 5, 643: 7, 705: 8, 725: 2, 740: 5, 800: 8, 835: 8, 836: 8, 849: 4, 869: 7, 870: 7, 871: 2, 896: 8, 900: 6, 902: 6, 905: 8, 911: 8, 916: 3, 921: 8, 922: 8, 933: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 979: 2, 998: 5, 999: 7, 1000: 8, 1001: 8, 1008: 2, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1043: 8, 1044: 8, 1056: 8, 1059: 1, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1176: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1181: 8, 1182: 8, 1183: 8, 1189: 8, 1190: 8, 1191: 8, 1192: 8, 1196: 8, 1197: 8, 1198: 8, 1199: 8, 1206: 8, 1207: 8, 1212: 8, 1227: 8, 1235: 8, 1237: 8, 1279: 8, 1408: 8, 1409: 8, 1410: 8, 1552: 8, 1553: 8, 1554: 8, 1556: 8, 1557: 8, 1561: 8, 1562: 8, 1568: 8, 1569: 8, 1570: 8, 1571: 8, 1572: 8, 1584: 8, 1589: 8, 1592: 8, 1593: 8, 1595: 8, 1599: 8, 1656: 8, 1666: 8, 1667: 8, 1728: 8, 1745: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 + }, + # 2017 Highlander Limited + { + 36: 8, 37: 8, 114: 5, 119: 6, 120: 4, 170: 8, 180: 8, 186: 4, 238: 4, 355: 5, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 545: 5, 550: 8, 552: 4, 608: 8, 610: 5, 643: 7, 705: 8, 725: 2, 740: 5, 800: 8, 835: 8, 836: 8, 849: 4, 869: 7, 870: 7, 871: 2, 896: 8, 900: 6, 902: 6, 905: 8, 911: 8, 916: 3, 918: 7, 921: 8, 922: 8, 933: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 979: 2, 998: 5, 999: 7, 1000: 8, 1001: 8, 1005: 2, 1008: 2, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1043: 8, 1044: 8, 1056: 8, 1059: 1, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1176: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1181: 8, 1182: 8, 1183: 8, 1189: 8, 1190: 8, 1191: 8, 1192: 8, 1196: 8, 1197: 8, 1198: 8, 1199: 8, 1206: 8, 1207: 8, 1212: 8, 1227: 8, 1235: 8, 1237: 8, 1264: 8, 1279: 8, 1408: 8, 1409: 8, 1410: 8, 1552: 8, 1553: 8, 1554: 8, 1556: 8, 1557: 8, 1561: 8, 1562: 8, 1568: 8, 1569: 8, 1570: 8, 1571: 8, 1572: 8, 1584: 8, 1589: 8, 1592: 8, 1593: 8, 1595: 8, 1599: 8, 1656: 8, 1728: 8, 1745: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 + }], + CAR.HIGHLANDERH: [{ + 36: 8, 37: 8, 170: 8, 180: 8, 296: 8, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 581: 5, 608: 8, 610: 5, 643: 7, 713: 8, 740: 5, 800: 8, 835: 8, 836: 8, 849: 4, 869: 7, 870: 7, 871: 2, 896: 8, 897: 8, 900: 6, 902: 6, 905: 8, 911: 8, 916: 3, 918: 7, 921: 8, 933: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 3, 955: 8, 956: 8, 979: 2, 998: 5, 999: 7, 1000: 8, 1001: 8, 1005: 2, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1043: 8, 1044: 8, 1056: 8, 1059: 1, 1112: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1176: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1181: 8, 1184: 8, 1185: 8, 1186: 8, 1189: 8, 1190: 8, 1191: 8, 1192: 8, 1196: 8, 1197: 8, 1198: 8, 1199: 8, 1206: 8, 1212: 8, 1227: 8, 1232: 8, 1235: 8, 1237: 8, 1264: 8, 1279: 8, 1552: 8, 1553: 8, 1554: 8, 1556: 8, 1557: 8, 1561: 8, 1562: 8, 1568: 8, 1569: 8, 1570: 8, 1571: 8, 1572: 8, 1584: 8, 1589: 8, 1592: 8, 1593: 8, 1595: 8, 1599: 8, 1656: 8, 1728: 8, 1745: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8 + }], +} + +STEER_THRESHOLD = 100 + +DBC = { + CAR.RAV4H: dbc_dict('toyota_rav4_hybrid_2017_pt_generated', 'toyota_prius_2017_adas'), + CAR.RAV4: dbc_dict('toyota_rav4_2017_pt_generated', 'toyota_prius_2017_adas'), + CAR.PRIUS: dbc_dict('toyota_prius_2017_pt_generated', 'toyota_prius_2017_adas'), + CAR.COROLLA: dbc_dict('toyota_corolla_2017_pt_generated', 'toyota_prius_2017_adas'), + CAR.LEXUS_RXH: dbc_dict('lexus_rx_hybrid_2017_pt_generated', 'toyota_prius_2017_adas'), + CAR.CHR: dbc_dict('toyota_chr_2018_pt_generated', 'toyota_prius_2017_adas'), + CAR.CHRH: dbc_dict('toyota_chr_hybrid_2018_pt_generated', 'toyota_prius_2017_adas'), + CAR.CAMRY: dbc_dict('toyota_chr_2018_pt_generated', 'toyota_prius_2017_adas'), + CAR.CAMRYH: dbc_dict('toyota_camry_hybrid_2018_pt_generated', 'toyota_prius_2017_adas'), + CAR.HIGHLANDER: dbc_dict('toyota_highlander_2017_pt_generated', 'toyota_prius_2017_adas'), + CAR.HIGHLANDERH: dbc_dict('toyota_highlander_hybrid_2018_pt_generated', 'toyota_prius_2017_adas'), +} + +NO_DSU_CAR = [CAR.CHR, CAR.CHRH, CAR.CAMRY, CAR.CAMRYH] diff --git a/selfdrive/common/buffering.c b/selfdrive/common/buffering.c new file mode 100644 index 00000000000000..9cbb1b86e0df11 --- /dev/null +++ b/selfdrive/common/buffering.c @@ -0,0 +1,438 @@ +#include +#include +#include +#include +#include +#include + +#include "common/efd.h" + +#include "buffering.h" + +void tbuffer_init(TBuffer *tb, int num_bufs, const char* name) { + assert(num_bufs >= 3); + + memset(tb, 0, sizeof(TBuffer)); + tb->reading = (bool*)calloc(num_bufs, sizeof(bool)); + assert(tb->reading); + tb->pending_idx = -1; + tb->num_bufs = num_bufs; + tb->name = name; + + pthread_mutex_init(&tb->lock, NULL); + pthread_cond_init(&tb->cv, NULL); + tb->efd = efd_init(); + assert(tb->efd >= 0); +} + +void tbuffer_init2(TBuffer *tb, int num_bufs, const char* name, + void (*release_cb)(void* c, int idx), + void* cb_cookie) { + + tbuffer_init(tb, num_bufs, name); + + tb->release_cb = release_cb; + tb->cb_cookie = cb_cookie; +} + +int tbuffer_efd(TBuffer *tb) { + return tb->efd; +} + +int tbuffer_select(TBuffer *tb) { + pthread_mutex_lock(&tb->lock); + + int i; + for (i=0; inum_bufs; i++) { + if (!tb->reading[i] && i != tb->pending_idx) { + break; + } + } + assert(i < tb->num_bufs); + + pthread_mutex_unlock(&tb->lock); + return i; +} + +void tbuffer_dispatch(TBuffer *tb, int idx) { + pthread_mutex_lock(&tb->lock); + + if (tb->pending_idx != -1) { + //printf("tbuffer (%s) dropped!\n", tb->name ? tb->name : "?"); + if (tb->release_cb) { + tb->release_cb(tb->cb_cookie, tb->pending_idx); + } + tb->pending_idx = -1; + } + + tb->pending_idx = idx; + + efd_write(tb->efd); + pthread_cond_signal(&tb->cv); + + pthread_mutex_unlock(&tb->lock); +} + +int tbuffer_acquire(TBuffer *tb) { + pthread_mutex_lock(&tb->lock); + + if (tb->stopped) { + pthread_mutex_unlock(&tb->lock); + return -1; + } + + while (tb->pending_idx == -1) { + pthread_cond_wait(&tb->cv, &tb->lock); + + if (tb->stopped) { + pthread_mutex_unlock(&tb->lock); + return -1; + } + } + + efd_clear(tb->efd); + + int ret = tb->pending_idx; + assert(ret < tb->num_bufs); + + tb->reading[ret] = true; + tb->pending_idx = -1; + + pthread_mutex_unlock(&tb->lock); + + return ret; +} + +static void tbuffer_release_locked(TBuffer *tb, int idx) { + assert(idx < tb->num_bufs); + if (!tb->reading[idx]) { + printf("!! releasing tbuffer we aren't reading %d\n", idx); + } + + if (tb->release_cb) { + tb->release_cb(tb->cb_cookie, idx); + } + + tb->reading[idx] = false; +} + +void tbuffer_release(TBuffer *tb, int idx) { + pthread_mutex_lock(&tb->lock); + tbuffer_release_locked(tb, idx); + pthread_mutex_unlock(&tb->lock); +} + +void tbuffer_release_all(TBuffer *tb) { + pthread_mutex_lock(&tb->lock); + for (int i=0; inum_bufs; i++) { + if (tb->reading[i]) { + tbuffer_release_locked(tb, i); + } + } + pthread_mutex_unlock(&tb->lock); +} + +void tbuffer_stop(TBuffer *tb) { + pthread_mutex_lock(&tb->lock); + tb->stopped = true; + efd_write(tb->efd); + pthread_cond_signal(&tb->cv); + pthread_mutex_unlock(&tb->lock); +} + + + + + + + + + + + +void pool_init(Pool *s, int num_bufs) { + assert(num_bufs > 3); + + memset(s, 0, sizeof(*s)); + s->num_bufs = num_bufs; + + s->refcnt = (int*)calloc(num_bufs, sizeof(int)); + s->ts = (int*)calloc(num_bufs, sizeof(int)); + + s->counter = 1; + + pthread_mutex_init(&s->lock, NULL); +} + +void pool_init2(Pool *s, int num_bufs, + void (*release_cb)(void* c, int idx), void* cb_cookie) { + + pool_init(s, num_bufs); + s->cb_cookie = cb_cookie; + s->release_cb = release_cb; + +} + + +void pool_acquire(Pool *s, int idx) { + pthread_mutex_lock(&s->lock); + + assert(idx >= 0 && idx < s->num_bufs); + + s->refcnt[idx]++; + + pthread_mutex_unlock(&s->lock); +} + +static void pool_release_locked(Pool *s, int idx) { + // printf("release %d refcnt %d\n", idx, s->refcnt[idx]); + + assert(idx >= 0 && idx < s->num_bufs); + + assert(s->refcnt[idx] > 0); + s->refcnt[idx]--; + + // printf("release %d -> %d, %p\n", idx, s->refcnt[idx], s->release_cb); + if (s->refcnt[idx] == 0 && s->release_cb) { + // printf("call %p\b", s->release_cb); + s->release_cb(s->cb_cookie, idx); + } +} + +void pool_release(Pool *s, int idx) { + pthread_mutex_lock(&s->lock); + pool_release_locked(s, idx); + pthread_mutex_unlock(&s->lock); +} + +TBuffer* pool_get_tbuffer(Pool *s) { + pthread_mutex_lock(&s->lock); + + assert(s->num_tbufs < POOL_MAX_TBUFS); + TBuffer* tbuf = &s->tbufs[s->num_tbufs]; + s->num_tbufs++; + tbuffer_init2(tbuf, s->num_bufs, + "pool", (void (*)(void *, int))pool_release, s); + + bool stopped = s->stopped; + pthread_mutex_unlock(&s->lock); + + // Stop the tbuffer so we can return a valid object. + // We must stop here because the pool_stop may have already been called, + // in which case tbuffer_stop may never be called again. + if (stopped) { + tbuffer_stop(tbuf); + } + return tbuf; +} + +PoolQueue* pool_get_queue(Pool *s) { + pthread_mutex_lock(&s->lock); + + int i; + for (i = 0; i < POOL_MAX_QUEUES; i++) { + if (!s->queues[i].inited) { + break; + } + } + assert(i < POOL_MAX_QUEUES); + + PoolQueue *c = &s->queues[i]; + memset(c, 0, sizeof(*c)); + + c->pool = s; + c->inited = true; + + c->efd = efd_init(); + assert(c->efd >= 0); + + c->num_bufs = s->num_bufs; + c->num = c->num_bufs+1; + c->idx = (int*)malloc(sizeof(int)*c->num); + memset(c->idx, -1, sizeof(int)*c->num); + + pthread_mutex_init(&c->lock, NULL); + pthread_cond_init(&c->cv, NULL); + + pthread_mutex_unlock(&s->lock); + return c; +} + +void pool_release_queue(PoolQueue *c) { + Pool *s = c->pool; + + pthread_mutex_lock(&s->lock); + pthread_mutex_lock(&c->lock); + + for (int i=0; inum; i++) { + if (c->idx[i] != -1) { + pool_release_locked(s, c->idx[i]); + } + } + + close(c->efd); + free(c->idx); + + c->inited = false; + + pthread_mutex_unlock(&c->lock); + + pthread_mutex_destroy(&c->lock); + pthread_cond_destroy(&c->cv); + + pthread_mutex_unlock(&s->lock); +} + +int pool_select(Pool *s) { + pthread_mutex_lock(&s->lock); + + int i; + for (i=0; inum_bufs; i++) { + if (s->refcnt[i] == 0) { + break; + } + } + + if (i >= s->num_bufs) { + // overwrite the oldest + // still being using in a queue or tbuffer :/ + + int min_k = 0; + int min_ts = s->ts[0]; + for (int k=1; knum_bufs; k++) { + if (s->ts[k] < min_ts) { + min_ts = s->ts[k]; + min_k = k; + } + } + i = min_k; + printf("pool is full! evicted %d\n", min_k); + + // might be really bad if the user is doing pointery stuff + if (s->release_cb) { + s->release_cb(s->cb_cookie, min_k); + } + } + + s->refcnt[i]++; + + s->ts[i] = s->counter; + s->counter++; + + pthread_mutex_unlock(&s->lock); + + return i; +} + +void pool_push(Pool *s, int idx) { + pthread_mutex_lock(&s->lock); + + // printf("push %d head %d tail %d\n", idx, s->head, s->tail); + + assert(idx >= 0 && idx < s->num_bufs); + + s->ts[idx] = s->counter; + s->counter++; + + assert(s->refcnt[idx] > 0); + s->refcnt[idx]--; //push is a implcit release + + int num_tbufs = s->num_tbufs; + s->refcnt[idx] += num_tbufs; + + // dispatch pool queues + for (int i=0; iqueues[i]; + if (!c->inited) continue; + + pthread_mutex_lock(&c->lock); + if (((c->head+1) % c->num) == c->tail) { + // queue is full. skip for now + pthread_mutex_unlock(&c->lock); + continue; + } + + s->refcnt[idx]++; + + c->idx[c->head] = idx; + c->head = (c->head+1) % c->num; + assert(c->head != c->tail); + pthread_mutex_unlock(&c->lock); + + efd_write(c->efd); + pthread_cond_signal(&c->cv); + } + + pthread_mutex_unlock(&s->lock); + + for (int i=0; itbufs[i], idx); + } +} + +int poolq_pop(PoolQueue *c) { + pthread_mutex_lock(&c->lock); + + if (c->stopped) { + pthread_mutex_unlock(&c->lock); + return -1; + } + + while (c->head == c->tail) { + pthread_cond_wait(&c->cv, &c->lock); + + if (c->stopped) { + pthread_mutex_unlock(&c->lock); + return -1; + } + } + + // printf("pop head %d tail %d\n", s->head, s->tail); + + assert(c->head != c->tail); + + int r = c->idx[c->tail]; + c->idx[c->tail] = -1; + c->tail = (c->tail+1) % c->num; + + // queue event is level triggered + if (c->head == c->tail) { + efd_clear(c->efd); + } + + // printf("pop %d head %d tail %d\n", r, s->head, s->tail); + + assert(r >= 0 && r < c->num_bufs); + + pthread_mutex_unlock(&c->lock); + + return r; +} + +int poolq_efd(PoolQueue *c) { + return c->efd; +} + +void poolq_release(PoolQueue *c, int idx) { + pool_release(c->pool, idx); +} + +void pool_stop(Pool *s) { + for (int i=0; inum_tbufs; i++) { + tbuffer_stop(&s->tbufs[i]); + } + + pthread_mutex_lock(&s->lock); + s->stopped = true; + for (int i=0; iqueues[i]; + if (!c->inited) continue; + + pthread_mutex_lock(&c->lock); + c->stopped = true; + pthread_mutex_unlock(&c->lock); + efd_write(c->efd); + pthread_cond_signal(&c->cv); + } + pthread_mutex_unlock(&s->lock); +} diff --git a/selfdrive/common/buffering.h b/selfdrive/common/buffering.h new file mode 100644 index 00000000000000..fda4c644928423 --- /dev/null +++ b/selfdrive/common/buffering.h @@ -0,0 +1,123 @@ +#ifndef BUFFERING_H +#define BUFFERING_H + +#include +#include + +#ifdef __cplusplus +extern "C" { +#endif + +// Tripple buffering helper + +typedef struct TBuffer { + pthread_mutex_t lock; + pthread_cond_t cv; + int efd; + + bool* reading; + int pending_idx; + + int num_bufs; + const char* name; + + void (*release_cb)(void* c, int idx); + void *cb_cookie; + + bool stopped; +} TBuffer; + +// num_bufs must be at least the number of buffers that can be acquired simultaniously plus two +void tbuffer_init(TBuffer *tb, int num_bufs, const char* name); + +void tbuffer_init2(TBuffer *tb, int num_bufs, const char* name, + void (*release_cb)(void* c, int idx), + void* cb_cookie); + +// returns an eventfd that signals if a buffer is ready and tbuffer_acquire shouldn't to block. +// useful to polling on multiple tbuffers. +int tbuffer_efd(TBuffer *tb); + +// Chooses a buffer that's not reading or pending +int tbuffer_select(TBuffer *tb); + +// Called when the writer is done with their buffer +// - Wakes up the reader if it's waiting +// - releases the pending buffer if the reader's too slow +void tbuffer_dispatch(TBuffer *tb, int idx); + +// Called when the reader wants a new buffer, will return -1 when stopped +int tbuffer_acquire(TBuffer *tb); + +// Called when the reader is done with their buffer +void tbuffer_release(TBuffer *tb, int idx); + +void tbuffer_release_all(TBuffer *tb); + +void tbuffer_stop(TBuffer *tb); + + + + +// pool: buffer pool + queue thing... + +#define POOL_MAX_TBUFS 8 +#define POOL_MAX_QUEUES 8 + +typedef struct Pool Pool; + +typedef struct PoolQueue { + pthread_mutex_t lock; + pthread_cond_t cv; + Pool* pool; + bool inited; + bool stopped; + int efd; + int num_bufs; + int num; + int head, tail; + int* idx; +} PoolQueue; + +int poolq_pop(PoolQueue *s); +int poolq_efd(PoolQueue *s); +void poolq_release(PoolQueue *c, int idx); + +typedef struct Pool { + pthread_mutex_t lock; + bool stopped; + int num_bufs; + int counter; + + int* ts; + int* refcnt; + + void (*release_cb)(void* c, int idx); + void *cb_cookie; + + int num_tbufs; + TBuffer tbufs[POOL_MAX_TBUFS]; + PoolQueue queues[POOL_MAX_QUEUES]; +} Pool; + +void pool_init(Pool *s, int num_bufs); +void pool_init2(Pool *s, int num_bufs, + void (*release_cb)(void* c, int idx), void* cb_cookie); + +TBuffer* pool_get_tbuffer(Pool *s); + +PoolQueue* pool_get_queue(Pool *s); +void pool_release_queue(PoolQueue *q); + +int pool_select(Pool *s); +void pool_push(Pool *s, int idx); +void pool_acquire(Pool *s, int idx); +void pool_release(Pool *s, int idx); +void pool_stop(Pool *s); + + +#ifdef __cplusplus +} // extern "C" +#endif + +#endif diff --git a/selfdrive/common/cereal.mk b/selfdrive/common/cereal.mk new file mode 100644 index 00000000000000..46f23be551a9d6 --- /dev/null +++ b/selfdrive/common/cereal.mk @@ -0,0 +1,49 @@ +UNAME_M ?= $(shell uname -m) +UNAME_S ?= $(shell uname -s) + + + +CEREAL_CFLAGS = -I$(PHONELIBS)/capnp-c/include + +ifeq ($(OPTEST),1) + +CEREAL_LIBS = -lcapnp -lkj + +else ifeq ($(UNAME_S),Darwin) + +CEREAL_CXXFLAGS = -I$(PHONELIBS)/capnp-cpp/mac/include +CEREAL_LIBS = $(PHONELIBS)/capnp-cpp/mac/lib/libcapnp.a \ + $(PHONELIBS)/capnp-cpp/mac/lib/libkj.a \ + $(PHONELIBS)/capnp-c/mac/lib/libcapnp_c.a + +else ifeq ($(UNAME_M),x86_64) + +CEREAL_CXXFLAGS = -I$(PHONELIBS)/capnp-cpp/include +ifeq ($(CEREAL_LIBS),) + CEREAL_LIBS = -L$(PHONELIBS)/capnp-cpp/x64/lib/ \ + -L$(PHONELIBS)/capnp-c/x64/lib/ \ + -l:libcapnp.a -l:libkj.a -l:libcapnp_c.a +endif + +else + +CEREAL_CXXFLAGS = -I$(PHONELIBS)/capnp-cpp/include +ifeq ($(CEREAL_LIBS),) + CEREAL_LIBS = -L$(PHONELIBS)/capnp-cpp/aarch64/lib/ \ + -L$(PHONELIBS)/capnp-c/aarch64/lib/ \ + -l:libcapn.a -l:libcapnp.a -l:libkj.a +endif + +endif + +CEREAL_OBJS = ../../cereal/gen/c/log.capnp.o ../../cereal/gen/c/car.capnp.o + +log.capnp.o: ../../cereal/gen/cpp/log.capnp.c++ + @echo "[ CXX ] $@" + $(CXX) $(CXXFLAGS) $(CEREAL_CXXFLAGS) \ + -c -o '$@' '$<' + +car.capnp.o: ../../cereal/gen/cpp/car.capnp.c++ + @echo "[ CXX ] $@" + $(CXX) $(CXXFLAGS) $(CEREAL_CXXFLAGS) \ + -c -o '$@' '$<' diff --git a/selfdrive/common/efd.c b/selfdrive/common/efd.c new file mode 100644 index 00000000000000..78a7c098949b56 --- /dev/null +++ b/selfdrive/common/efd.c @@ -0,0 +1,56 @@ +#include +#include + +#ifdef __linux__ +#include +#else +#include +#include +#define EVENT_IDENT 42 +#endif + +#include "efd.h" + + +int efd_init() { +#ifdef __linux__ + return eventfd(0, EFD_CLOEXEC); +#else + int fd = kqueue(); + assert(fd >= 0); + + struct kevent kev; + EV_SET(&kev, EVENT_IDENT, EVFILT_USER, EV_ADD | EV_CLEAR, 0, 0, NULL); + + struct timespec timeout = {0, 0}; + int err = kevent(fd, &kev, 1, NULL, 0, &timeout); + assert(err != -1); + + return fd; +#endif +} + +void efd_write(int fd) { +#ifdef __linux__ + eventfd_write(fd, 1); +#else + struct kevent kev; + EV_SET(&kev, EVENT_IDENT, EVFILT_USER, 0, NOTE_TRIGGER, 0, NULL); + + struct timespec timeout = {0, 0}; + int err = kevent(fd, &kev, 1, NULL, 0, &timeout); + assert(err != -1); +#endif +} + +void efd_clear(int fd) { +#ifdef __linux__ + eventfd_t efd_cnt; + eventfd_read(fd, &efd_cnt); +#else + struct kevent kev; + struct timespec timeout = {0, 0}; + int nfds = kevent(fd, NULL, 0, &kev, 1, &timeout); + assert(nfds != -1); +#endif +} diff --git a/selfdrive/common/efd.h b/selfdrive/common/efd.h new file mode 100644 index 00000000000000..056482ffa51f3e --- /dev/null +++ b/selfdrive/common/efd.h @@ -0,0 +1,17 @@ +#ifndef EFD_H +#define EFD_H + +#ifdef __cplusplus +extern "C" { +#endif + +// event fd: a semaphore that can be poll()'d +int efd_init(); +void efd_write(int fd); +void efd_clear(int fd); + +#ifdef __cplusplus +} +#endif + +#endif \ No newline at end of file diff --git a/selfdrive/common/framebuffer.cc b/selfdrive/common/framebuffer.cc new file mode 100644 index 00000000000000..757c2a1ead46f0 --- /dev/null +++ b/selfdrive/common/framebuffer.cc @@ -0,0 +1,141 @@ + +#include +#include +#include + +#include + +#include +#include +#include + + +#include +#include + +#define BACKLIGHT_CONTROL "/sys/class/leds/lcd-backlight/brightness" +#define BACKLIGHT_LEVEL "205" + +using namespace android; + +struct FramebufferState { + sp session; + sp dtoken; + DisplayInfo dinfo; + sp control; + + sp s; + EGLDisplay display; + + EGLint egl_major, egl_minor; + EGLConfig config; + EGLSurface surface; + EGLContext context; +}; + +extern "C" void framebuffer_set_power(FramebufferState *s, int mode) { + SurfaceComposerClient::setDisplayPowerMode(s->dtoken, mode); +} + +extern "C" FramebufferState* framebuffer_init( + const char* name, int32_t layer, int alpha, + EGLDisplay *out_display, EGLSurface *out_surface, + int *out_w, int *out_h) { + status_t status; + int success; + + FramebufferState *s = new FramebufferState; + + s->session = new SurfaceComposerClient(); + assert(s->session != NULL); + + s->dtoken = SurfaceComposerClient::getBuiltInDisplay( + ISurfaceComposer::eDisplayIdMain); + assert(s->dtoken != NULL); + + status = SurfaceComposerClient::getDisplayInfo(s->dtoken, &s->dinfo); + assert(status == 0); + + //int orientation = 3; // rotate framebuffer 270 degrees + int orientation = 1; // rotate framebuffer 90 degrees + if(orientation == 1 || orientation == 3) { + int temp = s->dinfo.h; + s->dinfo.h = s->dinfo.w; + s->dinfo.w = temp; + } + + printf("dinfo %dx%d\n", s->dinfo.w, s->dinfo.h); + + Rect destRect(s->dinfo.w, s->dinfo.h); + s->session->setDisplayProjection(s->dtoken, orientation, destRect, destRect); + + s->control = s->session->createSurface(String8(name), + s->dinfo.w, s->dinfo.h, PIXEL_FORMAT_RGBX_8888); + assert(s->control != NULL); + + SurfaceComposerClient::openGlobalTransaction(); + status = s->control->setLayer(layer); + SurfaceComposerClient::closeGlobalTransaction(); + assert(status == 0); + + s->s = s->control->getSurface(); + assert(s->s != NULL); + + // init opengl and egl + const EGLint attribs[] = { + EGL_RED_SIZE, 8, + EGL_GREEN_SIZE, 8, + EGL_BLUE_SIZE, 8, + EGL_ALPHA_SIZE, alpha ? 8 : 0, + EGL_DEPTH_SIZE, 0, + EGL_STENCIL_SIZE, 8, + EGL_RENDERABLE_TYPE, EGL_OPENGL_ES3_BIT_KHR, + EGL_NONE, + }; + + s->display = eglGetDisplay(EGL_DEFAULT_DISPLAY); + assert(s->display != EGL_NO_DISPLAY); + + success = eglInitialize(s->display, &s->egl_major, &s->egl_minor); + assert(success); + + printf("egl version %d.%d\n", s->egl_major, s->egl_minor); + + EGLint num_configs; + success = eglChooseConfig(s->display, attribs, &s->config, 1, &num_configs); + assert(success); + + s->surface = eglCreateWindowSurface(s->display, s->config, s->s.get(), NULL); + assert(s->surface != EGL_NO_SURFACE); + + const EGLint context_attribs[] = { + EGL_CONTEXT_CLIENT_VERSION, 3, + EGL_NONE, + }; + s->context = eglCreateContext(s->display, s->config, NULL, context_attribs); + assert(s->context != EGL_NO_CONTEXT); + + EGLint w, h; + eglQuerySurface(s->display, s->surface, EGL_WIDTH, &w); + eglQuerySurface(s->display, s->surface, EGL_HEIGHT, &h); + printf("egl w %d h %d\n", w, h); + + success = eglMakeCurrent(s->display, s->surface, s->surface, s->context); + assert(success); + + printf("gl version %s\n", glGetString(GL_VERSION)); + + + // set brightness + int brightness_fd = open(BACKLIGHT_CONTROL, O_RDWR); + const char brightness_level[] = BACKLIGHT_LEVEL; + write(brightness_fd, brightness_level, strlen(brightness_level)); + + + if (out_display) *out_display = s->display; + if (out_surface) *out_surface = s->surface; + if (out_w) *out_w = w; + if (out_h) *out_h = h; + + return s; +} diff --git a/selfdrive/common/framebuffer.h b/selfdrive/common/framebuffer.h new file mode 100644 index 00000000000000..6091eebce50780 --- /dev/null +++ b/selfdrive/common/framebuffer.h @@ -0,0 +1,50 @@ +#ifndef FRAMEBUFFER_H +#define FRAMEBUFFER_H + +#include + +#ifdef __cplusplus +extern "C" { +#endif + +typedef struct FramebufferState FramebufferState; + +FramebufferState* framebuffer_init( + const char* name, int32_t layer, int alpha, + EGLDisplay *out_display, EGLSurface *out_surface, + int *out_w, int *out_h); + +void framebuffer_set_power(FramebufferState *s, int mode); + +/* Display power modes */ +enum { + /* The display is turned off (blanked). */ + HWC_POWER_MODE_OFF = 0, + /* The display is turned on and configured in a low power state + * that is suitable for presenting ambient information to the user, + * possibly with lower fidelity than normal but greater efficiency. */ + HWC_POWER_MODE_DOZE = 1, + /* The display is turned on normally. */ + HWC_POWER_MODE_NORMAL = 2, + /* The display is configured as in HWC_POWER_MODE_DOZE but may + * stop applying frame buffer updates from the graphics subsystem. + * This power mode is effectively a hint from the doze dream to + * tell the hardware that it is done drawing to the display for the + * time being and that the display should remain on in a low power + * state and continue showing its current contents indefinitely + * until the mode changes. + * + * This mode may also be used as a signal to enable hardware-based doze + * functionality. In this case, the doze dream is effectively + * indicating that the hardware is free to take over the display + * and manage it autonomously to implement low power always-on display + * functionality. */ + HWC_POWER_MODE_DOZE_SUSPEND = 3, +}; + + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/selfdrive/common/glutil.c b/selfdrive/common/glutil.c new file mode 100644 index 00000000000000..d118dd8af68451 --- /dev/null +++ b/selfdrive/common/glutil.c @@ -0,0 +1,71 @@ +#include +#include + +#include + +#include "glutil.h" + +GLuint load_shader(GLenum shaderType, const char *src) { + GLint status = 0, len = 0; + GLuint shader; + + if (!(shader = glCreateShader(shaderType))) + return 0; + + glShaderSource(shader, 1, &src, NULL); + glCompileShader(shader); + glGetShaderiv(shader, GL_COMPILE_STATUS, &status); + + if (status) + return shader; + + glGetShaderiv(shader, GL_INFO_LOG_LENGTH, &len); + if (len) { + char *msg = (char*)malloc(len); + if (msg) { + glGetShaderInfoLog(shader, len, NULL, msg); + msg[len-1] = 0; + fprintf(stderr, "error compiling shader:\n%s\n", msg); + free(msg); + } + } + glDeleteShader(shader); + return 0; +} + +GLuint load_program(const char *vert_src, const char *frag_src) { + GLuint vert, frag, prog; + GLint status = 0, len = 0; + + if (!(vert = load_shader(GL_VERTEX_SHADER, vert_src))) + return 0; + if (!(frag = load_shader(GL_FRAGMENT_SHADER, frag_src))) + goto fail_frag; + if (!(prog = glCreateProgram())) + goto fail_prog; + + glAttachShader(prog, vert); + glAttachShader(prog, frag); + glLinkProgram(prog); + + glGetProgramiv(prog, GL_LINK_STATUS, &status); + if (status) + return prog; + + glGetProgramiv(prog, GL_INFO_LOG_LENGTH, &len); + if (len) { + char *buf = (char*) malloc(len); + if (buf) { + glGetProgramInfoLog(prog, len, NULL, buf); + buf[len-1] = 0; + fprintf(stderr, "error linking program:\n%s\n", buf); + free(buf); + } + } + glDeleteProgram(prog); +fail_prog: + glDeleteShader(frag); +fail_frag: + glDeleteShader(vert); + return 0; +} diff --git a/selfdrive/common/glutil.h b/selfdrive/common/glutil.h new file mode 100644 index 00000000000000..68d6cfa630d3c1 --- /dev/null +++ b/selfdrive/common/glutil.h @@ -0,0 +1,8 @@ +#ifndef COMMON_GLUTIL_H +#define COMMON_GLUTIL_H + +#include +GLuint load_shader(GLenum shaderType, const char *src); +GLuint load_program(const char *vert_src, const char *frag_src); + +#endif diff --git a/selfdrive/common/ipc.c b/selfdrive/common/ipc.c new file mode 100644 index 00000000000000..8d391074786815 --- /dev/null +++ b/selfdrive/common/ipc.c @@ -0,0 +1,119 @@ +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "ipc.h" + +int ipc_connect(const char* socket_path) { + int err; + + int sock = socket(AF_UNIX, SOCK_SEQPACKET, 0); + assert(sock >= 0); + struct sockaddr_un addr = { + .sun_family = AF_UNIX, + }; + snprintf(addr.sun_path, sizeof(addr.sun_path), "%s", socket_path); + err = connect(sock, (struct sockaddr*)&addr, sizeof(addr)); + if (err != 0) { + close(sock); + return -1; + } + + return sock; +} + +int ipc_bind(const char* socket_path) { + int err; + + unlink(socket_path); + + int sock = socket(AF_UNIX, SOCK_SEQPACKET, 0); + struct sockaddr_un addr = { + .sun_family = AF_UNIX, + }; + snprintf(addr.sun_path, sizeof(addr.sun_path), "%s", socket_path); + err = bind(sock, (struct sockaddr *)&addr, sizeof(addr)); + assert(err == 0); + + err = listen(sock, 3); + assert(err == 0); + + return sock; +} + + +int ipc_sendrecv_with_fds(bool send, int fd, void *buf, size_t buf_size, int* fds, int num_fds, + int *out_num_fds) { + int err; + + char control_buf[CMSG_SPACE(sizeof(int) * num_fds)]; + memset(control_buf, 0, CMSG_SPACE(sizeof(int) * num_fds)); + + struct iovec iov = { + .iov_base = buf, + .iov_len = buf_size, + }; + struct msghdr msg = { + .msg_iov = &iov, + .msg_iovlen = 1, + }; + + if (num_fds > 0) { + assert(fds); + + msg.msg_control = control_buf; + msg.msg_controllen = CMSG_SPACE(sizeof(int) * num_fds); + } + + if (send) { + if (num_fds) { + struct cmsghdr *cmsg = CMSG_FIRSTHDR(&msg); + assert(cmsg); + cmsg->cmsg_level = SOL_SOCKET; + cmsg->cmsg_type = SCM_RIGHTS; + cmsg->cmsg_len = CMSG_LEN(sizeof(int) * num_fds); + memcpy(CMSG_DATA(cmsg), fds, sizeof(int) * num_fds); + // printf("send clen %d -> %d\n", num_fds, cmsg->cmsg_len); + } + return sendmsg(fd, &msg, 0); + } else { + int r = recvmsg(fd, &msg, 0); + if (r < 0) return r; + + int recv_fds = 0; + if (msg.msg_controllen > 0) { + struct cmsghdr *cmsg = CMSG_FIRSTHDR(&msg); + assert(cmsg); + assert(cmsg->cmsg_level == SOL_SOCKET && cmsg->cmsg_type == SCM_RIGHTS); + recv_fds = (cmsg->cmsg_len - CMSG_LEN(0)); + assert(recv_fds > 0 && (recv_fds % sizeof(int)) == 0); + recv_fds /= sizeof(int); + // printf("recv clen %d -> %d\n", cmsg->cmsg_len, recv_fds); + // assert(cmsg->cmsg_len == CMSG_LEN(sizeof(int) * num_fds)); + + assert(fds && recv_fds <= num_fds); + memcpy(fds, CMSG_DATA(cmsg), sizeof(int) * recv_fds); + } + + if (msg.msg_flags) { + for (int i=0; i + +#ifdef __cplusplus +extern "C" { +#endif + +int ipc_connect(const char* socket_path); +int ipc_bind(const char* socket_path); +int ipc_sendrecv_with_fds(bool send, int fd, void *buf, size_t buf_size, int* fds, int num_fds, + int *out_num_fds); + +#ifdef __cplusplus +} // extern "C" +#endif + +#endif \ No newline at end of file diff --git a/selfdrive/common/mat.h b/selfdrive/common/mat.h new file mode 100644 index 00000000000000..1c20eae17fd034 --- /dev/null +++ b/selfdrive/common/mat.h @@ -0,0 +1,88 @@ +#ifndef COMMON_MAT_H +#define COMMON_MAT_H + +typedef struct vec3 { + float v[3]; +} vec3; + +typedef struct vec4 { + float v[4]; +} vec4; + +typedef struct mat3 { + float v[3*3]; +} mat3; + +typedef struct mat4 { + float v[4*4]; +} mat4; + +static inline mat3 matmul3(const mat3 a, const mat3 b) { + mat3 ret = {{0.0}}; + for (int r=0; r<3; r++) { + for (int c=0; c<3; c++) { + float v = 0.0; + for (int k=0; k<3; k++) { + v += a.v[r*3+k] * b.v[k*3+c]; + } + ret.v[r*3+c] = v; + } + } + return ret; +} + +static inline vec3 matvecmul3(const mat3 a, const vec3 b) { + vec3 ret = {{0.0}}; + for (int r=0; r<3; r++) { + for (int c=0; c<3; c++) { + ret.v[r] += a.v[r*3+c] * b.v[c]; + } + } + return ret; +} + +static inline mat4 matmul(const mat4 a, const mat4 b) { + mat4 ret = {{0.0}}; + for (int r=0; r<4; r++) { + for (int c=0; c<4; c++) { + float v = 0.0; + for (int k=0; k<4; k++) { + v += a.v[r*4+k] * b.v[k*4+c]; + } + ret.v[r*4+c] = v; + } + } + return ret; +} + +static inline vec4 matvecmul(const mat4 a, const vec4 b) { + vec4 ret = {{0.0}}; + for (int r=0; r<4; r++) { + for (int c=0; c<4; c++) { + ret.v[r] += a.v[r*4+c] * b.v[c]; + } + } + return ret; +} + +// scales the input and output space of a transformation matrix +// that assumes pixel-center origin. +static inline mat3 transform_scale_buffer(const mat3 in, float s) { + // in_pt = ( transform(out_pt/s + 0.5) - 0.5) * s + + mat3 transform_out = {{ + 1.0f/s, 0.0f, 0.5f, + 0.0f, 1.0f/s, 0.5f, + 0.0f, 0.0f, 1.0f, + }}; + + mat3 transform_in = {{ + s, 0.0f, -0.5f*s, + 0.0f, s, -0.5f*s, + 0.0f, 0.0f, 1.0f, + }}; + + return matmul3(transform_in, matmul3(in, transform_out)); +} + +#endif diff --git a/selfdrive/common/modeldata.h b/selfdrive/common/modeldata.h new file mode 100644 index 00000000000000..c3f48930f29e36 --- /dev/null +++ b/selfdrive/common/modeldata.h @@ -0,0 +1,25 @@ +#ifndef MODELDATA_H +#define MODELDATA_H + +#define MODEL_PATH_DISTANCE 50 + +typedef struct PathData { + float points[MODEL_PATH_DISTANCE]; + float prob; + float std; +} PathData; + +typedef struct LeadData { + float dist; + float prob; + float std; +} LeadData; + +typedef struct ModelData { + PathData path; + PathData left_lane; + PathData right_lane; + LeadData lead; +} ModelData; + +#endif diff --git a/selfdrive/common/params.cc b/selfdrive/common/params.cc new file mode 100644 index 00000000000000..7bbcf5fad11c60 --- /dev/null +++ b/selfdrive/common/params.cc @@ -0,0 +1,196 @@ +#include "common/params.h" + +#ifndef _GNU_SOURCE +#define _GNU_SOURCE +#endif // _GNU_SOURCE + +#include +#include +#include +#include +#include + +#include +#include + +#include "common/util.h" +#include "common/utilpp.h" + +namespace { + +template +T* null_coalesce(T* a, T* b) { + return a != NULL ? a : b; +} + +static const char* default_params_path = null_coalesce( + const_cast(getenv("PARAMS_PATH")), "/data/params"); + +} // namespace + +int write_db_value(const char* params_path, const char* key, const char* value, + size_t value_size) { + int lock_fd = -1; + int tmp_fd = -1; + int result; + char tmp_path[1024]; + char path[1024]; + ssize_t bytes_written; + + if (params_path == NULL) { + params_path = default_params_path; + } + + // Write value to temp. + result = + snprintf(tmp_path, sizeof(tmp_path), "%s/.tmp_value_XXXXXX", params_path); + if (result < 0) { + goto cleanup; + } + + tmp_fd = mkstemp(tmp_path); + bytes_written = write(tmp_fd, value, value_size); + if (bytes_written != value_size) { + result = -20; + goto cleanup; + } + + result = snprintf(path, sizeof(path), "%s/.lock", params_path); + if (result < 0) { + goto cleanup; + } + lock_fd = open(path, 0); + + result = snprintf(path, sizeof(path), "%s/d/%s", params_path, key); + if (result < 0) { + goto cleanup; + } + + // Take lock. + result = flock(lock_fd, LOCK_EX); + if (result < 0) { + goto cleanup; + } + + // fsync to force persist the changes. + result = fsync(tmp_fd); + if (result < 0) { + goto cleanup; + } + + // Move temp into place. + result = rename(tmp_path, path); + +cleanup: + // Release lock. + if (lock_fd >= 0) { + close(lock_fd); + } + if (tmp_fd >= 0) { + if (result < 0) { + remove(tmp_path); + } + close(tmp_fd); + } + return result; +} + +int read_db_value(const char* params_path, const char* key, char** value, + size_t* value_sz) { + int lock_fd = -1; + int result; + char path[1024]; + + if (params_path == NULL) { + params_path = default_params_path; + } + + result = snprintf(path, sizeof(path), "%s/.lock", params_path); + if (result < 0) { + goto cleanup; + } + lock_fd = open(path, 0); + + result = snprintf(path, sizeof(path), "%s/d/%s", params_path, key); + if (result < 0) { + goto cleanup; + } + + // Take lock. + result = flock(lock_fd, LOCK_EX); + if (result < 0) { + goto cleanup; + } + + // Read value. + // TODO(mgraczyk): If there is a lot of contention, we can release the lock + // after opening the file, before reading. + *value = static_cast(read_file(path, value_sz)); + if (*value == NULL) { + result = -22; + goto cleanup; + } + + // Remove one for null byte. + if (value_sz != NULL) { + *value_sz -= 1; + } + result = 0; + +cleanup: + // Release lock. + if (lock_fd >= 0) { + close(lock_fd); + } + return result; +} + +void read_db_value_blocking(const char* params_path, const char* key, + char** value, size_t* value_sz) { + while (1) { + const int result = read_db_value(params_path, key, value, value_sz); + if (result == 0) { + return; + } else { + // Sleep for 0.1 seconds. + usleep(100000); + } + } +} + +int read_db_all(const char* params_path, std::map *params) { + int err = 0; + + if (params_path == NULL) { + params_path = default_params_path; + } + + std::string lock_path = util::string_format("%s/.lock", params_path); + + int lock_fd = open(lock_path.c_str(), 0); + if (lock_fd < 0) return -1; + + err = flock(lock_fd, LOCK_EX); + if (err < 0) return err; + + std::string key_path = util::string_format("%s/d", params_path); + DIR *d = opendir(key_path.c_str()); + if (!d) { + close(lock_fd); + return -1; + } + + struct dirent *de = NULL; + while ((de = readdir(d))) { + if (!isalnum(de->d_name[0])) continue; + std::string key = std::string(de->d_name); + std::string value = util::read_file(util::string_format("%s/%s", key_path.c_str(), key.c_str())); + + (*params)[key] = value; + } + + closedir(d); + + close(lock_fd); + return 0; +} diff --git a/selfdrive/common/params.h b/selfdrive/common/params.h new file mode 100644 index 00000000000000..299dcccd0a412d --- /dev/null +++ b/selfdrive/common/params.h @@ -0,0 +1,41 @@ +#ifndef _SELFDRIVE_COMMON_PARAMS_H_ +#define _SELFDRIVE_COMMON_PARAMS_H_ + +#include + +#ifdef __cplusplus +extern "C" { +#endif + +int write_db_value(const char* params_path, const char* key, const char* value, + size_t value_size); + +// Reads a value from the params database. +// Inputs: +// params_path: The path of the database, or NULL to use the default. +// key: The key to read. +// value: A pointer where a newly allocated string containing the db value will +// be written. +// value_sz: A pointer where the size of value will be written. Does not +// include the NULL terminator. +// +// Returns: Negative on failure, otherwise 0. +int read_db_value(const char* params_path, const char* key, char** value, + size_t* value_sz); + +// Reads a value from the params database, blocking until successful. +// Inputs are the same as read_db_value. +void read_db_value_blocking(const char* params_path, const char* key, + char** value, size_t* value_sz); + +#ifdef __cplusplus +} // extern "C" +#endif + +#ifdef __cplusplus +#include +#include +int read_db_all(const char* params_path, std::map *params); +#endif + +#endif // _SELFDRIVE_COMMON_PARAMS_H_ diff --git a/selfdrive/common/swaglog.c b/selfdrive/common/swaglog.c new file mode 100644 index 00000000000000..70cba78167532b --- /dev/null +++ b/selfdrive/common/swaglog.c @@ -0,0 +1,119 @@ +#define _GNU_SOURCE + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "common/timing.h" +#include "common/version.h" + +#include "swaglog.h" + +typedef struct LogState { + pthread_mutex_t lock; + bool inited; + JsonNode *ctx_j; + void *zctx; + void *sock; + int print_level; +} LogState; + +static LogState s = { + .lock = PTHREAD_MUTEX_INITIALIZER, +}; + +static void cloudlog_bind_locked(const char* k, const char* v) { + json_append_member(s.ctx_j, k, json_mkstring(v)); +} + +static void cloudlog_init() { + if (s.inited) return; + s.ctx_j = json_mkobject(); + s.zctx = zmq_ctx_new(); + s.sock = zmq_socket(s.zctx, ZMQ_PUSH); + zmq_connect(s.sock, "ipc:///tmp/logmessage"); + + s.print_level = CLOUDLOG_WARNING; + const char* print_level = getenv("LOGPRINT"); + if (print_level) { + if (strcmp(print_level, "debug") == 0) { + s.print_level = CLOUDLOG_DEBUG; + } else if (strcmp(print_level, "info") == 0) { + s.print_level = CLOUDLOG_INFO; + } else if (strcmp(print_level, "warning") == 0) { + s.print_level = CLOUDLOG_WARNING; + } + } + + // openpilot bindings + char* dongle_id = getenv("DONGLE_ID"); + if (dongle_id) { + cloudlog_bind_locked("dongle_id", dongle_id); + } + cloudlog_bind_locked("version", COMMA_VERSION); + bool dirty = !getenv("CLEAN"); + json_append_member(s.ctx_j, "dirty", json_mkbool(dirty)); + + s.inited = true; +} + +void cloudlog_e(int levelnum, const char* filename, int lineno, const char* func, + const char* fmt, ...) { + pthread_mutex_lock(&s.lock); + cloudlog_init(); + + char* msg_buf = NULL; + va_list args; + va_start(args, fmt); + vasprintf(&msg_buf, fmt, args); + va_end(args); + + if (!msg_buf) { + pthread_mutex_unlock(&s.lock); + return; + } + + if (levelnum >= s.print_level) { + printf("%s: %s\n", filename, msg_buf); + } + + JsonNode *log_j = json_mkobject(); + assert(log_j); + + json_append_member(log_j, "msg", json_mkstring(msg_buf)); + json_append_member(log_j, "ctx", s.ctx_j); + json_append_member(log_j, "levelnum", json_mknumber(levelnum)); + json_append_member(log_j, "filename", json_mkstring(filename)); + json_append_member(log_j, "lineno", json_mknumber(lineno)); + json_append_member(log_j, "funcname", json_mkstring(func)); + json_append_member(log_j, "created", json_mknumber(seconds_since_epoch())); + + char* log_s = json_encode(log_j); + assert(log_s); + + json_remove_from_parent(s.ctx_j); + + json_delete(log_j); + free(msg_buf); + + char levelnum_c = levelnum; + zmq_send(s.sock, &levelnum_c, 1, ZMQ_NOBLOCK | ZMQ_SNDMORE); + zmq_send(s.sock, log_s, strlen(log_s), ZMQ_NOBLOCK); + free(log_s); + + pthread_mutex_unlock(&s.lock); +} + +void cloudlog_bind(const char* k, const char* v) { + pthread_mutex_lock(&s.lock); + cloudlog_init(); + cloudlog_bind_locked(k, v); + pthread_mutex_unlock(&s.lock); +} diff --git a/selfdrive/common/swaglog.h b/selfdrive/common/swaglog.h new file mode 100644 index 00000000000000..33e77f618aef59 --- /dev/null +++ b/selfdrive/common/swaglog.h @@ -0,0 +1,68 @@ +#ifndef SWAGLOG_H +#define SWAGLOG_H + +#include "common/timing.h" + +#define CLOUDLOG_DEBUG 10 +#define CLOUDLOG_INFO 20 +#define CLOUDLOG_WARNING 30 +#define CLOUDLOG_ERROR 40 +#define CLOUDLOG_CRITICAL 50 + +#ifdef __cplusplus +extern "C" { +#endif + +void cloudlog_e(int levelnum, const char* filename, int lineno, const char* func, + const char* fmt, ...) /*__attribute__ ((format (printf, 6, 7)))*/; + +void cloudlog_bind(const char* k, const char* v); + +#ifdef __cplusplus +} +#endif + +#define cloudlog(lvl, fmt, ...) cloudlog_e(lvl, __FILE__, __LINE__, \ + __func__, \ + fmt, ## __VA_ARGS__) + +#define cloudlog_rl(burst, millis, lvl, fmt, ...) \ +{ \ + static uint64_t __begin = 0; \ + static int __printed = 0; \ + static int __missed = 0; \ + \ + int __burst = (burst); \ + int __millis = (millis); \ + uint64_t __ts = nanos_since_boot(); \ + \ + if (!__begin) __begin = __ts; \ + \ + if (__begin + __millis*1000000ULL < __ts) { \ + if (__missed) { \ + cloudlog(CLOUDLOG_WARNING, "cloudlog: %d messages supressed", __missed); \ + } \ + __begin = 0; \ + __printed = 0; \ + __missed = 0; \ + } \ + \ + if (__printed < __burst) { \ + cloudlog(lvl, fmt, ## __VA_ARGS__); \ + __printed++; \ + } else { \ + __missed++; \ + } \ +} + +#define LOGD(fmt, ...) cloudlog(CLOUDLOG_DEBUG, fmt, ## __VA_ARGS__) +#define LOG(fmt, ...) cloudlog(CLOUDLOG_INFO, fmt, ## __VA_ARGS__) +#define LOGW(fmt, ...) cloudlog(CLOUDLOG_WARNING, fmt, ## __VA_ARGS__) +#define LOGE(fmt, ...) cloudlog(CLOUDLOG_ERROR, fmt, ## __VA_ARGS__) + +#define LOGD_100(fmt, ...) cloudlog_rl(2, 100, CLOUDLOG_DEBUG, fmt, ## __VA_ARGS__) +#define LOG_100(fmt, ...) cloudlog_rl(2, 100, CLOUDLOG_INFO, fmt, ## __VA_ARGS__) +#define LOGW_100(fmt, ...) cloudlog_rl(2, 100, CLOUDLOG_WARNING, fmt, ## __VA_ARGS__) +#define LOGE_100(fmt, ...) cloudlog_rl(2, 100, CLOUDLOG_ERROR, fmt, ## __VA_ARGS__) + +#endif diff --git a/selfdrive/common/timing.h b/selfdrive/common/timing.h new file mode 100644 index 00000000000000..1a30ad6e1e4d7b --- /dev/null +++ b/selfdrive/common/timing.h @@ -0,0 +1,54 @@ +#ifndef COMMON_TIMING_H +#define COMMON_TIMING_H + +#include +#include + +#ifdef __APPLE__ +#define CLOCK_BOOTTIME CLOCK_MONOTONIC +#endif + +static inline uint64_t nanos_since_boot() { + struct timespec t; + clock_gettime(CLOCK_BOOTTIME, &t); + return t.tv_sec * 1000000000ULL + t.tv_nsec; +} + +static inline double millis_since_boot() { + struct timespec t; + clock_gettime(CLOCK_BOOTTIME, &t); + return t.tv_sec * 1000.0 + t.tv_nsec * 1e-6; +} + +static inline double seconds_since_boot() { + struct timespec t; + clock_gettime(CLOCK_BOOTTIME, &t); + return (double)t.tv_sec + t.tv_nsec * 1e-9;; +} + +static inline uint64_t nanos_since_epoch() { + struct timespec t; + clock_gettime(CLOCK_REALTIME, &t); + return t.tv_sec * 1000000000ULL + t.tv_nsec; +} + +static inline double seconds_since_epoch() { + struct timespec t; + clock_gettime(CLOCK_REALTIME, &t); + return (double)t.tv_sec + t.tv_nsec * 1e-9; +} + +// you probably should use nanos_since_boot instead +static inline uint64_t nanos_monotonic() { + struct timespec t; + clock_gettime(CLOCK_MONOTONIC, &t); + return t.tv_sec * 1000000000ULL + t.tv_nsec; +} + +static inline uint64_t nanos_monotonic_raw() { + struct timespec t; + clock_gettime(CLOCK_MONOTONIC_RAW, &t); + return t.tv_sec * 1000000000ULL + t.tv_nsec; +} + +#endif diff --git a/selfdrive/common/touch.c b/selfdrive/common/touch.c new file mode 100644 index 00000000000000..f21fac8f07afd5 --- /dev/null +++ b/selfdrive/common/touch.c @@ -0,0 +1,92 @@ +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "touch.h" + +static int find_dev() { + int err; + + int ret = -1; + + DIR *dir = opendir("/dev/input"); + assert(dir); + struct dirent* de = NULL; + while ((de = readdir(dir))) { + if (strncmp(de->d_name, "event", 5)) continue; + + int fd = openat(dirfd(dir), de->d_name, O_RDONLY); + assert(fd >= 0); + + unsigned char ev_bits[KEY_MAX / 8 + 1]; + err = ioctl(fd, EVIOCGBIT(EV_ABS, sizeof(ev_bits)), ev_bits); + assert(err >= 0); + + const int x_key = ABS_MT_POSITION_X / 8; + const int y_key = ABS_MT_POSITION_Y / 8; + if ((ev_bits[x_key] & (ABS_MT_POSITION_X - x_key)) && + (ev_bits[y_key] & (ABS_MT_POSITION_Y - y_key))) { + ret = fd; + break; + } + close(fd); + } + closedir(dir); + + return ret; +} + +void touch_init(TouchState *s) { + s->fd = find_dev(); + assert(s->fd >= 0); +} + +int touch_poll(TouchState *s, int* out_x, int* out_y, int timeout) { + assert(out_x && out_y); + bool up = false; + while (true) { + struct pollfd polls[] = {{ + .fd = s->fd, + .events = POLLIN, + }}; + int err = poll(polls, 1, timeout); + if (err < 0) { + return -1; + } + if (!(polls[0].revents & POLLIN)) { + break; + } + + struct input_event event; + err = read(polls[0].fd, &event, sizeof(event)); + if (err < sizeof(event)) { + return -1; + } + + switch (event.type) { + case EV_ABS: + if (event.code == ABS_MT_POSITION_X) { + s->last_x = event.value; + } else if (event.code == ABS_MT_POSITION_Y) { + s->last_y = event.value; + } + up = true; + break; + default: + break; + } + } + if (up) { + // adjust for flippening + *out_x = s->last_y; + *out_y = 1080 - s->last_x; + } + return up; +} + diff --git a/selfdrive/common/touch.h b/selfdrive/common/touch.h new file mode 100644 index 00000000000000..c2bb6dfeced30c --- /dev/null +++ b/selfdrive/common/touch.h @@ -0,0 +1,20 @@ +#ifndef TOUCH_H +#define TOUCH_H + +#ifdef __cplusplus +extern "C" { +#endif + +typedef struct TouchState { + int fd; + int last_x, last_y; +} TouchState; + +void touch_init(TouchState *s); +int touch_poll(TouchState *s, int *out_x, int *out_y, int timeout); + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/selfdrive/common/util.c b/selfdrive/common/util.c new file mode 100644 index 00000000000000..6f8f0a9a6cf186 --- /dev/null +++ b/selfdrive/common/util.c @@ -0,0 +1,58 @@ +#include +#include +#include +#include +#include + +#ifdef __linux__ +#include +#include +#include +#endif + +void* read_file(const char* path, size_t* out_len) { + FILE* f = fopen(path, "r"); + if (!f) { + return NULL; + } + fseek(f, 0, SEEK_END); + long f_len = ftell(f); + rewind(f); + + char* buf = calloc(f_len + 1, 1); + assert(buf); + + size_t num_read = fread(buf, f_len, 1, f); + fclose(f); + + if (num_read != 1) { + return NULL; + } + + if (out_len) { + *out_len = f_len + 1; + } + + return buf; +} + +void set_thread_name(const char* name) { +#ifdef __linux__ + // pthread_setname_np is dumb (fails instead of truncates) + prctl(PR_SET_NAME, (unsigned long)name, 0, 0, 0); +#endif +} + +int set_realtime_priority(int level) { +#ifdef __linux__ + + long tid = syscall(SYS_gettid); + + // should match python using chrt + struct sched_param sa; + memset(&sa, 0, sizeof(sa)); + sa.sched_priority = level; + return sched_setscheduler(tid, SCHED_FIFO, &sa); +#endif +} + diff --git a/selfdrive/common/util.h b/selfdrive/common/util.h new file mode 100644 index 00000000000000..65dde16e24082e --- /dev/null +++ b/selfdrive/common/util.h @@ -0,0 +1,47 @@ +#ifndef COMMON_UTIL_H +#define COMMON_UTIL_H + + +#ifndef __cplusplus + +#define min(a,b) \ + ({ __typeof__ (a) _a = (a); \ + __typeof__ (b) _b = (b); \ + _a < _b ? _a : _b; }) + +#define max(a,b) \ + ({ __typeof__ (a) _a = (a); \ + __typeof__ (b) _b = (b); \ + _a > _b ? _a : _b; }) + +#endif + +#define clamp(a,b,c) \ + ({ __typeof__ (a) _a = (a); \ + __typeof__ (b) _b = (b); \ + __typeof__ (c) _c = (c); \ + _a < _b ? _b : (_a > _c ? _c : _a); }) + +#define ARRAYSIZE(x) (sizeof(x)/sizeof(x[0])) + +#define ALIGN(x, align) (((x) + (align)-1) & ~((align)-1)) + +#ifdef __cplusplus +extern "C" { +#endif + +// Reads a file into a newly allocated buffer. +// +// Returns NULL on failure, otherwise the NULL-terminated file contents. +// The result must be freed by the caller. +void* read_file(const char* path, size_t* out_len); + +void set_thread_name(const char* name); + +int set_realtime_priority(int level); + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/selfdrive/common/utilpp.h b/selfdrive/common/utilpp.h new file mode 100644 index 00000000000000..e374c5c256f772 --- /dev/null +++ b/selfdrive/common/utilpp.h @@ -0,0 +1,66 @@ +#ifndef UTILPP_H +#define UTILPP_H + +#include +#include + +#include +#include +#include +#include + +namespace util { + +inline bool starts_with(std::string s, std::string prefix) { + return s.compare(0, prefix.size(), prefix) == 0; +} + +template +inline std::string string_format( const std::string& format, Args ... args ) { + size_t size = snprintf( nullptr, 0, format.c_str(), args ... ) + 1; + std::unique_ptr buf( new char[ size ] ); + snprintf( buf.get(), size, format.c_str(), args ... ); + return std::string( buf.get(), buf.get() + size - 1 ); +} + +inline std::string read_file(std::string fn) { + std::ifstream t(fn); + std::stringstream buffer; + buffer << t.rdbuf(); + return buffer.str(); +} + +inline std::string tohex(const uint8_t* buf, size_t buf_size) { + std::unique_ptr hexbuf(new char[buf_size*2+1]); + for (int i=0; i +#else +#include +#endif + +#ifdef __cplusplus +extern "C" { +#endif + +typedef struct VisionBuf { + size_t len; + void* addr; + int handle; + int fd; + + cl_context ctx; + cl_device_id device_id; + cl_mem buf_cl; + cl_command_queue copy_q; +} VisionBuf; + +#define VISIONBUF_SYNC_FROM_DEVICE 0 +#define VISIONBUF_SYNC_TO_DEVICE 1 + +VisionBuf visionbuf_allocate(size_t len); +VisionBuf visionbuf_allocate_cl(size_t len, cl_device_id device_id, cl_context ctx, cl_mem *out_mem); +cl_mem visionbuf_to_cl(const VisionBuf* buf, cl_device_id device_id, cl_context ctx); +void visionbuf_sync(const VisionBuf* buf, int dir); +void visionbuf_free(const VisionBuf* buf); + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/selfdrive/common/visionbuf_ion.c b/selfdrive/common/visionbuf_ion.c new file mode 100644 index 00000000000000..724e75e9b0c0d5 --- /dev/null +++ b/selfdrive/common/visionbuf_ion.c @@ -0,0 +1,141 @@ +#include +#include +#include +#include +#include + +#include +#include + +#include + +#include "visionbuf.h" + + +// just hard-code these for convenience +// size_t device_page_size = 0; +// clGetDeviceInfo(device_id, CL_DEVICE_PAGE_SIZE_QCOM, +// sizeof(device_page_size), &device_page_size, +// NULL); + +// size_t padding_cl = 0; +// clGetDeviceInfo(device_id, CL_DEVICE_EXT_MEM_PADDING_IN_BYTES_QCOM, +// sizeof(padding_cl), &padding_cl, +// NULL); +#define DEVICE_PAGE_SIZE_CL 4096 +#define PADDING_CL 0 + +static int ion_fd = -1; +static void ion_init() { + if (ion_fd == -1) { + ion_fd = open("/dev/ion", O_RDWR | O_NONBLOCK); + } +} + +VisionBuf visionbuf_allocate(size_t len) { + int err; + + ion_init(); + + struct ion_allocation_data ion_alloc = {0}; + ion_alloc.len = len + PADDING_CL; + ion_alloc.align = 4096; + ion_alloc.heap_id_mask = 1 << ION_IOMMU_HEAP_ID; + ion_alloc.flags = ION_FLAG_CACHED; + + err = ioctl(ion_fd, ION_IOC_ALLOC, &ion_alloc); + assert(err == 0); + + struct ion_fd_data ion_fd_data = {0}; + ion_fd_data.handle = ion_alloc.handle; + err = ioctl(ion_fd, ION_IOC_SHARE, &ion_fd_data); + assert(err == 0); + + void *addr = mmap(NULL, ion_alloc.len, + PROT_READ | PROT_WRITE, + MAP_SHARED, ion_fd_data.fd, 0); + assert(addr != MAP_FAILED); + + memset(addr, 0, ion_alloc.len); + + return (VisionBuf){ + .len = len, + .addr = addr, + .handle = ion_alloc.handle, + .fd = ion_fd_data.fd, + }; +} + +VisionBuf visionbuf_allocate_cl(size_t len, cl_device_id device_id, cl_context ctx, cl_mem *out_mem) { + VisionBuf r = visionbuf_allocate(len); + *out_mem = visionbuf_to_cl(&r, device_id, ctx); + return r; +} + +cl_mem visionbuf_to_cl(const VisionBuf* buf, cl_device_id device_id, cl_context ctx) { + int err = 0; + + assert(((uintptr_t)buf->addr % DEVICE_PAGE_SIZE_CL) == 0); + + cl_mem_ion_host_ptr ion_cl = {0}; + ion_cl.ext_host_ptr.allocation_type = CL_MEM_ION_HOST_PTR_QCOM; + ion_cl.ext_host_ptr.host_cache_policy = CL_MEM_HOST_UNCACHED_QCOM; + ion_cl.ion_filedesc = buf->fd; + ion_cl.ion_hostptr = buf->addr; + + cl_mem mem = clCreateBuffer(ctx, + CL_MEM_USE_HOST_PTR | CL_MEM_EXT_HOST_PTR_QCOM, + buf->len, &ion_cl, &err); + assert(err == 0); + + return mem; +} + +void visionbuf_sync(const VisionBuf* buf, int dir) { + int err; + + struct ion_fd_data fd_data = {0}; + fd_data.fd = buf->fd; + err = ioctl(ion_fd, ION_IOC_IMPORT, &fd_data); + assert(err == 0); + + struct ion_flush_data flush_data = {0}; + flush_data.handle = fd_data.handle; + flush_data.vaddr = buf->addr; + flush_data.offset = 0; + flush_data.length = buf->len; + + // ION_IOC_INV_CACHES ~= DMA_FROM_DEVICE + // ION_IOC_CLEAN_CACHES ~= DMA_TO_DEVICE + // ION_IOC_CLEAN_INV_CACHES ~= DMA_BIDIRECTIONAL + + struct ion_custom_data custom_data = {0}; + + switch (dir) { + case VISIONBUF_SYNC_FROM_DEVICE: + custom_data.cmd = ION_IOC_INV_CACHES; + break; + case VISIONBUF_SYNC_TO_DEVICE: + custom_data.cmd = ION_IOC_CLEAN_CACHES; + break; + default: + assert(0); + } + + custom_data.arg = (unsigned long)&flush_data; + err = ioctl(ion_fd, ION_IOC_CUSTOM, &custom_data); + assert(err == 0); + + struct ion_handle_data handle_data = {0}; + handle_data.handle = fd_data.handle; + err = ioctl(ion_fd, ION_IOC_FREE, &handle_data); + assert(err == 0); +} + +void visionbuf_free(const VisionBuf* buf) { + struct ion_handle_data handle_data = { + .handle = buf->handle, + }; + int ret = ioctl(ion_fd, ION_IOC_FREE, &handle_data); + assert(ret == 0); +} diff --git a/selfdrive/common/visionimg.cc b/selfdrive/common/visionimg.cc new file mode 100644 index 00000000000000..8179166e1c7759 --- /dev/null +++ b/selfdrive/common/visionimg.cc @@ -0,0 +1,114 @@ +#include + +#ifdef QCOM +#include +#include +#include +#include + +#include +#define GL_GLEXT_PROTOTYPES +#include + +#include +#define EGL_EGLEXT_PROTOTYPES +#include + +#endif + +#include "common/util.h" +#include "common/visionbuf.h" + +#include "common/visionimg.h" + +#ifdef QCOM + +using namespace android; + +// from libadreno_utils.so +extern "C" void compute_aligned_width_and_height(int width, + int height, + int bpp, + int tile_mode, + int raster_mode, + int padding_threshold, + int *aligned_w, + int *aligned_h); +#endif + +void visionimg_compute_aligned_width_and_height(int width, int height, int *aligned_w, int *aligned_h) { +#ifdef QCOM + compute_aligned_width_and_height(ALIGN(width, 32), ALIGN(height, 32), 3, 0, 0, 512, aligned_w, aligned_h); +#else + *aligned_w = width; *aligned_h = height; +#endif +} + +VisionImg visionimg_alloc_rgb24(int width, int height, VisionBuf *out_buf) { + int aligned_w = 0, aligned_h = 0; + visionimg_compute_aligned_width_and_height(width, height, &aligned_w, &aligned_h); + + int stride = aligned_w * 3; + size_t size = aligned_w * aligned_h * 3; + + VisionBuf buf = visionbuf_allocate(size); + + *out_buf = buf; + + return (VisionImg){ + .fd = buf.fd, + .format = VISIONIMG_FORMAT_RGB24, + .width = width, + .height = height, + .stride = stride, + .size = size, + .bpp = 3, + }; +} + +#ifdef QCOM + +EGLClientBuffer visionimg_to_egl(const VisionImg *img) { + assert((img->size % img->stride) == 0); + assert((img->stride % img->bpp) == 0); + + int format = 0; + if (img->format == VISIONIMG_FORMAT_RGB24) { + format = HAL_PIXEL_FORMAT_RGB_888; + } else { + assert(false); + } + + private_handle_t* hnd = new private_handle_t(img->fd, img->size, + private_handle_t::PRIV_FLAGS_USES_ION|private_handle_t::PRIV_FLAGS_FRAMEBUFFER, + 0, format, + img->stride/img->bpp, img->size/img->stride, + img->width, img->height); + + GraphicBuffer* gb = new GraphicBuffer(img->width, img->height, (PixelFormat)format, + GraphicBuffer::USAGE_HW_TEXTURE, img->stride/img->bpp, hnd, false); + + return (EGLClientBuffer) gb->getNativeBuffer(); +} + +GLuint visionimg_to_gl(const VisionImg *img) { + + EGLClientBuffer buf = visionimg_to_egl(img); + + EGLDisplay display = eglGetDisplay(EGL_DEFAULT_DISPLAY); + assert(display != EGL_NO_DISPLAY); + + EGLint img_attrs[] = { EGL_IMAGE_PRESERVED_KHR, EGL_TRUE, EGL_NONE }; + EGLImageKHR image = eglCreateImageKHR(display, EGL_NO_CONTEXT, + EGL_NATIVE_BUFFER_ANDROID, buf, img_attrs); + assert(image != EGL_NO_IMAGE_KHR); + + GLuint tex = 0; + glGenTextures(1, &tex); + glBindTexture(GL_TEXTURE_2D, tex); + glEGLImageTargetTexture2DOES(GL_TEXTURE_2D, image); + + return tex; +} + +#endif diff --git a/selfdrive/common/visionimg.h b/selfdrive/common/visionimg.h new file mode 100644 index 00000000000000..9fabb6054f6dd3 --- /dev/null +++ b/selfdrive/common/visionimg.h @@ -0,0 +1,38 @@ +#ifndef VISIONIMG_H +#define VISIONIMG_H + +#ifdef QCOM +#include +#include +#include +#endif + +#include "common/visionbuf.h" + +#ifdef __cplusplus +extern "C" { +#endif + +#define VISIONIMG_FORMAT_RGB24 1 + +typedef struct VisionImg { + int fd; + int format; + int width, height, stride; + int bpp; + size_t size; +} VisionImg; + +void visionimg_compute_aligned_width_and_height(int width, int height, int *aligned_w, int *aligned_h); +VisionImg visionimg_alloc_rgb24(int width, int height, VisionBuf *out_buf); + +#ifdef QCOM +EGLClientBuffer visionimg_to_egl(const VisionImg *img); +GLuint visionimg_to_gl(const VisionImg *img); +#endif + +#ifdef __cplusplus +} // extern "C" +#endif + +#endif diff --git a/selfdrive/common/visionipc.c b/selfdrive/common/visionipc.c new file mode 100644 index 00000000000000..314f7d0a55c712 --- /dev/null +++ b/selfdrive/common/visionipc.c @@ -0,0 +1,191 @@ +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "ipc.h" + +#include "visionipc.h" + +typedef struct VisionPacketWire { + int type; + VisionPacketData d; +} VisionPacketWire; + +int vipc_connect() { + return ipc_connect(VIPC_SOCKET_PATH); +} + + +int vipc_recv(int fd, VisionPacket *out_p) { + VisionPacketWire p = {0}; + VisionPacket p2 = {0}; + int ret = ipc_sendrecv_with_fds(false, fd, &p, sizeof(p), (int*)p2.fds, VIPC_MAX_FDS, &p2.num_fds); + if (ret < 0) { + printf("vipc_recv err: %s\n", strerror(errno)); + } else { + p2.type = p.type; + p2.d = p.d; + *out_p = p2; + } + return ret; +} + +int vipc_send(int fd, const VisionPacket *p2) { + assert(p2->num_fds <= VIPC_MAX_FDS); + + VisionPacketWire p = { + .type = p2->type, + .d = p2->d, + }; + return ipc_sendrecv_with_fds(true, fd, (void*)&p, sizeof(p), (int*)p2->fds, p2->num_fds, NULL); +} + +void vipc_bufs_load(VIPCBuf *bufs, const VisionStreamBufs *stream_bufs, + int num_fds, const int* fds) { + for (int i=0; ibuf_len; + bufs[i].addr = mmap(NULL, bufs[i].len, + PROT_READ | PROT_WRITE, + MAP_SHARED, bufs[i].fd, 0); + // printf("b %d %zu -> %p\n", bufs[i].fd, bufs[i].len, bufs[i].addr); + assert(bufs[i].addr != MAP_FAILED); + } +} + + +int visionstream_init(VisionStream *s, VisionStreamType type, bool tbuffer, VisionStreamBufs *out_bufs_info) { + int err; + + memset(s, 0, sizeof(*s)); + + s->last_idx = -1; + + s->ipc_fd = vipc_connect(); + if (s->ipc_fd < 0) return -1; + + VisionPacket p = { + .type = VIPC_STREAM_SUBSCRIBE, + .d = { .stream_sub = { + .type = type, + .tbuffer = tbuffer, + }, }, + }; + err = vipc_send(s->ipc_fd, &p); + if (err < 0) { + close(s->ipc_fd); + return -1; + } + + VisionPacket rp; + err = vipc_recv(s->ipc_fd, &rp); + if (err <= 0) { + close(s->ipc_fd); + return -1; + } + assert(rp.type = VIPC_STREAM_BUFS); + assert(rp.d.stream_bufs.type == type); + + s->bufs_info = rp.d.stream_bufs; + + s->num_bufs = rp.num_fds; + s->bufs = calloc(s->num_bufs, sizeof(VIPCBuf)); + assert(s->bufs); + + vipc_bufs_load(s->bufs, &rp.d.stream_bufs, s->num_bufs, rp.fds); + + if (out_bufs_info) { + *out_bufs_info = s->bufs_info; + } + + return 0; +} + +void visionstream_release(VisionStream *s) { + int err; + if (s->last_idx >= 0) { + VisionPacket rep = { + .type = VIPC_STREAM_RELEASE, + .d = { .stream_rel = { + .type = s->last_type, + .idx = s->last_idx, + }} + }; + err = vipc_send(s->ipc_fd, &rep); + s->last_idx = -1; + } +} + +VIPCBuf* visionstream_get(VisionStream *s, VIPCBufExtra *out_extra) { + int err; + + VisionPacket rp; + err = vipc_recv(s->ipc_fd, &rp); + if (err <= 0) { + return NULL; + } + assert(rp.type == VIPC_STREAM_ACQUIRE); + + if (s->last_idx >= 0) { + VisionPacket rep = { + .type = VIPC_STREAM_RELEASE, + .d = { .stream_rel = { + .type = s->last_type, + .idx = s->last_idx, + }} + }; + err = vipc_send(s->ipc_fd, &rep); + if (err <= 0) { + return NULL; + } + } + + s->last_type = rp.d.stream_acq.type; + s->last_idx = rp.d.stream_acq.idx; + assert(s->last_idx < s->num_bufs); + + if (out_extra) { + *out_extra = rp.d.stream_acq.extra; + } + + return &s->bufs[s->last_idx]; +} + +void visionstream_destroy(VisionStream *s) { + int err; + + if (s->last_idx >= 0) { + VisionPacket rep = { + .type = VIPC_STREAM_RELEASE, + .d = { .stream_rel = { + .type = s->last_type, + .idx = s->last_idx, + }} + }; + err = vipc_send(s->ipc_fd, &rep); + s->last_idx = -1; + } + + for (int i=0; inum_bufs; i++) { + if (s->bufs[i].addr) { + munmap(s->bufs[i].addr, s->bufs[i].len); + s->bufs[i].addr = NULL; + close(s->bufs[i].fd); + } + } + if (s->bufs) free(s->bufs); + close(s->ipc_fd); +} diff --git a/selfdrive/common/visionipc.h b/selfdrive/common/visionipc.h new file mode 100644 index 00000000000000..4844a71b1d756b --- /dev/null +++ b/selfdrive/common/visionipc.h @@ -0,0 +1,113 @@ +#ifndef VISIONIPC_H +#define VISIONIPC_H + +#include +#include +#include + +#define VIPC_SOCKET_PATH "/tmp/vision_socket" +#define VIPC_MAX_FDS 64 + +#ifdef __cplusplus +extern "C" { +#endif + +typedef enum VisionIPCPacketType { + VIPC_INVALID = 0, + VIPC_STREAM_SUBSCRIBE, + VIPC_STREAM_BUFS, + VIPC_STREAM_ACQUIRE, + VIPC_STREAM_RELEASE, +} VisionIPCPacketType; + +typedef enum VisionStreamType { + VISION_STREAM_RGB_BACK, + VISION_STREAM_RGB_FRONT, + VISION_STREAM_YUV, + VISION_STREAM_YUV_FRONT, + VISION_STREAM_MAX, +} VisionStreamType; + +typedef struct VisionUIInfo { + int big_box_x, big_box_y; + int big_box_width, big_box_height; + int transformed_width, transformed_height; + + int front_box_x, front_box_y; + int front_box_width, front_box_height; +} VisionUIInfo; + +typedef struct VisionStreamBufs { + VisionStreamType type; + + int width, height, stride; + size_t buf_len; + + union { + VisionUIInfo ui_info; + } buf_info; +} VisionStreamBufs; + +typedef struct VIPCBufExtra { + // only for yuv + uint32_t frame_id; + uint64_t timestamp_eof; +} VIPCBufExtra; + +typedef union VisionPacketData { + struct { + VisionStreamType type; + bool tbuffer; + } stream_sub; + VisionStreamBufs stream_bufs; + struct { + VisionStreamType type; + int idx; + VIPCBufExtra extra; + } stream_acq; + struct { + VisionStreamType type; + int idx; + } stream_rel; +} VisionPacketData; + +typedef struct VisionPacket { + int type; + VisionPacketData d; + int num_fds; + int fds[VIPC_MAX_FDS]; +} VisionPacket; + +int vipc_connect(void); +int vipc_recv(int fd, VisionPacket *out_p); +int vipc_send(int fd, const VisionPacket *p); + +typedef struct VIPCBuf { + int fd; + size_t len; + void* addr; +} VIPCBuf; +void vipc_bufs_load(VIPCBuf *bufs, const VisionStreamBufs *stream_bufs, + int num_fds, const int* fds); + + + +typedef struct VisionStream { + int ipc_fd; + int last_idx; + int last_type; + int num_bufs; + VisionStreamBufs bufs_info; + VIPCBuf *bufs; +} VisionStream; + +int visionstream_init(VisionStream *s, VisionStreamType type, bool tbuffer, VisionStreamBufs *out_bufs_info); +void visionstream_release(VisionStream *s); +VIPCBuf* visionstream_get(VisionStream *s, VIPCBufExtra *out_extra); +void visionstream_destroy(VisionStream *s); + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/selfdrive/config.py b/selfdrive/config.py new file mode 100644 index 00000000000000..751a84e285f52c --- /dev/null +++ b/selfdrive/config.py @@ -0,0 +1,29 @@ +import numpy as np + +class Conversions: + #Speed + MPH_TO_KPH = 1.609344 + KPH_TO_MPH = 1. / MPH_TO_KPH + MS_TO_KPH = 3.6 + KPH_TO_MS = 1. / MS_TO_KPH + MS_TO_MPH = MS_TO_KPH * KPH_TO_MPH + MPH_TO_MS = MPH_TO_KPH * KPH_TO_MS + MS_TO_KNOTS = 1.9438 + KNOTS_TO_MS = 1. / MS_TO_KNOTS + #Angle + DEG_TO_RAD = np.pi/180. + RAD_TO_DEG = 1. / DEG_TO_RAD + #Mass + LB_TO_KG = 0.453592 + + +RADAR_TO_CENTER = 2.7 # RADAR is ~ 2.7m ahead from center of car + +class UIParams: + lidar_x, lidar_y, lidar_zoom = 384, 960, 6 + lidar_car_x, lidar_car_y = lidar_x/2., lidar_y/1.1 + car_hwidth = 1.7272/2 * lidar_zoom + car_front = 2.6924 * lidar_zoom + car_back = 1.8796 * lidar_zoom + car_color = 110 + diff --git a/selfdrive/controls/__init__.py b/selfdrive/controls/__init__.py new file mode 100644 index 00000000000000..e69de29bb2d1d6 diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py new file mode 100755 index 00000000000000..d5d057e04151b3 --- /dev/null +++ b/selfdrive/controls/controlsd.py @@ -0,0 +1,533 @@ +#!/usr/bin/env python +import gc +import zmq +import json +from cereal import car, log +from common.numpy_fast import clip +from common.realtime import sec_since_boot, set_realtime_priority, Ratekeeper +from common.profiler import Profiler +from common.params import Params +import selfdrive.messaging as messaging +from selfdrive.config import Conversions as CV +from selfdrive.services import service_list +from selfdrive.car.car_helpers import get_car +from selfdrive.controls.lib.planner import Planner +from selfdrive.controls.lib.drive_helpers import learn_angle_offset, \ + get_events, \ + create_event, \ + EventTypes as ET, \ + update_v_cruise, \ + initialize_v_cruise +from selfdrive.controls.lib.longcontrol import LongControl, STARTING_TARGET_SPEED +from selfdrive.controls.lib.latcontrol import LatControl +from selfdrive.controls.lib.alertmanager import AlertManager +from selfdrive.controls.lib.vehicle_model import VehicleModel +from selfdrive.controls.lib.driver_monitor import DriverStatus +from selfdrive.locationd.calibration_helpers import Calibration, Filter + +ThermalStatus = log.ThermalData.ThermalStatus +State = log.Live100Data.ControlState + + +def isActive(state): + """Check if the actuators are enabled""" + return state in [State.enabled, State.softDisabling] + + +def isEnabled(state): + """Check if openpilot is engaged""" + return (isActive(state) or state == State.preEnabled) + + +def data_sample(CI, CC, thermal, calibration, health, driver_monitor, gps_location, + poller, cal_status, cal_perc, overtemp, free_space, low_battery, + driver_status, geofence, state, mismatch_counter, params): + """Receive data from sockets and create events for battery, temperature and disk space""" + + # Update carstate from CAN and create events + CS = CI.update(CC) + events = list(CS.events) + enabled = isEnabled(state) + + # Receive from sockets + td = None + cal = None + hh = None + dm = None + gps = None + + for socket, event in poller.poll(0): + if socket is thermal: + td = messaging.recv_one(socket) + elif socket is calibration: + cal = messaging.recv_one(socket) + elif socket is health: + hh = messaging.recv_one(socket) + elif socket is driver_monitor: + dm = messaging.recv_one(socket) + elif socket is gps_location: + gps = messaging.recv_one(socket) + + if td is not None: + overtemp = td.thermal.thermalStatus >= ThermalStatus.red + free_space = td.thermal.freeSpace < 0.07 # under 7% of space free no enable allowed + low_battery = td.thermal.batteryPercent < 1 # at zero percent battery, OP should not be allowed + + # Create events for battery, temperature and disk space + if low_battery: + events.append(create_event('lowBattery', [ET.NO_ENTRY, ET.SOFT_DISABLE])) + if overtemp: + events.append(create_event('overheat', [ET.NO_ENTRY, ET.SOFT_DISABLE])) + if free_space: + events.append(create_event('outOfSpace', [ET.NO_ENTRY])) + + # Handle calibration + if cal is not None: + cal_status = cal.liveCalibration.calStatus + cal_perc = cal.liveCalibration.calPerc + + if cal_status != Calibration.CALIBRATED: + if cal_status == Calibration.UNCALIBRATED: + events.append(create_event('calibrationIncomplete', [ET.NO_ENTRY, ET.SOFT_DISABLE, ET.PERMANENT])) + else: + events.append(create_event('calibrationInvalid', [ET.NO_ENTRY, ET.SOFT_DISABLE])) + + # When the panda and controlsd do not agree on controls_allowed + # we want to disengage openpilot. However the status from the panda goes through + # another socket than the CAN messages, therefore one can arrive earlier than the other. + # Therefore we allow a mismatch for two samples, then we trigger the disengagement. + if not enabled: + mismatch_counter = 0 + + if hh is not None: + controls_allowed = hh.health.controlsAllowed + if not controls_allowed and enabled: + mismatch_counter += 1 + if mismatch_counter >= 2: + events.append(create_event('controlsMismatch', [ET.IMMEDIATE_DISABLE])) + + # Driver monitoring + if dm is not None: + driver_status.get_pose(dm.driverMonitoring, params) + + # Geofence + if geofence is not None and gps is not None: + geofence.update_geofence_status(gps.gpsLocationExternal, params) + if geofence is not None and not geofence.in_geofence: + events.append(create_event('geofence', [ET.NO_ENTRY, ET.WARNING])) + + return CS, events, cal_status, cal_perc, overtemp, free_space, low_battery, mismatch_counter + + +def calc_plan(CS, CP, VM, events, PL, LaC, LoC, v_cruise_kph, driver_status, geofence): + """Calculate a longitudinal plan using MPC""" + + # Slow down when based on driver monitoring or geofence + force_decel = driver_status.awareness < 0. or (geofence is not None and not geofence.in_geofence) + + # Update planner + plan_packet = PL.update(CS, CP, VM, LaC, LoC, v_cruise_kph, force_decel) + plan = plan_packet.plan + plan_ts = plan_packet.logMonoTime + events += list(plan.events) + + # Only allow engagement with brake pressed when stopped behind another stopped car + if CS.brakePressed and plan.vTargetFuture >= STARTING_TARGET_SPEED and not CP.radarOffCan and CS.vEgo < 0.3: + events.append(create_event('noTarget', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE])) + + return plan, plan_ts + + +def state_transition(CS, CP, state, events, soft_disable_timer, v_cruise_kph, AM): + """Compute conditional state transitions and execute actions on state transitions""" + enabled = isEnabled(state) + + v_cruise_kph_last = v_cruise_kph + + # if stock cruise is completely disabled, then we can use our own set speed logic + if not CP.enableCruise: + v_cruise_kph = update_v_cruise(v_cruise_kph, CS.buttonEvents, enabled) + elif CP.enableCruise and CS.cruiseState.enabled: + v_cruise_kph = CS.cruiseState.speed * CV.MS_TO_KPH + + # decrease the soft disable timer at every step, as it's reset on + # entrance in SOFT_DISABLING state + soft_disable_timer = max(0, soft_disable_timer - 1) + + # DISABLED + if state == State.disabled: + if get_events(events, [ET.ENABLE]): + if get_events(events, [ET.NO_ENTRY]): + for e in get_events(events, [ET.NO_ENTRY]): + AM.add(str(e) + "NoEntry", enabled) + + else: + if get_events(events, [ET.PRE_ENABLE]): + state = State.preEnabled + else: + state = State.enabled + AM.add("enable", enabled) + v_cruise_kph = initialize_v_cruise(CS.vEgo, CS.buttonEvents, v_cruise_kph_last) + + # ENABLED + elif state == State.enabled: + if get_events(events, [ET.USER_DISABLE]): + state = State.disabled + AM.add("disable", enabled) + + elif get_events(events, [ET.IMMEDIATE_DISABLE]): + state = State.disabled + for e in get_events(events, [ET.IMMEDIATE_DISABLE]): + AM.add(e, enabled) + + elif get_events(events, [ET.SOFT_DISABLE]): + state = State.softDisabling + soft_disable_timer = 300 # 3s + for e in get_events(events, [ET.SOFT_DISABLE]): + AM.add(e, enabled) + + # SOFT DISABLING + elif state == State.softDisabling: + if get_events(events, [ET.USER_DISABLE]): + state = State.disabled + AM.add("disable", enabled) + + elif get_events(events, [ET.IMMEDIATE_DISABLE]): + state = State.disabled + for e in get_events(events, [ET.IMMEDIATE_DISABLE]): + AM.add(e, enabled) + + elif not get_events(events, [ET.SOFT_DISABLE]): + # no more soft disabling condition, so go back to ENABLED + state = State.enabled + + elif get_events(events, [ET.SOFT_DISABLE]) and soft_disable_timer > 0: + for e in get_events(events, [ET.SOFT_DISABLE]): + AM.add(e, enabled) + + elif soft_disable_timer <= 0: + state = State.disabled + + # PRE ENABLING + elif state == State.preEnabled: + if get_events(events, [ET.USER_DISABLE]): + state = State.disabled + AM.add("disable", enabled) + + elif get_events(events, [ET.IMMEDIATE_DISABLE, ET.SOFT_DISABLE]): + state = State.disabled + for e in get_events(events, [ET.IMMEDIATE_DISABLE, ET.SOFT_DISABLE]): + AM.add(e, enabled) + + elif not get_events(events, [ET.PRE_ENABLE]): + state = State.enabled + + return state, soft_disable_timer, v_cruise_kph, v_cruise_kph_last + + +def state_control(plan, CS, CP, state, events, v_cruise_kph, v_cruise_kph_last, AM, rk, + driver_status, PL, LaC, LoC, VM, angle_offset, passive, is_metric, cal_perc): + """Given the state, this function returns an actuators packet""" + + actuators = car.CarControl.Actuators.new_message() + + enabled = isEnabled(state) + active = isActive(state) + + # check if user has interacted with the car + driver_engaged = len(CS.buttonEvents) > 0 or \ + v_cruise_kph != v_cruise_kph_last or \ + CS.steeringPressed + + # add eventual driver distracted events + events = driver_status.update(events, driver_engaged, isActive(state), CS.standstill) + + # send FCW alert if triggered by planner + if plan.fcw: + AM.add("fcw", enabled) + + # State specific actions + + if state in [State.preEnabled, State.disabled]: + LaC.reset() + LoC.reset(v_pid=CS.vEgo) + + elif state in [State.enabled, State.softDisabling]: + # parse warnings from car specific interface + for e in get_events(events, [ET.WARNING]): + extra_text = "" + if e == "belowSteerSpeed": + if is_metric: + extra_text = str(int(round(CP.minSteerSpeed * CV.MS_TO_KPH))) + " kph" + else: + extra_text = str(int(round(CP.minSteerSpeed * CV.MS_TO_MPH))) + " mph" + AM.add(e, enabled, extra_text_2=extra_text) + + # Run angle offset learner at 20 Hz + if rk.frame % 5 == 2 and plan.lateralValid: + angle_offset = learn_angle_offset(active, CS.vEgo, angle_offset, + PL.PP.c_poly, PL.PP.c_prob, CS.steeringAngle, + CS.steeringPressed) + + # Gas/Brake PID loop + actuators.gas, actuators.brake = LoC.update(active, CS.vEgo, CS.brakePressed, CS.standstill, CS.cruiseState.standstill, + v_cruise_kph, plan.vTarget, plan.vTargetFuture, plan.aTarget, + CP, PL.lead_1) + # Steering PID loop and lateral MPC + actuators.steer, actuators.steerAngle = LaC.update(active, CS.vEgo, CS.steeringAngle, CS.steeringRate, + CS.steeringPressed, plan.dPoly, angle_offset, CP, VM, PL) + + # Send a "steering required alert" if saturation count has reached the limit + if LaC.sat_flag and CP.steerLimitAlert and CS.lkMode and not CS.leftBlinker and not CS.rightBlinker: + AM.add("steerSaturated", enabled) + + # Parse permanent warnings to display constantly + for e in get_events(events, [ET.PERMANENT]): + extra_text_1, extra_text_2 = "", "" + if e == "calibrationIncomplete": + extra_text_1 = str(cal_perc) + "%" + if is_metric: + extra_text_2 = str(int(round(Filter.MIN_SPEED * CV.MS_TO_KPH))) + " kph" + else: + extra_text_2 = str(int(round(Filter.MIN_SPEED * CV.MS_TO_MPH))) + " mph" + AM.add(str(e) + "Permanent", enabled, extra_text_1=extra_text_1, extra_text_2=extra_text_2) + + AM.process_alerts(sec_since_boot()) + + return actuators, v_cruise_kph, driver_status, angle_offset + + +def data_send(perception_state, plan, plan_ts, CS, CI, CP, VM, state, events, actuators, v_cruise_kph, rk, carstate, + carcontrol, live100, livempc, AM, driver_status, + LaC, LoC, angle_offset, passive, start_time): + """Send actuators and hud commands to the car, send live100 and MPC logging""" + + CC = car.CarControl.new_message() + + if not passive: + CC.enabled = isEnabled(state) + CC.actuators = actuators + + CC.cruiseControl.override = True + CC.cruiseControl.cancel = not CP.enableCruise or (not isEnabled(state) and CS.cruiseState.enabled) + + # Some override values for Honda + brake_discount = (1.0 - clip(actuators.brake * 3., 0.0, 1.0)) # brake discount removes a sharp nonlinearity + CC.cruiseControl.speedOverride = float(max(0.0, (LoC.v_pid + CS.cruiseState.speedOffset) * brake_discount) if CP.enableCruise else 0.0) + CC.cruiseControl.accelOverride = CI.calc_accel_override(CS.aEgo, plan.aTarget, CS.vEgo, plan.vTarget) + + CC.hudControl.setSpeed = float(v_cruise_kph * CV.KPH_TO_MS) + CC.hudControl.speedVisible = isEnabled(state) + CC.hudControl.lanesVisible = isEnabled(state) + CC.hudControl.leadVisible = plan.hasLead + CC.hudControl.rightLaneVisible = plan.hasRightLane + CC.hudControl.leftLaneVisible = plan.hasLeftLane + CC.hudControl.visualAlert = AM.visual_alert + CC.hudControl.audibleAlert = AM.audible_alert + + # send car controls over can + CI.apply(CC, perception_state) + + # live100 + dat = messaging.new_message() + dat.init('live100') + dat.live100 = { + "alertText1": AM.alert_text_1, + "alertText2": AM.alert_text_2, + "alertSize": AM.alert_size, + "alertStatus": AM.alert_status, + "alertBlinkingRate": AM.alert_rate, + "alertType": AM.alert_type, + "alertSound": "", # no EON sounds yet + "awarenessStatus": max(driver_status.awareness, 0.0) if isEnabled(state) else 0.0, + "driverMonitoringOn": bool(driver_status.monitor_on), + "canMonoTimes": list(CS.canMonoTimes), + "planMonoTime": plan_ts, + "enabled": isEnabled(state), + "active": isActive(state), + "vEgo": CS.vEgo, + "vEgoRaw": CS.vEgoRaw, + "angleSteers": CS.steeringAngle, + "curvature": VM.calc_curvature(CS.steeringAngle * CV.DEG_TO_RAD, CS.vEgo), + "steerOverride": CS.steeringPressed, + "state": state, + "engageable": not bool(get_events(events, [ET.NO_ENTRY])), + "longControlState": LoC.long_control_state, + "vPid": float(LoC.v_pid), + "vCruise": float(v_cruise_kph), + "upAccelCmd": float(LoC.pid.p), + "uiAccelCmd": float(LoC.pid.i), + "ufAccelCmd": float(LoC.pid.f), + "angleSteersDes": float(LaC.angle_steers_des), + "upSteer": float(LaC.pid.p), + "uiSteer": float(LaC.pid.i), + "ufSteer": float(LaC.pid.f), + "vTargetLead": float(plan.vTarget), + "aTarget": float(plan.aTarget), + "jerkFactor": float(plan.jerkFactor), + "angleOffset": float(angle_offset), + "gpsPlannerActive": plan.gpsPlannerActive, + "vCurvature": plan.vCurvature, + "decelForTurn": plan.decelForTurn, + "cumLagMs": -rk.remaining * 1000., + "startMonoTime": start_time, + "mapValid": plan.mapValid, + } + live100.send(dat.to_bytes()) + + # carState + cs_send = messaging.new_message() + cs_send.init('carState') + cs_send.carState = CS + cs_send.carState.events = events + carstate.send(cs_send.to_bytes()) + + # carControl + cc_send = messaging.new_message() + cc_send.init('carControl') + cc_send.carControl = CC + carcontrol.send(cc_send.to_bytes()) + + # send MPC when updated (20 Hz) + if hasattr(LaC, 'mpc_updated') and LaC.mpc_updated: + dat = messaging.new_message() + dat.init('liveMpc') + dat.liveMpc.x = list(LaC.mpc_solution[0].x) + dat.liveMpc.y = list(LaC.mpc_solution[0].y) + dat.liveMpc.psi = list(LaC.mpc_solution[0].psi) + dat.liveMpc.delta = list(LaC.mpc_solution[0].delta) + dat.liveMpc.cost = LaC.mpc_solution[0].cost + livempc.send(dat.to_bytes()) + + return CC + + +def controlsd_thread(gctx=None, rate=100, default_bias=0.): + gc.disable() + + # start the loop + set_realtime_priority(3) + + context = zmq.Context() + params = Params() + + # Pub Sockets + live100 = messaging.pub_sock(context, service_list['live100'].port) + carstate = messaging.pub_sock(context, service_list['carState'].port) + carcontrol = messaging.pub_sock(context, service_list['carControl'].port) + livempc = messaging.pub_sock(context, service_list['liveMpc'].port) + + is_metric = params.get("IsMetric") == "1" + passive = params.get("Passive") != "0" + + # No sendcan if passive + if not passive: + sendcan = messaging.pub_sock(context, service_list['sendcan'].port) + else: + sendcan = None + + # Sub sockets + poller = zmq.Poller() + thermal = messaging.sub_sock(context, service_list['thermal'].port, conflate=True, poller=poller) + health = messaging.sub_sock(context, service_list['health'].port, conflate=True, poller=poller) + cal = messaging.sub_sock(context, service_list['liveCalibration'].port, conflate=True, poller=poller) + driver_monitor = messaging.sub_sock(context, service_list['driverMonitoring'].port, conflate=True, poller=poller) + gps_location = messaging.sub_sock(context, service_list['gpsLocationExternal'].port, conflate=True, poller=poller) + logcan = messaging.sub_sock(context, service_list['can'].port) + + CC = car.CarControl.new_message() + CI, CP = get_car(logcan, sendcan, 1.0 if passive else None) + + if CI is None: + raise Exception("unsupported car") + + # if stock camera is connected, then force passive behavior + if not CP.enableCamera: + passive = True + sendcan = None + + if passive: + CP.safetyModel = car.CarParams.SafetyModels.noOutput + + # Get FCW toggle from settings + fcw_enabled = params.get("IsFcwEnabled") == "1" + geofence = None + + PL = Planner(CP, fcw_enabled) + LoC = LongControl(CP, CI.compute_gb) + VM = VehicleModel(CP) + LaC = LatControl(CP) + AM = AlertManager() + driver_status = DriverStatus() + + if not passive: + AM.add("startup", False) + + # Write CarParams for radard and boardd safety mode + params.put("CarParams", CP.to_bytes()) + params.put("LongitudinalControl", "1" if CP.openpilotLongitudinalControl else "0") + + state = State.disabled + soft_disable_timer = 0 + v_cruise_kph = 255 + v_cruise_kph_last = 0 + overtemp = False + free_space = False + cal_status = Calibration.INVALID + cal_perc = 0 + mismatch_counter = 0 + low_battery = False + + rk = Ratekeeper(rate, print_delay_threshold=2. / 1000) + + # Read angle offset from previous drive, fallback to default + angle_offset = default_bias + calibration_params = params.get("CalibrationParams") + if calibration_params: + try: + calibration_params = json.loads(calibration_params) + angle_offset = calibration_params["angle_offset2"] + except (ValueError, KeyError): + pass + + prof = Profiler(False) # off by default + + while True: + start_time = int(sec_since_boot() * 1e9) + prof.checkpoint("Ratekeeper", ignore=True) + + # Sample data and compute car events + CS, events, cal_status, cal_perc, overtemp, free_space, low_battery, mismatch_counter = data_sample(CI, CC, thermal, cal, health, + driver_monitor, gps_location, poller, cal_status, cal_perc, overtemp, free_space, low_battery, driver_status, geofence, state, mismatch_counter, params) + prof.checkpoint("Sample") + + # Define longitudinal plan (MPC) + plan, plan_ts = calc_plan(CS, CP, VM, events, PL, LaC, LoC, v_cruise_kph, driver_status, geofence) + prof.checkpoint("Plan") + + if not passive: + # update control state + state, soft_disable_timer, v_cruise_kph, v_cruise_kph_last = \ + state_transition(CS, CP, state, events, soft_disable_timer, v_cruise_kph, AM) + prof.checkpoint("State transition") + + # Compute actuators (runs PID loops and lateral MPC) + actuators, v_cruise_kph, driver_status, angle_offset = state_control(plan, CS, CP, state, events, v_cruise_kph, + v_cruise_kph_last, AM, rk, driver_status, PL, LaC, LoC, VM, angle_offset, passive, is_metric, cal_perc) + prof.checkpoint("State Control") + + # Publish data + CC = data_send(PL.perception_state, plan, plan_ts, CS, CI, CP, VM, state, events, actuators, v_cruise_kph, rk, carstate, carcontrol, + live100, livempc, AM, driver_status, LaC, LoC, angle_offset, passive, start_time) + prof.checkpoint("Sent") + + rk.keep_time() # Run at 100Hz + prof.display() + + +def main(gctx=None): + controlsd_thread(gctx, 100) + + +if __name__ == "__main__": + main() diff --git a/selfdrive/controls/lib/__init__.py b/selfdrive/controls/lib/__init__.py new file mode 100644 index 00000000000000..e69de29bb2d1d6 diff --git a/selfdrive/controls/lib/alertmanager.py b/selfdrive/controls/lib/alertmanager.py new file mode 100644 index 00000000000000..5884e987033fc3 --- /dev/null +++ b/selfdrive/controls/lib/alertmanager.py @@ -0,0 +1,69 @@ +from cereal import log +from selfdrive.swaglog import cloudlog +from selfdrive.controls.lib.alerts import ALERTS +from common.realtime import sec_since_boot +import copy + + +AlertSize = log.Live100Data.AlertSize +AlertStatus = log.Live100Data.AlertStatus + + +class AlertManager(object): + + def __init__(self): + self.activealerts = [] + self.alerts = {alert.alert_type: alert for alert in ALERTS} + + def alertPresent(self): + return len(self.activealerts) > 0 + + def add(self, alert_type, enabled=True, extra_text_1='', extra_text_2=''): + alert_type = str(alert_type) + added_alert = copy.copy(self.alerts[alert_type]) + added_alert.alert_text_1 += extra_text_1 + added_alert.alert_text_2 += extra_text_2 + added_alert.start_time = sec_since_boot() + + # if new alert is higher priority, log it + if not self.alertPresent() or added_alert.alert_priority > self.activealerts[0].alert_priority: + cloudlog.event('alert_add', alert_type=alert_type, enabled=enabled) + + self.activealerts.append(added_alert) + + # sort by priority first and then by start_time + self.activealerts.sort(key=lambda k: (k.alert_priority, k.start_time), reverse=True) + + def process_alerts(self, cur_time): + + # first get rid of all the expired alerts + self.activealerts = [a for a in self.activealerts if a.start_time + + max(a.duration_sound, a.duration_hud_alert, a.duration_text) > cur_time] + + current_alert = self.activealerts[0] if self.alertPresent() else None + + # start with assuming no alerts + self.alert_type = "" + self.alert_text_1 = "" + self.alert_text_2 = "" + self.alert_status = AlertStatus.normal + self.alert_size = AlertSize.none + self.visual_alert = "none" + self.audible_alert = "none" + self.alert_rate = 0. + + if current_alert: + self.alert_type = current_alert.alert_type + + if current_alert.start_time + current_alert.duration_sound > cur_time: + self.audible_alert = current_alert.audible_alert + + if current_alert.start_time + current_alert.duration_hud_alert > cur_time: + self.visual_alert = current_alert.visual_alert + + if current_alert.start_time + current_alert.duration_text > cur_time: + self.alert_text_1 = current_alert.alert_text_1 + self.alert_text_2 = current_alert.alert_text_2 + self.alert_status = current_alert.alert_status + self.alert_size = current_alert.alert_size + self.alert_rate = current_alert.alert_rate diff --git a/selfdrive/controls/lib/alerts.py b/selfdrive/controls/lib/alerts.py new file mode 100644 index 00000000000000..13ebf7f3f460d7 --- /dev/null +++ b/selfdrive/controls/lib/alerts.py @@ -0,0 +1,648 @@ +from cereal import car, log + +# Priority +class Priority: + LOWEST = 0 + LOW_LOWEST = 1 + LOW = 2 + MID = 3 + HIGH = 4 + HIGHEST = 5 + +AlertSize = log.Live100Data.AlertSize +AlertStatus = log.Live100Data.AlertStatus +AudibleAlert = car.CarControl.HUDControl.AudibleAlert +VisualAlert = car.CarControl.HUDControl.VisualAlert + +class Alert(object): + def __init__(self, + alert_type, + alert_text_1, + alert_text_2, + alert_status, + alert_size, + alert_priority, + visual_alert, + audible_alert, + duration_sound, + duration_hud_alert, + duration_text, + alert_rate=0.): + + self.alert_type = alert_type + self.alert_text_1 = alert_text_1 + self.alert_text_2 = alert_text_2 + self.alert_status = alert_status + self.alert_size = alert_size + self.alert_priority = alert_priority + self.visual_alert = visual_alert + self.audible_alert = audible_alert + + self.duration_sound = duration_sound + self.duration_hud_alert = duration_hud_alert + self.duration_text = duration_text + + self.start_time = 0. + self.alert_rate = alert_rate + + # typecheck that enums are valid on startup + tst = car.CarControl.new_message() + tst.hudControl.visualAlert = self.visual_alert + + def __str__(self): + return self.alert_text_1 + "/" + self.alert_text_2 + " " + str(self.alert_priority) + " " + str( + self.visual_alert) + " " + str(self.audible_alert) + + def __gt__(self, alert2): + return self.alert_priority > alert2.alert_priority + + +ALERTS = [ + # Miscellaneous alerts + Alert( + "enable", + "", + "", + AlertStatus.normal, AlertSize.none, + Priority.MID, VisualAlert.none, AudibleAlert.chimeEngage, .2, 0., 0.), + + Alert( + "disable", + "", + "", + AlertStatus.normal, AlertSize.none, + Priority.MID, VisualAlert.none, AudibleAlert.chimeDisengage, .2, 0., 0.), + + Alert( + "fcw", + "BRAKE!", + "Risk of Collision", + AlertStatus.critical, AlertSize.full, + Priority.HIGHEST, VisualAlert.fcw, AudibleAlert.chimeWarningRepeat, 1., 2., 2.), + + Alert( + "steerSaturated", + "TAKE CONTROL", + "Turn Exceeds Steering Limit", + AlertStatus.userPrompt, AlertSize.mid, + Priority.LOW, VisualAlert.steerRequired, AudibleAlert.chimePrompt, 1., 2., 3.), + + Alert( + "steerTempUnavailable", + "TAKE CONTROL", + "Steering Temporarily Unavailable", + AlertStatus.userPrompt, AlertSize.mid, + Priority.LOW, VisualAlert.steerRequired, AudibleAlert.chimeWarning1, .4, 2., 3.), + + Alert( + "steerTempUnavailableMute", + "TAKE CONTROL", + "Steering Temporarily Unavailable", + AlertStatus.userPrompt, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.none, .2, .2, .2), + + Alert( + "manualSteeringRequired", + "MANUAL STEERING REQUIRED", + "Steering is Off - Press LKAS button to turn On", + AlertStatus.userPrompt, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.none, .2, .2, .2), + + Alert( + "manualSteeringRequiredBlinkerOnLeft", + "MANUAL STEERING REQUIRED", + "Left Turn Signal is On", + AlertStatus.userPrompt, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.none, .2, .2, .2), + + Alert( + "manualSteeringRequiredBlinkerOnRight", + "MANUAL STEERING REQUIRED", + "Right Turn Signal is On", + AlertStatus.userPrompt, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.none, .2, .2, .2), + + Alert( + "preDriverDistracted", + "KEEP EYES ON ROAD: User Appears Distracted", + "", + AlertStatus.normal, AlertSize.small, + Priority.LOW, VisualAlert.steerRequired, AudibleAlert.none, .0, .1, .1, alert_rate=0.75), + + Alert( + "promptDriverDistracted", + "KEEP EYES ON ROAD", + "User Appears Distracted", + AlertStatus.userPrompt, AlertSize.mid, + Priority.MID, VisualAlert.steerRequired, AudibleAlert.chimeWarning2, .1, .1, .1), + + Alert( + "driverDistracted", + "DISENGAGE IMMEDIATELY", + "User Was Distracted", + AlertStatus.critical, AlertSize.full, + Priority.HIGH, VisualAlert.steerRequired, AudibleAlert.chimeWarningRepeat, .1, .1, .1), + + Alert( + "preDriverUnresponsive", + "TOUCH STEERING WHEEL: No Driver Monitoring", + "", + AlertStatus.normal, AlertSize.small, + Priority.LOW, VisualAlert.steerRequired, AudibleAlert.none, .0, .1, .1, alert_rate=0.75), + + Alert( + "promptDriverUnresponsive", + "TOUCH STEERING WHEEL", + "User Is Unresponsive", + AlertStatus.userPrompt, AlertSize.mid, + Priority.MID, VisualAlert.steerRequired, AudibleAlert.chimeWarning2, .1, .1, .1), + + Alert( + "driverUnresponsive", + "DISENGAGE IMMEDIATELY", + "User Was Unresponsive", + AlertStatus.critical, AlertSize.full, + Priority.HIGH, VisualAlert.steerRequired, AudibleAlert.chimeWarningRepeat, .1, .1, .1), + + Alert( + "driverMonitorOff", + "DRIVER MONITOR IS UNAVAILABLE", + "Accuracy Is Low", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.none, .4, 0., 4.), + + Alert( + "driverMonitorOn", + "DRIVER MONITOR IS AVAILABLE", + "Accuracy Is High", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.none, .4, 0., 4.), + + Alert( + "geofence", + "DISENGAGEMENT REQUIRED", + "Not in Geofenced Area", + AlertStatus.userPrompt, AlertSize.mid, + Priority.HIGH, VisualAlert.steerRequired, AudibleAlert.chimeWarningRepeat, .1, .1, .1), + + Alert( + "startup", + "Be ready to take over at any time", + "Always keep hands on wheel and eyes on road", + AlertStatus.normal, AlertSize.mid, + Priority.LOW_LOWEST, VisualAlert.none, AudibleAlert.none, 0., 0., 15.), + + Alert( + "ethicalDilemma", + "TAKE CONTROL IMMEDIATELY", + "Ethical Dilemma Detected", + AlertStatus.critical, AlertSize.full, + Priority.HIGHEST, VisualAlert.steerRequired, AudibleAlert.chimeWarningRepeat, 1., 3., 3.), + + Alert( + "steerTempUnavailableNoEntry", + "openpilot Unavailable", + "Steering Temporarily Unavailable", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.chimeError, .4, 0., 3.), + + Alert( + "manualRestart", + "TAKE CONTROL", + "Resume Driving Manually", + AlertStatus.userPrompt, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.none, 0., 0., .2), + + Alert( + "resumeRequired", + "STOPPED", + "Press Resume to Move", + AlertStatus.userPrompt, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.none, 0., 0., .2), + + Alert( + "belowSteerSpeed", + "TAKE CONTROL", + "Steer Unavailable Below ", + AlertStatus.userPrompt, AlertSize.mid, + Priority.MID, VisualAlert.steerRequired, AudibleAlert.chimeWarning1, 0., 0., .1), + + Alert( + "debugAlert", + "DEBUG ALERT", + "", + AlertStatus.userPrompt, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.none, .1, .1, .1), + + # Non-entry only alerts + Alert( + "wrongCarModeNoEntry", + "openpilot Unavailable", + "Main Switch Off", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.chimeError, .4, 0., 3.), + + Alert( + "dataNeededNoEntry", + "openpilot Unavailable", + "Data Needed for Calibration. Upload Drive, Try Again", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.chimeError, .4, 0., 3.), + + Alert( + "outOfSpaceNoEntry", + "openpilot Unavailable", + "Out of Storage Space", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.chimeError, .4, 0., 3.), + + Alert( + "pedalPressedNoEntry", + "openpilot Unavailable", + "Pedal Pressed During Attempt", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, "brakePressed", AudibleAlert.chimeError, .4, 2., 3.), + + Alert( + "speedTooLowNoEntry", + "openpilot Unavailable", + "Speed Too Low", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.chimeError, .4, 2., 3.), + + Alert( + "brakeHoldNoEntry", + "openpilot Unavailable", + "Brake Hold Active", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.chimeError, .4, 2., 3.), + + Alert( + "parkBrakeNoEntry", + "openpilot Unavailable", + "Park Brake Engaged", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.chimeError, .4, 2., 3.), + + Alert( + "lowSpeedLockoutNoEntry", + "openpilot Unavailable", + "Cruise Fault: Restart the Car", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.chimeError, .4, 2., 3.), + + Alert( + "lowBatteryNoEntry", + "openpilot Unavailable", + "Low Battery", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.chimeError, .4, 2., 3.), + + # Cancellation alerts causing soft disabling + Alert( + "overheat", + "TAKE CONTROL IMMEDIATELY", + "System Overheated", + AlertStatus.critical, AlertSize.full, + Priority.MID, VisualAlert.steerRequired, AudibleAlert.chimeWarning2, .1, 2., 2.), + + Alert( + "wrongGear", + "TAKE CONTROL IMMEDIATELY", + "Gear not D", + AlertStatus.critical, AlertSize.full, + Priority.MID, VisualAlert.steerRequired, AudibleAlert.chimeWarning2, .1, 2., 2.), + + Alert( + "calibrationInvalid", + "TAKE CONTROL IMMEDIATELY", + "Calibration Invalid: Reposition EON and Recalibrate", + AlertStatus.critical, AlertSize.full, + Priority.MID, VisualAlert.steerRequired, AudibleAlert.chimeWarning2, .1, 2., 2.), + + Alert( + "calibrationIncomplete", + "TAKE CONTROL IMMEDIATELY", + "Calibration in Progress", + AlertStatus.critical, AlertSize.full, + Priority.MID, VisualAlert.steerRequired, AudibleAlert.chimeWarning2, .1, 2., 2.), + + Alert( + "doorOpen", + "TAKE CONTROL IMMEDIATELY", + "Door Open", + AlertStatus.critical, AlertSize.full, + Priority.MID, VisualAlert.steerRequired, AudibleAlert.chimeWarning2, .1, 2., 2.), + + Alert( + "seatbeltNotLatched", + "TAKE CONTROL IMMEDIATELY", + "Seatbelt Unlatched", + AlertStatus.critical, AlertSize.full, + Priority.MID, VisualAlert.steerRequired, AudibleAlert.chimeWarning2, .1, 2., 2.), + + Alert( + "espDisabled", + "TAKE CONTROL IMMEDIATELY", + "ESP Off", + AlertStatus.critical, AlertSize.full, + Priority.MID, VisualAlert.steerRequired, AudibleAlert.chimeWarning2, .1, 2., 2.), + + Alert( + "lowBattery", + "TAKE CONTROL IMMEDIATELY", + "Low Battery", + AlertStatus.critical, AlertSize.full, + Priority.MID, VisualAlert.steerRequired, AudibleAlert.chimeWarning2, .1, 2., 2.), + + # Cancellation alerts causing immediate disabling + Alert( + "radarCommIssue", + "TAKE CONTROL IMMEDIATELY", + "Radar Error: Restart the Car", + AlertStatus.critical, AlertSize.full, + Priority.HIGHEST, VisualAlert.steerRequired, AudibleAlert.chimeWarningRepeat, 1., 3., 4.), + + Alert( + "radarFault", + "TAKE CONTROL IMMEDIATELY", + "Radar Error: Restart the Car", + AlertStatus.critical, AlertSize.full, + Priority.HIGHEST, VisualAlert.steerRequired, AudibleAlert.chimeWarningRepeat, 1., 3., 4.), + + Alert( + "modelCommIssue", + "TAKE CONTROL IMMEDIATELY", + "Model Error: Check Internet Connection", + AlertStatus.critical, AlertSize.full, + Priority.HIGHEST, VisualAlert.steerRequired, AudibleAlert.chimeWarningRepeat, 1., 3., 4.), + + Alert( + "controlsFailed", + "TAKE CONTROL IMMEDIATELY", + "Controls Failed", + AlertStatus.critical, AlertSize.full, + Priority.HIGHEST, VisualAlert.steerRequired, AudibleAlert.chimeWarningRepeat, 1., 3., 4.), + + Alert( + "controlsMismatch", + "TAKE CONTROL IMMEDIATELY", + "Controls Mismatch", + AlertStatus.critical, AlertSize.full, + Priority.HIGHEST, VisualAlert.steerRequired, AudibleAlert.chimeWarningRepeat, 1., 3., 4.), + + Alert( + "commIssue", + "TAKE CONTROL IMMEDIATELY", + "CAN Error: Check Connections", + AlertStatus.critical, AlertSize.full, + Priority.HIGHEST, VisualAlert.steerRequired, AudibleAlert.chimeWarningRepeat, 1., 3., 4.), + + Alert( + "steerUnavailable", + "TAKE CONTROL IMMEDIATELY", + "LKAS Fault: Restart the Car", + AlertStatus.critical, AlertSize.full, + Priority.HIGHEST, VisualAlert.steerRequired, AudibleAlert.chimeWarningRepeat, 1., 3., 4.), + + Alert( + "brakeUnavailable", + "TAKE CONTROL IMMEDIATELY", + "Cruise Fault: Restart the Car", + AlertStatus.critical, AlertSize.full, + Priority.HIGHEST, VisualAlert.steerRequired, AudibleAlert.chimeWarningRepeat, 1., 3., 4.), + + Alert( + "gasUnavailable", + "TAKE CONTROL IMMEDIATELY", + "Gas Fault: Restart the Car", + AlertStatus.critical, AlertSize.full, + Priority.HIGHEST, VisualAlert.steerRequired, AudibleAlert.chimeWarningRepeat, 1., 3., 4.), + + Alert( + "reverseGear", + "TAKE CONTROL IMMEDIATELY", + "Reverse Gear", + AlertStatus.critical, AlertSize.full, + Priority.HIGHEST, VisualAlert.steerRequired, AudibleAlert.chimeWarningRepeat, 1., 3., 4.), + + Alert( + "cruiseDisabled", + "TAKE CONTROL IMMEDIATELY", + "Cruise Is Off", + AlertStatus.critical, AlertSize.full, + Priority.HIGHEST, VisualAlert.steerRequired, AudibleAlert.chimeWarningRepeat, 1., 3., 4.), + + Alert( + "plannerError", + "TAKE CONTROL IMMEDIATELY", + "Planner Solution Error", + AlertStatus.critical, AlertSize.full, + Priority.HIGHEST, VisualAlert.steerRequired, AudibleAlert.chimeWarningRepeat, 1., 3., 4.), + + # not loud cancellations (user is in control) + Alert( + "noTarget", + "openpilot Canceled", + "No close lead car", + AlertStatus.normal, AlertSize.mid, + Priority.HIGH, VisualAlert.none, AudibleAlert.chimeDisengage, .4, 2., 3.), + + Alert( + "speedTooLow", + "openpilot Canceled", + "Speed too low", + AlertStatus.normal, AlertSize.mid, + Priority.HIGH, VisualAlert.none, AudibleAlert.chimeDisengage, .4, 2., 3.), + + Alert( + "invalidGiraffeHonda", + "Invalid Giraffe Configuration", + "Set 0111 for openpilot. 1011 for stock", + AlertStatus.normal, AlertSize.mid, + Priority.HIGH, VisualAlert.none, AudibleAlert.chimeDisengage, .4, 2., 3.), + + # Cancellation alerts causing non-entry + Alert( + "overheatNoEntry", + "openpilot Unavailable", + "System overheated", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.chimeError, .4, 2., 3.), + + Alert( + "wrongGearNoEntry", + "openpilot Unavailable", + "Gear not D", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.chimeError, .4, 2., 3.), + + Alert( + "calibrationInvalidNoEntry", + "openpilot Unavailable", + "Calibration Invalid: Reposition EON and Recalibrate", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.chimeError, .4, 2., 3.), + + Alert( + "calibrationIncompleteNoEntry", + "openpilot Unavailable", + "Calibration in Progress", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.chimeError, .4, 2., 3.), + + Alert( + "doorOpenNoEntry", + "openpilot Unavailable", + "Door open", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.chimeError, .4, 2., 3.), + + Alert( + "seatbeltNotLatchedNoEntry", + "openpilot Unavailable", + "Seatbelt unlatched", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.chimeError, .4, 2., 3.), + + Alert( + "espDisabledNoEntry", + "openpilot Unavailable", + "ESP Off", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.chimeError, .4, 2., 3.), + + Alert( + "geofenceNoEntry", + "openpilot Unavailable", + "Not in Geofenced Area", + AlertStatus.normal, AlertSize.mid, + Priority.MID, VisualAlert.none, AudibleAlert.chimeError, .4, 2., 3.), + + Alert( + "radarCommIssueNoEntry", + "openpilot Unavailable", + "Radar Error: Restart the Car", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.chimeError, .4, 2., 3.), + + Alert( + "radarFaultNoEntry", + "openpilot Unavailable", + "Radar Error: Restart the Car", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.chimeError, .4, 2., 3.), + + Alert( + "modelCommIssueNoEntry", + "openpilot Unavailable", + "Model Error: Check Internet Connection", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.chimeError, .4, 2., 3.), + + Alert( + "controlsFailedNoEntry", + "openpilot Unavailable", + "Controls Failed", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.chimeError, .4, 2., 3.), + + Alert( + "commIssueNoEntry", + "openpilot Unavailable", + "CAN Error: Check Connections", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.chimeError, .4, 2., 3.), + + Alert( + "steerUnavailableNoEntry", + "openpilot Unavailable", + "LKAS Fault: Restart the Car", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.chimeError, .4, 2., 3.), + + Alert( + "brakeUnavailableNoEntry", + "openpilot Unavailable", + "Cruise Fault: Restart the Car", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.chimeError, .4, 2., 3.), + + Alert( + "gasUnavailableNoEntry", + "openpilot Unavailable", + "Gas Error: Restart the Car", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.chimeError, .4, 2., 3.), + + Alert( + "reverseGearNoEntry", + "openpilot Unavailable", + "Reverse Gear", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.chimeError, .4, 2., 3.), + + Alert( + "cruiseDisabledNoEntry", + "openpilot Unavailable", + "Cruise is Off", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.chimeError, .4, 2., 3.), + + Alert( + "noTargetNoEntry", + "openpilot Unavailable", + "No Close Lead Car", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.chimeError, .4, 2., 3.), + + Alert( + "plannerErrorNoEntry", + "openpilot Unavailable", + "Planner Solution Error", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.chimeError, .4, 2., 3.), + + Alert( + "invalidGiraffeHondaNoEntry", + "openpilot Unavailable", + "Set 0111 for openpilot. 1011 for stock", + AlertStatus.normal, AlertSize.mid, + Priority.LOW, VisualAlert.none, AudibleAlert.chimeDisengage, .4, 2., 3.), + + # permanent alerts + Alert( + "steerUnavailablePermanent", + "LKAS Fault: Restart the car to engage", + "", + AlertStatus.normal, AlertSize.small, + Priority.LOW_LOWEST, VisualAlert.none, AudibleAlert.none, 0., 0., .2), + + Alert( + "brakeUnavailablePermanent", + "Cruise Fault: Restart the car to engage", + "", + AlertStatus.normal, AlertSize.small, + Priority.LOW_LOWEST, VisualAlert.none, AudibleAlert.none, 0., 0., .2), + + Alert( + "lowSpeedLockoutPermanent", + "Cruise Fault: Restart the car to engage", + "", + AlertStatus.normal, AlertSize.small, + Priority.LOW_LOWEST, VisualAlert.none, AudibleAlert.none, 0., 0., .2), + + Alert( + "calibrationIncompletePermanent", + "Calibration in Progress: ", + "Drive Above ", + AlertStatus.normal, AlertSize.mid, + Priority.LOWEST, VisualAlert.none, AudibleAlert.none, 0., 0., .2), + + Alert( + "invalidGiraffeHondaPermanent", + "Invalid Giraffe Configuration", + "Set 0111 for openpilot. 1011 for stock", + AlertStatus.normal, AlertSize.mid, + Priority.LOW_LOWEST, VisualAlert.none, AudibleAlert.none, 0., 0., .2), +] diff --git a/selfdrive/controls/lib/drive_helpers.py b/selfdrive/controls/lib/drive_helpers.py new file mode 100644 index 00000000000000..c3db502fcfe4bb --- /dev/null +++ b/selfdrive/controls/lib/drive_helpers.py @@ -0,0 +1,98 @@ +from cereal import car +from common.numpy_fast import clip +from selfdrive.config import Conversions as CV + +# kph +V_CRUISE_MAX = 144 +V_CRUISE_MIN = 8 +V_CRUISE_DELTA = 8 +V_CRUISE_ENABLE_MIN = 40 + + +class MPC_COST_LAT: + PATH = 1.0 + LANE = 3.0 + HEADING = 1.0 + STEER_RATE = 1.0 + + +class MPC_COST_LONG: + TTC = 5.0 + DISTANCE = 0.1 + ACCELERATION = 10.0 + JERK = 20.0 + + +class EventTypes: + ENABLE = 'enable' + PRE_ENABLE = 'preEnable' + NO_ENTRY = 'noEntry' + WARNING = 'warning' + USER_DISABLE = 'userDisable' + SOFT_DISABLE = 'softDisable' + IMMEDIATE_DISABLE = 'immediateDisable' + PERMANENT = 'permanent' + + +def create_event(name, types): + event = car.CarEvent.new_message() + event.name = name + for t in types: + setattr(event, t, True) + return event + + +def get_events(events, types): + out = [] + for e in events: + for t in types: + if getattr(e, t): + out.append(e.name) + return out + + +def rate_limit(new_value, last_value, dw_step, up_step): + return clip(new_value, last_value + dw_step, last_value + up_step) + + +def learn_angle_offset(lateral_control, v_ego, angle_offset, c_poly, c_prob, angle_steers, steer_override): + # simple integral controller that learns how much steering offset to put to have the car going straight + # while being in the middle of the lane + min_offset = -7. # deg + max_offset = 7. # deg + alpha = 1. / 36000. # correct by 1 deg in 2 mins, at 30m/s, with 50cm of error, at 20Hz + min_learn_speed = 1. + + # learn less at low speed or when turning + slow_factor = 1. / (1. + 0.02 * abs(angle_steers) * v_ego) + alpha_v = alpha * c_prob * (max(v_ego - min_learn_speed, 0.)) * slow_factor + + # only learn if lateral control is active and if driver is not overriding: + if lateral_control and not steer_override: + angle_offset += c_poly[3] * alpha_v + angle_offset = clip(angle_offset, min_offset, max_offset) + + return angle_offset + + +def update_v_cruise(v_cruise_kph, buttonEvents, enabled): + # handle button presses. TODO: this should be in state_control, but a decelCruise press + # would have the effect of both enabling and changing speed is checked after the state transition + for b in buttonEvents: + if enabled and not b.pressed: + if b.type == "accelCruise": + v_cruise_kph += V_CRUISE_DELTA - (v_cruise_kph % V_CRUISE_DELTA) + elif b.type == "decelCruise": + v_cruise_kph -= V_CRUISE_DELTA - ((V_CRUISE_DELTA - v_cruise_kph) % V_CRUISE_DELTA) + v_cruise_kph = clip(v_cruise_kph, V_CRUISE_MIN, V_CRUISE_MAX) + + return v_cruise_kph + + +def initialize_v_cruise(v_ego, buttonEvents, v_cruise_last): + for b in buttonEvents: + # 250kph or above probably means we never had a set speed + if b.type == "accelCruise" and v_cruise_last < 250: + return v_cruise_last + + return int(round(clip(v_ego * CV.MS_TO_KPH, V_CRUISE_ENABLE_MIN, V_CRUISE_MAX))) diff --git a/selfdrive/controls/lib/driver_monitor.py b/selfdrive/controls/lib/driver_monitor.py new file mode 100644 index 00000000000000..57d5af8db4f4ea --- /dev/null +++ b/selfdrive/controls/lib/driver_monitor.py @@ -0,0 +1,152 @@ +import numpy as np +from common.realtime import sec_since_boot +from selfdrive.controls.lib.drive_helpers import create_event, EventTypes as ET +from common.filter_simple import FirstOrderFilter +from kegman_conf import kegman_conf + +k = kegman_conf() + +_DT = 0.01 # update runs at 100Hz +_DTM = 0.1 # DM runs at 10Hz +_AWARENESS_TIME = min(int(k.conf['wheelTouchSeconds']), 600) # x minutes limit without user touching steering wheels make the car enter a terminal status +_AWARENESS_PRE_TIME = 20. # a first alert is issued 20s before expiration +_AWARENESS_PROMPT_TIME = 5. # a second alert is issued 5s before start decelerating the car +_DISTRACTED_TIME = 7. +_DISTRACTED_PRE_TIME = 4. +_DISTRACTED_PROMPT_TIME = 2. +# measured 1 rad in x FOV. 1152x864 is original image, 160x320 is a right crop for model +_CAMERA_FOV_X = 1. # rad +_CAMERA_FOV_Y = 0.75 # 4/3 aspect ratio +# model output refers to center of cropped image, so need to apply the x displacement offset +_CAMERA_OFFSET_X = 0.3125 #(1152/2 - 0.5*(160*864/320))/1152 +_CAMERA_X_CONV = 0.375 # 160*864/320/1152 +_PITCH_WEIGHT = 1.5 # pitch matters a lot more +_METRIC_THRESHOLD = 0.4 +_PITCH_POS_ALLOWANCE = 0.08 # rad, to not be too sensitive on positive pitch +_PITCH_NATURAL_OFFSET = 0.1 # people don't seem to look straight when they drive relaxed, rather a bit up +_STD_THRESHOLD = 0.1 # above this standard deviation consider the measurement invalid +_DISTRACTED_FILTER_TS = 0.25 # 0.6Hz +_VARIANCE_FILTER_TS = 20. # 0.008Hz + + +class _DriverPose(): + def __init__(self): + self.yaw = 0. + self.pitch = 0. + self.roll = 0. + self.yaw_offset = 0. + self.pitch_offset = 0. + +def _monitor_hysteresys(variance_level, monitor_valid_prev): + var_thr = 0.63 if monitor_valid_prev else 0.37 + return variance_level < var_thr + +class DriverStatus(): + def __init__(self, monitor_on=False): + self.pose = _DriverPose() + self.monitor_on = monitor_on + self.monitor_param_on = monitor_on + self.monitor_valid = True # variance needs to be low + self.awareness = 1. + self.driver_distracted = False + self.driver_distraction_filter = FirstOrderFilter(0., _DISTRACTED_FILTER_TS, _DTM) + self.variance_high = False + self.variance_filter = FirstOrderFilter(0., _VARIANCE_FILTER_TS, _DTM) + self.ts_last_check = 0. + self._set_timers() + + def _reset_filters(self): + self.driver_distraction_filter.x = 0. + self.variance_filter.x = 0. + self.monitor_valid = True + + def _set_timers(self): + if self.monitor_on: + self.threshold_pre = _DISTRACTED_PRE_TIME / _DISTRACTED_TIME + self.threshold_prompt = _DISTRACTED_PROMPT_TIME / _DISTRACTED_TIME + self.step_change = _DT / _DISTRACTED_TIME + else: + self.threshold_pre = _AWARENESS_PRE_TIME / _AWARENESS_TIME + self.threshold_prompt = _AWARENESS_PROMPT_TIME / _AWARENESS_TIME + self.step_change = _DT / _AWARENESS_TIME + + def _is_driver_distracted(self, pose): + # to be tuned and to learn the driver's normal pose + yaw_error = pose.yaw - pose.yaw_offset + pitch_error = pose.pitch - pose.pitch_offset - _PITCH_NATURAL_OFFSET + # add positive pitch allowance + if pitch_error > 0.: + pitch_error = max(pitch_error - _PITCH_POS_ALLOWANCE, 0.) + pitch_error *= _PITCH_WEIGHT + metric = np.sqrt(yaw_error**2 + pitch_error**2) + #print "%02.4f" % np.degrees(pose.pitch), "%02.4f" % np.degrees(pitch_error), "%03.4f" % np.degrees(pose.pitch_offset), metric + return 1 if metric > _METRIC_THRESHOLD else 0 + + + def get_pose(self, driver_monitoring, params): + + self.pose.pitch = driver_monitoring.descriptor[0] + self.pose.yaw = driver_monitoring.descriptor[1] + self.pose.roll = driver_monitoring.descriptor[2] + self.pose.yaw_offset = (driver_monitoring.descriptor[3] * _CAMERA_X_CONV + _CAMERA_OFFSET_X) * _CAMERA_FOV_X + self.pose.pitch_offset = -driver_monitoring.descriptor[4] * _CAMERA_FOV_Y # positive y is down + self.driver_distracted = self._is_driver_distracted(self.pose) + # first order filters + self.driver_distraction_filter.update(self.driver_distracted) + self.variance_high = driver_monitoring.std > _STD_THRESHOLD + self.variance_filter.update(self.variance_high) + + monitor_param_on_prev = self.monitor_param_on + monitor_valid_prev = self.monitor_valid + + # don't check for param too often as it's a kernel call + ts = sec_since_boot() + if ts - self.ts_last_check > 1.: + self.monitor_param_on = params.get("IsDriverMonitoringEnabled") == "1" + self.ts_last_check = ts + + self.monitor_valid = _monitor_hysteresys(self.variance_filter.x, monitor_valid_prev) + self.monitor_on = self.monitor_valid and self.monitor_param_on + if monitor_param_on_prev != self.monitor_param_on: + self._reset_filters() + self._set_timers() + + + def update(self, events, driver_engaged, ctrl_active, standstill): + + driver_engaged |= (self.driver_distraction_filter.x < 0.37 and self.monitor_on) + + if (driver_engaged and self.awareness > 0.) or not ctrl_active: + # always reset if driver is in control (unless we are in red alert state) or op isn't active + self.awareness = 1. + + if (not self.monitor_on or (self.driver_distraction_filter.x > 0.63 and self.driver_distracted)) and \ + not (standstill and self.awareness - self.step_change <= self.threshold_prompt): + self.awareness = max(self.awareness - self.step_change, -0.1) + + alert = None + if self.awareness <= 0.: + # terminal red alert: disengagement required + alert = 'driverDistracted' if self.monitor_on else 'driverUnresponsive' + elif self.awareness <= self.threshold_prompt: + # prompt orange alert + alert = 'promptDriverDistracted' if self.monitor_on else 'promptDriverUnresponsive' + elif self.awareness <= self.threshold_pre: + # pre green alert + alert = 'preDriverDistracted' if self.monitor_on else 'preDriverUnresponsive' + if alert is not None: + events.append(create_event(alert, [ET.WARNING])) + + return events + + +if __name__ == "__main__": + ds = DriverStatus(True) + ds.driver_distraction_filter.x = 0. + ds.driver_distracted = 1 + for i in range(10): + ds.update([], False, True, False) + print(ds.awareness, ds.driver_distracted, ds.driver_distraction_filter.x) + ds.update([], True, True, False) + print(ds.awareness, ds.driver_distracted, ds.driver_distraction_filter.x) + diff --git a/selfdrive/controls/lib/latcontrol.py b/selfdrive/controls/lib/latcontrol.py new file mode 100644 index 00000000000000..603a44b20f456b --- /dev/null +++ b/selfdrive/controls/lib/latcontrol.py @@ -0,0 +1,226 @@ +import zmq +import math +import numpy as np +import time +import json +from selfdrive.controls.lib.pid import PIController +from selfdrive.controls.lib.drive_helpers import MPC_COST_LAT +from selfdrive.controls.lib.lateral_mpc import libmpc_py +from common.numpy_fast import interp +from common.realtime import sec_since_boot +from selfdrive.swaglog import cloudlog +from cereal import car + +_DT = 0.01 # 100Hz +_DT_MPC = 0.05 # 20Hz + + +def calc_states_after_delay(states, v_ego, steer_angle, curvature_factor, steer_ratio, delay): + states[0].x = v_ego * delay + states[0].psi = v_ego * curvature_factor * math.radians(steer_angle) / steer_ratio * delay + return states + + +def get_steer_max(CP, v_ego): + return interp(v_ego, CP.steerMaxBP, CP.steerMaxV) + +def apply_deadzone(angle, deadzone): + if angle > deadzone: + angle -= deadzone + elif angle < -deadzone: + angle += deadzone + else: + angle = 0. + return angle + +class LatControl(object): + def __init__(self, CP): + self.pid = PIController((CP.steerKpBP, CP.steerKpV), + (CP.steerKiBP, CP.steerKiV), + k_f=CP.steerKf, pos_limit=1.0) + self.last_cloudlog_t = 0.0 + self.setup_mpc(CP.steerRateCost) + self.smooth_factor = 2.0 * CP.steerActuatorDelay / _DT # Multiplier for inductive component (feed forward) + self.projection_factor = 5.0 * _DT # Mutiplier for reactive component (PI) + self.accel_limit = 5.0 # Desired acceleration limit to prevent "whip steer" (resistive component) + self.ff_angle_factor = 0.5 # Kf multiplier for angle-based feed forward + self.ff_rate_factor = 5.0 # Kf multiplier for rate-based feed forward + self.ratioDelayExp = 2.0 # Exponential coefficient for variable steering rate (delay) + self.ratioDelayScale = 0.0 # Multiplier for variable steering rate (delay) + self.prev_angle_rate = 0 + self.feed_forward = 0.0 + self.angle_rate_desired = 0.0 + + # variables for dashboarding + self.context = zmq.Context() + self.steerpub = self.context.socket(zmq.PUB) + self.steerpub.bind("tcp://*:8594") + self.frames = 0 + self.curvature_factor = 0.0 + self.slip_factor = 0.0 + self.influxString = 'steerData3,testName=none,active=%s,ff_type=%s ff_type_a=%s,ff_type_r=%s,' \ + 'angle_rate=%s,angle_steers=%s,angle_steers_des=%s,angle_steers_des_mpc=%s,p=%s,i=%s,f=%s %s\n~' + self.steerdata = self.influxString + + def setup_mpc(self, steer_rate_cost): + self.libmpc = libmpc_py.libmpc + self.libmpc.init(MPC_COST_LAT.PATH, MPC_COST_LAT.LANE, MPC_COST_LAT.HEADING, steer_rate_cost) + + self.mpc_solution = libmpc_py.ffi.new("log_t *") + self.cur_state = libmpc_py.ffi.new("state_t *") + self.mpc_updated = False + self.mpc_nans = False + self.cur_state[0].x = 0.0 + self.cur_state[0].y = 0.0 + self.cur_state[0].psi = 0.0 + self.cur_state[0].delta = 0.0 + + self.last_mpc_ts = 0.0 + self.angle_steers_des = 0.0 + self.angle_steers_des_mpc = 0.0 + self.angle_steers_des_prev = 0.0 + self.angle_steers_des_time = 0.0 + + def reset(self): + self.pid.reset() + + def update(self, active, v_ego, angle_steers, angle_rate, steer_override, d_poly, angle_offset, CP, VM, PL): + cur_time = sec_since_boot() + self.mpc_updated = False + # TODO: this creates issues in replay when rewinding time: mpc won't run + if self.last_mpc_ts < PL.last_md_ts: + self.last_mpc_ts = PL.last_md_ts + self.angle_steers_des_prev = self.angle_steers_des_mpc + + self.curvature_factor = VM.curvature_factor(v_ego) + + # This is currently disabled, but it is used to compensate for variable steering rate + ratioDelayFactor = 1. + self.ratioDelayScale * abs(angle_steers / 100.) ** self.ratioDelayExp + + # Determine a proper delay time that includes the model's processing time, which is variable + plan_age = _DT_MPC + cur_time - float(PL.last_md_ts / 1000000000.0) + total_delay = ratioDelayFactor * CP.steerActuatorDelay + plan_age + + # Use steering rate from the last 2 samples to estimate acceleration for a more realistic future steering rate + accelerated_angle_rate = 2.0 * angle_rate - self.prev_angle_rate + + # Project the future steering angle for the actuator delay only (not model delay) + projected_angle_steers = ratioDelayFactor * CP.steerActuatorDelay * accelerated_angle_rate + angle_steers + + self.l_poly = libmpc_py.ffi.new("double[4]", list(PL.PP.l_poly)) + self.r_poly = libmpc_py.ffi.new("double[4]", list(PL.PP.r_poly)) + self.p_poly = libmpc_py.ffi.new("double[4]", list(PL.PP.p_poly)) + + # account for actuation delay and the age of the plan + self.cur_state = calc_states_after_delay(self.cur_state, v_ego, projected_angle_steers, self.curvature_factor, CP.steerRatio, total_delay) + + v_ego_mpc = max(v_ego, 5.0) # avoid mpc roughness due to low speed + self.libmpc.run_mpc(self.cur_state, self.mpc_solution, + self.l_poly, self.r_poly, self.p_poly, + PL.PP.l_prob, PL.PP.r_prob, PL.PP.p_prob, self.curvature_factor, v_ego_mpc, PL.PP.lane_width) + + # reset to current steer angle if not active or overriding + if active: + self.isActive = 1 + delta_desired = self.mpc_solution[0].delta[1] + else: + self.isActive = 0 + delta_desired = math.radians(angle_steers - angle_offset) / CP.steerRatio + + self.cur_state[0].delta = delta_desired + + self.angle_steers_des_mpc = float(math.degrees(delta_desired * CP.steerRatio) + angle_offset) + + # Use the model's solve time instead of cur_time + self.angle_steers_des_time = float(PL.last_md_ts / 1000000000.0) + + # Use last 2 desired angles to determine the model's desired steer rate + self.angle_rate_desired = (self.angle_steers_des_mpc - self.angle_steers_des_prev) / _DT_MPC + self.mpc_updated = True + + # Check for infeasable MPC solution + self.mpc_nans = np.any(np.isnan(list(self.mpc_solution[0].delta))) + t = sec_since_boot() + if self.mpc_nans: + self.libmpc.init(MPC_COST_LAT.PATH, MPC_COST_LAT.LANE, MPC_COST_LAT.HEADING, CP.steerRateCost) + self.cur_state[0].delta = math.radians(angle_steers) / CP.steerRatio + + if t > self.last_cloudlog_t + 5.0: + self.last_cloudlog_t = t + cloudlog.warning("Lateral mpc - nan: True") + + elif self.steerdata != "" and self.frames > 10: + self.steerpub.send(self.steerdata) + self.frames = 0 + self.steerdata = self.influxString + + if v_ego < 0.3 or not active: + output_steer = 0.0 + self.feed_forward = 0.0 + self.pid.reset() + else: + # Interpolate desired angle between MPC updates + self.angle_steers_des = self.angle_steers_des_prev + self.angle_rate_desired * (cur_time - self.angle_steers_des_time) + + # Determine the target steer rate for desired angle, but prevent the acceleration limit from being exceeded + # Restricting the steer rate creates the resistive component needed for resonance + restricted_steer_rate = np.clip(self.angle_steers_des - float(angle_steers) , float(angle_rate) - self.accel_limit, float(angle_rate) + self.accel_limit) + + # Determine projected desired angle that is within the acceleration limit (prevent the steering wheel from jerking) + projected_angle_steers_des = self.angle_steers_des + self.projection_factor * restricted_steer_rate + + # Determine project angle steers using current steer rate + projected_angle_steers = float(angle_steers) + self.projection_factor * float(angle_rate) + + steers_max = get_steer_max(CP, v_ego) + self.pid.pos_limit = steers_max + self.pid.neg_limit = -steers_max + + if CP.steerControlType == car.CarParams.SteerControlType.torque: + # Decide which feed forward mode should be used (angle or rate). Use more dominant mode, and only if conditions are met + # Spread feed forward out over a period of time to make it more inductive (for resonance) + if abs(self.ff_rate_factor * float(restricted_steer_rate)) > abs(self.ff_angle_factor * float(self.angle_steers_des) - float(angle_offset)) - 0.5 \ + and (abs(float(restricted_steer_rate)) > abs(angle_rate) or (float(restricted_steer_rate) < 0) != (angle_rate < 0)) \ + and (float(restricted_steer_rate) < 0) == (float(self.angle_steers_des) - float(angle_offset) - 0.5 < 0): + ff_type = "r" + self.feed_forward = (((self.smooth_factor - 1.) * self.feed_forward) + self.ff_rate_factor * v_ego**2 * float(restricted_steer_rate)) / self.smooth_factor + elif abs(self.angle_steers_des - float(angle_offset)) > 0.5: + ff_type = "a" + self.feed_forward = (((self.smooth_factor - 1.) * self.feed_forward) + self.ff_angle_factor * v_ego**2 * float(apply_deadzone(float(self.angle_steers_des) - float(angle_offset), 0.5))) / self.smooth_factor + else: + ff_type = "r" + self.feed_forward = (((self.smooth_factor - 1.) * self.feed_forward) + 0.0) / self.smooth_factor + else: + self.feed_forward = self.angle_steers_des_mpc # feedforward desired angle + deadzone = 0.0 + + # Use projected desired and actual angles instead of "current" values, in order to make PI more reactive (for resonance) + output_steer = self.pid.update(projected_angle_steers_des, projected_angle_steers, check_saturation=(v_ego > 10), override=steer_override, + feedforward=self.feed_forward, speed=v_ego, deadzone=deadzone) + + + # All but the last 3 lines after here are for real-time dashboarding + self.pCost = 0.0 + self.lCost = 0.0 + self.rCost = 0.0 + self.hCost = 0.0 + self.srCost = 0.0 + self.last_ff_a = 0.0 + self.last_ff_r = 0.0 + self.center_angle = 0.0 + self.steer_zero_crossing = 0.0 + self.steer_rate_cost = 0.0 + self.avg_angle_rate = 0.0 + self.angle_rate_count = 0.0 + driver_torque = 0.0 + steer_motor = 0.0 + self.frames += 1 + + self.steerdata += ("%d,%s,%d,%d,%f,%f,%f,%f,%f,%f,%f,%d|" % \ + (1, ff_type, 1 if ff_type == "a" else 0, 1 if ff_type == "r" else 0, \ + float(angle_rate), angle_steers, self.angle_steers_des, self.angle_steers_des_mpc, \ + self.pid.p, self.pid.i, self.pid.f, int(time.time() * 100) * 10000000)) + + self.sat_flag = self.pid.saturated + self.prev_angle_rate = angle_rate + return output_steer, float(self.angle_steers_des) diff --git a/selfdrive/controls/lib/latcontrol_helpers.py b/selfdrive/controls/lib/latcontrol_helpers.py new file mode 100644 index 00000000000000..d47c99c0392070 --- /dev/null +++ b/selfdrive/controls/lib/latcontrol_helpers.py @@ -0,0 +1,89 @@ +import numpy as np +import math +from common.numpy_fast import interp + +_K_CURV_V = [1., 0.6] +_K_CURV_BP = [0., 0.002] + +# lane width http://safety.fhwa.dot.gov/geometric/pubs/mitigationstrategies/chapter3/3_lanewidth.cfm +_LANE_WIDTH_V = [2.85, 3.5] + +# break points of speed +_LANE_WIDTH_BP = [0., 31.] + + +def calc_d_lookahead(v_ego, d_poly): + # this function computes how far too look for lateral control + # howfar we look ahead is function of speed and how much curvy is the path + offset_lookahead = 1. + k_lookahead = 7. + # integrate abs value of second derivative of poly to get a measure of path curvature + pts_len = 50. # m + if len(d_poly) > 0: + pts = np.polyval([6 * d_poly[0], 2 * d_poly[1]], np.arange(0, pts_len)) + else: + pts = 0. + curv = np.sum(np.abs(pts)) / pts_len + + k_curv = interp(curv, _K_CURV_BP, _K_CURV_V) + + # sqrt on speed is needed to keep, for a given curvature, the y_des + # proportional to speed. Indeed, y_des is prop to d_lookahead^2 + # 36m at 25m/s + d_lookahead = offset_lookahead + math.sqrt(max(v_ego, 0)) * k_lookahead * k_curv + return d_lookahead + + +def calc_lookahead_offset(v_ego, angle_steers, d_lookahead, VM, angle_offset): + # this function returns the lateral offset given the steering angle, speed and the lookahead distance + sa = math.radians(angle_steers - angle_offset) + curvature = VM.calc_curvature(sa, v_ego) + # clip is to avoid arcsin NaNs due to too sharp turns + y_actual = d_lookahead * np.tan(np.arcsin(np.clip(d_lookahead * curvature, -0.999, 0.999)) / 2.) + return y_actual, curvature + + +def calc_desired_steer_angle(v_ego, y_des, d_lookahead, VM, angle_offset): + # inverse of the above function + curvature = np.sin(np.arctan(y_des / d_lookahead) * 2.) / d_lookahead + steer_des = math.degrees(VM.get_steer_from_curvature(curvature, v_ego)) + angle_offset + return steer_des, curvature + + +def compute_path_pinv(l=50): + deg = 3 + x = np.arange(l*1.0) + X = np.vstack(tuple(x**n for n in range(deg, -1, -1))).T + pinv = np.linalg.pinv(X) + return pinv + + +def model_polyfit(points, path_pinv): + return np.dot(path_pinv, map(float, points)) + + +def calc_desired_path(l_poly, + r_poly, + p_poly, + l_prob, + r_prob, + p_prob, + speed, + lane_width=None): + # this function computes the poly for the center of the lane, averaging left and right polys + if lane_width is None: + lane_width = interp(speed, _LANE_WIDTH_BP, _LANE_WIDTH_V) + + # lanes in US are ~3.6m wide + half_lane_poly = np.array([0., 0., 0., lane_width / 2.]) + if l_prob + r_prob > 0.01: + c_poly = ((l_poly - half_lane_poly) * l_prob + + (r_poly + half_lane_poly) * r_prob) / (l_prob + r_prob) + c_prob = l_prob + r_prob - l_prob * r_prob + else: + c_poly = np.zeros(4) + c_prob = 0. + + p_weight = 1. # predicted path weight relatively to the center of the lane + d_poly = list((c_poly * c_prob + p_poly * p_prob * p_weight) / (c_prob + p_prob * p_weight)) + return d_poly, c_poly, c_prob diff --git a/selfdrive/controls/lib/lateral_mpc/Makefile b/selfdrive/controls/lib/lateral_mpc/Makefile new file mode 100644 index 00000000000000..97579e751c833e --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc/Makefile @@ -0,0 +1,87 @@ + +CC = clang +CXX = clang++ + +PHONELIBS = ../../../../phonelibs + +UNAME_S := $(shell uname -s) +UNAME_M := $(shell uname -m) + +CFLAGS = -O3 -fPIC -I. +CXXFLAGS = -O3 -fPIC -I. + +QPOASES_FLAGS = -I$(PHONELIBS)/qpoases -I$(PHONELIBS)/qpoases/INCLUDE -I$(PHONELIBS)/qpoases/SRC + +ACADO_FLAGS = -I$(PHONELIBS)/acado/include -I$(PHONELIBS)/acado/include/acado + +ifeq ($(UNAME_S),Darwin) + ACADO_LIBS := -lacado_toolkit_s +else ifeq ($(UNAME_M),aarch64) + ACADO_LIBS := -L $(PHONELIBS)/acado/aarch64/lib -l:libacado_toolkit.a -l:libacado_casadi.a -l:libacado_csparse.a +else + ACADO_LIBS := -L $(PHONELIBS)/acado/x64/lib -l:libacado_toolkit.a -l:libacado_casadi.a -l:libacado_csparse.a +endif + +OBJS = \ + lib_qp/Bounds.o \ + lib_qp/Constraints.o \ + lib_qp/CyclingManager.o \ + lib_qp/Indexlist.o \ + lib_qp/MessageHandling.o \ + lib_qp/QProblem.o \ + lib_qp/QProblemB.o \ + lib_qp/SubjectTo.o \ + lib_qp/Utils.o \ + lib_qp/EXTRAS/SolutionAnalysis.o \ + lib_mpc_export/acado_qpoases_interface.o \ + lib_mpc_export/acado_integrator.o \ + lib_mpc_export/acado_solver.o \ + lib_mpc_export/acado_auxiliary_functions.o \ + lateral_mpc.o + +DEPS := $(OBJS:.o=.d) + +.PHONY: all +all: libmpc.so + +libmpc.so: $(OBJS) + $(CXX) -shared -o '$@' $^ -lm + +lib_qp/%.o: $(PHONELIBS)/qpoases/SRC/%.cpp + @echo "[ CXX ] $@" + mkdir -p lib_qp/EXTRAS + $(CXX) $(CXXFLAGS) -MMD \ + -I lib_mpc_export/ \ + $(QPOASES_FLAGS) \ + -c -o '$@' '$<' + +%.o: %.cpp + @echo "[ CXX ] $@" + $(CXX) $(CXXFLAGS) -MMD \ + -I lib_mpc_export/ \ + $(QPOASES_FLAGS) \ + -c -o '$@' '$<' + +%.o: %.c + @echo "[ CC ] $@" + $(CC) $(CFLAGS) -MMD \ + -I lib_mpc_export/ \ + $(QPOASES_FLAGS) \ + -c -o '$@' '$<' + +generator: generator.cpp + $(CXX) -v -Wall -std=c++11 \ + generator.cpp \ + -o generator \ + $(ACADO_FLAGS) \ + $(ACADO_LIBS) + +.PHONY: generate +generate: generator + ./generator + +.PHONY: clean +clean: + rm -f *.so generator $(OBJS) $(DEPS) + +-include $(DEPS) diff --git a/selfdrive/controls/lib/lateral_mpc/__init__.py b/selfdrive/controls/lib/lateral_mpc/__init__.py new file mode 100644 index 00000000000000..e69de29bb2d1d6 diff --git a/selfdrive/controls/lib/lateral_mpc/generator.cpp b/selfdrive/controls/lib/lateral_mpc/generator.cpp new file mode 100644 index 00000000000000..9af88f9dc8a732 --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc/generator.cpp @@ -0,0 +1,150 @@ +#include + +#define PI 3.1415926536 +#define deg2rad(d) (d/180.0*PI) + +const int controlHorizon = 50; + +using namespace std; + +int main( ) +{ + USING_NAMESPACE_ACADO + + + DifferentialEquation f; + + DifferentialState xx; // x position + DifferentialState yy; // y position + DifferentialState psi; // vehicle heading + DifferentialState delta; + + OnlineData curvature_factor; + OnlineData v_ref; // m/s + OnlineData l_poly_r0, l_poly_r1, l_poly_r2, l_poly_r3; + OnlineData r_poly_r0, r_poly_r1, r_poly_r2, r_poly_r3; + OnlineData p_poly_r0, p_poly_r1, p_poly_r2, p_poly_r3; + OnlineData l_prob, r_prob, p_prob; + OnlineData lane_width; + + Control t; + + // Equations of motion + f << dot(xx) == v_ref * cos(psi); + f << dot(yy) == v_ref * sin(psi); + f << dot(psi) == v_ref * delta * curvature_factor; + f << dot(delta) == t; + + auto lr_prob = l_prob + r_prob - l_prob * r_prob; + + auto poly_l = l_poly_r0*(xx*xx*xx) + l_poly_r1*(xx*xx) + l_poly_r2*xx + l_poly_r3; + auto poly_r = r_poly_r0*(xx*xx*xx) + r_poly_r1*(xx*xx) + r_poly_r2*xx + r_poly_r3; + auto poly_p = p_poly_r0*(xx*xx*xx) + p_poly_r1*(xx*xx) + p_poly_r2*xx + p_poly_r3; + + auto angle_l = atan(3*l_poly_r0*xx*xx + 2*l_poly_r1*xx + l_poly_r2); + auto angle_r = atan(3*r_poly_r0*xx*xx + 2*r_poly_r1*xx + r_poly_r2); + auto angle_p = atan(3*p_poly_r0*xx*xx + 2*p_poly_r1*xx + p_poly_r2); + + // given the lane width estimate, this is where we estimate the path given lane lines + auto l_phantom = poly_l - lane_width/2.0; + auto r_phantom = poly_r + lane_width/2.0; + + // best path estimate path is a linear combination of poly_p and the path estimate + // given the lane lines + auto path = lr_prob * (l_prob * l_phantom + r_prob * r_phantom) / (l_prob + r_prob + 0.0001) + + (1-lr_prob) * poly_p; + + auto angle = lr_prob * (l_prob * angle_l + r_prob * angle_r) / (l_prob + r_prob + 0.0001) + + (1-lr_prob) * angle_p; + + // instead of using actual lane lines, use their estimated distance from path given lane_width + auto c_left_lane = exp(-(path + lane_width/2.0 - yy)); + auto c_right_lane = exp(path - lane_width/2.0 - yy); + + // Running cost + Function h; + + // Distance errors + h << path - yy; + h << lr_prob * c_left_lane; + h << lr_prob * c_right_lane; + + // Heading error + h << (v_ref + 1.0 ) * (angle - psi); + + // Angular rate error + h << (v_ref + 1.0 ) * t; + + BMatrix Q(5,5); Q.setAll(true); + // Q(0,0) = 1.0; + // Q(1,1) = 1.0; + // Q(2,2) = 1.0; + // Q(3,3) = 1.0; + // Q(4,4) = 2.0; + + // Terminal cost + Function hN; + + // Distance errors + hN << path - yy; + hN << l_prob * c_left_lane; + hN << r_prob * c_right_lane; + + // Heading errors + hN << (2.0 * v_ref + 1.0 ) * (angle - psi); + + BMatrix QN(4,4); QN.setAll(true); + // QN(0,0) = 1.0; + // QN(1,1) = 1.0; + // QN(2,2) = 1.0; + // QN(3,3) = 1.0; + + // Non uniform time grid + // First 5 timesteps are 0.05, after that it's 0.15 + DMatrix numSteps(20, 1); + for (int i = 0; i < 5; i++){ + numSteps(i) = 1; + } + for (int i = 5; i < 20; i++){ + numSteps(i) = 3; + } + + // Setup Optimal Control Problem + const double tStart = 0.0; + const double tEnd = 2.5; + + OCP ocp( tStart, tEnd, numSteps); + ocp.subjectTo(f); + + ocp.minimizeLSQ(Q, h); + ocp.minimizeLSQEndTerm(QN, hN); + + // car can't go backward to avoid "circles" + ocp.subjectTo( deg2rad(-90) <= psi <= deg2rad(90)); + // more than absolute max steer angle + ocp.subjectTo( deg2rad(-50) <= delta <= deg2rad(50)); + ocp.setNOD(18); + + OCPexport mpc(ocp); + mpc.set( HESSIAN_APPROXIMATION, GAUSS_NEWTON ); + mpc.set( DISCRETIZATION_TYPE, MULTIPLE_SHOOTING ); + mpc.set( INTEGRATOR_TYPE, INT_RK4 ); + mpc.set( NUM_INTEGRATOR_STEPS, 1 * controlHorizon); + mpc.set( MAX_NUM_QP_ITERATIONS, 500); + mpc.set( CG_USE_VARIABLE_WEIGHTING_MATRIX, YES); + + mpc.set( SPARSE_QP_SOLUTION, CONDENSING ); + mpc.set( QP_SOLVER, QP_QPOASES ); + mpc.set( HOTSTART_QP, YES ); + mpc.set( GENERATE_TEST_FILE, NO); + mpc.set( GENERATE_MAKE_FILE, NO ); + mpc.set( GENERATE_MATLAB_INTERFACE, NO ); + mpc.set( GENERATE_SIMULINK_INTERFACE, NO ); + + if (mpc.exportCode( "lib_mpc_export" ) != SUCCESSFUL_RETURN) + exit( EXIT_FAILURE ); + + mpc.printDimensionsQP( ); + + return EXIT_SUCCESS; +} diff --git a/selfdrive/controls/lib/lateral_mpc/lateral_mpc.c b/selfdrive/controls/lib/lateral_mpc/lateral_mpc.c new file mode 100644 index 00000000000000..f4cee7f2d0a2aa --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc/lateral_mpc.c @@ -0,0 +1,124 @@ +#include "acado_common.h" +#include "acado_auxiliary_functions.h" + +#include + +#define NX ACADO_NX /* Number of differential state variables. */ +#define NXA ACADO_NXA /* Number of algebraic variables. */ +#define NU ACADO_NU /* Number of control inputs. */ +#define NOD ACADO_NOD /* Number of online data values. */ + +#define NY ACADO_NY /* Number of measurements/references on nodes 0..N - 1. */ +#define NYN ACADO_NYN /* Number of measurements/references on node N. */ + +#define N ACADO_N /* Number of intervals in the horizon. */ + +ACADOvariables acadoVariables; +ACADOworkspace acadoWorkspace; + +typedef struct { + double x, y, psi, delta, t; +} state_t; + + +typedef struct { + double x[N+1]; + double y[N+1]; + double psi[N+1]; + double delta[N+1]; + double cost; +} log_t; + +void init(double pathCost, double laneCost, double headingCost, double steerRateCost){ + acado_initializeSolver(); + int i; + const int STEP_MULTIPLIER = 3; + + /* Initialize the states and controls. */ + for (i = 0; i < NX * (N + 1); ++i) acadoVariables.x[ i ] = 0.0; + for (i = 0; i < NU * N; ++i) acadoVariables.u[ i ] = 0.1; + + /* Initialize the measurements/reference. */ + for (i = 0; i < NY * N; ++i) acadoVariables.y[ i ] = 0.0; + for (i = 0; i < NYN; ++i) acadoVariables.yN[ i ] = 0.0; + + /* MPC: initialize the current state feedback. */ + for (i = 0; i < NX; ++i) acadoVariables.x0[ i ] = 0.0; + + for (i = 0; i < N; i++) { + int f = 1; + if (i > 4){ + f = STEP_MULTIPLIER; + } + acadoVariables.W[25 * i + 0] = pathCost * f; + acadoVariables.W[25 * i + 6] = laneCost * f; + acadoVariables.W[25 * i + 12] = laneCost * f; + acadoVariables.W[25 * i + 18] = headingCost * f; + acadoVariables.W[25 * i + 24] = steerRateCost * f; + } + acadoVariables.WN[0] = pathCost * STEP_MULTIPLIER; + acadoVariables.WN[5] = laneCost * STEP_MULTIPLIER; + acadoVariables.WN[10] = laneCost * STEP_MULTIPLIER; + acadoVariables.WN[15] = headingCost * STEP_MULTIPLIER; +} + +int run_mpc(state_t * x0, log_t * solution, + double l_poly[4], double r_poly[4], double p_poly[4], + double l_prob, double r_prob, double p_prob, double curvature_factor, double v_ref, double lane_width){ + + int i; + + for (i = 0; i <= NOD * N; i+= NOD){ + acadoVariables.od[i] = curvature_factor; + acadoVariables.od[i+1] = v_ref; + + acadoVariables.od[i+2] = l_poly[0]; + acadoVariables.od[i+3] = l_poly[1]; + acadoVariables.od[i+4] = l_poly[2]; + acadoVariables.od[i+5] = l_poly[3]; + + acadoVariables.od[i+6] = r_poly[0]; + acadoVariables.od[i+7] = r_poly[1]; + acadoVariables.od[i+8] = r_poly[2]; + acadoVariables.od[i+9] = r_poly[3]; + + acadoVariables.od[i+10] = p_poly[0]; + acadoVariables.od[i+11] = p_poly[1]; + acadoVariables.od[i+12] = p_poly[2]; + acadoVariables.od[i+13] = p_poly[3]; + + + acadoVariables.od[i+14] = l_prob; + acadoVariables.od[i+15] = r_prob; + acadoVariables.od[i+16] = p_prob; + acadoVariables.od[i+17] = lane_width; + + } + + acadoVariables.x0[0] = x0->x; + acadoVariables.x0[1] = x0->y; + acadoVariables.x0[2] = x0->psi; + acadoVariables.x0[3] = x0->delta; + + + acado_preparationStep(); + acado_feedbackStep(); + + /* printf("lat its: %d\n", acado_getNWSR()); // n iterations + printf("Objective: %.6f\n", acado_getObjective()); // solution cost */ + + for (i = 0; i <= N; i++){ + solution->x[i] = acadoVariables.x[i*NX]; + solution->y[i] = acadoVariables.x[i*NX+1]; + solution->psi[i] = acadoVariables.x[i*NX+2]; + solution->delta[i] = acadoVariables.x[i*NX+3]; + } + solution->cost = acado_getObjective(); + + // Dont shift states here. Current solution is closer to next timestep than if + // we use the old solution as a starting point + //acado_shiftStates(2, 0, 0); + //acado_shiftControls( 0 ); + + return acado_getNWSR(); +} diff --git a/selfdrive/controls/lib/lateral_mpc/lateral_mpc.d b/selfdrive/controls/lib/lateral_mpc/lateral_mpc.d new file mode 100644 index 00000000000000..6cac7c2e148128 --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc/lateral_mpc.d @@ -0,0 +1,3 @@ +lateral_mpc.o: lateral_mpc.c lib_mpc_export/acado_common.h \ + lib_mpc_export/acado_qpoases_interface.hpp \ + lib_mpc_export/acado_auxiliary_functions.h diff --git a/selfdrive/controls/lib/lateral_mpc/lateral_mpc.o b/selfdrive/controls/lib/lateral_mpc/lateral_mpc.o new file mode 100644 index 00000000000000..029fda217c0111 Binary files /dev/null and b/selfdrive/controls/lib/lateral_mpc/lateral_mpc.o differ diff --git a/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_auxiliary_functions.c b/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_auxiliary_functions.c new file mode 100644 index 00000000000000..6f0bb705c8a897 --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_auxiliary_functions.c @@ -0,0 +1,212 @@ +/* + * This file was auto-generated using the ACADO Toolkit. + * + * While ACADO Toolkit is free software released under the terms of + * the GNU Lesser General Public License (LGPL), the generated code + * as such remains the property of the user who used ACADO Toolkit + * to generate this code. In particular, user dependent data of the code + * do not inherit the GNU LGPL license. On the other hand, parts of the + * generated code that are a direct copy of source code from the + * ACADO Toolkit or the software tools it is based on, remain, as derived + * work, automatically covered by the LGPL license. + * + * ACADO Toolkit 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. + * + */ + + +#include "acado_auxiliary_functions.h" + +#include + +real_t* acado_getVariablesX( ) +{ + return acadoVariables.x; +} + +real_t* acado_getVariablesU( ) +{ + return acadoVariables.u; +} + +#if ACADO_NY > 0 +real_t* acado_getVariablesY( ) +{ + return acadoVariables.y; +} +#endif + +#if ACADO_NYN > 0 +real_t* acado_getVariablesYN( ) +{ + return acadoVariables.yN; +} +#endif + +real_t* acado_getVariablesX0( ) +{ +#if ACADO_INITIAL_VALUE_FIXED + return acadoVariables.x0; +#else + return 0; +#endif +} + +/** Print differential variables. */ +void acado_printDifferentialVariables( ) +{ + int i, j; + printf("\nDifferential variables:\n[\n"); + for (i = 0; i < ACADO_N + 1; ++i) + { + for (j = 0; j < ACADO_NX; ++j) + printf("\t%e", acadoVariables.x[i * ACADO_NX + j]); + printf("\n"); + } + printf("]\n\n"); +} + +/** Print control variables. */ +void acado_printControlVariables( ) +{ + int i, j; + printf("\nControl variables:\n[\n"); + for (i = 0; i < ACADO_N; ++i) + { + for (j = 0; j < ACADO_NU; ++j) + printf("\t%e", acadoVariables.u[i * ACADO_NU + j]); + printf("\n"); + } + printf("]\n\n"); +} + +/** Print ACADO code generation notice. */ +void acado_printHeader( ) +{ + printf( + "\nACADO Toolkit -- A Toolkit for Automatic Control and Dynamic Optimization.\n" + "Copyright (C) 2008-2015 by Boris Houska, Hans Joachim Ferreau,\n" + "Milan Vukov and Rien Quirynen, KU Leuven.\n" + ); + + printf( + "Developed within the Optimization in Engineering Center (OPTEC) under\n" + "supervision of Moritz Diehl. All rights reserved.\n\n" + "ACADO Toolkit is distributed under the terms of the GNU Lesser\n" + "General Public License 3 in the hope that it will be useful,\n" + "but WITHOUT ANY WARRANTY; without even the implied warranty of\n" + "MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the\n" + "GNU Lesser General Public License for more details.\n\n" + ); +} + +#if !(defined _DSPACE) +#if (defined _WIN32 || defined _WIN64) && !(defined __MINGW32__ || defined __MINGW64__) + +void acado_tic( acado_timer* t ) +{ + QueryPerformanceFrequency(&t->freq); + QueryPerformanceCounter(&t->tic); +} + +real_t acado_toc( acado_timer* t ) +{ + QueryPerformanceCounter(&t->toc); + return ((t->toc.QuadPart - t->tic.QuadPart) / (real_t)t->freq.QuadPart); +} + + +#elif (defined __APPLE__) + +void acado_tic( acado_timer* t ) +{ + /* read current clock cycles */ + t->tic = mach_absolute_time(); +} + +real_t acado_toc( acado_timer* t ) +{ + + uint64_t duration; /* elapsed time in clock cycles*/ + + t->toc = mach_absolute_time(); + duration = t->toc - t->tic; + + /*conversion from clock cycles to nanoseconds*/ + mach_timebase_info(&(t->tinfo)); + duration *= t->tinfo.numer; + duration /= t->tinfo.denom; + + return (real_t)duration / 1e9; +} + +#else + +#if __STDC_VERSION__ >= 199901L +/* C99 mode */ + +/* read current time */ +void acado_tic( acado_timer* t ) +{ + gettimeofday(&t->tic, 0); +} + +/* return time passed since last call to tic on this timer */ +real_t acado_toc( acado_timer* t ) +{ + struct timeval temp; + + gettimeofday(&t->toc, 0); + + if ((t->toc.tv_usec - t->tic.tv_usec) < 0) + { + temp.tv_sec = t->toc.tv_sec - t->tic.tv_sec - 1; + temp.tv_usec = 1000000 + t->toc.tv_usec - t->tic.tv_usec; + } + else + { + temp.tv_sec = t->toc.tv_sec - t->tic.tv_sec; + temp.tv_usec = t->toc.tv_usec - t->tic.tv_usec; + } + + return (real_t)temp.tv_sec + (real_t)temp.tv_usec / 1e6; +} + +#else +/* ANSI */ + +/* read current time */ +void acado_tic( acado_timer* t ) +{ + clock_gettime(CLOCK_MONOTONIC, &t->tic); +} + + +/* return time passed since last call to tic on this timer */ +real_t acado_toc( acado_timer* t ) +{ + struct timespec temp; + + clock_gettime(CLOCK_MONOTONIC, &t->toc); + + if ((t->toc.tv_nsec - t->tic.tv_nsec) < 0) + { + temp.tv_sec = t->toc.tv_sec - t->tic.tv_sec - 1; + temp.tv_nsec = 1000000000+t->toc.tv_nsec - t->tic.tv_nsec; + } + else + { + temp.tv_sec = t->toc.tv_sec - t->tic.tv_sec; + temp.tv_nsec = t->toc.tv_nsec - t->tic.tv_nsec; + } + + return (real_t)temp.tv_sec + (real_t)temp.tv_nsec / 1e9; +} + +#endif /* __STDC_VERSION__ >= 199901L */ + +#endif /* (defined _WIN32 || _WIN64) */ + +#endif diff --git a/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_auxiliary_functions.d b/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_auxiliary_functions.d new file mode 100644 index 00000000000000..50c6a60d1fb846 --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_auxiliary_functions.d @@ -0,0 +1,5 @@ +lib_mpc_export/acado_auxiliary_functions.o: \ + lib_mpc_export/acado_auxiliary_functions.c \ + lib_mpc_export/acado_auxiliary_functions.h \ + lib_mpc_export/acado_common.h \ + lib_mpc_export/acado_qpoases_interface.hpp diff --git a/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_auxiliary_functions.h b/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_auxiliary_functions.h new file mode 100644 index 00000000000000..b1be0a661c0125 --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_auxiliary_functions.h @@ -0,0 +1,138 @@ +/* + * This file was auto-generated using the ACADO Toolkit. + * + * While ACADO Toolkit is free software released under the terms of + * the GNU Lesser General Public License (LGPL), the generated code + * as such remains the property of the user who used ACADO Toolkit + * to generate this code. In particular, user dependent data of the code + * do not inherit the GNU LGPL license. On the other hand, parts of the + * generated code that are a direct copy of source code from the + * ACADO Toolkit or the software tools it is based on, remain, as derived + * work, automatically covered by the LGPL license. + * + * ACADO Toolkit 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. + * + */ + + +#ifndef ACADO_AUXILIARY_FUNCTIONS_H +#define ACADO_AUXILIARY_FUNCTIONS_H + +#include "acado_common.h" + +#ifndef __MATLAB__ +#ifdef __cplusplus +extern "C" +{ +#endif /* __cplusplus */ +#endif /* __MATLAB__ */ + +/** Get pointer to the matrix with differential variables. */ +real_t* acado_getVariablesX( ); + +/** Get pointer to the matrix with control variables. */ +real_t* acado_getVariablesU( ); + +#if ACADO_NY > 0 +/** Get pointer to the matrix with references/measurements. */ +real_t* acado_getVariablesY( ); +#endif + +#if ACADO_NYN > 0 +/** Get pointer to the vector with references/measurement on the last node. */ +real_t* acado_getVariablesYN( ); +#endif + +/** Get pointer to the current state feedback vector. Only applicable for NMPC. */ +real_t* acado_getVariablesX0( ); + +/** Print differential variables. */ +void acado_printDifferentialVariables( ); + +/** Print control variables. */ +void acado_printControlVariables( ); + +/** Print ACADO code generation notice. */ +void acado_printHeader( ); + +/* + * A huge thanks goes to Alexander Domahidi from ETHZ, Switzerland, for + * providing us with the following timing routines. + */ + +#if !(defined _DSPACE) +#if (defined _WIN32 || defined _WIN64) && !(defined __MINGW32__ || defined __MINGW64__) + +/* Use Windows QueryPerformanceCounter for timing. */ +#include + +/** A structure for keeping internal timer data. */ +typedef struct acado_timer_ +{ + LARGE_INTEGER tic; + LARGE_INTEGER toc; + LARGE_INTEGER freq; +} acado_timer; + + +#elif (defined __APPLE__) + +#include "unistd.h" +#include + +/** A structure for keeping internal timer data. */ +typedef struct acado_timer_ +{ + uint64_t tic; + uint64_t toc; + mach_timebase_info_data_t tinfo; +} acado_timer; + +#else + +/* Use POSIX clock_gettime() for timing on non-Windows machines. */ +#include + +#if __STDC_VERSION__ >= 199901L +/* C99 mode of operation. */ + +#include +#include + +typedef struct acado_timer_ +{ + struct timeval tic; + struct timeval toc; +} acado_timer; + +#else +/* ANSI C */ + +/** A structure for keeping internal timer data. */ +typedef struct acado_timer_ +{ + struct timespec tic; + struct timespec toc; +} acado_timer; + +#endif /* __STDC_VERSION__ >= 199901L */ + +#endif /* (defined _WIN32 || defined _WIN64) */ + +/** A function for measurement of the current time. */ +void acado_tic( acado_timer* t ); + +/** A function which returns the elapsed time. */ +real_t acado_toc( acado_timer* t ); + +#endif + +#ifndef __MATLAB__ +#ifdef __cplusplus +} /* extern "C" */ +#endif /* __cplusplus */ +#endif /* __MATLAB__ */ + +#endif /* ACADO_AUXILIARY_FUNCTIONS_H */ diff --git a/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_auxiliary_functions.o b/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_auxiliary_functions.o new file mode 100644 index 00000000000000..07d92429b217f2 Binary files /dev/null and b/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_auxiliary_functions.o differ diff --git a/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_common.h b/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_common.h new file mode 100644 index 00000000000000..d5b56727707ff0 --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_common.h @@ -0,0 +1,357 @@ +/* + * This file was auto-generated using the ACADO Toolkit. + * + * While ACADO Toolkit is free software released under the terms of + * the GNU Lesser General Public License (LGPL), the generated code + * as such remains the property of the user who used ACADO Toolkit + * to generate this code. In particular, user dependent data of the code + * do not inherit the GNU LGPL license. On the other hand, parts of the + * generated code that are a direct copy of source code from the + * ACADO Toolkit or the software tools it is based on, remain, as derived + * work, automatically covered by the LGPL license. + * + * ACADO Toolkit 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. + * + */ + + +#ifndef ACADO_COMMON_H +#define ACADO_COMMON_H + +#include +#include + +#ifndef __MATLAB__ +#ifdef __cplusplus +extern "C" +{ +#endif /* __cplusplus */ +#endif /* __MATLAB__ */ + +/** \defgroup ACADO ACADO CGT generated module. */ +/** @{ */ + +/** qpOASES QP solver indicator. */ +#define ACADO_QPOASES 0 +#define ACADO_QPOASES3 1 +/** FORCES QP solver indicator.*/ +#define ACADO_FORCES 2 +/** qpDUNES QP solver indicator.*/ +#define ACADO_QPDUNES 3 +/** HPMPC QP solver indicator. */ +#define ACADO_HPMPC 4 +#define ACADO_GENERIC 5 + +/** Indicator for determining the QP solver used by the ACADO solver code. */ +#define ACADO_QP_SOLVER ACADO_QPOASES + +#include "acado_qpoases_interface.hpp" + + +/* + * Common definitions + */ +/** User defined block based condensing. */ +#define ACADO_BLOCK_CONDENSING 0 +/** Compute covariance matrix of the last state estimate. */ +#define ACADO_COMPUTE_COVARIANCE_MATRIX 0 +/** Flag indicating whether constraint values are hard-coded or not. */ +#define ACADO_HARDCODED_CONSTRAINT_VALUES 1 +/** Indicator for fixed initial state. */ +#define ACADO_INITIAL_STATE_FIXED 1 +/** Number of control/estimation intervals. */ +#define ACADO_N 20 +/** Number of online data values. */ +#define ACADO_NOD 18 +/** Number of path constraints. */ +#define ACADO_NPAC 0 +/** Number of control variables. */ +#define ACADO_NU 1 +/** Number of differential variables. */ +#define ACADO_NX 4 +/** Number of algebraic variables. */ +#define ACADO_NXA 0 +/** Number of differential derivative variables. */ +#define ACADO_NXD 0 +/** Number of references/measurements per node on the first N nodes. */ +#define ACADO_NY 5 +/** Number of references/measurements on the last (N + 1)st node. */ +#define ACADO_NYN 4 +/** Total number of QP optimization variables. */ +#define ACADO_QP_NV 24 +/** Number of Runge-Kutta stages per integration step. */ +#define ACADO_RK_NSTAGES 4 +/** Providing interface for arrival cost. */ +#define ACADO_USE_ARRIVAL_COST 0 +/** Indicator for usage of non-hard-coded linear terms in the objective. */ +#define ACADO_USE_LINEAR_TERMS 0 +/** Indicator for type of fixed weighting matrices. */ +#define ACADO_WEIGHTING_MATRICES_TYPE 2 + + +/* + * Globally used structure definitions + */ + +/** The structure containing the user data. + * + * Via this structure the user "communicates" with the solver code. + */ +typedef struct ACADOvariables_ +{ +int dummy; +/** Matrix of size: 21 x 4 (row major format) + * + * Matrix containing 21 differential variable vectors. + */ +real_t x[ 84 ]; + +/** Column vector of size: 20 + * + * Matrix containing 20 control variable vectors. + */ +real_t u[ 20 ]; + +/** Matrix of size: 21 x 18 (row major format) + * + * Matrix containing 21 online data vectors. + */ +real_t od[ 378 ]; + +/** Column vector of size: 100 + * + * Matrix containing 20 reference/measurement vectors of size 5 for first 20 nodes. + */ +real_t y[ 100 ]; + +/** Column vector of size: 4 + * + * Reference/measurement vector for the 21. node. + */ +real_t yN[ 4 ]; + +/** Matrix of size: 100 x 5 (row major format) */ +real_t W[ 500 ]; + +/** Matrix of size: 4 x 4 (row major format) */ +real_t WN[ 16 ]; + +/** Column vector of size: 4 + * + * Current state feedback vector. + */ +real_t x0[ 4 ]; + + +} ACADOvariables; + +/** Private workspace used by the auto-generated code. + * + * Data members of this structure are private to the solver. + * In other words, the user code should not modify values of this + * structure. + */ +typedef struct ACADOworkspace_ +{ +/** Column vector of size: 14 */ +real_t rhs_aux[ 14 ]; + +real_t rk_ttt; + +/** Row vector of size: 43 */ +real_t rk_xxx[ 43 ]; + +/** Matrix of size: 4 x 24 (row major format) */ +real_t rk_kkk[ 96 ]; + +/** Row vector of size: 43 */ +real_t state[ 43 ]; + +/** Column vector of size: 80 */ +real_t d[ 80 ]; + +/** Column vector of size: 100 */ +real_t Dy[ 100 ]; + +/** Column vector of size: 4 */ +real_t DyN[ 4 ]; + +/** Matrix of size: 80 x 4 (row major format) */ +real_t evGx[ 320 ]; + +/** Column vector of size: 80 */ +real_t evGu[ 80 ]; + +/** Column vector of size: 21 */ +real_t objAuxVar[ 21 ]; + +/** Row vector of size: 23 */ +real_t objValueIn[ 23 ]; + +/** Row vector of size: 30 */ +real_t objValueOut[ 30 ]; + +/** Matrix of size: 80 x 4 (row major format) */ +real_t Q1[ 320 ]; + +/** Matrix of size: 80 x 5 (row major format) */ +real_t Q2[ 400 ]; + +/** Column vector of size: 20 */ +real_t R1[ 20 ]; + +/** Matrix of size: 20 x 5 (row major format) */ +real_t R2[ 100 ]; + +/** Column vector of size: 80 */ +real_t S1[ 80 ]; + +/** Matrix of size: 4 x 4 (row major format) */ +real_t QN1[ 16 ]; + +/** Matrix of size: 4 x 4 (row major format) */ +real_t QN2[ 16 ]; + +/** Column vector of size: 4 */ +real_t Dx0[ 4 ]; + +/** Matrix of size: 4 x 4 (row major format) */ +real_t T[ 16 ]; + +/** Column vector of size: 840 */ +real_t E[ 840 ]; + +/** Column vector of size: 840 */ +real_t QE[ 840 ]; + +/** Matrix of size: 80 x 4 (row major format) */ +real_t QGx[ 320 ]; + +/** Column vector of size: 80 */ +real_t Qd[ 80 ]; + +/** Column vector of size: 84 */ +real_t QDy[ 84 ]; + +/** Matrix of size: 20 x 4 (row major format) */ +real_t H10[ 80 ]; + +/** Matrix of size: 24 x 24 (row major format) */ +real_t H[ 576 ]; + +/** Matrix of size: 40 x 24 (row major format) */ +real_t A[ 960 ]; + +/** Column vector of size: 24 */ +real_t g[ 24 ]; + +/** Column vector of size: 24 */ +real_t lb[ 24 ]; + +/** Column vector of size: 24 */ +real_t ub[ 24 ]; + +/** Column vector of size: 40 */ +real_t lbA[ 40 ]; + +/** Column vector of size: 40 */ +real_t ubA[ 40 ]; + +/** Column vector of size: 24 */ +real_t x[ 24 ]; + +/** Column vector of size: 64 */ +real_t y[ 64 ]; + + +} ACADOworkspace; + +/* + * Forward function declarations. + */ + + +/** Performs the integration and sensitivity propagation for one shooting interval. + * + * \param rk_eta Working array to pass the input values and return the results. + * \param resetIntegrator The internal memory of the integrator can be reset. + * \param rk_index Number of the shooting interval. + * + * \return Status code of the integrator. + */ +int acado_integrate( real_t* const rk_eta, int resetIntegrator, int rk_index ); + +/** Export of an ACADO symbolic function. + * + * \param in Input to the exported function. + * \param out Output of the exported function. + */ +void acado_rhs_forw(const real_t* in, real_t* out); + +/** Preparation step of the RTI scheme. + * + * \return Status of the integration module. =0: OK, otherwise the error code. + */ +int acado_preparationStep( ); + +/** Feedback/estimation step of the RTI scheme. + * + * \return Status code of the qpOASES QP solver. + */ +int acado_feedbackStep( ); + +/** Solver initialization. Must be called once before any other function call. + * + * \return =0: OK, otherwise an error code of a QP solver. + */ +int acado_initializeSolver( ); + +/** Initialize shooting nodes by a forward simulation starting from the first node. + */ +void acado_initializeNodesByForwardSimulation( ); + +/** Shift differential variables vector by one interval. + * + * \param strategy Shifting strategy: 1. Initialize node 21 with xEnd. 2. Initialize node 21 by forward simulation. + * \param xEnd Value for the x vector on the last node. If =0 the old value is used. + * \param uEnd Value for the u vector on the second to last node. If =0 the old value is used. + */ +void acado_shiftStates( int strategy, real_t* const xEnd, real_t* const uEnd ); + +/** Shift controls vector by one interval. + * + * \param uEnd Value for the u vector on the second to last node. If =0 the old value is used. + */ +void acado_shiftControls( real_t* const uEnd ); + +/** Get the KKT tolerance of the current iterate. + * + * \return The KKT tolerance value. + */ +real_t acado_getKKT( ); + +/** Calculate the objective value. + * + * \return Value of the objective function. + */ +real_t acado_getObjective( ); + + +/* + * Extern declarations. + */ + +extern ACADOworkspace acadoWorkspace; +extern ACADOvariables acadoVariables; + +/** @} */ + +#ifndef __MATLAB__ +#ifdef __cplusplus +} /* extern "C" */ +#endif /* __cplusplus */ +#endif /* __MATLAB__ */ + +#endif /* ACADO_COMMON_H */ diff --git a/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_integrator.c b/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_integrator.c new file mode 100644 index 00000000000000..b931088991a33d --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_integrator.c @@ -0,0 +1,256 @@ +/* + * This file was auto-generated using the ACADO Toolkit. + * + * While ACADO Toolkit is free software released under the terms of + * the GNU Lesser General Public License (LGPL), the generated code + * as such remains the property of the user who used ACADO Toolkit + * to generate this code. In particular, user dependent data of the code + * do not inherit the GNU LGPL license. On the other hand, parts of the + * generated code that are a direct copy of source code from the + * ACADO Toolkit or the software tools it is based on, remain, as derived + * work, automatically covered by the LGPL license. + * + * ACADO Toolkit 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. + * + */ + + +#include "acado_common.h" + + +void acado_rhs_forw(const real_t* in, real_t* out) +{ +const real_t* xd = in; +const real_t* u = in + 24; +const real_t* od = in + 25; +/* Vector of auxiliary variables; number of elements: 14. */ +real_t* a = acadoWorkspace.rhs_aux; + +/* Compute intermediate quantities: */ +a[0] = (cos(xd[2])); +a[1] = (sin(xd[2])); +a[2] = ((real_t)(-1.0000000000000000e+00)*(sin(xd[2]))); +a[3] = (xd[12]*a[2]); +a[4] = (xd[13]*a[2]); +a[5] = (xd[14]*a[2]); +a[6] = (xd[15]*a[2]); +a[7] = (cos(xd[2])); +a[8] = (xd[12]*a[7]); +a[9] = (xd[13]*a[7]); +a[10] = (xd[14]*a[7]); +a[11] = (xd[15]*a[7]); +a[12] = (xd[22]*a[2]); +a[13] = (xd[22]*a[7]); + +/* Compute outputs: */ +out[0] = (od[1]*a[0]); +out[1] = (od[1]*a[1]); +out[2] = ((od[1]*xd[3])*od[0]); +out[3] = u[0]; +out[4] = (od[1]*a[3]); +out[5] = (od[1]*a[4]); +out[6] = (od[1]*a[5]); +out[7] = (od[1]*a[6]); +out[8] = (od[1]*a[8]); +out[9] = (od[1]*a[9]); +out[10] = (od[1]*a[10]); +out[11] = (od[1]*a[11]); +out[12] = ((od[1]*xd[16])*od[0]); +out[13] = ((od[1]*xd[17])*od[0]); +out[14] = ((od[1]*xd[18])*od[0]); +out[15] = ((od[1]*xd[19])*od[0]); +out[16] = (real_t)(0.0000000000000000e+00); +out[17] = (real_t)(0.0000000000000000e+00); +out[18] = (real_t)(0.0000000000000000e+00); +out[19] = (real_t)(0.0000000000000000e+00); +out[20] = (od[1]*a[12]); +out[21] = (od[1]*a[13]); +out[22] = ((od[1]*xd[23])*od[0]); +out[23] = (real_t)(1.0000000000000000e+00); +} + +/* Fixed step size:0.05 */ +int acado_integrate( real_t* const rk_eta, int resetIntegrator, int rk_index ) +{ +int error; + +int run1; +int numSteps[20] = {1, 1, 1, 1, 1, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3}; +int numInts = numSteps[rk_index]; +acadoWorkspace.rk_ttt = 0.0000000000000000e+00; +rk_eta[4] = 1.0000000000000000e+00; +rk_eta[5] = 0.0000000000000000e+00; +rk_eta[6] = 0.0000000000000000e+00; +rk_eta[7] = 0.0000000000000000e+00; +rk_eta[8] = 0.0000000000000000e+00; +rk_eta[9] = 1.0000000000000000e+00; +rk_eta[10] = 0.0000000000000000e+00; +rk_eta[11] = 0.0000000000000000e+00; +rk_eta[12] = 0.0000000000000000e+00; +rk_eta[13] = 0.0000000000000000e+00; +rk_eta[14] = 1.0000000000000000e+00; +rk_eta[15] = 0.0000000000000000e+00; +rk_eta[16] = 0.0000000000000000e+00; +rk_eta[17] = 0.0000000000000000e+00; +rk_eta[18] = 0.0000000000000000e+00; +rk_eta[19] = 1.0000000000000000e+00; +rk_eta[20] = 0.0000000000000000e+00; +rk_eta[21] = 0.0000000000000000e+00; +rk_eta[22] = 0.0000000000000000e+00; +rk_eta[23] = 0.0000000000000000e+00; +acadoWorkspace.rk_xxx[24] = rk_eta[24]; +acadoWorkspace.rk_xxx[25] = rk_eta[25]; +acadoWorkspace.rk_xxx[26] = rk_eta[26]; +acadoWorkspace.rk_xxx[27] = rk_eta[27]; +acadoWorkspace.rk_xxx[28] = rk_eta[28]; +acadoWorkspace.rk_xxx[29] = rk_eta[29]; +acadoWorkspace.rk_xxx[30] = rk_eta[30]; +acadoWorkspace.rk_xxx[31] = rk_eta[31]; +acadoWorkspace.rk_xxx[32] = rk_eta[32]; +acadoWorkspace.rk_xxx[33] = rk_eta[33]; +acadoWorkspace.rk_xxx[34] = rk_eta[34]; +acadoWorkspace.rk_xxx[35] = rk_eta[35]; +acadoWorkspace.rk_xxx[36] = rk_eta[36]; +acadoWorkspace.rk_xxx[37] = rk_eta[37]; +acadoWorkspace.rk_xxx[38] = rk_eta[38]; +acadoWorkspace.rk_xxx[39] = rk_eta[39]; +acadoWorkspace.rk_xxx[40] = rk_eta[40]; +acadoWorkspace.rk_xxx[41] = rk_eta[41]; +acadoWorkspace.rk_xxx[42] = rk_eta[42]; + +for (run1 = 0; run1 < 1; ++run1) +{ +for(run1 = 0; run1 < numInts; run1++ ) { +acadoWorkspace.rk_xxx[0] = + rk_eta[0]; +acadoWorkspace.rk_xxx[1] = + rk_eta[1]; +acadoWorkspace.rk_xxx[2] = + rk_eta[2]; +acadoWorkspace.rk_xxx[3] = + rk_eta[3]; +acadoWorkspace.rk_xxx[4] = + rk_eta[4]; +acadoWorkspace.rk_xxx[5] = + rk_eta[5]; +acadoWorkspace.rk_xxx[6] = + rk_eta[6]; +acadoWorkspace.rk_xxx[7] = + rk_eta[7]; +acadoWorkspace.rk_xxx[8] = + rk_eta[8]; +acadoWorkspace.rk_xxx[9] = + rk_eta[9]; +acadoWorkspace.rk_xxx[10] = + rk_eta[10]; +acadoWorkspace.rk_xxx[11] = + rk_eta[11]; +acadoWorkspace.rk_xxx[12] = + rk_eta[12]; +acadoWorkspace.rk_xxx[13] = + rk_eta[13]; +acadoWorkspace.rk_xxx[14] = + rk_eta[14]; +acadoWorkspace.rk_xxx[15] = + rk_eta[15]; +acadoWorkspace.rk_xxx[16] = + rk_eta[16]; +acadoWorkspace.rk_xxx[17] = + rk_eta[17]; +acadoWorkspace.rk_xxx[18] = + rk_eta[18]; +acadoWorkspace.rk_xxx[19] = + rk_eta[19]; +acadoWorkspace.rk_xxx[20] = + rk_eta[20]; +acadoWorkspace.rk_xxx[21] = + rk_eta[21]; +acadoWorkspace.rk_xxx[22] = + rk_eta[22]; +acadoWorkspace.rk_xxx[23] = + rk_eta[23]; +acado_rhs_forw( acadoWorkspace.rk_xxx, acadoWorkspace.rk_kkk ); +acadoWorkspace.rk_xxx[0] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[0] + rk_eta[0]; +acadoWorkspace.rk_xxx[1] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[1] + rk_eta[1]; +acadoWorkspace.rk_xxx[2] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[2] + rk_eta[2]; +acadoWorkspace.rk_xxx[3] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[3] + rk_eta[3]; +acadoWorkspace.rk_xxx[4] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[4] + rk_eta[4]; +acadoWorkspace.rk_xxx[5] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[5] + rk_eta[5]; +acadoWorkspace.rk_xxx[6] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[6] + rk_eta[6]; +acadoWorkspace.rk_xxx[7] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[7] + rk_eta[7]; +acadoWorkspace.rk_xxx[8] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[8] + rk_eta[8]; +acadoWorkspace.rk_xxx[9] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[9] + rk_eta[9]; +acadoWorkspace.rk_xxx[10] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[10] + rk_eta[10]; +acadoWorkspace.rk_xxx[11] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[11] + rk_eta[11]; +acadoWorkspace.rk_xxx[12] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[12] + rk_eta[12]; +acadoWorkspace.rk_xxx[13] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[13] + rk_eta[13]; +acadoWorkspace.rk_xxx[14] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[14] + rk_eta[14]; +acadoWorkspace.rk_xxx[15] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[15] + rk_eta[15]; +acadoWorkspace.rk_xxx[16] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[16] + rk_eta[16]; +acadoWorkspace.rk_xxx[17] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[17] + rk_eta[17]; +acadoWorkspace.rk_xxx[18] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[18] + rk_eta[18]; +acadoWorkspace.rk_xxx[19] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[19] + rk_eta[19]; +acadoWorkspace.rk_xxx[20] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[20] + rk_eta[20]; +acadoWorkspace.rk_xxx[21] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[21] + rk_eta[21]; +acadoWorkspace.rk_xxx[22] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[22] + rk_eta[22]; +acadoWorkspace.rk_xxx[23] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[23] + rk_eta[23]; +acado_rhs_forw( acadoWorkspace.rk_xxx, &(acadoWorkspace.rk_kkk[ 24 ]) ); +acadoWorkspace.rk_xxx[0] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[24] + rk_eta[0]; +acadoWorkspace.rk_xxx[1] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[25] + rk_eta[1]; +acadoWorkspace.rk_xxx[2] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[26] + rk_eta[2]; +acadoWorkspace.rk_xxx[3] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[27] + rk_eta[3]; +acadoWorkspace.rk_xxx[4] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[28] + rk_eta[4]; +acadoWorkspace.rk_xxx[5] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[29] + rk_eta[5]; +acadoWorkspace.rk_xxx[6] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[30] + rk_eta[6]; +acadoWorkspace.rk_xxx[7] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[31] + rk_eta[7]; +acadoWorkspace.rk_xxx[8] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[32] + rk_eta[8]; +acadoWorkspace.rk_xxx[9] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[33] + rk_eta[9]; +acadoWorkspace.rk_xxx[10] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[34] + rk_eta[10]; +acadoWorkspace.rk_xxx[11] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[35] + rk_eta[11]; +acadoWorkspace.rk_xxx[12] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[36] + rk_eta[12]; +acadoWorkspace.rk_xxx[13] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[37] + rk_eta[13]; +acadoWorkspace.rk_xxx[14] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[38] + rk_eta[14]; +acadoWorkspace.rk_xxx[15] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[39] + rk_eta[15]; +acadoWorkspace.rk_xxx[16] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[40] + rk_eta[16]; +acadoWorkspace.rk_xxx[17] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[41] + rk_eta[17]; +acadoWorkspace.rk_xxx[18] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[42] + rk_eta[18]; +acadoWorkspace.rk_xxx[19] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[43] + rk_eta[19]; +acadoWorkspace.rk_xxx[20] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[44] + rk_eta[20]; +acadoWorkspace.rk_xxx[21] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[45] + rk_eta[21]; +acadoWorkspace.rk_xxx[22] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[46] + rk_eta[22]; +acadoWorkspace.rk_xxx[23] = + (real_t)2.4999999999999991e-02*acadoWorkspace.rk_kkk[47] + rk_eta[23]; +acado_rhs_forw( acadoWorkspace.rk_xxx, &(acadoWorkspace.rk_kkk[ 48 ]) ); +acadoWorkspace.rk_xxx[0] = + (real_t)4.9999999999999982e-02*acadoWorkspace.rk_kkk[48] + rk_eta[0]; +acadoWorkspace.rk_xxx[1] = + (real_t)4.9999999999999982e-02*acadoWorkspace.rk_kkk[49] + rk_eta[1]; +acadoWorkspace.rk_xxx[2] = + (real_t)4.9999999999999982e-02*acadoWorkspace.rk_kkk[50] + rk_eta[2]; +acadoWorkspace.rk_xxx[3] = + (real_t)4.9999999999999982e-02*acadoWorkspace.rk_kkk[51] + rk_eta[3]; +acadoWorkspace.rk_xxx[4] = + (real_t)4.9999999999999982e-02*acadoWorkspace.rk_kkk[52] + rk_eta[4]; +acadoWorkspace.rk_xxx[5] = + (real_t)4.9999999999999982e-02*acadoWorkspace.rk_kkk[53] + rk_eta[5]; +acadoWorkspace.rk_xxx[6] = + (real_t)4.9999999999999982e-02*acadoWorkspace.rk_kkk[54] + rk_eta[6]; +acadoWorkspace.rk_xxx[7] = + (real_t)4.9999999999999982e-02*acadoWorkspace.rk_kkk[55] + rk_eta[7]; +acadoWorkspace.rk_xxx[8] = + (real_t)4.9999999999999982e-02*acadoWorkspace.rk_kkk[56] + rk_eta[8]; +acadoWorkspace.rk_xxx[9] = + (real_t)4.9999999999999982e-02*acadoWorkspace.rk_kkk[57] + rk_eta[9]; +acadoWorkspace.rk_xxx[10] = + (real_t)4.9999999999999982e-02*acadoWorkspace.rk_kkk[58] + rk_eta[10]; +acadoWorkspace.rk_xxx[11] = + (real_t)4.9999999999999982e-02*acadoWorkspace.rk_kkk[59] + rk_eta[11]; +acadoWorkspace.rk_xxx[12] = + (real_t)4.9999999999999982e-02*acadoWorkspace.rk_kkk[60] + rk_eta[12]; +acadoWorkspace.rk_xxx[13] = + (real_t)4.9999999999999982e-02*acadoWorkspace.rk_kkk[61] + rk_eta[13]; +acadoWorkspace.rk_xxx[14] = + (real_t)4.9999999999999982e-02*acadoWorkspace.rk_kkk[62] + rk_eta[14]; +acadoWorkspace.rk_xxx[15] = + (real_t)4.9999999999999982e-02*acadoWorkspace.rk_kkk[63] + rk_eta[15]; +acadoWorkspace.rk_xxx[16] = + (real_t)4.9999999999999982e-02*acadoWorkspace.rk_kkk[64] + rk_eta[16]; +acadoWorkspace.rk_xxx[17] = + (real_t)4.9999999999999982e-02*acadoWorkspace.rk_kkk[65] + rk_eta[17]; +acadoWorkspace.rk_xxx[18] = + (real_t)4.9999999999999982e-02*acadoWorkspace.rk_kkk[66] + rk_eta[18]; +acadoWorkspace.rk_xxx[19] = + (real_t)4.9999999999999982e-02*acadoWorkspace.rk_kkk[67] + rk_eta[19]; +acadoWorkspace.rk_xxx[20] = + (real_t)4.9999999999999982e-02*acadoWorkspace.rk_kkk[68] + rk_eta[20]; +acadoWorkspace.rk_xxx[21] = + (real_t)4.9999999999999982e-02*acadoWorkspace.rk_kkk[69] + rk_eta[21]; +acadoWorkspace.rk_xxx[22] = + (real_t)4.9999999999999982e-02*acadoWorkspace.rk_kkk[70] + rk_eta[22]; +acadoWorkspace.rk_xxx[23] = + (real_t)4.9999999999999982e-02*acadoWorkspace.rk_kkk[71] + rk_eta[23]; +acado_rhs_forw( acadoWorkspace.rk_xxx, &(acadoWorkspace.rk_kkk[ 72 ]) ); +rk_eta[0] += + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[0] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[24] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[48] + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[72]; +rk_eta[1] += + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[1] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[25] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[49] + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[73]; +rk_eta[2] += + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[2] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[26] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[50] + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[74]; +rk_eta[3] += + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[3] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[27] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[51] + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[75]; +rk_eta[4] += + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[4] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[28] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[52] + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[76]; +rk_eta[5] += + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[5] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[29] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[53] + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[77]; +rk_eta[6] += + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[6] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[30] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[54] + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[78]; +rk_eta[7] += + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[7] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[31] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[55] + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[79]; +rk_eta[8] += + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[8] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[32] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[56] + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[80]; +rk_eta[9] += + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[9] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[33] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[57] + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[81]; +rk_eta[10] += + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[10] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[34] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[58] + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[82]; +rk_eta[11] += + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[11] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[35] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[59] + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[83]; +rk_eta[12] += + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[12] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[36] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[60] + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[84]; +rk_eta[13] += + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[13] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[37] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[61] + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[85]; +rk_eta[14] += + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[14] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[38] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[62] + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[86]; +rk_eta[15] += + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[15] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[39] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[63] + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[87]; +rk_eta[16] += + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[16] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[40] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[64] + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[88]; +rk_eta[17] += + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[17] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[41] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[65] + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[89]; +rk_eta[18] += + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[18] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[42] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[66] + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[90]; +rk_eta[19] += + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[19] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[43] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[67] + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[91]; +rk_eta[20] += + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[20] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[44] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[68] + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[92]; +rk_eta[21] += + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[21] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[45] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[69] + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[93]; +rk_eta[22] += + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[22] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[46] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[70] + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[94]; +rk_eta[23] += + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[23] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[47] + (real_t)1.6666666666666659e-02*acadoWorkspace.rk_kkk[71] + (real_t)8.3333333333333297e-03*acadoWorkspace.rk_kkk[95]; +acadoWorkspace.rk_ttt += 1.0000000000000000e+00; +} +} +error = 0; +return error; +} + diff --git a/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_integrator.d b/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_integrator.d new file mode 100644 index 00000000000000..7c057e5ec0f3a9 --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_integrator.d @@ -0,0 +1,3 @@ +lib_mpc_export/acado_integrator.o: lib_mpc_export/acado_integrator.c \ + lib_mpc_export/acado_common.h \ + lib_mpc_export/acado_qpoases_interface.hpp diff --git a/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_integrator.o b/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_integrator.o new file mode 100644 index 00000000000000..d08f1e41279bb7 Binary files /dev/null and b/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_integrator.o differ diff --git a/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_qpoases_interface.cpp b/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_qpoases_interface.cpp new file mode 100644 index 00000000000000..f2665a45c09b39 --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_qpoases_interface.cpp @@ -0,0 +1,70 @@ +/* + * This file was auto-generated using the ACADO Toolkit. + * + * While ACADO Toolkit is free software released under the terms of + * the GNU Lesser General Public License (LGPL), the generated code + * as such remains the property of the user who used ACADO Toolkit + * to generate this code. In particular, user dependent data of the code + * do not inherit the GNU LGPL license. On the other hand, parts of the + * generated code that are a direct copy of source code from the + * ACADO Toolkit or the software tools it is based on, remain, as derived + * work, automatically covered by the LGPL license. + * + * ACADO Toolkit 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. + * + */ + + +extern "C" +{ +#include "acado_common.h" +} + +#include "INCLUDE/QProblem.hpp" + +#if ACADO_COMPUTE_COVARIANCE_MATRIX == 1 +#include "INCLUDE/EXTRAS/SolutionAnalysis.hpp" +#endif /* ACADO_COMPUTE_COVARIANCE_MATRIX */ + +static int acado_nWSR; + + + +#if ACADO_COMPUTE_COVARIANCE_MATRIX == 1 +static SolutionAnalysis acado_sa; +#endif /* ACADO_COMPUTE_COVARIANCE_MATRIX */ + +int acado_solve( void ) +{ + acado_nWSR = QPOASES_NWSRMAX; + + QProblem qp(24, 40); + + returnValue retVal = qp.init(acadoWorkspace.H, acadoWorkspace.g, acadoWorkspace.A, acadoWorkspace.lb, acadoWorkspace.ub, acadoWorkspace.lbA, acadoWorkspace.ubA, acado_nWSR, acadoWorkspace.y); + + qp.getPrimalSolution( acadoWorkspace.x ); + qp.getDualSolution( acadoWorkspace.y ); + +#if ACADO_COMPUTE_COVARIANCE_MATRIX == 1 + + if (retVal != SUCCESSFUL_RETURN) + return (int)retVal; + + retVal = acado_sa.getHessianInverse( &qp,var ); + +#endif /* ACADO_COMPUTE_COVARIANCE_MATRIX */ + + return (int)retVal; +} + +int acado_getNWSR( void ) +{ + return acado_nWSR; +} + +const char* acado_getErrorString( int error ) +{ + return MessageHandling::getErrorString( error ); +} diff --git a/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_qpoases_interface.d b/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_qpoases_interface.d new file mode 100644 index 00000000000000..ba3c6ef1c831b7 --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_qpoases_interface.d @@ -0,0 +1,24 @@ +lib_mpc_export/acado_qpoases_interface.o: \ + lib_mpc_export/acado_qpoases_interface.cpp \ + lib_mpc_export/acado_common.h \ + lib_mpc_export/acado_qpoases_interface.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/QProblem.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/QProblemB.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Bounds.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/SubjectTo.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Indexlist.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Utils.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/MessageHandling.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Types.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Constants.hpp \ + ../../../../phonelibs/qpoases/SRC/MessageHandling.ipp \ + ../../../../phonelibs/qpoases/SRC/Utils.ipp \ + ../../../../phonelibs/qpoases/SRC/Indexlist.ipp \ + ../../../../phonelibs/qpoases/SRC/SubjectTo.ipp \ + ../../../../phonelibs/qpoases/SRC/Bounds.ipp \ + ../../../../phonelibs/qpoases/SRC/QProblemB.ipp \ + ../../../../phonelibs/qpoases/INCLUDE/Constraints.hpp \ + ../../../../phonelibs/qpoases/SRC/Constraints.ipp \ + ../../../../phonelibs/qpoases/INCLUDE/CyclingManager.hpp \ + ../../../../phonelibs/qpoases/SRC/CyclingManager.ipp \ + ../../../../phonelibs/qpoases/SRC/QProblem.ipp diff --git a/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_qpoases_interface.hpp b/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_qpoases_interface.hpp new file mode 100644 index 00000000000000..47d41855e6fe89 --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_qpoases_interface.hpp @@ -0,0 +1,65 @@ +/* + * This file was auto-generated using the ACADO Toolkit. + * + * While ACADO Toolkit is free software released under the terms of + * the GNU Lesser General Public License (LGPL), the generated code + * as such remains the property of the user who used ACADO Toolkit + * to generate this code. In particular, user dependent data of the code + * do not inherit the GNU LGPL license. On the other hand, parts of the + * generated code that are a direct copy of source code from the + * ACADO Toolkit or the software tools it is based on, remain, as derived + * work, automatically covered by the LGPL license. + * + * ACADO Toolkit 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. + * + */ + + +#ifndef QPOASES_HEADER +#define QPOASES_HEADER + +#ifdef PC_DEBUG +#include +#endif /* PC_DEBUG */ + +#include + +#ifdef __cplusplus +#define EXTERNC extern "C" +#else +#define EXTERNC +#endif + +/* + * A set of options for qpOASES + */ + +/** Maximum number of optimization variables. */ +#define QPOASES_NVMAX 24 +/** Maximum number of constraints. */ +#define QPOASES_NCMAX 40 +/** Maximum number of working set recalculations. */ +#define QPOASES_NWSRMAX 500 +/** Print level for qpOASES. */ +#define QPOASES_PRINTLEVEL PL_NONE +/** The value of EPS */ +#define QPOASES_EPS 2.221e-16 +/** Internally used floating point type */ +typedef double real_t; + +/* + * Forward function declarations + */ + +/** A function that calls the QP solver */ +EXTERNC int acado_solve( void ); + +/** Get the number of active set changes */ +EXTERNC int acado_getNWSR( void ); + +/** Get the error string. */ +const char* acado_getErrorString( int error ); + +#endif /* QPOASES_HEADER */ diff --git a/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_qpoases_interface.o b/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_qpoases_interface.o new file mode 100644 index 00000000000000..e10c9772ab2b29 Binary files /dev/null and b/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_qpoases_interface.o differ diff --git a/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_solver.c b/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_solver.c new file mode 100644 index 00000000000000..85b67db8a12249 --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_solver.c @@ -0,0 +1,5190 @@ +/* + * This file was auto-generated using the ACADO Toolkit. + * + * While ACADO Toolkit is free software released under the terms of + * the GNU Lesser General Public License (LGPL), the generated code + * as such remains the property of the user who used ACADO Toolkit + * to generate this code. In particular, user dependent data of the code + * do not inherit the GNU LGPL license. On the other hand, parts of the + * generated code that are a direct copy of source code from the + * ACADO Toolkit or the software tools it is based on, remain, as derived + * work, automatically covered by the LGPL license. + * + * ACADO Toolkit 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. + * + */ + + +#include "acado_common.h" + + + + +/******************************************************************************/ +/* */ +/* ACADO code generation */ +/* */ +/******************************************************************************/ + + +int acado_modelSimulation( ) +{ +int ret; + +int lRun1; +ret = 0; +for (lRun1 = 0; lRun1 < 20; ++lRun1) +{ +acadoWorkspace.state[0] = acadoVariables.x[lRun1 * 4]; +acadoWorkspace.state[1] = acadoVariables.x[lRun1 * 4 + 1]; +acadoWorkspace.state[2] = acadoVariables.x[lRun1 * 4 + 2]; +acadoWorkspace.state[3] = acadoVariables.x[lRun1 * 4 + 3]; + +acadoWorkspace.state[24] = acadoVariables.u[lRun1]; +acadoWorkspace.state[25] = acadoVariables.od[lRun1 * 18]; +acadoWorkspace.state[26] = acadoVariables.od[lRun1 * 18 + 1]; +acadoWorkspace.state[27] = acadoVariables.od[lRun1 * 18 + 2]; +acadoWorkspace.state[28] = acadoVariables.od[lRun1 * 18 + 3]; +acadoWorkspace.state[29] = acadoVariables.od[lRun1 * 18 + 4]; +acadoWorkspace.state[30] = acadoVariables.od[lRun1 * 18 + 5]; +acadoWorkspace.state[31] = acadoVariables.od[lRun1 * 18 + 6]; +acadoWorkspace.state[32] = acadoVariables.od[lRun1 * 18 + 7]; +acadoWorkspace.state[33] = acadoVariables.od[lRun1 * 18 + 8]; +acadoWorkspace.state[34] = acadoVariables.od[lRun1 * 18 + 9]; +acadoWorkspace.state[35] = acadoVariables.od[lRun1 * 18 + 10]; +acadoWorkspace.state[36] = acadoVariables.od[lRun1 * 18 + 11]; +acadoWorkspace.state[37] = acadoVariables.od[lRun1 * 18 + 12]; +acadoWorkspace.state[38] = acadoVariables.od[lRun1 * 18 + 13]; +acadoWorkspace.state[39] = acadoVariables.od[lRun1 * 18 + 14]; +acadoWorkspace.state[40] = acadoVariables.od[lRun1 * 18 + 15]; +acadoWorkspace.state[41] = acadoVariables.od[lRun1 * 18 + 16]; +acadoWorkspace.state[42] = acadoVariables.od[lRun1 * 18 + 17]; + +ret = acado_integrate(acadoWorkspace.state, 1, lRun1); + +acadoWorkspace.d[lRun1 * 4] = acadoWorkspace.state[0] - acadoVariables.x[lRun1 * 4 + 4]; +acadoWorkspace.d[lRun1 * 4 + 1] = acadoWorkspace.state[1] - acadoVariables.x[lRun1 * 4 + 5]; +acadoWorkspace.d[lRun1 * 4 + 2] = acadoWorkspace.state[2] - acadoVariables.x[lRun1 * 4 + 6]; +acadoWorkspace.d[lRun1 * 4 + 3] = acadoWorkspace.state[3] - acadoVariables.x[lRun1 * 4 + 7]; + +acadoWorkspace.evGx[lRun1 * 16] = acadoWorkspace.state[4]; +acadoWorkspace.evGx[lRun1 * 16 + 1] = acadoWorkspace.state[5]; +acadoWorkspace.evGx[lRun1 * 16 + 2] = acadoWorkspace.state[6]; +acadoWorkspace.evGx[lRun1 * 16 + 3] = acadoWorkspace.state[7]; +acadoWorkspace.evGx[lRun1 * 16 + 4] = acadoWorkspace.state[8]; +acadoWorkspace.evGx[lRun1 * 16 + 5] = acadoWorkspace.state[9]; +acadoWorkspace.evGx[lRun1 * 16 + 6] = acadoWorkspace.state[10]; +acadoWorkspace.evGx[lRun1 * 16 + 7] = acadoWorkspace.state[11]; +acadoWorkspace.evGx[lRun1 * 16 + 8] = acadoWorkspace.state[12]; +acadoWorkspace.evGx[lRun1 * 16 + 9] = acadoWorkspace.state[13]; +acadoWorkspace.evGx[lRun1 * 16 + 10] = acadoWorkspace.state[14]; +acadoWorkspace.evGx[lRun1 * 16 + 11] = acadoWorkspace.state[15]; +acadoWorkspace.evGx[lRun1 * 16 + 12] = acadoWorkspace.state[16]; +acadoWorkspace.evGx[lRun1 * 16 + 13] = acadoWorkspace.state[17]; +acadoWorkspace.evGx[lRun1 * 16 + 14] = acadoWorkspace.state[18]; +acadoWorkspace.evGx[lRun1 * 16 + 15] = acadoWorkspace.state[19]; + +acadoWorkspace.evGu[lRun1 * 4] = acadoWorkspace.state[20]; +acadoWorkspace.evGu[lRun1 * 4 + 1] = acadoWorkspace.state[21]; +acadoWorkspace.evGu[lRun1 * 4 + 2] = acadoWorkspace.state[22]; +acadoWorkspace.evGu[lRun1 * 4 + 3] = acadoWorkspace.state[23]; +} +return ret; +} + +void acado_evaluateLSQ(const real_t* in, real_t* out) +{ +const real_t* xd = in; +const real_t* u = in + 4; +const real_t* od = in + 5; +/* Vector of auxiliary variables; number of elements: 21. */ +real_t* a = acadoWorkspace.objAuxVar; + +/* Compute intermediate quantities: */ +a[0] = (exp(((real_t)(0.0000000000000000e+00)-(((((((od[14]+od[15])-(od[14]*od[15]))*((od[14]*(((((od[2]*((xd[0]*xd[0])*xd[0]))+(od[3]*(xd[0]*xd[0])))+(od[4]*xd[0]))+od[5])-(od[17]/(real_t)(2.0000000000000000e+00))))+(od[15]*(((((od[6]*((xd[0]*xd[0])*xd[0]))+(od[7]*(xd[0]*xd[0])))+(od[8]*xd[0]))+od[9])+(od[17]/(real_t)(2.0000000000000000e+00))))))/((od[14]+od[15])+(real_t)(1.0000000000000000e-04)))+(((real_t)(1.0000000000000000e+00)-((od[14]+od[15])-(od[14]*od[15])))*((((od[10]*((xd[0]*xd[0])*xd[0]))+(od[11]*(xd[0]*xd[0])))+(od[12]*xd[0]))+od[13])))+(od[17]/(real_t)(2.0000000000000000e+00)))-xd[1])))); +a[1] = (exp((((((((od[14]+od[15])-(od[14]*od[15]))*((od[14]*(((((od[2]*((xd[0]*xd[0])*xd[0]))+(od[3]*(xd[0]*xd[0])))+(od[4]*xd[0]))+od[5])-(od[17]/(real_t)(2.0000000000000000e+00))))+(od[15]*(((((od[6]*((xd[0]*xd[0])*xd[0]))+(od[7]*(xd[0]*xd[0])))+(od[8]*xd[0]))+od[9])+(od[17]/(real_t)(2.0000000000000000e+00))))))/((od[14]+od[15])+(real_t)(1.0000000000000000e-04)))+(((real_t)(1.0000000000000000e+00)-((od[14]+od[15])-(od[14]*od[15])))*((((od[10]*((xd[0]*xd[0])*xd[0]))+(od[11]*(xd[0]*xd[0])))+(od[12]*xd[0]))+od[13])))-(od[17]/(real_t)(2.0000000000000000e+00)))-xd[1]))); +a[2] = (atan(((((((real_t)(3.0000000000000000e+00)*od[2])*xd[0])*xd[0])+(((real_t)(2.0000000000000000e+00)*od[3])*xd[0]))+od[4]))); +a[3] = (atan(((((((real_t)(3.0000000000000000e+00)*od[6])*xd[0])*xd[0])+(((real_t)(2.0000000000000000e+00)*od[7])*xd[0]))+od[8]))); +a[4] = (atan(((((((real_t)(3.0000000000000000e+00)*od[10])*xd[0])*xd[0])+(((real_t)(2.0000000000000000e+00)*od[11])*xd[0]))+od[12]))); +a[5] = ((real_t)(1.0000000000000000e+00)/((od[14]+od[15])+(real_t)(1.0000000000000000e-04))); +a[6] = ((real_t)(1.0000000000000000e+00)/((od[14]+od[15])+(real_t)(1.0000000000000000e-04))); +a[7] = (exp(((real_t)(0.0000000000000000e+00)-(((((((od[14]+od[15])-(od[14]*od[15]))*((od[14]*(((((od[2]*((xd[0]*xd[0])*xd[0]))+(od[3]*(xd[0]*xd[0])))+(od[4]*xd[0]))+od[5])-(od[17]/(real_t)(2.0000000000000000e+00))))+(od[15]*(((((od[6]*((xd[0]*xd[0])*xd[0]))+(od[7]*(xd[0]*xd[0])))+(od[8]*xd[0]))+od[9])+(od[17]/(real_t)(2.0000000000000000e+00))))))/((od[14]+od[15])+(real_t)(1.0000000000000000e-04)))+(((real_t)(1.0000000000000000e+00)-((od[14]+od[15])-(od[14]*od[15])))*((((od[10]*((xd[0]*xd[0])*xd[0]))+(od[11]*(xd[0]*xd[0])))+(od[12]*xd[0]))+od[13])))+(od[17]/(real_t)(2.0000000000000000e+00)))-xd[1])))); +a[8] = (((real_t)(0.0000000000000000e+00)-(((((od[14]+od[15])-(od[14]*od[15]))*((od[14]*(((od[2]*(((xd[0]+xd[0])*xd[0])+(xd[0]*xd[0])))+(od[3]*(xd[0]+xd[0])))+od[4]))+(od[15]*(((od[6]*(((xd[0]+xd[0])*xd[0])+(xd[0]*xd[0])))+(od[7]*(xd[0]+xd[0])))+od[8]))))*a[6])+(((real_t)(1.0000000000000000e+00)-((od[14]+od[15])-(od[14]*od[15])))*(((od[10]*(((xd[0]+xd[0])*xd[0])+(xd[0]*xd[0])))+(od[11]*(xd[0]+xd[0])))+od[12]))))*a[7]); +a[9] = (((real_t)(0.0000000000000000e+00)-((real_t)(0.0000000000000000e+00)-(real_t)(1.0000000000000000e+00)))*a[7]); +a[10] = ((real_t)(1.0000000000000000e+00)/((od[14]+od[15])+(real_t)(1.0000000000000000e-04))); +a[11] = (exp((((((((od[14]+od[15])-(od[14]*od[15]))*((od[14]*(((((od[2]*((xd[0]*xd[0])*xd[0]))+(od[3]*(xd[0]*xd[0])))+(od[4]*xd[0]))+od[5])-(od[17]/(real_t)(2.0000000000000000e+00))))+(od[15]*(((((od[6]*((xd[0]*xd[0])*xd[0]))+(od[7]*(xd[0]*xd[0])))+(od[8]*xd[0]))+od[9])+(od[17]/(real_t)(2.0000000000000000e+00))))))/((od[14]+od[15])+(real_t)(1.0000000000000000e-04)))+(((real_t)(1.0000000000000000e+00)-((od[14]+od[15])-(od[14]*od[15])))*((((od[10]*((xd[0]*xd[0])*xd[0]))+(od[11]*(xd[0]*xd[0])))+(od[12]*xd[0]))+od[13])))-(od[17]/(real_t)(2.0000000000000000e+00)))-xd[1]))); +a[12] = ((((((od[14]+od[15])-(od[14]*od[15]))*((od[14]*(((od[2]*(((xd[0]+xd[0])*xd[0])+(xd[0]*xd[0])))+(od[3]*(xd[0]+xd[0])))+od[4]))+(od[15]*(((od[6]*(((xd[0]+xd[0])*xd[0])+(xd[0]*xd[0])))+(od[7]*(xd[0]+xd[0])))+od[8]))))*a[10])+(((real_t)(1.0000000000000000e+00)-((od[14]+od[15])-(od[14]*od[15])))*(((od[10]*(((xd[0]+xd[0])*xd[0])+(xd[0]*xd[0])))+(od[11]*(xd[0]+xd[0])))+od[12])))*a[11]); +a[13] = (((real_t)(0.0000000000000000e+00)-(real_t)(1.0000000000000000e+00))*a[11]); +a[14] = ((real_t)(1.0000000000000000e+00)/((real_t)(1.0000000000000000e+00)+(pow(((((((real_t)(3.0000000000000000e+00)*od[2])*xd[0])*xd[0])+(((real_t)(2.0000000000000000e+00)*od[3])*xd[0]))+od[4]),2)))); +a[15] = ((((((real_t)(3.0000000000000000e+00)*od[2])*xd[0])+(((real_t)(3.0000000000000000e+00)*od[2])*xd[0]))+((real_t)(2.0000000000000000e+00)*od[3]))*a[14]); +a[16] = ((real_t)(1.0000000000000000e+00)/((real_t)(1.0000000000000000e+00)+(pow(((((((real_t)(3.0000000000000000e+00)*od[6])*xd[0])*xd[0])+(((real_t)(2.0000000000000000e+00)*od[7])*xd[0]))+od[8]),2)))); +a[17] = ((((((real_t)(3.0000000000000000e+00)*od[6])*xd[0])+(((real_t)(3.0000000000000000e+00)*od[6])*xd[0]))+((real_t)(2.0000000000000000e+00)*od[7]))*a[16]); +a[18] = ((real_t)(1.0000000000000000e+00)/((od[14]+od[15])+(real_t)(1.0000000000000000e-04))); +a[19] = ((real_t)(1.0000000000000000e+00)/((real_t)(1.0000000000000000e+00)+(pow(((((((real_t)(3.0000000000000000e+00)*od[10])*xd[0])*xd[0])+(((real_t)(2.0000000000000000e+00)*od[11])*xd[0]))+od[12]),2)))); +a[20] = ((((((real_t)(3.0000000000000000e+00)*od[10])*xd[0])+(((real_t)(3.0000000000000000e+00)*od[10])*xd[0]))+((real_t)(2.0000000000000000e+00)*od[11]))*a[19]); + +/* Compute outputs: */ +out[0] = ((((((od[14]+od[15])-(od[14]*od[15]))*((od[14]*(((((od[2]*((xd[0]*xd[0])*xd[0]))+(od[3]*(xd[0]*xd[0])))+(od[4]*xd[0]))+od[5])-(od[17]/(real_t)(2.0000000000000000e+00))))+(od[15]*(((((od[6]*((xd[0]*xd[0])*xd[0]))+(od[7]*(xd[0]*xd[0])))+(od[8]*xd[0]))+od[9])+(od[17]/(real_t)(2.0000000000000000e+00))))))/((od[14]+od[15])+(real_t)(1.0000000000000000e-04)))+(((real_t)(1.0000000000000000e+00)-((od[14]+od[15])-(od[14]*od[15])))*((((od[10]*((xd[0]*xd[0])*xd[0]))+(od[11]*(xd[0]*xd[0])))+(od[12]*xd[0]))+od[13])))-xd[1]); +out[1] = (((od[14]+od[15])-(od[14]*od[15]))*a[0]); +out[2] = (((od[14]+od[15])-(od[14]*od[15]))*a[1]); +out[3] = ((od[1]+(real_t)(1.0000000000000000e+00))*((((((od[14]+od[15])-(od[14]*od[15]))*((od[14]*a[2])+(od[15]*a[3])))/((od[14]+od[15])+(real_t)(1.0000000000000000e-04)))+(((real_t)(1.0000000000000000e+00)-((od[14]+od[15])-(od[14]*od[15])))*a[4]))-xd[2])); +out[4] = ((od[1]+(real_t)(1.0000000000000000e+00))*u[0]); +out[5] = (((((od[14]+od[15])-(od[14]*od[15]))*((od[14]*(((od[2]*(((xd[0]+xd[0])*xd[0])+(xd[0]*xd[0])))+(od[3]*(xd[0]+xd[0])))+od[4]))+(od[15]*(((od[6]*(((xd[0]+xd[0])*xd[0])+(xd[0]*xd[0])))+(od[7]*(xd[0]+xd[0])))+od[8]))))*a[5])+(((real_t)(1.0000000000000000e+00)-((od[14]+od[15])-(od[14]*od[15])))*(((od[10]*(((xd[0]+xd[0])*xd[0])+(xd[0]*xd[0])))+(od[11]*(xd[0]+xd[0])))+od[12]))); +out[6] = ((real_t)(0.0000000000000000e+00)-(real_t)(1.0000000000000000e+00)); +out[7] = (real_t)(0.0000000000000000e+00); +out[8] = (real_t)(0.0000000000000000e+00); +out[9] = (((od[14]+od[15])-(od[14]*od[15]))*a[8]); +out[10] = (((od[14]+od[15])-(od[14]*od[15]))*a[9]); +out[11] = (real_t)(0.0000000000000000e+00); +out[12] = (real_t)(0.0000000000000000e+00); +out[13] = (((od[14]+od[15])-(od[14]*od[15]))*a[12]); +out[14] = (((od[14]+od[15])-(od[14]*od[15]))*a[13]); +out[15] = (real_t)(0.0000000000000000e+00); +out[16] = (real_t)(0.0000000000000000e+00); +out[17] = ((od[1]+(real_t)(1.0000000000000000e+00))*(((((od[14]+od[15])-(od[14]*od[15]))*((od[14]*a[15])+(od[15]*a[17])))*a[18])+(((real_t)(1.0000000000000000e+00)-((od[14]+od[15])-(od[14]*od[15])))*a[20]))); +out[18] = (real_t)(0.0000000000000000e+00); +out[19] = ((od[1]+(real_t)(1.0000000000000000e+00))*((real_t)(0.0000000000000000e+00)-(real_t)(1.0000000000000000e+00))); +out[20] = (real_t)(0.0000000000000000e+00); +out[21] = (real_t)(0.0000000000000000e+00); +out[22] = (real_t)(0.0000000000000000e+00); +out[23] = (real_t)(0.0000000000000000e+00); +out[24] = (real_t)(0.0000000000000000e+00); +out[25] = (real_t)(0.0000000000000000e+00); +out[26] = (real_t)(0.0000000000000000e+00); +out[27] = (real_t)(0.0000000000000000e+00); +out[28] = (real_t)(0.0000000000000000e+00); +out[29] = (od[1]+(real_t)(1.0000000000000000e+00)); +} + +void acado_evaluateLSQEndTerm(const real_t* in, real_t* out) +{ +const real_t* xd = in; +const real_t* od = in + 4; +/* Vector of auxiliary variables; number of elements: 21. */ +real_t* a = acadoWorkspace.objAuxVar; + +/* Compute intermediate quantities: */ +a[0] = (exp(((real_t)(0.0000000000000000e+00)-(((((((od[14]+od[15])-(od[14]*od[15]))*((od[14]*(((((od[2]*((xd[0]*xd[0])*xd[0]))+(od[3]*(xd[0]*xd[0])))+(od[4]*xd[0]))+od[5])-(od[17]/(real_t)(2.0000000000000000e+00))))+(od[15]*(((((od[6]*((xd[0]*xd[0])*xd[0]))+(od[7]*(xd[0]*xd[0])))+(od[8]*xd[0]))+od[9])+(od[17]/(real_t)(2.0000000000000000e+00))))))/((od[14]+od[15])+(real_t)(1.0000000000000000e-04)))+(((real_t)(1.0000000000000000e+00)-((od[14]+od[15])-(od[14]*od[15])))*((((od[10]*((xd[0]*xd[0])*xd[0]))+(od[11]*(xd[0]*xd[0])))+(od[12]*xd[0]))+od[13])))+(od[17]/(real_t)(2.0000000000000000e+00)))-xd[1])))); +a[1] = (exp((((((((od[14]+od[15])-(od[14]*od[15]))*((od[14]*(((((od[2]*((xd[0]*xd[0])*xd[0]))+(od[3]*(xd[0]*xd[0])))+(od[4]*xd[0]))+od[5])-(od[17]/(real_t)(2.0000000000000000e+00))))+(od[15]*(((((od[6]*((xd[0]*xd[0])*xd[0]))+(od[7]*(xd[0]*xd[0])))+(od[8]*xd[0]))+od[9])+(od[17]/(real_t)(2.0000000000000000e+00))))))/((od[14]+od[15])+(real_t)(1.0000000000000000e-04)))+(((real_t)(1.0000000000000000e+00)-((od[14]+od[15])-(od[14]*od[15])))*((((od[10]*((xd[0]*xd[0])*xd[0]))+(od[11]*(xd[0]*xd[0])))+(od[12]*xd[0]))+od[13])))-(od[17]/(real_t)(2.0000000000000000e+00)))-xd[1]))); +a[2] = (atan(((((((real_t)(3.0000000000000000e+00)*od[2])*xd[0])*xd[0])+(((real_t)(2.0000000000000000e+00)*od[3])*xd[0]))+od[4]))); +a[3] = (atan(((((((real_t)(3.0000000000000000e+00)*od[6])*xd[0])*xd[0])+(((real_t)(2.0000000000000000e+00)*od[7])*xd[0]))+od[8]))); +a[4] = (atan(((((((real_t)(3.0000000000000000e+00)*od[10])*xd[0])*xd[0])+(((real_t)(2.0000000000000000e+00)*od[11])*xd[0]))+od[12]))); +a[5] = ((real_t)(1.0000000000000000e+00)/((od[14]+od[15])+(real_t)(1.0000000000000000e-04))); +a[6] = ((real_t)(1.0000000000000000e+00)/((od[14]+od[15])+(real_t)(1.0000000000000000e-04))); +a[7] = (exp(((real_t)(0.0000000000000000e+00)-(((((((od[14]+od[15])-(od[14]*od[15]))*((od[14]*(((((od[2]*((xd[0]*xd[0])*xd[0]))+(od[3]*(xd[0]*xd[0])))+(od[4]*xd[0]))+od[5])-(od[17]/(real_t)(2.0000000000000000e+00))))+(od[15]*(((((od[6]*((xd[0]*xd[0])*xd[0]))+(od[7]*(xd[0]*xd[0])))+(od[8]*xd[0]))+od[9])+(od[17]/(real_t)(2.0000000000000000e+00))))))/((od[14]+od[15])+(real_t)(1.0000000000000000e-04)))+(((real_t)(1.0000000000000000e+00)-((od[14]+od[15])-(od[14]*od[15])))*((((od[10]*((xd[0]*xd[0])*xd[0]))+(od[11]*(xd[0]*xd[0])))+(od[12]*xd[0]))+od[13])))+(od[17]/(real_t)(2.0000000000000000e+00)))-xd[1])))); +a[8] = (((real_t)(0.0000000000000000e+00)-(((((od[14]+od[15])-(od[14]*od[15]))*((od[14]*(((od[2]*(((xd[0]+xd[0])*xd[0])+(xd[0]*xd[0])))+(od[3]*(xd[0]+xd[0])))+od[4]))+(od[15]*(((od[6]*(((xd[0]+xd[0])*xd[0])+(xd[0]*xd[0])))+(od[7]*(xd[0]+xd[0])))+od[8]))))*a[6])+(((real_t)(1.0000000000000000e+00)-((od[14]+od[15])-(od[14]*od[15])))*(((od[10]*(((xd[0]+xd[0])*xd[0])+(xd[0]*xd[0])))+(od[11]*(xd[0]+xd[0])))+od[12]))))*a[7]); +a[9] = (((real_t)(0.0000000000000000e+00)-((real_t)(0.0000000000000000e+00)-(real_t)(1.0000000000000000e+00)))*a[7]); +a[10] = ((real_t)(1.0000000000000000e+00)/((od[14]+od[15])+(real_t)(1.0000000000000000e-04))); +a[11] = (exp((((((((od[14]+od[15])-(od[14]*od[15]))*((od[14]*(((((od[2]*((xd[0]*xd[0])*xd[0]))+(od[3]*(xd[0]*xd[0])))+(od[4]*xd[0]))+od[5])-(od[17]/(real_t)(2.0000000000000000e+00))))+(od[15]*(((((od[6]*((xd[0]*xd[0])*xd[0]))+(od[7]*(xd[0]*xd[0])))+(od[8]*xd[0]))+od[9])+(od[17]/(real_t)(2.0000000000000000e+00))))))/((od[14]+od[15])+(real_t)(1.0000000000000000e-04)))+(((real_t)(1.0000000000000000e+00)-((od[14]+od[15])-(od[14]*od[15])))*((((od[10]*((xd[0]*xd[0])*xd[0]))+(od[11]*(xd[0]*xd[0])))+(od[12]*xd[0]))+od[13])))-(od[17]/(real_t)(2.0000000000000000e+00)))-xd[1]))); +a[12] = ((((((od[14]+od[15])-(od[14]*od[15]))*((od[14]*(((od[2]*(((xd[0]+xd[0])*xd[0])+(xd[0]*xd[0])))+(od[3]*(xd[0]+xd[0])))+od[4]))+(od[15]*(((od[6]*(((xd[0]+xd[0])*xd[0])+(xd[0]*xd[0])))+(od[7]*(xd[0]+xd[0])))+od[8]))))*a[10])+(((real_t)(1.0000000000000000e+00)-((od[14]+od[15])-(od[14]*od[15])))*(((od[10]*(((xd[0]+xd[0])*xd[0])+(xd[0]*xd[0])))+(od[11]*(xd[0]+xd[0])))+od[12])))*a[11]); +a[13] = (((real_t)(0.0000000000000000e+00)-(real_t)(1.0000000000000000e+00))*a[11]); +a[14] = ((real_t)(1.0000000000000000e+00)/((real_t)(1.0000000000000000e+00)+(pow(((((((real_t)(3.0000000000000000e+00)*od[2])*xd[0])*xd[0])+(((real_t)(2.0000000000000000e+00)*od[3])*xd[0]))+od[4]),2)))); +a[15] = ((((((real_t)(3.0000000000000000e+00)*od[2])*xd[0])+(((real_t)(3.0000000000000000e+00)*od[2])*xd[0]))+((real_t)(2.0000000000000000e+00)*od[3]))*a[14]); +a[16] = ((real_t)(1.0000000000000000e+00)/((real_t)(1.0000000000000000e+00)+(pow(((((((real_t)(3.0000000000000000e+00)*od[6])*xd[0])*xd[0])+(((real_t)(2.0000000000000000e+00)*od[7])*xd[0]))+od[8]),2)))); +a[17] = ((((((real_t)(3.0000000000000000e+00)*od[6])*xd[0])+(((real_t)(3.0000000000000000e+00)*od[6])*xd[0]))+((real_t)(2.0000000000000000e+00)*od[7]))*a[16]); +a[18] = ((real_t)(1.0000000000000000e+00)/((od[14]+od[15])+(real_t)(1.0000000000000000e-04))); +a[19] = ((real_t)(1.0000000000000000e+00)/((real_t)(1.0000000000000000e+00)+(pow(((((((real_t)(3.0000000000000000e+00)*od[10])*xd[0])*xd[0])+(((real_t)(2.0000000000000000e+00)*od[11])*xd[0]))+od[12]),2)))); +a[20] = ((((((real_t)(3.0000000000000000e+00)*od[10])*xd[0])+(((real_t)(3.0000000000000000e+00)*od[10])*xd[0]))+((real_t)(2.0000000000000000e+00)*od[11]))*a[19]); + +/* Compute outputs: */ +out[0] = ((((((od[14]+od[15])-(od[14]*od[15]))*((od[14]*(((((od[2]*((xd[0]*xd[0])*xd[0]))+(od[3]*(xd[0]*xd[0])))+(od[4]*xd[0]))+od[5])-(od[17]/(real_t)(2.0000000000000000e+00))))+(od[15]*(((((od[6]*((xd[0]*xd[0])*xd[0]))+(od[7]*(xd[0]*xd[0])))+(od[8]*xd[0]))+od[9])+(od[17]/(real_t)(2.0000000000000000e+00))))))/((od[14]+od[15])+(real_t)(1.0000000000000000e-04)))+(((real_t)(1.0000000000000000e+00)-((od[14]+od[15])-(od[14]*od[15])))*((((od[10]*((xd[0]*xd[0])*xd[0]))+(od[11]*(xd[0]*xd[0])))+(od[12]*xd[0]))+od[13])))-xd[1]); +out[1] = (od[14]*a[0]); +out[2] = (od[15]*a[1]); +out[3] = ((((real_t)(2.0000000000000000e+00)*od[1])+(real_t)(1.0000000000000000e+00))*((((((od[14]+od[15])-(od[14]*od[15]))*((od[14]*a[2])+(od[15]*a[3])))/((od[14]+od[15])+(real_t)(1.0000000000000000e-04)))+(((real_t)(1.0000000000000000e+00)-((od[14]+od[15])-(od[14]*od[15])))*a[4]))-xd[2])); +out[4] = (((((od[14]+od[15])-(od[14]*od[15]))*((od[14]*(((od[2]*(((xd[0]+xd[0])*xd[0])+(xd[0]*xd[0])))+(od[3]*(xd[0]+xd[0])))+od[4]))+(od[15]*(((od[6]*(((xd[0]+xd[0])*xd[0])+(xd[0]*xd[0])))+(od[7]*(xd[0]+xd[0])))+od[8]))))*a[5])+(((real_t)(1.0000000000000000e+00)-((od[14]+od[15])-(od[14]*od[15])))*(((od[10]*(((xd[0]+xd[0])*xd[0])+(xd[0]*xd[0])))+(od[11]*(xd[0]+xd[0])))+od[12]))); +out[5] = ((real_t)(0.0000000000000000e+00)-(real_t)(1.0000000000000000e+00)); +out[6] = (real_t)(0.0000000000000000e+00); +out[7] = (real_t)(0.0000000000000000e+00); +out[8] = (od[14]*a[8]); +out[9] = (od[14]*a[9]); +out[10] = (real_t)(0.0000000000000000e+00); +out[11] = (real_t)(0.0000000000000000e+00); +out[12] = (od[15]*a[12]); +out[13] = (od[15]*a[13]); +out[14] = (real_t)(0.0000000000000000e+00); +out[15] = (real_t)(0.0000000000000000e+00); +out[16] = ((((real_t)(2.0000000000000000e+00)*od[1])+(real_t)(1.0000000000000000e+00))*(((((od[14]+od[15])-(od[14]*od[15]))*((od[14]*a[15])+(od[15]*a[17])))*a[18])+(((real_t)(1.0000000000000000e+00)-((od[14]+od[15])-(od[14]*od[15])))*a[20]))); +out[17] = (real_t)(0.0000000000000000e+00); +out[18] = ((((real_t)(2.0000000000000000e+00)*od[1])+(real_t)(1.0000000000000000e+00))*((real_t)(0.0000000000000000e+00)-(real_t)(1.0000000000000000e+00))); +out[19] = (real_t)(0.0000000000000000e+00); +} + +void acado_setObjQ1Q2( real_t* const tmpFx, real_t* const tmpObjS, real_t* const tmpQ1, real_t* const tmpQ2 ) +{ +tmpQ2[0] = + tmpFx[0]*tmpObjS[0] + tmpFx[4]*tmpObjS[5] + tmpFx[8]*tmpObjS[10] + tmpFx[12]*tmpObjS[15] + tmpFx[16]*tmpObjS[20]; +tmpQ2[1] = + tmpFx[0]*tmpObjS[1] + tmpFx[4]*tmpObjS[6] + tmpFx[8]*tmpObjS[11] + tmpFx[12]*tmpObjS[16] + tmpFx[16]*tmpObjS[21]; +tmpQ2[2] = + tmpFx[0]*tmpObjS[2] + tmpFx[4]*tmpObjS[7] + tmpFx[8]*tmpObjS[12] + tmpFx[12]*tmpObjS[17] + tmpFx[16]*tmpObjS[22]; +tmpQ2[3] = + tmpFx[0]*tmpObjS[3] + tmpFx[4]*tmpObjS[8] + tmpFx[8]*tmpObjS[13] + tmpFx[12]*tmpObjS[18] + tmpFx[16]*tmpObjS[23]; +tmpQ2[4] = + tmpFx[0]*tmpObjS[4] + tmpFx[4]*tmpObjS[9] + tmpFx[8]*tmpObjS[14] + tmpFx[12]*tmpObjS[19] + tmpFx[16]*tmpObjS[24]; +tmpQ2[5] = + tmpFx[1]*tmpObjS[0] + tmpFx[5]*tmpObjS[5] + tmpFx[9]*tmpObjS[10] + tmpFx[13]*tmpObjS[15] + tmpFx[17]*tmpObjS[20]; +tmpQ2[6] = + tmpFx[1]*tmpObjS[1] + tmpFx[5]*tmpObjS[6] + tmpFx[9]*tmpObjS[11] + tmpFx[13]*tmpObjS[16] + tmpFx[17]*tmpObjS[21]; +tmpQ2[7] = + tmpFx[1]*tmpObjS[2] + tmpFx[5]*tmpObjS[7] + tmpFx[9]*tmpObjS[12] + tmpFx[13]*tmpObjS[17] + tmpFx[17]*tmpObjS[22]; +tmpQ2[8] = + tmpFx[1]*tmpObjS[3] + tmpFx[5]*tmpObjS[8] + tmpFx[9]*tmpObjS[13] + tmpFx[13]*tmpObjS[18] + tmpFx[17]*tmpObjS[23]; +tmpQ2[9] = + tmpFx[1]*tmpObjS[4] + tmpFx[5]*tmpObjS[9] + tmpFx[9]*tmpObjS[14] + tmpFx[13]*tmpObjS[19] + tmpFx[17]*tmpObjS[24]; +tmpQ2[10] = + tmpFx[2]*tmpObjS[0] + tmpFx[6]*tmpObjS[5] + tmpFx[10]*tmpObjS[10] + tmpFx[14]*tmpObjS[15] + tmpFx[18]*tmpObjS[20]; +tmpQ2[11] = + tmpFx[2]*tmpObjS[1] + tmpFx[6]*tmpObjS[6] + tmpFx[10]*tmpObjS[11] + tmpFx[14]*tmpObjS[16] + tmpFx[18]*tmpObjS[21]; +tmpQ2[12] = + tmpFx[2]*tmpObjS[2] + tmpFx[6]*tmpObjS[7] + tmpFx[10]*tmpObjS[12] + tmpFx[14]*tmpObjS[17] + tmpFx[18]*tmpObjS[22]; +tmpQ2[13] = + tmpFx[2]*tmpObjS[3] + tmpFx[6]*tmpObjS[8] + tmpFx[10]*tmpObjS[13] + tmpFx[14]*tmpObjS[18] + tmpFx[18]*tmpObjS[23]; +tmpQ2[14] = + tmpFx[2]*tmpObjS[4] + tmpFx[6]*tmpObjS[9] + tmpFx[10]*tmpObjS[14] + tmpFx[14]*tmpObjS[19] + tmpFx[18]*tmpObjS[24]; +tmpQ2[15] = + tmpFx[3]*tmpObjS[0] + tmpFx[7]*tmpObjS[5] + tmpFx[11]*tmpObjS[10] + tmpFx[15]*tmpObjS[15] + tmpFx[19]*tmpObjS[20]; +tmpQ2[16] = + tmpFx[3]*tmpObjS[1] + tmpFx[7]*tmpObjS[6] + tmpFx[11]*tmpObjS[11] + tmpFx[15]*tmpObjS[16] + tmpFx[19]*tmpObjS[21]; +tmpQ2[17] = + tmpFx[3]*tmpObjS[2] + tmpFx[7]*tmpObjS[7] + tmpFx[11]*tmpObjS[12] + tmpFx[15]*tmpObjS[17] + tmpFx[19]*tmpObjS[22]; +tmpQ2[18] = + tmpFx[3]*tmpObjS[3] + tmpFx[7]*tmpObjS[8] + tmpFx[11]*tmpObjS[13] + tmpFx[15]*tmpObjS[18] + tmpFx[19]*tmpObjS[23]; +tmpQ2[19] = + tmpFx[3]*tmpObjS[4] + tmpFx[7]*tmpObjS[9] + tmpFx[11]*tmpObjS[14] + tmpFx[15]*tmpObjS[19] + tmpFx[19]*tmpObjS[24]; +tmpQ1[0] = + tmpQ2[0]*tmpFx[0] + tmpQ2[1]*tmpFx[4] + tmpQ2[2]*tmpFx[8] + tmpQ2[3]*tmpFx[12] + tmpQ2[4]*tmpFx[16]; +tmpQ1[1] = + tmpQ2[0]*tmpFx[1] + tmpQ2[1]*tmpFx[5] + tmpQ2[2]*tmpFx[9] + tmpQ2[3]*tmpFx[13] + tmpQ2[4]*tmpFx[17]; +tmpQ1[2] = + tmpQ2[0]*tmpFx[2] + tmpQ2[1]*tmpFx[6] + tmpQ2[2]*tmpFx[10] + tmpQ2[3]*tmpFx[14] + tmpQ2[4]*tmpFx[18]; +tmpQ1[3] = + tmpQ2[0]*tmpFx[3] + tmpQ2[1]*tmpFx[7] + tmpQ2[2]*tmpFx[11] + tmpQ2[3]*tmpFx[15] + tmpQ2[4]*tmpFx[19]; +tmpQ1[4] = + tmpQ2[5]*tmpFx[0] + tmpQ2[6]*tmpFx[4] + tmpQ2[7]*tmpFx[8] + tmpQ2[8]*tmpFx[12] + tmpQ2[9]*tmpFx[16]; +tmpQ1[5] = + tmpQ2[5]*tmpFx[1] + tmpQ2[6]*tmpFx[5] + tmpQ2[7]*tmpFx[9] + tmpQ2[8]*tmpFx[13] + tmpQ2[9]*tmpFx[17]; +tmpQ1[6] = + tmpQ2[5]*tmpFx[2] + tmpQ2[6]*tmpFx[6] + tmpQ2[7]*tmpFx[10] + tmpQ2[8]*tmpFx[14] + tmpQ2[9]*tmpFx[18]; +tmpQ1[7] = + tmpQ2[5]*tmpFx[3] + tmpQ2[6]*tmpFx[7] + tmpQ2[7]*tmpFx[11] + tmpQ2[8]*tmpFx[15] + tmpQ2[9]*tmpFx[19]; +tmpQ1[8] = + tmpQ2[10]*tmpFx[0] + tmpQ2[11]*tmpFx[4] + tmpQ2[12]*tmpFx[8] + tmpQ2[13]*tmpFx[12] + tmpQ2[14]*tmpFx[16]; +tmpQ1[9] = + tmpQ2[10]*tmpFx[1] + tmpQ2[11]*tmpFx[5] + tmpQ2[12]*tmpFx[9] + tmpQ2[13]*tmpFx[13] + tmpQ2[14]*tmpFx[17]; +tmpQ1[10] = + tmpQ2[10]*tmpFx[2] + tmpQ2[11]*tmpFx[6] + tmpQ2[12]*tmpFx[10] + tmpQ2[13]*tmpFx[14] + tmpQ2[14]*tmpFx[18]; +tmpQ1[11] = + tmpQ2[10]*tmpFx[3] + tmpQ2[11]*tmpFx[7] + tmpQ2[12]*tmpFx[11] + tmpQ2[13]*tmpFx[15] + tmpQ2[14]*tmpFx[19]; +tmpQ1[12] = + tmpQ2[15]*tmpFx[0] + tmpQ2[16]*tmpFx[4] + tmpQ2[17]*tmpFx[8] + tmpQ2[18]*tmpFx[12] + tmpQ2[19]*tmpFx[16]; +tmpQ1[13] = + tmpQ2[15]*tmpFx[1] + tmpQ2[16]*tmpFx[5] + tmpQ2[17]*tmpFx[9] + tmpQ2[18]*tmpFx[13] + tmpQ2[19]*tmpFx[17]; +tmpQ1[14] = + tmpQ2[15]*tmpFx[2] + tmpQ2[16]*tmpFx[6] + tmpQ2[17]*tmpFx[10] + tmpQ2[18]*tmpFx[14] + tmpQ2[19]*tmpFx[18]; +tmpQ1[15] = + tmpQ2[15]*tmpFx[3] + tmpQ2[16]*tmpFx[7] + tmpQ2[17]*tmpFx[11] + tmpQ2[18]*tmpFx[15] + tmpQ2[19]*tmpFx[19]; +} + +void acado_setObjR1R2( real_t* const tmpFu, real_t* const tmpObjS, real_t* const tmpR1, real_t* const tmpR2 ) +{ +tmpR2[0] = + tmpFu[0]*tmpObjS[0] + tmpFu[1]*tmpObjS[5] + tmpFu[2]*tmpObjS[10] + tmpFu[3]*tmpObjS[15] + tmpFu[4]*tmpObjS[20]; +tmpR2[1] = + tmpFu[0]*tmpObjS[1] + tmpFu[1]*tmpObjS[6] + tmpFu[2]*tmpObjS[11] + tmpFu[3]*tmpObjS[16] + tmpFu[4]*tmpObjS[21]; +tmpR2[2] = + tmpFu[0]*tmpObjS[2] + tmpFu[1]*tmpObjS[7] + tmpFu[2]*tmpObjS[12] + tmpFu[3]*tmpObjS[17] + tmpFu[4]*tmpObjS[22]; +tmpR2[3] = + tmpFu[0]*tmpObjS[3] + tmpFu[1]*tmpObjS[8] + tmpFu[2]*tmpObjS[13] + tmpFu[3]*tmpObjS[18] + tmpFu[4]*tmpObjS[23]; +tmpR2[4] = + tmpFu[0]*tmpObjS[4] + tmpFu[1]*tmpObjS[9] + tmpFu[2]*tmpObjS[14] + tmpFu[3]*tmpObjS[19] + tmpFu[4]*tmpObjS[24]; +tmpR1[0] = + tmpR2[0]*tmpFu[0] + tmpR2[1]*tmpFu[1] + tmpR2[2]*tmpFu[2] + tmpR2[3]*tmpFu[3] + tmpR2[4]*tmpFu[4]; +} + +void acado_setObjQN1QN2( real_t* const tmpFx, real_t* const tmpObjSEndTerm, real_t* const tmpQN1, real_t* const tmpQN2 ) +{ +tmpQN2[0] = + tmpFx[0]*tmpObjSEndTerm[0] + tmpFx[4]*tmpObjSEndTerm[4] + tmpFx[8]*tmpObjSEndTerm[8] + tmpFx[12]*tmpObjSEndTerm[12]; +tmpQN2[1] = + tmpFx[0]*tmpObjSEndTerm[1] + tmpFx[4]*tmpObjSEndTerm[5] + tmpFx[8]*tmpObjSEndTerm[9] + tmpFx[12]*tmpObjSEndTerm[13]; +tmpQN2[2] = + tmpFx[0]*tmpObjSEndTerm[2] + tmpFx[4]*tmpObjSEndTerm[6] + tmpFx[8]*tmpObjSEndTerm[10] + tmpFx[12]*tmpObjSEndTerm[14]; +tmpQN2[3] = + tmpFx[0]*tmpObjSEndTerm[3] + tmpFx[4]*tmpObjSEndTerm[7] + tmpFx[8]*tmpObjSEndTerm[11] + tmpFx[12]*tmpObjSEndTerm[15]; +tmpQN2[4] = + tmpFx[1]*tmpObjSEndTerm[0] + tmpFx[5]*tmpObjSEndTerm[4] + tmpFx[9]*tmpObjSEndTerm[8] + tmpFx[13]*tmpObjSEndTerm[12]; +tmpQN2[5] = + tmpFx[1]*tmpObjSEndTerm[1] + tmpFx[5]*tmpObjSEndTerm[5] + tmpFx[9]*tmpObjSEndTerm[9] + tmpFx[13]*tmpObjSEndTerm[13]; +tmpQN2[6] = + tmpFx[1]*tmpObjSEndTerm[2] + tmpFx[5]*tmpObjSEndTerm[6] + tmpFx[9]*tmpObjSEndTerm[10] + tmpFx[13]*tmpObjSEndTerm[14]; +tmpQN2[7] = + tmpFx[1]*tmpObjSEndTerm[3] + tmpFx[5]*tmpObjSEndTerm[7] + tmpFx[9]*tmpObjSEndTerm[11] + tmpFx[13]*tmpObjSEndTerm[15]; +tmpQN2[8] = + tmpFx[2]*tmpObjSEndTerm[0] + tmpFx[6]*tmpObjSEndTerm[4] + tmpFx[10]*tmpObjSEndTerm[8] + tmpFx[14]*tmpObjSEndTerm[12]; +tmpQN2[9] = + tmpFx[2]*tmpObjSEndTerm[1] + tmpFx[6]*tmpObjSEndTerm[5] + tmpFx[10]*tmpObjSEndTerm[9] + tmpFx[14]*tmpObjSEndTerm[13]; +tmpQN2[10] = + tmpFx[2]*tmpObjSEndTerm[2] + tmpFx[6]*tmpObjSEndTerm[6] + tmpFx[10]*tmpObjSEndTerm[10] + tmpFx[14]*tmpObjSEndTerm[14]; +tmpQN2[11] = + tmpFx[2]*tmpObjSEndTerm[3] + tmpFx[6]*tmpObjSEndTerm[7] + tmpFx[10]*tmpObjSEndTerm[11] + tmpFx[14]*tmpObjSEndTerm[15]; +tmpQN2[12] = + tmpFx[3]*tmpObjSEndTerm[0] + tmpFx[7]*tmpObjSEndTerm[4] + tmpFx[11]*tmpObjSEndTerm[8] + tmpFx[15]*tmpObjSEndTerm[12]; +tmpQN2[13] = + tmpFx[3]*tmpObjSEndTerm[1] + tmpFx[7]*tmpObjSEndTerm[5] + tmpFx[11]*tmpObjSEndTerm[9] + tmpFx[15]*tmpObjSEndTerm[13]; +tmpQN2[14] = + tmpFx[3]*tmpObjSEndTerm[2] + tmpFx[7]*tmpObjSEndTerm[6] + tmpFx[11]*tmpObjSEndTerm[10] + tmpFx[15]*tmpObjSEndTerm[14]; +tmpQN2[15] = + tmpFx[3]*tmpObjSEndTerm[3] + tmpFx[7]*tmpObjSEndTerm[7] + tmpFx[11]*tmpObjSEndTerm[11] + tmpFx[15]*tmpObjSEndTerm[15]; +tmpQN1[0] = + tmpQN2[0]*tmpFx[0] + tmpQN2[1]*tmpFx[4] + tmpQN2[2]*tmpFx[8] + tmpQN2[3]*tmpFx[12]; +tmpQN1[1] = + tmpQN2[0]*tmpFx[1] + tmpQN2[1]*tmpFx[5] + tmpQN2[2]*tmpFx[9] + tmpQN2[3]*tmpFx[13]; +tmpQN1[2] = + tmpQN2[0]*tmpFx[2] + tmpQN2[1]*tmpFx[6] + tmpQN2[2]*tmpFx[10] + tmpQN2[3]*tmpFx[14]; +tmpQN1[3] = + tmpQN2[0]*tmpFx[3] + tmpQN2[1]*tmpFx[7] + tmpQN2[2]*tmpFx[11] + tmpQN2[3]*tmpFx[15]; +tmpQN1[4] = + tmpQN2[4]*tmpFx[0] + tmpQN2[5]*tmpFx[4] + tmpQN2[6]*tmpFx[8] + tmpQN2[7]*tmpFx[12]; +tmpQN1[5] = + tmpQN2[4]*tmpFx[1] + tmpQN2[5]*tmpFx[5] + tmpQN2[6]*tmpFx[9] + tmpQN2[7]*tmpFx[13]; +tmpQN1[6] = + tmpQN2[4]*tmpFx[2] + tmpQN2[5]*tmpFx[6] + tmpQN2[6]*tmpFx[10] + tmpQN2[7]*tmpFx[14]; +tmpQN1[7] = + tmpQN2[4]*tmpFx[3] + tmpQN2[5]*tmpFx[7] + tmpQN2[6]*tmpFx[11] + tmpQN2[7]*tmpFx[15]; +tmpQN1[8] = + tmpQN2[8]*tmpFx[0] + tmpQN2[9]*tmpFx[4] + tmpQN2[10]*tmpFx[8] + tmpQN2[11]*tmpFx[12]; +tmpQN1[9] = + tmpQN2[8]*tmpFx[1] + tmpQN2[9]*tmpFx[5] + tmpQN2[10]*tmpFx[9] + tmpQN2[11]*tmpFx[13]; +tmpQN1[10] = + tmpQN2[8]*tmpFx[2] + tmpQN2[9]*tmpFx[6] + tmpQN2[10]*tmpFx[10] + tmpQN2[11]*tmpFx[14]; +tmpQN1[11] = + tmpQN2[8]*tmpFx[3] + tmpQN2[9]*tmpFx[7] + tmpQN2[10]*tmpFx[11] + tmpQN2[11]*tmpFx[15]; +tmpQN1[12] = + tmpQN2[12]*tmpFx[0] + tmpQN2[13]*tmpFx[4] + tmpQN2[14]*tmpFx[8] + tmpQN2[15]*tmpFx[12]; +tmpQN1[13] = + tmpQN2[12]*tmpFx[1] + tmpQN2[13]*tmpFx[5] + tmpQN2[14]*tmpFx[9] + tmpQN2[15]*tmpFx[13]; +tmpQN1[14] = + tmpQN2[12]*tmpFx[2] + tmpQN2[13]*tmpFx[6] + tmpQN2[14]*tmpFx[10] + tmpQN2[15]*tmpFx[14]; +tmpQN1[15] = + tmpQN2[12]*tmpFx[3] + tmpQN2[13]*tmpFx[7] + tmpQN2[14]*tmpFx[11] + tmpQN2[15]*tmpFx[15]; +} + +void acado_evaluateObjective( ) +{ +int runObj; +for (runObj = 0; runObj < 20; ++runObj) +{ +acadoWorkspace.objValueIn[0] = acadoVariables.x[runObj * 4]; +acadoWorkspace.objValueIn[1] = acadoVariables.x[runObj * 4 + 1]; +acadoWorkspace.objValueIn[2] = acadoVariables.x[runObj * 4 + 2]; +acadoWorkspace.objValueIn[3] = acadoVariables.x[runObj * 4 + 3]; +acadoWorkspace.objValueIn[4] = acadoVariables.u[runObj]; +acadoWorkspace.objValueIn[5] = acadoVariables.od[runObj * 18]; +acadoWorkspace.objValueIn[6] = acadoVariables.od[runObj * 18 + 1]; +acadoWorkspace.objValueIn[7] = acadoVariables.od[runObj * 18 + 2]; +acadoWorkspace.objValueIn[8] = acadoVariables.od[runObj * 18 + 3]; +acadoWorkspace.objValueIn[9] = acadoVariables.od[runObj * 18 + 4]; +acadoWorkspace.objValueIn[10] = acadoVariables.od[runObj * 18 + 5]; +acadoWorkspace.objValueIn[11] = acadoVariables.od[runObj * 18 + 6]; +acadoWorkspace.objValueIn[12] = acadoVariables.od[runObj * 18 + 7]; +acadoWorkspace.objValueIn[13] = acadoVariables.od[runObj * 18 + 8]; +acadoWorkspace.objValueIn[14] = acadoVariables.od[runObj * 18 + 9]; +acadoWorkspace.objValueIn[15] = acadoVariables.od[runObj * 18 + 10]; +acadoWorkspace.objValueIn[16] = acadoVariables.od[runObj * 18 + 11]; +acadoWorkspace.objValueIn[17] = acadoVariables.od[runObj * 18 + 12]; +acadoWorkspace.objValueIn[18] = acadoVariables.od[runObj * 18 + 13]; +acadoWorkspace.objValueIn[19] = acadoVariables.od[runObj * 18 + 14]; +acadoWorkspace.objValueIn[20] = acadoVariables.od[runObj * 18 + 15]; +acadoWorkspace.objValueIn[21] = acadoVariables.od[runObj * 18 + 16]; +acadoWorkspace.objValueIn[22] = acadoVariables.od[runObj * 18 + 17]; + +acado_evaluateLSQ( acadoWorkspace.objValueIn, acadoWorkspace.objValueOut ); +acadoWorkspace.Dy[runObj * 5] = acadoWorkspace.objValueOut[0]; +acadoWorkspace.Dy[runObj * 5 + 1] = acadoWorkspace.objValueOut[1]; +acadoWorkspace.Dy[runObj * 5 + 2] = acadoWorkspace.objValueOut[2]; +acadoWorkspace.Dy[runObj * 5 + 3] = acadoWorkspace.objValueOut[3]; +acadoWorkspace.Dy[runObj * 5 + 4] = acadoWorkspace.objValueOut[4]; + +acado_setObjQ1Q2( &(acadoWorkspace.objValueOut[ 5 ]), &(acadoVariables.W[ runObj * 25 ]), &(acadoWorkspace.Q1[ runObj * 16 ]), &(acadoWorkspace.Q2[ runObj * 20 ]) ); + +acado_setObjR1R2( &(acadoWorkspace.objValueOut[ 25 ]), &(acadoVariables.W[ runObj * 25 ]), &(acadoWorkspace.R1[ runObj ]), &(acadoWorkspace.R2[ runObj * 5 ]) ); + +} +acadoWorkspace.objValueIn[0] = acadoVariables.x[80]; +acadoWorkspace.objValueIn[1] = acadoVariables.x[81]; +acadoWorkspace.objValueIn[2] = acadoVariables.x[82]; +acadoWorkspace.objValueIn[3] = acadoVariables.x[83]; +acadoWorkspace.objValueIn[4] = acadoVariables.od[360]; +acadoWorkspace.objValueIn[5] = acadoVariables.od[361]; +acadoWorkspace.objValueIn[6] = acadoVariables.od[362]; +acadoWorkspace.objValueIn[7] = acadoVariables.od[363]; +acadoWorkspace.objValueIn[8] = acadoVariables.od[364]; +acadoWorkspace.objValueIn[9] = acadoVariables.od[365]; +acadoWorkspace.objValueIn[10] = acadoVariables.od[366]; +acadoWorkspace.objValueIn[11] = acadoVariables.od[367]; +acadoWorkspace.objValueIn[12] = acadoVariables.od[368]; +acadoWorkspace.objValueIn[13] = acadoVariables.od[369]; +acadoWorkspace.objValueIn[14] = acadoVariables.od[370]; +acadoWorkspace.objValueIn[15] = acadoVariables.od[371]; +acadoWorkspace.objValueIn[16] = acadoVariables.od[372]; +acadoWorkspace.objValueIn[17] = acadoVariables.od[373]; +acadoWorkspace.objValueIn[18] = acadoVariables.od[374]; +acadoWorkspace.objValueIn[19] = acadoVariables.od[375]; +acadoWorkspace.objValueIn[20] = acadoVariables.od[376]; +acadoWorkspace.objValueIn[21] = acadoVariables.od[377]; +acado_evaluateLSQEndTerm( acadoWorkspace.objValueIn, acadoWorkspace.objValueOut ); + +acadoWorkspace.DyN[0] = acadoWorkspace.objValueOut[0]; +acadoWorkspace.DyN[1] = acadoWorkspace.objValueOut[1]; +acadoWorkspace.DyN[2] = acadoWorkspace.objValueOut[2]; +acadoWorkspace.DyN[3] = acadoWorkspace.objValueOut[3]; + +acado_setObjQN1QN2( &(acadoWorkspace.objValueOut[ 4 ]), acadoVariables.WN, acadoWorkspace.QN1, acadoWorkspace.QN2 ); + +} + +void acado_multGxd( real_t* const dOld, real_t* const Gx1, real_t* const dNew ) +{ +dNew[0] += + Gx1[0]*dOld[0] + Gx1[1]*dOld[1] + Gx1[2]*dOld[2] + Gx1[3]*dOld[3]; +dNew[1] += + Gx1[4]*dOld[0] + Gx1[5]*dOld[1] + Gx1[6]*dOld[2] + Gx1[7]*dOld[3]; +dNew[2] += + Gx1[8]*dOld[0] + Gx1[9]*dOld[1] + Gx1[10]*dOld[2] + Gx1[11]*dOld[3]; +dNew[3] += + Gx1[12]*dOld[0] + Gx1[13]*dOld[1] + Gx1[14]*dOld[2] + Gx1[15]*dOld[3]; +} + +void acado_moveGxT( real_t* const Gx1, real_t* const Gx2 ) +{ +Gx2[0] = Gx1[0]; +Gx2[1] = Gx1[1]; +Gx2[2] = Gx1[2]; +Gx2[3] = Gx1[3]; +Gx2[4] = Gx1[4]; +Gx2[5] = Gx1[5]; +Gx2[6] = Gx1[6]; +Gx2[7] = Gx1[7]; +Gx2[8] = Gx1[8]; +Gx2[9] = Gx1[9]; +Gx2[10] = Gx1[10]; +Gx2[11] = Gx1[11]; +Gx2[12] = Gx1[12]; +Gx2[13] = Gx1[13]; +Gx2[14] = Gx1[14]; +Gx2[15] = Gx1[15]; +} + +void acado_multGxGx( real_t* const Gx1, real_t* const Gx2, real_t* const Gx3 ) +{ +Gx3[0] = + Gx1[0]*Gx2[0] + Gx1[1]*Gx2[4] + Gx1[2]*Gx2[8] + Gx1[3]*Gx2[12]; +Gx3[1] = + Gx1[0]*Gx2[1] + Gx1[1]*Gx2[5] + Gx1[2]*Gx2[9] + Gx1[3]*Gx2[13]; +Gx3[2] = + Gx1[0]*Gx2[2] + Gx1[1]*Gx2[6] + Gx1[2]*Gx2[10] + Gx1[3]*Gx2[14]; +Gx3[3] = + Gx1[0]*Gx2[3] + Gx1[1]*Gx2[7] + Gx1[2]*Gx2[11] + Gx1[3]*Gx2[15]; +Gx3[4] = + Gx1[4]*Gx2[0] + Gx1[5]*Gx2[4] + Gx1[6]*Gx2[8] + Gx1[7]*Gx2[12]; +Gx3[5] = + Gx1[4]*Gx2[1] + Gx1[5]*Gx2[5] + Gx1[6]*Gx2[9] + Gx1[7]*Gx2[13]; +Gx3[6] = + Gx1[4]*Gx2[2] + Gx1[5]*Gx2[6] + Gx1[6]*Gx2[10] + Gx1[7]*Gx2[14]; +Gx3[7] = + Gx1[4]*Gx2[3] + Gx1[5]*Gx2[7] + Gx1[6]*Gx2[11] + Gx1[7]*Gx2[15]; +Gx3[8] = + Gx1[8]*Gx2[0] + Gx1[9]*Gx2[4] + Gx1[10]*Gx2[8] + Gx1[11]*Gx2[12]; +Gx3[9] = + Gx1[8]*Gx2[1] + Gx1[9]*Gx2[5] + Gx1[10]*Gx2[9] + Gx1[11]*Gx2[13]; +Gx3[10] = + Gx1[8]*Gx2[2] + Gx1[9]*Gx2[6] + Gx1[10]*Gx2[10] + Gx1[11]*Gx2[14]; +Gx3[11] = + Gx1[8]*Gx2[3] + Gx1[9]*Gx2[7] + Gx1[10]*Gx2[11] + Gx1[11]*Gx2[15]; +Gx3[12] = + Gx1[12]*Gx2[0] + Gx1[13]*Gx2[4] + Gx1[14]*Gx2[8] + Gx1[15]*Gx2[12]; +Gx3[13] = + Gx1[12]*Gx2[1] + Gx1[13]*Gx2[5] + Gx1[14]*Gx2[9] + Gx1[15]*Gx2[13]; +Gx3[14] = + Gx1[12]*Gx2[2] + Gx1[13]*Gx2[6] + Gx1[14]*Gx2[10] + Gx1[15]*Gx2[14]; +Gx3[15] = + Gx1[12]*Gx2[3] + Gx1[13]*Gx2[7] + Gx1[14]*Gx2[11] + Gx1[15]*Gx2[15]; +} + +void acado_multGxGu( real_t* const Gx1, real_t* const Gu1, real_t* const Gu2 ) +{ +Gu2[0] = + Gx1[0]*Gu1[0] + Gx1[1]*Gu1[1] + Gx1[2]*Gu1[2] + Gx1[3]*Gu1[3]; +Gu2[1] = + Gx1[4]*Gu1[0] + Gx1[5]*Gu1[1] + Gx1[6]*Gu1[2] + Gx1[7]*Gu1[3]; +Gu2[2] = + Gx1[8]*Gu1[0] + Gx1[9]*Gu1[1] + Gx1[10]*Gu1[2] + Gx1[11]*Gu1[3]; +Gu2[3] = + Gx1[12]*Gu1[0] + Gx1[13]*Gu1[1] + Gx1[14]*Gu1[2] + Gx1[15]*Gu1[3]; +} + +void acado_moveGuE( real_t* const Gu1, real_t* const Gu2 ) +{ +Gu2[0] = Gu1[0]; +Gu2[1] = Gu1[1]; +Gu2[2] = Gu1[2]; +Gu2[3] = Gu1[3]; +} + +void acado_setBlockH11( int iRow, int iCol, real_t* const Gu1, real_t* const Gu2 ) +{ +acadoWorkspace.H[(iRow * 24 + 96) + (iCol + 4)] += + Gu1[0]*Gu2[0] + Gu1[1]*Gu2[1] + Gu1[2]*Gu2[2] + Gu1[3]*Gu2[3]; +} + +void acado_setBlockH11_R1( int iRow, int iCol, real_t* const R11 ) +{ +acadoWorkspace.H[(iRow * 24 + 96) + (iCol + 4)] = R11[0]; +} + +void acado_zeroBlockH11( int iRow, int iCol ) +{ +acadoWorkspace.H[(iRow * 24 + 96) + (iCol + 4)] = 0.0000000000000000e+00; +} + +void acado_copyHTH( int iRow, int iCol ) +{ +acadoWorkspace.H[(iRow * 24 + 96) + (iCol + 4)] = acadoWorkspace.H[(iCol * 24 + 96) + (iRow + 4)]; +} + +void acado_multQ1d( real_t* const Gx1, real_t* const dOld, real_t* const dNew ) +{ +dNew[0] = + Gx1[0]*dOld[0] + Gx1[1]*dOld[1] + Gx1[2]*dOld[2] + Gx1[3]*dOld[3]; +dNew[1] = + Gx1[4]*dOld[0] + Gx1[5]*dOld[1] + Gx1[6]*dOld[2] + Gx1[7]*dOld[3]; +dNew[2] = + Gx1[8]*dOld[0] + Gx1[9]*dOld[1] + Gx1[10]*dOld[2] + Gx1[11]*dOld[3]; +dNew[3] = + Gx1[12]*dOld[0] + Gx1[13]*dOld[1] + Gx1[14]*dOld[2] + Gx1[15]*dOld[3]; +} + +void acado_multQN1d( real_t* const QN1, real_t* const dOld, real_t* const dNew ) +{ +dNew[0] = + acadoWorkspace.QN1[0]*dOld[0] + acadoWorkspace.QN1[1]*dOld[1] + acadoWorkspace.QN1[2]*dOld[2] + acadoWorkspace.QN1[3]*dOld[3]; +dNew[1] = + acadoWorkspace.QN1[4]*dOld[0] + acadoWorkspace.QN1[5]*dOld[1] + acadoWorkspace.QN1[6]*dOld[2] + acadoWorkspace.QN1[7]*dOld[3]; +dNew[2] = + acadoWorkspace.QN1[8]*dOld[0] + acadoWorkspace.QN1[9]*dOld[1] + acadoWorkspace.QN1[10]*dOld[2] + acadoWorkspace.QN1[11]*dOld[3]; +dNew[3] = + acadoWorkspace.QN1[12]*dOld[0] + acadoWorkspace.QN1[13]*dOld[1] + acadoWorkspace.QN1[14]*dOld[2] + acadoWorkspace.QN1[15]*dOld[3]; +} + +void acado_multRDy( real_t* const R2, real_t* const Dy1, real_t* const RDy1 ) +{ +RDy1[0] = + R2[0]*Dy1[0] + R2[1]*Dy1[1] + R2[2]*Dy1[2] + R2[3]*Dy1[3] + R2[4]*Dy1[4]; +} + +void acado_multQDy( real_t* const Q2, real_t* const Dy1, real_t* const QDy1 ) +{ +QDy1[0] = + Q2[0]*Dy1[0] + Q2[1]*Dy1[1] + Q2[2]*Dy1[2] + Q2[3]*Dy1[3] + Q2[4]*Dy1[4]; +QDy1[1] = + Q2[5]*Dy1[0] + Q2[6]*Dy1[1] + Q2[7]*Dy1[2] + Q2[8]*Dy1[3] + Q2[9]*Dy1[4]; +QDy1[2] = + Q2[10]*Dy1[0] + Q2[11]*Dy1[1] + Q2[12]*Dy1[2] + Q2[13]*Dy1[3] + Q2[14]*Dy1[4]; +QDy1[3] = + Q2[15]*Dy1[0] + Q2[16]*Dy1[1] + Q2[17]*Dy1[2] + Q2[18]*Dy1[3] + Q2[19]*Dy1[4]; +} + +void acado_multEQDy( real_t* const E1, real_t* const QDy1, real_t* const U1 ) +{ +U1[0] += + E1[0]*QDy1[0] + E1[1]*QDy1[1] + E1[2]*QDy1[2] + E1[3]*QDy1[3]; +} + +void acado_multQETGx( real_t* const E1, real_t* const Gx1, real_t* const H101 ) +{ +H101[0] += + E1[0]*Gx1[0] + E1[1]*Gx1[4] + E1[2]*Gx1[8] + E1[3]*Gx1[12]; +H101[1] += + E1[0]*Gx1[1] + E1[1]*Gx1[5] + E1[2]*Gx1[9] + E1[3]*Gx1[13]; +H101[2] += + E1[0]*Gx1[2] + E1[1]*Gx1[6] + E1[2]*Gx1[10] + E1[3]*Gx1[14]; +H101[3] += + E1[0]*Gx1[3] + E1[1]*Gx1[7] + E1[2]*Gx1[11] + E1[3]*Gx1[15]; +} + +void acado_zeroBlockH10( real_t* const H101 ) +{ +{ int lCopy; for (lCopy = 0; lCopy < 4; lCopy++) H101[ lCopy ] = 0; } +} + +void acado_multEDu( real_t* const E1, real_t* const U1, real_t* const dNew ) +{ +dNew[0] += + E1[0]*U1[0]; +dNew[1] += + E1[1]*U1[0]; +dNew[2] += + E1[2]*U1[0]; +dNew[3] += + E1[3]*U1[0]; +} + +void acado_zeroBlockH00( ) +{ +acadoWorkspace.H[0] = 0.0000000000000000e+00; +acadoWorkspace.H[1] = 0.0000000000000000e+00; +acadoWorkspace.H[2] = 0.0000000000000000e+00; +acadoWorkspace.H[3] = 0.0000000000000000e+00; +acadoWorkspace.H[24] = 0.0000000000000000e+00; +acadoWorkspace.H[25] = 0.0000000000000000e+00; +acadoWorkspace.H[26] = 0.0000000000000000e+00; +acadoWorkspace.H[27] = 0.0000000000000000e+00; +acadoWorkspace.H[48] = 0.0000000000000000e+00; +acadoWorkspace.H[49] = 0.0000000000000000e+00; +acadoWorkspace.H[50] = 0.0000000000000000e+00; +acadoWorkspace.H[51] = 0.0000000000000000e+00; +acadoWorkspace.H[72] = 0.0000000000000000e+00; +acadoWorkspace.H[73] = 0.0000000000000000e+00; +acadoWorkspace.H[74] = 0.0000000000000000e+00; +acadoWorkspace.H[75] = 0.0000000000000000e+00; +} + +void acado_multCTQC( real_t* const Gx1, real_t* const Gx2 ) +{ +acadoWorkspace.H[0] += + Gx1[0]*Gx2[0] + Gx1[4]*Gx2[4] + Gx1[8]*Gx2[8] + Gx1[12]*Gx2[12]; +acadoWorkspace.H[1] += + Gx1[0]*Gx2[1] + Gx1[4]*Gx2[5] + Gx1[8]*Gx2[9] + Gx1[12]*Gx2[13]; +acadoWorkspace.H[2] += + Gx1[0]*Gx2[2] + Gx1[4]*Gx2[6] + Gx1[8]*Gx2[10] + Gx1[12]*Gx2[14]; +acadoWorkspace.H[3] += + Gx1[0]*Gx2[3] + Gx1[4]*Gx2[7] + Gx1[8]*Gx2[11] + Gx1[12]*Gx2[15]; +acadoWorkspace.H[24] += + Gx1[1]*Gx2[0] + Gx1[5]*Gx2[4] + Gx1[9]*Gx2[8] + Gx1[13]*Gx2[12]; +acadoWorkspace.H[25] += + Gx1[1]*Gx2[1] + Gx1[5]*Gx2[5] + Gx1[9]*Gx2[9] + Gx1[13]*Gx2[13]; +acadoWorkspace.H[26] += + Gx1[1]*Gx2[2] + Gx1[5]*Gx2[6] + Gx1[9]*Gx2[10] + Gx1[13]*Gx2[14]; +acadoWorkspace.H[27] += + Gx1[1]*Gx2[3] + Gx1[5]*Gx2[7] + Gx1[9]*Gx2[11] + Gx1[13]*Gx2[15]; +acadoWorkspace.H[48] += + Gx1[2]*Gx2[0] + Gx1[6]*Gx2[4] + Gx1[10]*Gx2[8] + Gx1[14]*Gx2[12]; +acadoWorkspace.H[49] += + Gx1[2]*Gx2[1] + Gx1[6]*Gx2[5] + Gx1[10]*Gx2[9] + Gx1[14]*Gx2[13]; +acadoWorkspace.H[50] += + Gx1[2]*Gx2[2] + Gx1[6]*Gx2[6] + Gx1[10]*Gx2[10] + Gx1[14]*Gx2[14]; +acadoWorkspace.H[51] += + Gx1[2]*Gx2[3] + Gx1[6]*Gx2[7] + Gx1[10]*Gx2[11] + Gx1[14]*Gx2[15]; +acadoWorkspace.H[72] += + Gx1[3]*Gx2[0] + Gx1[7]*Gx2[4] + Gx1[11]*Gx2[8] + Gx1[15]*Gx2[12]; +acadoWorkspace.H[73] += + Gx1[3]*Gx2[1] + Gx1[7]*Gx2[5] + Gx1[11]*Gx2[9] + Gx1[15]*Gx2[13]; +acadoWorkspace.H[74] += + Gx1[3]*Gx2[2] + Gx1[7]*Gx2[6] + Gx1[11]*Gx2[10] + Gx1[15]*Gx2[14]; +acadoWorkspace.H[75] += + Gx1[3]*Gx2[3] + Gx1[7]*Gx2[7] + Gx1[11]*Gx2[11] + Gx1[15]*Gx2[15]; +} + +void acado_macCTSlx( real_t* const C0, real_t* const g0 ) +{ +g0[0] += 0.0; +; +g0[1] += 0.0; +; +g0[2] += 0.0; +; +g0[3] += 0.0; +; +} + +void acado_macETSlu( real_t* const E0, real_t* const g1 ) +{ +g1[0] += 0.0; +; +} + +void acado_condensePrep( ) +{ +int lRun1; +int lRun2; +int lRun3; +int lRun4; +int lRun5; +/** Row vector of size: 40 */ +static const int xBoundIndices[ 40 ] = +{ 6, 7, 10, 11, 14, 15, 18, 19, 22, 23, 26, 27, 30, 31, 34, 35, 38, 39, 42, 43, 46, 47, 50, 51, 54, 55, 58, 59, 62, 63, 66, 67, 70, 71, 74, 75, 78, 79, 82, 83 }; +acado_moveGuE( acadoWorkspace.evGu, acadoWorkspace.E ); +acado_moveGxT( &(acadoWorkspace.evGx[ 16 ]), acadoWorkspace.T ); +acado_multGxd( acadoWorkspace.d, &(acadoWorkspace.evGx[ 16 ]), &(acadoWorkspace.d[ 4 ]) ); +acado_multGxGx( acadoWorkspace.T, acadoWorkspace.evGx, &(acadoWorkspace.evGx[ 16 ]) ); + +acado_multGxGu( acadoWorkspace.T, acadoWorkspace.E, &(acadoWorkspace.E[ 4 ]) ); + +acado_moveGuE( &(acadoWorkspace.evGu[ 4 ]), &(acadoWorkspace.E[ 8 ]) ); + +acado_moveGxT( &(acadoWorkspace.evGx[ 32 ]), acadoWorkspace.T ); +acado_multGxd( &(acadoWorkspace.d[ 4 ]), &(acadoWorkspace.evGx[ 32 ]), &(acadoWorkspace.d[ 8 ]) ); +acado_multGxGx( acadoWorkspace.T, &(acadoWorkspace.evGx[ 16 ]), &(acadoWorkspace.evGx[ 32 ]) ); + +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 4 ]), &(acadoWorkspace.E[ 12 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 8 ]), &(acadoWorkspace.E[ 16 ]) ); + +acado_moveGuE( &(acadoWorkspace.evGu[ 8 ]), &(acadoWorkspace.E[ 20 ]) ); + +acado_moveGxT( &(acadoWorkspace.evGx[ 48 ]), acadoWorkspace.T ); +acado_multGxd( &(acadoWorkspace.d[ 8 ]), &(acadoWorkspace.evGx[ 48 ]), &(acadoWorkspace.d[ 12 ]) ); +acado_multGxGx( acadoWorkspace.T, &(acadoWorkspace.evGx[ 32 ]), &(acadoWorkspace.evGx[ 48 ]) ); + +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 12 ]), &(acadoWorkspace.E[ 24 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 16 ]), &(acadoWorkspace.E[ 28 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 20 ]), &(acadoWorkspace.E[ 32 ]) ); + +acado_moveGuE( &(acadoWorkspace.evGu[ 12 ]), &(acadoWorkspace.E[ 36 ]) ); + +acado_moveGxT( &(acadoWorkspace.evGx[ 64 ]), acadoWorkspace.T ); +acado_multGxd( &(acadoWorkspace.d[ 12 ]), &(acadoWorkspace.evGx[ 64 ]), &(acadoWorkspace.d[ 16 ]) ); +acado_multGxGx( acadoWorkspace.T, &(acadoWorkspace.evGx[ 48 ]), &(acadoWorkspace.evGx[ 64 ]) ); + +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 24 ]), &(acadoWorkspace.E[ 40 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 28 ]), &(acadoWorkspace.E[ 44 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 32 ]), &(acadoWorkspace.E[ 48 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 36 ]), &(acadoWorkspace.E[ 52 ]) ); + +acado_moveGuE( &(acadoWorkspace.evGu[ 16 ]), &(acadoWorkspace.E[ 56 ]) ); + +acado_moveGxT( &(acadoWorkspace.evGx[ 80 ]), acadoWorkspace.T ); +acado_multGxd( &(acadoWorkspace.d[ 16 ]), &(acadoWorkspace.evGx[ 80 ]), &(acadoWorkspace.d[ 20 ]) ); +acado_multGxGx( acadoWorkspace.T, &(acadoWorkspace.evGx[ 64 ]), &(acadoWorkspace.evGx[ 80 ]) ); + +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 40 ]), &(acadoWorkspace.E[ 60 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 44 ]), &(acadoWorkspace.E[ 64 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 48 ]), &(acadoWorkspace.E[ 68 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 52 ]), &(acadoWorkspace.E[ 72 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 56 ]), &(acadoWorkspace.E[ 76 ]) ); + +acado_moveGuE( &(acadoWorkspace.evGu[ 20 ]), &(acadoWorkspace.E[ 80 ]) ); + +acado_moveGxT( &(acadoWorkspace.evGx[ 96 ]), acadoWorkspace.T ); +acado_multGxd( &(acadoWorkspace.d[ 20 ]), &(acadoWorkspace.evGx[ 96 ]), &(acadoWorkspace.d[ 24 ]) ); +acado_multGxGx( acadoWorkspace.T, &(acadoWorkspace.evGx[ 80 ]), &(acadoWorkspace.evGx[ 96 ]) ); + +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 60 ]), &(acadoWorkspace.E[ 84 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 64 ]), &(acadoWorkspace.E[ 88 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 68 ]), &(acadoWorkspace.E[ 92 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 72 ]), &(acadoWorkspace.E[ 96 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 76 ]), &(acadoWorkspace.E[ 100 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 80 ]), &(acadoWorkspace.E[ 104 ]) ); + +acado_moveGuE( &(acadoWorkspace.evGu[ 24 ]), &(acadoWorkspace.E[ 108 ]) ); + +acado_moveGxT( &(acadoWorkspace.evGx[ 112 ]), acadoWorkspace.T ); +acado_multGxd( &(acadoWorkspace.d[ 24 ]), &(acadoWorkspace.evGx[ 112 ]), &(acadoWorkspace.d[ 28 ]) ); +acado_multGxGx( acadoWorkspace.T, &(acadoWorkspace.evGx[ 96 ]), &(acadoWorkspace.evGx[ 112 ]) ); + +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 84 ]), &(acadoWorkspace.E[ 112 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 88 ]), &(acadoWorkspace.E[ 116 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 92 ]), &(acadoWorkspace.E[ 120 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 96 ]), &(acadoWorkspace.E[ 124 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 100 ]), &(acadoWorkspace.E[ 128 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 104 ]), &(acadoWorkspace.E[ 132 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 108 ]), &(acadoWorkspace.E[ 136 ]) ); + +acado_moveGuE( &(acadoWorkspace.evGu[ 28 ]), &(acadoWorkspace.E[ 140 ]) ); + +acado_moveGxT( &(acadoWorkspace.evGx[ 128 ]), acadoWorkspace.T ); +acado_multGxd( &(acadoWorkspace.d[ 28 ]), &(acadoWorkspace.evGx[ 128 ]), &(acadoWorkspace.d[ 32 ]) ); +acado_multGxGx( acadoWorkspace.T, &(acadoWorkspace.evGx[ 112 ]), &(acadoWorkspace.evGx[ 128 ]) ); + +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 112 ]), &(acadoWorkspace.E[ 144 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 116 ]), &(acadoWorkspace.E[ 148 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 120 ]), &(acadoWorkspace.E[ 152 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 124 ]), &(acadoWorkspace.E[ 156 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 128 ]), &(acadoWorkspace.E[ 160 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 132 ]), &(acadoWorkspace.E[ 164 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 136 ]), &(acadoWorkspace.E[ 168 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 140 ]), &(acadoWorkspace.E[ 172 ]) ); + +acado_moveGuE( &(acadoWorkspace.evGu[ 32 ]), &(acadoWorkspace.E[ 176 ]) ); + +acado_moveGxT( &(acadoWorkspace.evGx[ 144 ]), acadoWorkspace.T ); +acado_multGxd( &(acadoWorkspace.d[ 32 ]), &(acadoWorkspace.evGx[ 144 ]), &(acadoWorkspace.d[ 36 ]) ); +acado_multGxGx( acadoWorkspace.T, &(acadoWorkspace.evGx[ 128 ]), &(acadoWorkspace.evGx[ 144 ]) ); + +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 144 ]), &(acadoWorkspace.E[ 180 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 148 ]), &(acadoWorkspace.E[ 184 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 152 ]), &(acadoWorkspace.E[ 188 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 156 ]), &(acadoWorkspace.E[ 192 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 160 ]), &(acadoWorkspace.E[ 196 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 164 ]), &(acadoWorkspace.E[ 200 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 168 ]), &(acadoWorkspace.E[ 204 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 172 ]), &(acadoWorkspace.E[ 208 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 176 ]), &(acadoWorkspace.E[ 212 ]) ); + +acado_moveGuE( &(acadoWorkspace.evGu[ 36 ]), &(acadoWorkspace.E[ 216 ]) ); + +acado_moveGxT( &(acadoWorkspace.evGx[ 160 ]), acadoWorkspace.T ); +acado_multGxd( &(acadoWorkspace.d[ 36 ]), &(acadoWorkspace.evGx[ 160 ]), &(acadoWorkspace.d[ 40 ]) ); +acado_multGxGx( acadoWorkspace.T, &(acadoWorkspace.evGx[ 144 ]), &(acadoWorkspace.evGx[ 160 ]) ); + +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 180 ]), &(acadoWorkspace.E[ 220 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 184 ]), &(acadoWorkspace.E[ 224 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 188 ]), &(acadoWorkspace.E[ 228 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 192 ]), &(acadoWorkspace.E[ 232 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 196 ]), &(acadoWorkspace.E[ 236 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 200 ]), &(acadoWorkspace.E[ 240 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 204 ]), &(acadoWorkspace.E[ 244 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 208 ]), &(acadoWorkspace.E[ 248 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 212 ]), &(acadoWorkspace.E[ 252 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 216 ]), &(acadoWorkspace.E[ 256 ]) ); + +acado_moveGuE( &(acadoWorkspace.evGu[ 40 ]), &(acadoWorkspace.E[ 260 ]) ); + +acado_moveGxT( &(acadoWorkspace.evGx[ 176 ]), acadoWorkspace.T ); +acado_multGxd( &(acadoWorkspace.d[ 40 ]), &(acadoWorkspace.evGx[ 176 ]), &(acadoWorkspace.d[ 44 ]) ); +acado_multGxGx( acadoWorkspace.T, &(acadoWorkspace.evGx[ 160 ]), &(acadoWorkspace.evGx[ 176 ]) ); + +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 220 ]), &(acadoWorkspace.E[ 264 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 224 ]), &(acadoWorkspace.E[ 268 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 228 ]), &(acadoWorkspace.E[ 272 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 232 ]), &(acadoWorkspace.E[ 276 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 236 ]), &(acadoWorkspace.E[ 280 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 240 ]), &(acadoWorkspace.E[ 284 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 244 ]), &(acadoWorkspace.E[ 288 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 248 ]), &(acadoWorkspace.E[ 292 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 252 ]), &(acadoWorkspace.E[ 296 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 256 ]), &(acadoWorkspace.E[ 300 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 260 ]), &(acadoWorkspace.E[ 304 ]) ); + +acado_moveGuE( &(acadoWorkspace.evGu[ 44 ]), &(acadoWorkspace.E[ 308 ]) ); + +acado_moveGxT( &(acadoWorkspace.evGx[ 192 ]), acadoWorkspace.T ); +acado_multGxd( &(acadoWorkspace.d[ 44 ]), &(acadoWorkspace.evGx[ 192 ]), &(acadoWorkspace.d[ 48 ]) ); +acado_multGxGx( acadoWorkspace.T, &(acadoWorkspace.evGx[ 176 ]), &(acadoWorkspace.evGx[ 192 ]) ); + +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 264 ]), &(acadoWorkspace.E[ 312 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 268 ]), &(acadoWorkspace.E[ 316 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 272 ]), &(acadoWorkspace.E[ 320 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 276 ]), &(acadoWorkspace.E[ 324 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 280 ]), &(acadoWorkspace.E[ 328 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 284 ]), &(acadoWorkspace.E[ 332 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 288 ]), &(acadoWorkspace.E[ 336 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 292 ]), &(acadoWorkspace.E[ 340 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 296 ]), &(acadoWorkspace.E[ 344 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 300 ]), &(acadoWorkspace.E[ 348 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 304 ]), &(acadoWorkspace.E[ 352 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 308 ]), &(acadoWorkspace.E[ 356 ]) ); + +acado_moveGuE( &(acadoWorkspace.evGu[ 48 ]), &(acadoWorkspace.E[ 360 ]) ); + +acado_moveGxT( &(acadoWorkspace.evGx[ 208 ]), acadoWorkspace.T ); +acado_multGxd( &(acadoWorkspace.d[ 48 ]), &(acadoWorkspace.evGx[ 208 ]), &(acadoWorkspace.d[ 52 ]) ); +acado_multGxGx( acadoWorkspace.T, &(acadoWorkspace.evGx[ 192 ]), &(acadoWorkspace.evGx[ 208 ]) ); + +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 312 ]), &(acadoWorkspace.E[ 364 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 316 ]), &(acadoWorkspace.E[ 368 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 320 ]), &(acadoWorkspace.E[ 372 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 324 ]), &(acadoWorkspace.E[ 376 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 328 ]), &(acadoWorkspace.E[ 380 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 332 ]), &(acadoWorkspace.E[ 384 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 336 ]), &(acadoWorkspace.E[ 388 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 340 ]), &(acadoWorkspace.E[ 392 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 344 ]), &(acadoWorkspace.E[ 396 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 348 ]), &(acadoWorkspace.E[ 400 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 352 ]), &(acadoWorkspace.E[ 404 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 356 ]), &(acadoWorkspace.E[ 408 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 360 ]), &(acadoWorkspace.E[ 412 ]) ); + +acado_moveGuE( &(acadoWorkspace.evGu[ 52 ]), &(acadoWorkspace.E[ 416 ]) ); + +acado_moveGxT( &(acadoWorkspace.evGx[ 224 ]), acadoWorkspace.T ); +acado_multGxd( &(acadoWorkspace.d[ 52 ]), &(acadoWorkspace.evGx[ 224 ]), &(acadoWorkspace.d[ 56 ]) ); +acado_multGxGx( acadoWorkspace.T, &(acadoWorkspace.evGx[ 208 ]), &(acadoWorkspace.evGx[ 224 ]) ); + +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 364 ]), &(acadoWorkspace.E[ 420 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 368 ]), &(acadoWorkspace.E[ 424 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 372 ]), &(acadoWorkspace.E[ 428 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 376 ]), &(acadoWorkspace.E[ 432 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 380 ]), &(acadoWorkspace.E[ 436 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 384 ]), &(acadoWorkspace.E[ 440 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 388 ]), &(acadoWorkspace.E[ 444 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 392 ]), &(acadoWorkspace.E[ 448 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 396 ]), &(acadoWorkspace.E[ 452 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 400 ]), &(acadoWorkspace.E[ 456 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 404 ]), &(acadoWorkspace.E[ 460 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 408 ]), &(acadoWorkspace.E[ 464 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 412 ]), &(acadoWorkspace.E[ 468 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 416 ]), &(acadoWorkspace.E[ 472 ]) ); + +acado_moveGuE( &(acadoWorkspace.evGu[ 56 ]), &(acadoWorkspace.E[ 476 ]) ); + +acado_moveGxT( &(acadoWorkspace.evGx[ 240 ]), acadoWorkspace.T ); +acado_multGxd( &(acadoWorkspace.d[ 56 ]), &(acadoWorkspace.evGx[ 240 ]), &(acadoWorkspace.d[ 60 ]) ); +acado_multGxGx( acadoWorkspace.T, &(acadoWorkspace.evGx[ 224 ]), &(acadoWorkspace.evGx[ 240 ]) ); + +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 420 ]), &(acadoWorkspace.E[ 480 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 424 ]), &(acadoWorkspace.E[ 484 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 428 ]), &(acadoWorkspace.E[ 488 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 432 ]), &(acadoWorkspace.E[ 492 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 436 ]), &(acadoWorkspace.E[ 496 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 440 ]), &(acadoWorkspace.E[ 500 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 444 ]), &(acadoWorkspace.E[ 504 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 448 ]), &(acadoWorkspace.E[ 508 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 452 ]), &(acadoWorkspace.E[ 512 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 456 ]), &(acadoWorkspace.E[ 516 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 460 ]), &(acadoWorkspace.E[ 520 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 464 ]), &(acadoWorkspace.E[ 524 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 468 ]), &(acadoWorkspace.E[ 528 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 472 ]), &(acadoWorkspace.E[ 532 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 476 ]), &(acadoWorkspace.E[ 536 ]) ); + +acado_moveGuE( &(acadoWorkspace.evGu[ 60 ]), &(acadoWorkspace.E[ 540 ]) ); + +acado_moveGxT( &(acadoWorkspace.evGx[ 256 ]), acadoWorkspace.T ); +acado_multGxd( &(acadoWorkspace.d[ 60 ]), &(acadoWorkspace.evGx[ 256 ]), &(acadoWorkspace.d[ 64 ]) ); +acado_multGxGx( acadoWorkspace.T, &(acadoWorkspace.evGx[ 240 ]), &(acadoWorkspace.evGx[ 256 ]) ); + +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 480 ]), &(acadoWorkspace.E[ 544 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 484 ]), &(acadoWorkspace.E[ 548 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 488 ]), &(acadoWorkspace.E[ 552 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 492 ]), &(acadoWorkspace.E[ 556 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 496 ]), &(acadoWorkspace.E[ 560 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 500 ]), &(acadoWorkspace.E[ 564 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 504 ]), &(acadoWorkspace.E[ 568 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 508 ]), &(acadoWorkspace.E[ 572 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 512 ]), &(acadoWorkspace.E[ 576 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 516 ]), &(acadoWorkspace.E[ 580 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 520 ]), &(acadoWorkspace.E[ 584 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 524 ]), &(acadoWorkspace.E[ 588 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 528 ]), &(acadoWorkspace.E[ 592 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 532 ]), &(acadoWorkspace.E[ 596 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 536 ]), &(acadoWorkspace.E[ 600 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 540 ]), &(acadoWorkspace.E[ 604 ]) ); + +acado_moveGuE( &(acadoWorkspace.evGu[ 64 ]), &(acadoWorkspace.E[ 608 ]) ); + +acado_moveGxT( &(acadoWorkspace.evGx[ 272 ]), acadoWorkspace.T ); +acado_multGxd( &(acadoWorkspace.d[ 64 ]), &(acadoWorkspace.evGx[ 272 ]), &(acadoWorkspace.d[ 68 ]) ); +acado_multGxGx( acadoWorkspace.T, &(acadoWorkspace.evGx[ 256 ]), &(acadoWorkspace.evGx[ 272 ]) ); + +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 544 ]), &(acadoWorkspace.E[ 612 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 548 ]), &(acadoWorkspace.E[ 616 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 552 ]), &(acadoWorkspace.E[ 620 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 556 ]), &(acadoWorkspace.E[ 624 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 560 ]), &(acadoWorkspace.E[ 628 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 564 ]), &(acadoWorkspace.E[ 632 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 568 ]), &(acadoWorkspace.E[ 636 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 572 ]), &(acadoWorkspace.E[ 640 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 576 ]), &(acadoWorkspace.E[ 644 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 580 ]), &(acadoWorkspace.E[ 648 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 584 ]), &(acadoWorkspace.E[ 652 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 588 ]), &(acadoWorkspace.E[ 656 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 592 ]), &(acadoWorkspace.E[ 660 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 596 ]), &(acadoWorkspace.E[ 664 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 600 ]), &(acadoWorkspace.E[ 668 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 604 ]), &(acadoWorkspace.E[ 672 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 608 ]), &(acadoWorkspace.E[ 676 ]) ); + +acado_moveGuE( &(acadoWorkspace.evGu[ 68 ]), &(acadoWorkspace.E[ 680 ]) ); + +acado_moveGxT( &(acadoWorkspace.evGx[ 288 ]), acadoWorkspace.T ); +acado_multGxd( &(acadoWorkspace.d[ 68 ]), &(acadoWorkspace.evGx[ 288 ]), &(acadoWorkspace.d[ 72 ]) ); +acado_multGxGx( acadoWorkspace.T, &(acadoWorkspace.evGx[ 272 ]), &(acadoWorkspace.evGx[ 288 ]) ); + +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 612 ]), &(acadoWorkspace.E[ 684 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 616 ]), &(acadoWorkspace.E[ 688 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 620 ]), &(acadoWorkspace.E[ 692 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 624 ]), &(acadoWorkspace.E[ 696 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 628 ]), &(acadoWorkspace.E[ 700 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 632 ]), &(acadoWorkspace.E[ 704 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 636 ]), &(acadoWorkspace.E[ 708 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 640 ]), &(acadoWorkspace.E[ 712 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 644 ]), &(acadoWorkspace.E[ 716 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 648 ]), &(acadoWorkspace.E[ 720 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 652 ]), &(acadoWorkspace.E[ 724 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 656 ]), &(acadoWorkspace.E[ 728 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 660 ]), &(acadoWorkspace.E[ 732 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 664 ]), &(acadoWorkspace.E[ 736 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 668 ]), &(acadoWorkspace.E[ 740 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 672 ]), &(acadoWorkspace.E[ 744 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 676 ]), &(acadoWorkspace.E[ 748 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 680 ]), &(acadoWorkspace.E[ 752 ]) ); + +acado_moveGuE( &(acadoWorkspace.evGu[ 72 ]), &(acadoWorkspace.E[ 756 ]) ); + +acado_moveGxT( &(acadoWorkspace.evGx[ 304 ]), acadoWorkspace.T ); +acado_multGxd( &(acadoWorkspace.d[ 72 ]), &(acadoWorkspace.evGx[ 304 ]), &(acadoWorkspace.d[ 76 ]) ); +acado_multGxGx( acadoWorkspace.T, &(acadoWorkspace.evGx[ 288 ]), &(acadoWorkspace.evGx[ 304 ]) ); + +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 684 ]), &(acadoWorkspace.E[ 760 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 688 ]), &(acadoWorkspace.E[ 764 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 692 ]), &(acadoWorkspace.E[ 768 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 696 ]), &(acadoWorkspace.E[ 772 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 700 ]), &(acadoWorkspace.E[ 776 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 704 ]), &(acadoWorkspace.E[ 780 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 708 ]), &(acadoWorkspace.E[ 784 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 712 ]), &(acadoWorkspace.E[ 788 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 716 ]), &(acadoWorkspace.E[ 792 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 720 ]), &(acadoWorkspace.E[ 796 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 724 ]), &(acadoWorkspace.E[ 800 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 728 ]), &(acadoWorkspace.E[ 804 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 732 ]), &(acadoWorkspace.E[ 808 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 736 ]), &(acadoWorkspace.E[ 812 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 740 ]), &(acadoWorkspace.E[ 816 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 744 ]), &(acadoWorkspace.E[ 820 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 748 ]), &(acadoWorkspace.E[ 824 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 752 ]), &(acadoWorkspace.E[ 828 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 756 ]), &(acadoWorkspace.E[ 832 ]) ); + +acado_moveGuE( &(acadoWorkspace.evGu[ 76 ]), &(acadoWorkspace.E[ 836 ]) ); + +acado_multGxGx( &(acadoWorkspace.Q1[ 16 ]), acadoWorkspace.evGx, acadoWorkspace.QGx ); +acado_multGxGx( &(acadoWorkspace.Q1[ 32 ]), &(acadoWorkspace.evGx[ 16 ]), &(acadoWorkspace.QGx[ 16 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 48 ]), &(acadoWorkspace.evGx[ 32 ]), &(acadoWorkspace.QGx[ 32 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 64 ]), &(acadoWorkspace.evGx[ 48 ]), &(acadoWorkspace.QGx[ 48 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 80 ]), &(acadoWorkspace.evGx[ 64 ]), &(acadoWorkspace.QGx[ 64 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 96 ]), &(acadoWorkspace.evGx[ 80 ]), &(acadoWorkspace.QGx[ 80 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 112 ]), &(acadoWorkspace.evGx[ 96 ]), &(acadoWorkspace.QGx[ 96 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 128 ]), &(acadoWorkspace.evGx[ 112 ]), &(acadoWorkspace.QGx[ 112 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 144 ]), &(acadoWorkspace.evGx[ 128 ]), &(acadoWorkspace.QGx[ 128 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 160 ]), &(acadoWorkspace.evGx[ 144 ]), &(acadoWorkspace.QGx[ 144 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 176 ]), &(acadoWorkspace.evGx[ 160 ]), &(acadoWorkspace.QGx[ 160 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 192 ]), &(acadoWorkspace.evGx[ 176 ]), &(acadoWorkspace.QGx[ 176 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 208 ]), &(acadoWorkspace.evGx[ 192 ]), &(acadoWorkspace.QGx[ 192 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 224 ]), &(acadoWorkspace.evGx[ 208 ]), &(acadoWorkspace.QGx[ 208 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 240 ]), &(acadoWorkspace.evGx[ 224 ]), &(acadoWorkspace.QGx[ 224 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 256 ]), &(acadoWorkspace.evGx[ 240 ]), &(acadoWorkspace.QGx[ 240 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 272 ]), &(acadoWorkspace.evGx[ 256 ]), &(acadoWorkspace.QGx[ 256 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 288 ]), &(acadoWorkspace.evGx[ 272 ]), &(acadoWorkspace.QGx[ 272 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 304 ]), &(acadoWorkspace.evGx[ 288 ]), &(acadoWorkspace.QGx[ 288 ]) ); +acado_multGxGx( acadoWorkspace.QN1, &(acadoWorkspace.evGx[ 304 ]), &(acadoWorkspace.QGx[ 304 ]) ); + +acado_multGxGu( &(acadoWorkspace.Q1[ 16 ]), acadoWorkspace.E, acadoWorkspace.QE ); +acado_multGxGu( &(acadoWorkspace.Q1[ 32 ]), &(acadoWorkspace.E[ 4 ]), &(acadoWorkspace.QE[ 4 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 32 ]), &(acadoWorkspace.E[ 8 ]), &(acadoWorkspace.QE[ 8 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 48 ]), &(acadoWorkspace.E[ 12 ]), &(acadoWorkspace.QE[ 12 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 48 ]), &(acadoWorkspace.E[ 16 ]), &(acadoWorkspace.QE[ 16 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 48 ]), &(acadoWorkspace.E[ 20 ]), &(acadoWorkspace.QE[ 20 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 64 ]), &(acadoWorkspace.E[ 24 ]), &(acadoWorkspace.QE[ 24 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 64 ]), &(acadoWorkspace.E[ 28 ]), &(acadoWorkspace.QE[ 28 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 64 ]), &(acadoWorkspace.E[ 32 ]), &(acadoWorkspace.QE[ 32 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 64 ]), &(acadoWorkspace.E[ 36 ]), &(acadoWorkspace.QE[ 36 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 80 ]), &(acadoWorkspace.E[ 40 ]), &(acadoWorkspace.QE[ 40 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 80 ]), &(acadoWorkspace.E[ 44 ]), &(acadoWorkspace.QE[ 44 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 80 ]), &(acadoWorkspace.E[ 48 ]), &(acadoWorkspace.QE[ 48 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 80 ]), &(acadoWorkspace.E[ 52 ]), &(acadoWorkspace.QE[ 52 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 80 ]), &(acadoWorkspace.E[ 56 ]), &(acadoWorkspace.QE[ 56 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 96 ]), &(acadoWorkspace.E[ 60 ]), &(acadoWorkspace.QE[ 60 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 96 ]), &(acadoWorkspace.E[ 64 ]), &(acadoWorkspace.QE[ 64 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 96 ]), &(acadoWorkspace.E[ 68 ]), &(acadoWorkspace.QE[ 68 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 96 ]), &(acadoWorkspace.E[ 72 ]), &(acadoWorkspace.QE[ 72 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 96 ]), &(acadoWorkspace.E[ 76 ]), &(acadoWorkspace.QE[ 76 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 96 ]), &(acadoWorkspace.E[ 80 ]), &(acadoWorkspace.QE[ 80 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 112 ]), &(acadoWorkspace.E[ 84 ]), &(acadoWorkspace.QE[ 84 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 112 ]), &(acadoWorkspace.E[ 88 ]), &(acadoWorkspace.QE[ 88 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 112 ]), &(acadoWorkspace.E[ 92 ]), &(acadoWorkspace.QE[ 92 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 112 ]), &(acadoWorkspace.E[ 96 ]), &(acadoWorkspace.QE[ 96 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 112 ]), &(acadoWorkspace.E[ 100 ]), &(acadoWorkspace.QE[ 100 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 112 ]), &(acadoWorkspace.E[ 104 ]), &(acadoWorkspace.QE[ 104 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 112 ]), &(acadoWorkspace.E[ 108 ]), &(acadoWorkspace.QE[ 108 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 128 ]), &(acadoWorkspace.E[ 112 ]), &(acadoWorkspace.QE[ 112 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 128 ]), &(acadoWorkspace.E[ 116 ]), &(acadoWorkspace.QE[ 116 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 128 ]), &(acadoWorkspace.E[ 120 ]), &(acadoWorkspace.QE[ 120 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 128 ]), &(acadoWorkspace.E[ 124 ]), &(acadoWorkspace.QE[ 124 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 128 ]), &(acadoWorkspace.E[ 128 ]), &(acadoWorkspace.QE[ 128 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 128 ]), &(acadoWorkspace.E[ 132 ]), &(acadoWorkspace.QE[ 132 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 128 ]), &(acadoWorkspace.E[ 136 ]), &(acadoWorkspace.QE[ 136 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 128 ]), &(acadoWorkspace.E[ 140 ]), &(acadoWorkspace.QE[ 140 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 144 ]), &(acadoWorkspace.E[ 144 ]), &(acadoWorkspace.QE[ 144 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 144 ]), &(acadoWorkspace.E[ 148 ]), &(acadoWorkspace.QE[ 148 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 144 ]), &(acadoWorkspace.E[ 152 ]), &(acadoWorkspace.QE[ 152 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 144 ]), &(acadoWorkspace.E[ 156 ]), &(acadoWorkspace.QE[ 156 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 144 ]), &(acadoWorkspace.E[ 160 ]), &(acadoWorkspace.QE[ 160 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 144 ]), &(acadoWorkspace.E[ 164 ]), &(acadoWorkspace.QE[ 164 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 144 ]), &(acadoWorkspace.E[ 168 ]), &(acadoWorkspace.QE[ 168 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 144 ]), &(acadoWorkspace.E[ 172 ]), &(acadoWorkspace.QE[ 172 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 144 ]), &(acadoWorkspace.E[ 176 ]), &(acadoWorkspace.QE[ 176 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 160 ]), &(acadoWorkspace.E[ 180 ]), &(acadoWorkspace.QE[ 180 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 160 ]), &(acadoWorkspace.E[ 184 ]), &(acadoWorkspace.QE[ 184 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 160 ]), &(acadoWorkspace.E[ 188 ]), &(acadoWorkspace.QE[ 188 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 160 ]), &(acadoWorkspace.E[ 192 ]), &(acadoWorkspace.QE[ 192 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 160 ]), &(acadoWorkspace.E[ 196 ]), &(acadoWorkspace.QE[ 196 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 160 ]), &(acadoWorkspace.E[ 200 ]), &(acadoWorkspace.QE[ 200 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 160 ]), &(acadoWorkspace.E[ 204 ]), &(acadoWorkspace.QE[ 204 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 160 ]), &(acadoWorkspace.E[ 208 ]), &(acadoWorkspace.QE[ 208 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 160 ]), &(acadoWorkspace.E[ 212 ]), &(acadoWorkspace.QE[ 212 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 160 ]), &(acadoWorkspace.E[ 216 ]), &(acadoWorkspace.QE[ 216 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 176 ]), &(acadoWorkspace.E[ 220 ]), &(acadoWorkspace.QE[ 220 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 176 ]), &(acadoWorkspace.E[ 224 ]), &(acadoWorkspace.QE[ 224 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 176 ]), &(acadoWorkspace.E[ 228 ]), &(acadoWorkspace.QE[ 228 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 176 ]), &(acadoWorkspace.E[ 232 ]), &(acadoWorkspace.QE[ 232 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 176 ]), &(acadoWorkspace.E[ 236 ]), &(acadoWorkspace.QE[ 236 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 176 ]), &(acadoWorkspace.E[ 240 ]), &(acadoWorkspace.QE[ 240 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 176 ]), &(acadoWorkspace.E[ 244 ]), &(acadoWorkspace.QE[ 244 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 176 ]), &(acadoWorkspace.E[ 248 ]), &(acadoWorkspace.QE[ 248 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 176 ]), &(acadoWorkspace.E[ 252 ]), &(acadoWorkspace.QE[ 252 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 176 ]), &(acadoWorkspace.E[ 256 ]), &(acadoWorkspace.QE[ 256 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 176 ]), &(acadoWorkspace.E[ 260 ]), &(acadoWorkspace.QE[ 260 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 192 ]), &(acadoWorkspace.E[ 264 ]), &(acadoWorkspace.QE[ 264 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 192 ]), &(acadoWorkspace.E[ 268 ]), &(acadoWorkspace.QE[ 268 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 192 ]), &(acadoWorkspace.E[ 272 ]), &(acadoWorkspace.QE[ 272 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 192 ]), &(acadoWorkspace.E[ 276 ]), &(acadoWorkspace.QE[ 276 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 192 ]), &(acadoWorkspace.E[ 280 ]), &(acadoWorkspace.QE[ 280 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 192 ]), &(acadoWorkspace.E[ 284 ]), &(acadoWorkspace.QE[ 284 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 192 ]), &(acadoWorkspace.E[ 288 ]), &(acadoWorkspace.QE[ 288 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 192 ]), &(acadoWorkspace.E[ 292 ]), &(acadoWorkspace.QE[ 292 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 192 ]), &(acadoWorkspace.E[ 296 ]), &(acadoWorkspace.QE[ 296 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 192 ]), &(acadoWorkspace.E[ 300 ]), &(acadoWorkspace.QE[ 300 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 192 ]), &(acadoWorkspace.E[ 304 ]), &(acadoWorkspace.QE[ 304 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 192 ]), &(acadoWorkspace.E[ 308 ]), &(acadoWorkspace.QE[ 308 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 208 ]), &(acadoWorkspace.E[ 312 ]), &(acadoWorkspace.QE[ 312 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 208 ]), &(acadoWorkspace.E[ 316 ]), &(acadoWorkspace.QE[ 316 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 208 ]), &(acadoWorkspace.E[ 320 ]), &(acadoWorkspace.QE[ 320 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 208 ]), &(acadoWorkspace.E[ 324 ]), &(acadoWorkspace.QE[ 324 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 208 ]), &(acadoWorkspace.E[ 328 ]), &(acadoWorkspace.QE[ 328 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 208 ]), &(acadoWorkspace.E[ 332 ]), &(acadoWorkspace.QE[ 332 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 208 ]), &(acadoWorkspace.E[ 336 ]), &(acadoWorkspace.QE[ 336 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 208 ]), &(acadoWorkspace.E[ 340 ]), &(acadoWorkspace.QE[ 340 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 208 ]), &(acadoWorkspace.E[ 344 ]), &(acadoWorkspace.QE[ 344 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 208 ]), &(acadoWorkspace.E[ 348 ]), &(acadoWorkspace.QE[ 348 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 208 ]), &(acadoWorkspace.E[ 352 ]), &(acadoWorkspace.QE[ 352 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 208 ]), &(acadoWorkspace.E[ 356 ]), &(acadoWorkspace.QE[ 356 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 208 ]), &(acadoWorkspace.E[ 360 ]), &(acadoWorkspace.QE[ 360 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 224 ]), &(acadoWorkspace.E[ 364 ]), &(acadoWorkspace.QE[ 364 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 224 ]), &(acadoWorkspace.E[ 368 ]), &(acadoWorkspace.QE[ 368 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 224 ]), &(acadoWorkspace.E[ 372 ]), &(acadoWorkspace.QE[ 372 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 224 ]), &(acadoWorkspace.E[ 376 ]), &(acadoWorkspace.QE[ 376 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 224 ]), &(acadoWorkspace.E[ 380 ]), &(acadoWorkspace.QE[ 380 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 224 ]), &(acadoWorkspace.E[ 384 ]), &(acadoWorkspace.QE[ 384 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 224 ]), &(acadoWorkspace.E[ 388 ]), &(acadoWorkspace.QE[ 388 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 224 ]), &(acadoWorkspace.E[ 392 ]), &(acadoWorkspace.QE[ 392 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 224 ]), &(acadoWorkspace.E[ 396 ]), &(acadoWorkspace.QE[ 396 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 224 ]), &(acadoWorkspace.E[ 400 ]), &(acadoWorkspace.QE[ 400 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 224 ]), &(acadoWorkspace.E[ 404 ]), &(acadoWorkspace.QE[ 404 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 224 ]), &(acadoWorkspace.E[ 408 ]), &(acadoWorkspace.QE[ 408 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 224 ]), &(acadoWorkspace.E[ 412 ]), &(acadoWorkspace.QE[ 412 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 224 ]), &(acadoWorkspace.E[ 416 ]), &(acadoWorkspace.QE[ 416 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 240 ]), &(acadoWorkspace.E[ 420 ]), &(acadoWorkspace.QE[ 420 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 240 ]), &(acadoWorkspace.E[ 424 ]), &(acadoWorkspace.QE[ 424 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 240 ]), &(acadoWorkspace.E[ 428 ]), &(acadoWorkspace.QE[ 428 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 240 ]), &(acadoWorkspace.E[ 432 ]), &(acadoWorkspace.QE[ 432 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 240 ]), &(acadoWorkspace.E[ 436 ]), &(acadoWorkspace.QE[ 436 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 240 ]), &(acadoWorkspace.E[ 440 ]), &(acadoWorkspace.QE[ 440 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 240 ]), &(acadoWorkspace.E[ 444 ]), &(acadoWorkspace.QE[ 444 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 240 ]), &(acadoWorkspace.E[ 448 ]), &(acadoWorkspace.QE[ 448 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 240 ]), &(acadoWorkspace.E[ 452 ]), &(acadoWorkspace.QE[ 452 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 240 ]), &(acadoWorkspace.E[ 456 ]), &(acadoWorkspace.QE[ 456 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 240 ]), &(acadoWorkspace.E[ 460 ]), &(acadoWorkspace.QE[ 460 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 240 ]), &(acadoWorkspace.E[ 464 ]), &(acadoWorkspace.QE[ 464 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 240 ]), &(acadoWorkspace.E[ 468 ]), &(acadoWorkspace.QE[ 468 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 240 ]), &(acadoWorkspace.E[ 472 ]), &(acadoWorkspace.QE[ 472 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 240 ]), &(acadoWorkspace.E[ 476 ]), &(acadoWorkspace.QE[ 476 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 256 ]), &(acadoWorkspace.E[ 480 ]), &(acadoWorkspace.QE[ 480 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 256 ]), &(acadoWorkspace.E[ 484 ]), &(acadoWorkspace.QE[ 484 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 256 ]), &(acadoWorkspace.E[ 488 ]), &(acadoWorkspace.QE[ 488 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 256 ]), &(acadoWorkspace.E[ 492 ]), &(acadoWorkspace.QE[ 492 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 256 ]), &(acadoWorkspace.E[ 496 ]), &(acadoWorkspace.QE[ 496 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 256 ]), &(acadoWorkspace.E[ 500 ]), &(acadoWorkspace.QE[ 500 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 256 ]), &(acadoWorkspace.E[ 504 ]), &(acadoWorkspace.QE[ 504 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 256 ]), &(acadoWorkspace.E[ 508 ]), &(acadoWorkspace.QE[ 508 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 256 ]), &(acadoWorkspace.E[ 512 ]), &(acadoWorkspace.QE[ 512 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 256 ]), &(acadoWorkspace.E[ 516 ]), &(acadoWorkspace.QE[ 516 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 256 ]), &(acadoWorkspace.E[ 520 ]), &(acadoWorkspace.QE[ 520 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 256 ]), &(acadoWorkspace.E[ 524 ]), &(acadoWorkspace.QE[ 524 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 256 ]), &(acadoWorkspace.E[ 528 ]), &(acadoWorkspace.QE[ 528 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 256 ]), &(acadoWorkspace.E[ 532 ]), &(acadoWorkspace.QE[ 532 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 256 ]), &(acadoWorkspace.E[ 536 ]), &(acadoWorkspace.QE[ 536 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 256 ]), &(acadoWorkspace.E[ 540 ]), &(acadoWorkspace.QE[ 540 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 272 ]), &(acadoWorkspace.E[ 544 ]), &(acadoWorkspace.QE[ 544 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 272 ]), &(acadoWorkspace.E[ 548 ]), &(acadoWorkspace.QE[ 548 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 272 ]), &(acadoWorkspace.E[ 552 ]), &(acadoWorkspace.QE[ 552 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 272 ]), &(acadoWorkspace.E[ 556 ]), &(acadoWorkspace.QE[ 556 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 272 ]), &(acadoWorkspace.E[ 560 ]), &(acadoWorkspace.QE[ 560 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 272 ]), &(acadoWorkspace.E[ 564 ]), &(acadoWorkspace.QE[ 564 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 272 ]), &(acadoWorkspace.E[ 568 ]), &(acadoWorkspace.QE[ 568 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 272 ]), &(acadoWorkspace.E[ 572 ]), &(acadoWorkspace.QE[ 572 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 272 ]), &(acadoWorkspace.E[ 576 ]), &(acadoWorkspace.QE[ 576 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 272 ]), &(acadoWorkspace.E[ 580 ]), &(acadoWorkspace.QE[ 580 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 272 ]), &(acadoWorkspace.E[ 584 ]), &(acadoWorkspace.QE[ 584 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 272 ]), &(acadoWorkspace.E[ 588 ]), &(acadoWorkspace.QE[ 588 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 272 ]), &(acadoWorkspace.E[ 592 ]), &(acadoWorkspace.QE[ 592 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 272 ]), &(acadoWorkspace.E[ 596 ]), &(acadoWorkspace.QE[ 596 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 272 ]), &(acadoWorkspace.E[ 600 ]), &(acadoWorkspace.QE[ 600 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 272 ]), &(acadoWorkspace.E[ 604 ]), &(acadoWorkspace.QE[ 604 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 272 ]), &(acadoWorkspace.E[ 608 ]), &(acadoWorkspace.QE[ 608 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 288 ]), &(acadoWorkspace.E[ 612 ]), &(acadoWorkspace.QE[ 612 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 288 ]), &(acadoWorkspace.E[ 616 ]), &(acadoWorkspace.QE[ 616 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 288 ]), &(acadoWorkspace.E[ 620 ]), &(acadoWorkspace.QE[ 620 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 288 ]), &(acadoWorkspace.E[ 624 ]), &(acadoWorkspace.QE[ 624 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 288 ]), &(acadoWorkspace.E[ 628 ]), &(acadoWorkspace.QE[ 628 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 288 ]), &(acadoWorkspace.E[ 632 ]), &(acadoWorkspace.QE[ 632 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 288 ]), &(acadoWorkspace.E[ 636 ]), &(acadoWorkspace.QE[ 636 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 288 ]), &(acadoWorkspace.E[ 640 ]), &(acadoWorkspace.QE[ 640 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 288 ]), &(acadoWorkspace.E[ 644 ]), &(acadoWorkspace.QE[ 644 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 288 ]), &(acadoWorkspace.E[ 648 ]), &(acadoWorkspace.QE[ 648 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 288 ]), &(acadoWorkspace.E[ 652 ]), &(acadoWorkspace.QE[ 652 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 288 ]), &(acadoWorkspace.E[ 656 ]), &(acadoWorkspace.QE[ 656 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 288 ]), &(acadoWorkspace.E[ 660 ]), &(acadoWorkspace.QE[ 660 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 288 ]), &(acadoWorkspace.E[ 664 ]), &(acadoWorkspace.QE[ 664 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 288 ]), &(acadoWorkspace.E[ 668 ]), &(acadoWorkspace.QE[ 668 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 288 ]), &(acadoWorkspace.E[ 672 ]), &(acadoWorkspace.QE[ 672 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 288 ]), &(acadoWorkspace.E[ 676 ]), &(acadoWorkspace.QE[ 676 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 288 ]), &(acadoWorkspace.E[ 680 ]), &(acadoWorkspace.QE[ 680 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 304 ]), &(acadoWorkspace.E[ 684 ]), &(acadoWorkspace.QE[ 684 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 304 ]), &(acadoWorkspace.E[ 688 ]), &(acadoWorkspace.QE[ 688 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 304 ]), &(acadoWorkspace.E[ 692 ]), &(acadoWorkspace.QE[ 692 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 304 ]), &(acadoWorkspace.E[ 696 ]), &(acadoWorkspace.QE[ 696 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 304 ]), &(acadoWorkspace.E[ 700 ]), &(acadoWorkspace.QE[ 700 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 304 ]), &(acadoWorkspace.E[ 704 ]), &(acadoWorkspace.QE[ 704 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 304 ]), &(acadoWorkspace.E[ 708 ]), &(acadoWorkspace.QE[ 708 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 304 ]), &(acadoWorkspace.E[ 712 ]), &(acadoWorkspace.QE[ 712 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 304 ]), &(acadoWorkspace.E[ 716 ]), &(acadoWorkspace.QE[ 716 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 304 ]), &(acadoWorkspace.E[ 720 ]), &(acadoWorkspace.QE[ 720 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 304 ]), &(acadoWorkspace.E[ 724 ]), &(acadoWorkspace.QE[ 724 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 304 ]), &(acadoWorkspace.E[ 728 ]), &(acadoWorkspace.QE[ 728 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 304 ]), &(acadoWorkspace.E[ 732 ]), &(acadoWorkspace.QE[ 732 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 304 ]), &(acadoWorkspace.E[ 736 ]), &(acadoWorkspace.QE[ 736 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 304 ]), &(acadoWorkspace.E[ 740 ]), &(acadoWorkspace.QE[ 740 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 304 ]), &(acadoWorkspace.E[ 744 ]), &(acadoWorkspace.QE[ 744 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 304 ]), &(acadoWorkspace.E[ 748 ]), &(acadoWorkspace.QE[ 748 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 304 ]), &(acadoWorkspace.E[ 752 ]), &(acadoWorkspace.QE[ 752 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 304 ]), &(acadoWorkspace.E[ 756 ]), &(acadoWorkspace.QE[ 756 ]) ); +acado_multGxGu( acadoWorkspace.QN1, &(acadoWorkspace.E[ 760 ]), &(acadoWorkspace.QE[ 760 ]) ); +acado_multGxGu( acadoWorkspace.QN1, &(acadoWorkspace.E[ 764 ]), &(acadoWorkspace.QE[ 764 ]) ); +acado_multGxGu( acadoWorkspace.QN1, &(acadoWorkspace.E[ 768 ]), &(acadoWorkspace.QE[ 768 ]) ); +acado_multGxGu( acadoWorkspace.QN1, &(acadoWorkspace.E[ 772 ]), &(acadoWorkspace.QE[ 772 ]) ); +acado_multGxGu( acadoWorkspace.QN1, &(acadoWorkspace.E[ 776 ]), &(acadoWorkspace.QE[ 776 ]) ); +acado_multGxGu( acadoWorkspace.QN1, &(acadoWorkspace.E[ 780 ]), &(acadoWorkspace.QE[ 780 ]) ); +acado_multGxGu( acadoWorkspace.QN1, &(acadoWorkspace.E[ 784 ]), &(acadoWorkspace.QE[ 784 ]) ); +acado_multGxGu( acadoWorkspace.QN1, &(acadoWorkspace.E[ 788 ]), &(acadoWorkspace.QE[ 788 ]) ); +acado_multGxGu( acadoWorkspace.QN1, &(acadoWorkspace.E[ 792 ]), &(acadoWorkspace.QE[ 792 ]) ); +acado_multGxGu( acadoWorkspace.QN1, &(acadoWorkspace.E[ 796 ]), &(acadoWorkspace.QE[ 796 ]) ); +acado_multGxGu( acadoWorkspace.QN1, &(acadoWorkspace.E[ 800 ]), &(acadoWorkspace.QE[ 800 ]) ); +acado_multGxGu( acadoWorkspace.QN1, &(acadoWorkspace.E[ 804 ]), &(acadoWorkspace.QE[ 804 ]) ); +acado_multGxGu( acadoWorkspace.QN1, &(acadoWorkspace.E[ 808 ]), &(acadoWorkspace.QE[ 808 ]) ); +acado_multGxGu( acadoWorkspace.QN1, &(acadoWorkspace.E[ 812 ]), &(acadoWorkspace.QE[ 812 ]) ); +acado_multGxGu( acadoWorkspace.QN1, &(acadoWorkspace.E[ 816 ]), &(acadoWorkspace.QE[ 816 ]) ); +acado_multGxGu( acadoWorkspace.QN1, &(acadoWorkspace.E[ 820 ]), &(acadoWorkspace.QE[ 820 ]) ); +acado_multGxGu( acadoWorkspace.QN1, &(acadoWorkspace.E[ 824 ]), &(acadoWorkspace.QE[ 824 ]) ); +acado_multGxGu( acadoWorkspace.QN1, &(acadoWorkspace.E[ 828 ]), &(acadoWorkspace.QE[ 828 ]) ); +acado_multGxGu( acadoWorkspace.QN1, &(acadoWorkspace.E[ 832 ]), &(acadoWorkspace.QE[ 832 ]) ); +acado_multGxGu( acadoWorkspace.QN1, &(acadoWorkspace.E[ 836 ]), &(acadoWorkspace.QE[ 836 ]) ); + +acado_zeroBlockH00( ); +acado_multCTQC( acadoWorkspace.evGx, acadoWorkspace.QGx ); +acado_multCTQC( &(acadoWorkspace.evGx[ 16 ]), &(acadoWorkspace.QGx[ 16 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 32 ]), &(acadoWorkspace.QGx[ 32 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 48 ]), &(acadoWorkspace.QGx[ 48 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 64 ]), &(acadoWorkspace.QGx[ 64 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 80 ]), &(acadoWorkspace.QGx[ 80 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 96 ]), &(acadoWorkspace.QGx[ 96 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 112 ]), &(acadoWorkspace.QGx[ 112 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 128 ]), &(acadoWorkspace.QGx[ 128 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 144 ]), &(acadoWorkspace.QGx[ 144 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 160 ]), &(acadoWorkspace.QGx[ 160 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 176 ]), &(acadoWorkspace.QGx[ 176 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 192 ]), &(acadoWorkspace.QGx[ 192 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 208 ]), &(acadoWorkspace.QGx[ 208 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 224 ]), &(acadoWorkspace.QGx[ 224 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 240 ]), &(acadoWorkspace.QGx[ 240 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 256 ]), &(acadoWorkspace.QGx[ 256 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 272 ]), &(acadoWorkspace.QGx[ 272 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 288 ]), &(acadoWorkspace.QGx[ 288 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 304 ]), &(acadoWorkspace.QGx[ 304 ]) ); + +acado_zeroBlockH10( acadoWorkspace.H10 ); +acado_multQETGx( acadoWorkspace.QE, acadoWorkspace.evGx, acadoWorkspace.H10 ); +acado_multQETGx( &(acadoWorkspace.QE[ 4 ]), &(acadoWorkspace.evGx[ 16 ]), acadoWorkspace.H10 ); +acado_multQETGx( &(acadoWorkspace.QE[ 12 ]), &(acadoWorkspace.evGx[ 32 ]), acadoWorkspace.H10 ); +acado_multQETGx( &(acadoWorkspace.QE[ 24 ]), &(acadoWorkspace.evGx[ 48 ]), acadoWorkspace.H10 ); +acado_multQETGx( &(acadoWorkspace.QE[ 40 ]), &(acadoWorkspace.evGx[ 64 ]), acadoWorkspace.H10 ); +acado_multQETGx( &(acadoWorkspace.QE[ 60 ]), &(acadoWorkspace.evGx[ 80 ]), acadoWorkspace.H10 ); +acado_multQETGx( &(acadoWorkspace.QE[ 84 ]), &(acadoWorkspace.evGx[ 96 ]), acadoWorkspace.H10 ); +acado_multQETGx( &(acadoWorkspace.QE[ 112 ]), &(acadoWorkspace.evGx[ 112 ]), acadoWorkspace.H10 ); +acado_multQETGx( &(acadoWorkspace.QE[ 144 ]), &(acadoWorkspace.evGx[ 128 ]), acadoWorkspace.H10 ); +acado_multQETGx( &(acadoWorkspace.QE[ 180 ]), &(acadoWorkspace.evGx[ 144 ]), acadoWorkspace.H10 ); +acado_multQETGx( &(acadoWorkspace.QE[ 220 ]), &(acadoWorkspace.evGx[ 160 ]), acadoWorkspace.H10 ); +acado_multQETGx( &(acadoWorkspace.QE[ 264 ]), &(acadoWorkspace.evGx[ 176 ]), acadoWorkspace.H10 ); +acado_multQETGx( &(acadoWorkspace.QE[ 312 ]), &(acadoWorkspace.evGx[ 192 ]), acadoWorkspace.H10 ); +acado_multQETGx( &(acadoWorkspace.QE[ 364 ]), &(acadoWorkspace.evGx[ 208 ]), acadoWorkspace.H10 ); +acado_multQETGx( &(acadoWorkspace.QE[ 420 ]), &(acadoWorkspace.evGx[ 224 ]), acadoWorkspace.H10 ); +acado_multQETGx( &(acadoWorkspace.QE[ 480 ]), &(acadoWorkspace.evGx[ 240 ]), acadoWorkspace.H10 ); +acado_multQETGx( &(acadoWorkspace.QE[ 544 ]), &(acadoWorkspace.evGx[ 256 ]), acadoWorkspace.H10 ); +acado_multQETGx( &(acadoWorkspace.QE[ 612 ]), &(acadoWorkspace.evGx[ 272 ]), acadoWorkspace.H10 ); +acado_multQETGx( &(acadoWorkspace.QE[ 684 ]), &(acadoWorkspace.evGx[ 288 ]), acadoWorkspace.H10 ); +acado_multQETGx( &(acadoWorkspace.QE[ 760 ]), &(acadoWorkspace.evGx[ 304 ]), acadoWorkspace.H10 ); +acado_zeroBlockH10( &(acadoWorkspace.H10[ 4 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 8 ]), &(acadoWorkspace.evGx[ 16 ]), &(acadoWorkspace.H10[ 4 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 16 ]), &(acadoWorkspace.evGx[ 32 ]), &(acadoWorkspace.H10[ 4 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 28 ]), &(acadoWorkspace.evGx[ 48 ]), &(acadoWorkspace.H10[ 4 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 44 ]), &(acadoWorkspace.evGx[ 64 ]), &(acadoWorkspace.H10[ 4 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 64 ]), &(acadoWorkspace.evGx[ 80 ]), &(acadoWorkspace.H10[ 4 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 88 ]), &(acadoWorkspace.evGx[ 96 ]), &(acadoWorkspace.H10[ 4 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 116 ]), &(acadoWorkspace.evGx[ 112 ]), &(acadoWorkspace.H10[ 4 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 148 ]), &(acadoWorkspace.evGx[ 128 ]), &(acadoWorkspace.H10[ 4 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 184 ]), &(acadoWorkspace.evGx[ 144 ]), &(acadoWorkspace.H10[ 4 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 224 ]), &(acadoWorkspace.evGx[ 160 ]), &(acadoWorkspace.H10[ 4 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 268 ]), &(acadoWorkspace.evGx[ 176 ]), &(acadoWorkspace.H10[ 4 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 316 ]), &(acadoWorkspace.evGx[ 192 ]), &(acadoWorkspace.H10[ 4 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 368 ]), &(acadoWorkspace.evGx[ 208 ]), &(acadoWorkspace.H10[ 4 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 424 ]), &(acadoWorkspace.evGx[ 224 ]), &(acadoWorkspace.H10[ 4 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 484 ]), &(acadoWorkspace.evGx[ 240 ]), &(acadoWorkspace.H10[ 4 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 548 ]), &(acadoWorkspace.evGx[ 256 ]), &(acadoWorkspace.H10[ 4 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 616 ]), &(acadoWorkspace.evGx[ 272 ]), &(acadoWorkspace.H10[ 4 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 688 ]), &(acadoWorkspace.evGx[ 288 ]), &(acadoWorkspace.H10[ 4 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 764 ]), &(acadoWorkspace.evGx[ 304 ]), &(acadoWorkspace.H10[ 4 ]) ); +acado_zeroBlockH10( &(acadoWorkspace.H10[ 8 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 20 ]), &(acadoWorkspace.evGx[ 32 ]), &(acadoWorkspace.H10[ 8 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 32 ]), &(acadoWorkspace.evGx[ 48 ]), &(acadoWorkspace.H10[ 8 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 48 ]), &(acadoWorkspace.evGx[ 64 ]), &(acadoWorkspace.H10[ 8 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 68 ]), &(acadoWorkspace.evGx[ 80 ]), &(acadoWorkspace.H10[ 8 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 92 ]), &(acadoWorkspace.evGx[ 96 ]), &(acadoWorkspace.H10[ 8 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 120 ]), &(acadoWorkspace.evGx[ 112 ]), &(acadoWorkspace.H10[ 8 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 152 ]), &(acadoWorkspace.evGx[ 128 ]), &(acadoWorkspace.H10[ 8 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 188 ]), &(acadoWorkspace.evGx[ 144 ]), &(acadoWorkspace.H10[ 8 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 228 ]), &(acadoWorkspace.evGx[ 160 ]), &(acadoWorkspace.H10[ 8 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 272 ]), &(acadoWorkspace.evGx[ 176 ]), &(acadoWorkspace.H10[ 8 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 320 ]), &(acadoWorkspace.evGx[ 192 ]), &(acadoWorkspace.H10[ 8 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 372 ]), &(acadoWorkspace.evGx[ 208 ]), &(acadoWorkspace.H10[ 8 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 428 ]), &(acadoWorkspace.evGx[ 224 ]), &(acadoWorkspace.H10[ 8 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 488 ]), &(acadoWorkspace.evGx[ 240 ]), &(acadoWorkspace.H10[ 8 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 552 ]), &(acadoWorkspace.evGx[ 256 ]), &(acadoWorkspace.H10[ 8 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 620 ]), &(acadoWorkspace.evGx[ 272 ]), &(acadoWorkspace.H10[ 8 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 692 ]), &(acadoWorkspace.evGx[ 288 ]), &(acadoWorkspace.H10[ 8 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 768 ]), &(acadoWorkspace.evGx[ 304 ]), &(acadoWorkspace.H10[ 8 ]) ); +acado_zeroBlockH10( &(acadoWorkspace.H10[ 12 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 36 ]), &(acadoWorkspace.evGx[ 48 ]), &(acadoWorkspace.H10[ 12 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 52 ]), &(acadoWorkspace.evGx[ 64 ]), &(acadoWorkspace.H10[ 12 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 72 ]), &(acadoWorkspace.evGx[ 80 ]), &(acadoWorkspace.H10[ 12 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 96 ]), &(acadoWorkspace.evGx[ 96 ]), &(acadoWorkspace.H10[ 12 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 124 ]), &(acadoWorkspace.evGx[ 112 ]), &(acadoWorkspace.H10[ 12 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 156 ]), &(acadoWorkspace.evGx[ 128 ]), &(acadoWorkspace.H10[ 12 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 192 ]), &(acadoWorkspace.evGx[ 144 ]), &(acadoWorkspace.H10[ 12 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 232 ]), &(acadoWorkspace.evGx[ 160 ]), &(acadoWorkspace.H10[ 12 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 276 ]), &(acadoWorkspace.evGx[ 176 ]), &(acadoWorkspace.H10[ 12 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 324 ]), &(acadoWorkspace.evGx[ 192 ]), &(acadoWorkspace.H10[ 12 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 376 ]), &(acadoWorkspace.evGx[ 208 ]), &(acadoWorkspace.H10[ 12 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 432 ]), &(acadoWorkspace.evGx[ 224 ]), &(acadoWorkspace.H10[ 12 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 492 ]), &(acadoWorkspace.evGx[ 240 ]), &(acadoWorkspace.H10[ 12 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 556 ]), &(acadoWorkspace.evGx[ 256 ]), &(acadoWorkspace.H10[ 12 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 624 ]), &(acadoWorkspace.evGx[ 272 ]), &(acadoWorkspace.H10[ 12 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 696 ]), &(acadoWorkspace.evGx[ 288 ]), &(acadoWorkspace.H10[ 12 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 772 ]), &(acadoWorkspace.evGx[ 304 ]), &(acadoWorkspace.H10[ 12 ]) ); +acado_zeroBlockH10( &(acadoWorkspace.H10[ 16 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 56 ]), &(acadoWorkspace.evGx[ 64 ]), &(acadoWorkspace.H10[ 16 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 76 ]), &(acadoWorkspace.evGx[ 80 ]), &(acadoWorkspace.H10[ 16 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 100 ]), &(acadoWorkspace.evGx[ 96 ]), &(acadoWorkspace.H10[ 16 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 128 ]), &(acadoWorkspace.evGx[ 112 ]), &(acadoWorkspace.H10[ 16 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 160 ]), &(acadoWorkspace.evGx[ 128 ]), &(acadoWorkspace.H10[ 16 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 196 ]), &(acadoWorkspace.evGx[ 144 ]), &(acadoWorkspace.H10[ 16 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 236 ]), &(acadoWorkspace.evGx[ 160 ]), &(acadoWorkspace.H10[ 16 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 280 ]), &(acadoWorkspace.evGx[ 176 ]), &(acadoWorkspace.H10[ 16 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 328 ]), &(acadoWorkspace.evGx[ 192 ]), &(acadoWorkspace.H10[ 16 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 380 ]), &(acadoWorkspace.evGx[ 208 ]), &(acadoWorkspace.H10[ 16 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 436 ]), &(acadoWorkspace.evGx[ 224 ]), &(acadoWorkspace.H10[ 16 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 496 ]), &(acadoWorkspace.evGx[ 240 ]), &(acadoWorkspace.H10[ 16 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 560 ]), &(acadoWorkspace.evGx[ 256 ]), &(acadoWorkspace.H10[ 16 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 628 ]), &(acadoWorkspace.evGx[ 272 ]), &(acadoWorkspace.H10[ 16 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 700 ]), &(acadoWorkspace.evGx[ 288 ]), &(acadoWorkspace.H10[ 16 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 776 ]), &(acadoWorkspace.evGx[ 304 ]), &(acadoWorkspace.H10[ 16 ]) ); +acado_zeroBlockH10( &(acadoWorkspace.H10[ 20 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 80 ]), &(acadoWorkspace.evGx[ 80 ]), &(acadoWorkspace.H10[ 20 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 104 ]), &(acadoWorkspace.evGx[ 96 ]), &(acadoWorkspace.H10[ 20 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 132 ]), &(acadoWorkspace.evGx[ 112 ]), &(acadoWorkspace.H10[ 20 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 164 ]), &(acadoWorkspace.evGx[ 128 ]), &(acadoWorkspace.H10[ 20 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 200 ]), &(acadoWorkspace.evGx[ 144 ]), &(acadoWorkspace.H10[ 20 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 240 ]), &(acadoWorkspace.evGx[ 160 ]), &(acadoWorkspace.H10[ 20 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 284 ]), &(acadoWorkspace.evGx[ 176 ]), &(acadoWorkspace.H10[ 20 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 332 ]), &(acadoWorkspace.evGx[ 192 ]), &(acadoWorkspace.H10[ 20 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 384 ]), &(acadoWorkspace.evGx[ 208 ]), &(acadoWorkspace.H10[ 20 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 440 ]), &(acadoWorkspace.evGx[ 224 ]), &(acadoWorkspace.H10[ 20 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 500 ]), &(acadoWorkspace.evGx[ 240 ]), &(acadoWorkspace.H10[ 20 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 564 ]), &(acadoWorkspace.evGx[ 256 ]), &(acadoWorkspace.H10[ 20 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 632 ]), &(acadoWorkspace.evGx[ 272 ]), &(acadoWorkspace.H10[ 20 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 704 ]), &(acadoWorkspace.evGx[ 288 ]), &(acadoWorkspace.H10[ 20 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 780 ]), &(acadoWorkspace.evGx[ 304 ]), &(acadoWorkspace.H10[ 20 ]) ); +acado_zeroBlockH10( &(acadoWorkspace.H10[ 24 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 108 ]), &(acadoWorkspace.evGx[ 96 ]), &(acadoWorkspace.H10[ 24 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 136 ]), &(acadoWorkspace.evGx[ 112 ]), &(acadoWorkspace.H10[ 24 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 168 ]), &(acadoWorkspace.evGx[ 128 ]), &(acadoWorkspace.H10[ 24 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 204 ]), &(acadoWorkspace.evGx[ 144 ]), &(acadoWorkspace.H10[ 24 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 244 ]), &(acadoWorkspace.evGx[ 160 ]), &(acadoWorkspace.H10[ 24 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 288 ]), &(acadoWorkspace.evGx[ 176 ]), &(acadoWorkspace.H10[ 24 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 336 ]), &(acadoWorkspace.evGx[ 192 ]), &(acadoWorkspace.H10[ 24 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 388 ]), &(acadoWorkspace.evGx[ 208 ]), &(acadoWorkspace.H10[ 24 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 444 ]), &(acadoWorkspace.evGx[ 224 ]), &(acadoWorkspace.H10[ 24 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 504 ]), &(acadoWorkspace.evGx[ 240 ]), &(acadoWorkspace.H10[ 24 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 568 ]), &(acadoWorkspace.evGx[ 256 ]), &(acadoWorkspace.H10[ 24 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 636 ]), &(acadoWorkspace.evGx[ 272 ]), &(acadoWorkspace.H10[ 24 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 708 ]), &(acadoWorkspace.evGx[ 288 ]), &(acadoWorkspace.H10[ 24 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 784 ]), &(acadoWorkspace.evGx[ 304 ]), &(acadoWorkspace.H10[ 24 ]) ); +acado_zeroBlockH10( &(acadoWorkspace.H10[ 28 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 140 ]), &(acadoWorkspace.evGx[ 112 ]), &(acadoWorkspace.H10[ 28 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 172 ]), &(acadoWorkspace.evGx[ 128 ]), &(acadoWorkspace.H10[ 28 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 208 ]), &(acadoWorkspace.evGx[ 144 ]), &(acadoWorkspace.H10[ 28 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 248 ]), &(acadoWorkspace.evGx[ 160 ]), &(acadoWorkspace.H10[ 28 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 292 ]), &(acadoWorkspace.evGx[ 176 ]), &(acadoWorkspace.H10[ 28 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 340 ]), &(acadoWorkspace.evGx[ 192 ]), &(acadoWorkspace.H10[ 28 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 392 ]), &(acadoWorkspace.evGx[ 208 ]), &(acadoWorkspace.H10[ 28 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 448 ]), &(acadoWorkspace.evGx[ 224 ]), &(acadoWorkspace.H10[ 28 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 508 ]), &(acadoWorkspace.evGx[ 240 ]), &(acadoWorkspace.H10[ 28 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 572 ]), &(acadoWorkspace.evGx[ 256 ]), &(acadoWorkspace.H10[ 28 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 640 ]), &(acadoWorkspace.evGx[ 272 ]), &(acadoWorkspace.H10[ 28 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 712 ]), &(acadoWorkspace.evGx[ 288 ]), &(acadoWorkspace.H10[ 28 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 788 ]), &(acadoWorkspace.evGx[ 304 ]), &(acadoWorkspace.H10[ 28 ]) ); +acado_zeroBlockH10( &(acadoWorkspace.H10[ 32 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 176 ]), &(acadoWorkspace.evGx[ 128 ]), &(acadoWorkspace.H10[ 32 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 212 ]), &(acadoWorkspace.evGx[ 144 ]), &(acadoWorkspace.H10[ 32 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 252 ]), &(acadoWorkspace.evGx[ 160 ]), &(acadoWorkspace.H10[ 32 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 296 ]), &(acadoWorkspace.evGx[ 176 ]), &(acadoWorkspace.H10[ 32 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 344 ]), &(acadoWorkspace.evGx[ 192 ]), &(acadoWorkspace.H10[ 32 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 396 ]), &(acadoWorkspace.evGx[ 208 ]), &(acadoWorkspace.H10[ 32 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 452 ]), &(acadoWorkspace.evGx[ 224 ]), &(acadoWorkspace.H10[ 32 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 512 ]), &(acadoWorkspace.evGx[ 240 ]), &(acadoWorkspace.H10[ 32 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 576 ]), &(acadoWorkspace.evGx[ 256 ]), &(acadoWorkspace.H10[ 32 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 644 ]), &(acadoWorkspace.evGx[ 272 ]), &(acadoWorkspace.H10[ 32 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 716 ]), &(acadoWorkspace.evGx[ 288 ]), &(acadoWorkspace.H10[ 32 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 792 ]), &(acadoWorkspace.evGx[ 304 ]), &(acadoWorkspace.H10[ 32 ]) ); +acado_zeroBlockH10( &(acadoWorkspace.H10[ 36 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 216 ]), &(acadoWorkspace.evGx[ 144 ]), &(acadoWorkspace.H10[ 36 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 256 ]), &(acadoWorkspace.evGx[ 160 ]), &(acadoWorkspace.H10[ 36 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 300 ]), &(acadoWorkspace.evGx[ 176 ]), &(acadoWorkspace.H10[ 36 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 348 ]), &(acadoWorkspace.evGx[ 192 ]), &(acadoWorkspace.H10[ 36 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 400 ]), &(acadoWorkspace.evGx[ 208 ]), &(acadoWorkspace.H10[ 36 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 456 ]), &(acadoWorkspace.evGx[ 224 ]), &(acadoWorkspace.H10[ 36 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 516 ]), &(acadoWorkspace.evGx[ 240 ]), &(acadoWorkspace.H10[ 36 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 580 ]), &(acadoWorkspace.evGx[ 256 ]), &(acadoWorkspace.H10[ 36 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 648 ]), &(acadoWorkspace.evGx[ 272 ]), &(acadoWorkspace.H10[ 36 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 720 ]), &(acadoWorkspace.evGx[ 288 ]), &(acadoWorkspace.H10[ 36 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 796 ]), &(acadoWorkspace.evGx[ 304 ]), &(acadoWorkspace.H10[ 36 ]) ); +acado_zeroBlockH10( &(acadoWorkspace.H10[ 40 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 260 ]), &(acadoWorkspace.evGx[ 160 ]), &(acadoWorkspace.H10[ 40 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 304 ]), &(acadoWorkspace.evGx[ 176 ]), &(acadoWorkspace.H10[ 40 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 352 ]), &(acadoWorkspace.evGx[ 192 ]), &(acadoWorkspace.H10[ 40 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 404 ]), &(acadoWorkspace.evGx[ 208 ]), &(acadoWorkspace.H10[ 40 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 460 ]), &(acadoWorkspace.evGx[ 224 ]), &(acadoWorkspace.H10[ 40 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 520 ]), &(acadoWorkspace.evGx[ 240 ]), &(acadoWorkspace.H10[ 40 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 584 ]), &(acadoWorkspace.evGx[ 256 ]), &(acadoWorkspace.H10[ 40 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 652 ]), &(acadoWorkspace.evGx[ 272 ]), &(acadoWorkspace.H10[ 40 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 724 ]), &(acadoWorkspace.evGx[ 288 ]), &(acadoWorkspace.H10[ 40 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 800 ]), &(acadoWorkspace.evGx[ 304 ]), &(acadoWorkspace.H10[ 40 ]) ); +acado_zeroBlockH10( &(acadoWorkspace.H10[ 44 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 308 ]), &(acadoWorkspace.evGx[ 176 ]), &(acadoWorkspace.H10[ 44 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 356 ]), &(acadoWorkspace.evGx[ 192 ]), &(acadoWorkspace.H10[ 44 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 408 ]), &(acadoWorkspace.evGx[ 208 ]), &(acadoWorkspace.H10[ 44 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 464 ]), &(acadoWorkspace.evGx[ 224 ]), &(acadoWorkspace.H10[ 44 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 524 ]), &(acadoWorkspace.evGx[ 240 ]), &(acadoWorkspace.H10[ 44 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 588 ]), &(acadoWorkspace.evGx[ 256 ]), &(acadoWorkspace.H10[ 44 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 656 ]), &(acadoWorkspace.evGx[ 272 ]), &(acadoWorkspace.H10[ 44 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 728 ]), &(acadoWorkspace.evGx[ 288 ]), &(acadoWorkspace.H10[ 44 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 804 ]), &(acadoWorkspace.evGx[ 304 ]), &(acadoWorkspace.H10[ 44 ]) ); +acado_zeroBlockH10( &(acadoWorkspace.H10[ 48 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 360 ]), &(acadoWorkspace.evGx[ 192 ]), &(acadoWorkspace.H10[ 48 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 412 ]), &(acadoWorkspace.evGx[ 208 ]), &(acadoWorkspace.H10[ 48 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 468 ]), &(acadoWorkspace.evGx[ 224 ]), &(acadoWorkspace.H10[ 48 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 528 ]), &(acadoWorkspace.evGx[ 240 ]), &(acadoWorkspace.H10[ 48 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 592 ]), &(acadoWorkspace.evGx[ 256 ]), &(acadoWorkspace.H10[ 48 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 660 ]), &(acadoWorkspace.evGx[ 272 ]), &(acadoWorkspace.H10[ 48 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 732 ]), &(acadoWorkspace.evGx[ 288 ]), &(acadoWorkspace.H10[ 48 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 808 ]), &(acadoWorkspace.evGx[ 304 ]), &(acadoWorkspace.H10[ 48 ]) ); +acado_zeroBlockH10( &(acadoWorkspace.H10[ 52 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 416 ]), &(acadoWorkspace.evGx[ 208 ]), &(acadoWorkspace.H10[ 52 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 472 ]), &(acadoWorkspace.evGx[ 224 ]), &(acadoWorkspace.H10[ 52 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 532 ]), &(acadoWorkspace.evGx[ 240 ]), &(acadoWorkspace.H10[ 52 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 596 ]), &(acadoWorkspace.evGx[ 256 ]), &(acadoWorkspace.H10[ 52 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 664 ]), &(acadoWorkspace.evGx[ 272 ]), &(acadoWorkspace.H10[ 52 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 736 ]), &(acadoWorkspace.evGx[ 288 ]), &(acadoWorkspace.H10[ 52 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 812 ]), &(acadoWorkspace.evGx[ 304 ]), &(acadoWorkspace.H10[ 52 ]) ); +acado_zeroBlockH10( &(acadoWorkspace.H10[ 56 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 476 ]), &(acadoWorkspace.evGx[ 224 ]), &(acadoWorkspace.H10[ 56 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 536 ]), &(acadoWorkspace.evGx[ 240 ]), &(acadoWorkspace.H10[ 56 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 600 ]), &(acadoWorkspace.evGx[ 256 ]), &(acadoWorkspace.H10[ 56 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 668 ]), &(acadoWorkspace.evGx[ 272 ]), &(acadoWorkspace.H10[ 56 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 740 ]), &(acadoWorkspace.evGx[ 288 ]), &(acadoWorkspace.H10[ 56 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 816 ]), &(acadoWorkspace.evGx[ 304 ]), &(acadoWorkspace.H10[ 56 ]) ); +acado_zeroBlockH10( &(acadoWorkspace.H10[ 60 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 540 ]), &(acadoWorkspace.evGx[ 240 ]), &(acadoWorkspace.H10[ 60 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 604 ]), &(acadoWorkspace.evGx[ 256 ]), &(acadoWorkspace.H10[ 60 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 672 ]), &(acadoWorkspace.evGx[ 272 ]), &(acadoWorkspace.H10[ 60 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 744 ]), &(acadoWorkspace.evGx[ 288 ]), &(acadoWorkspace.H10[ 60 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 820 ]), &(acadoWorkspace.evGx[ 304 ]), &(acadoWorkspace.H10[ 60 ]) ); +acado_zeroBlockH10( &(acadoWorkspace.H10[ 64 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 608 ]), &(acadoWorkspace.evGx[ 256 ]), &(acadoWorkspace.H10[ 64 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 676 ]), &(acadoWorkspace.evGx[ 272 ]), &(acadoWorkspace.H10[ 64 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 748 ]), &(acadoWorkspace.evGx[ 288 ]), &(acadoWorkspace.H10[ 64 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 824 ]), &(acadoWorkspace.evGx[ 304 ]), &(acadoWorkspace.H10[ 64 ]) ); +acado_zeroBlockH10( &(acadoWorkspace.H10[ 68 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 680 ]), &(acadoWorkspace.evGx[ 272 ]), &(acadoWorkspace.H10[ 68 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 752 ]), &(acadoWorkspace.evGx[ 288 ]), &(acadoWorkspace.H10[ 68 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 828 ]), &(acadoWorkspace.evGx[ 304 ]), &(acadoWorkspace.H10[ 68 ]) ); +acado_zeroBlockH10( &(acadoWorkspace.H10[ 72 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 756 ]), &(acadoWorkspace.evGx[ 288 ]), &(acadoWorkspace.H10[ 72 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 832 ]), &(acadoWorkspace.evGx[ 304 ]), &(acadoWorkspace.H10[ 72 ]) ); +acado_zeroBlockH10( &(acadoWorkspace.H10[ 76 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 836 ]), &(acadoWorkspace.evGx[ 304 ]), &(acadoWorkspace.H10[ 76 ]) ); + +acadoWorkspace.H[4] = acadoWorkspace.H10[0]; +acadoWorkspace.H[5] = acadoWorkspace.H10[4]; +acadoWorkspace.H[6] = acadoWorkspace.H10[8]; +acadoWorkspace.H[7] = acadoWorkspace.H10[12]; +acadoWorkspace.H[8] = acadoWorkspace.H10[16]; +acadoWorkspace.H[9] = acadoWorkspace.H10[20]; +acadoWorkspace.H[10] = acadoWorkspace.H10[24]; +acadoWorkspace.H[11] = acadoWorkspace.H10[28]; +acadoWorkspace.H[12] = acadoWorkspace.H10[32]; +acadoWorkspace.H[13] = acadoWorkspace.H10[36]; +acadoWorkspace.H[14] = acadoWorkspace.H10[40]; +acadoWorkspace.H[15] = acadoWorkspace.H10[44]; +acadoWorkspace.H[16] = acadoWorkspace.H10[48]; +acadoWorkspace.H[17] = acadoWorkspace.H10[52]; +acadoWorkspace.H[18] = acadoWorkspace.H10[56]; +acadoWorkspace.H[19] = acadoWorkspace.H10[60]; +acadoWorkspace.H[20] = acadoWorkspace.H10[64]; +acadoWorkspace.H[21] = acadoWorkspace.H10[68]; +acadoWorkspace.H[22] = acadoWorkspace.H10[72]; +acadoWorkspace.H[23] = acadoWorkspace.H10[76]; +acadoWorkspace.H[28] = acadoWorkspace.H10[1]; +acadoWorkspace.H[29] = acadoWorkspace.H10[5]; +acadoWorkspace.H[30] = acadoWorkspace.H10[9]; +acadoWorkspace.H[31] = acadoWorkspace.H10[13]; +acadoWorkspace.H[32] = acadoWorkspace.H10[17]; +acadoWorkspace.H[33] = acadoWorkspace.H10[21]; +acadoWorkspace.H[34] = acadoWorkspace.H10[25]; +acadoWorkspace.H[35] = acadoWorkspace.H10[29]; +acadoWorkspace.H[36] = acadoWorkspace.H10[33]; +acadoWorkspace.H[37] = acadoWorkspace.H10[37]; +acadoWorkspace.H[38] = acadoWorkspace.H10[41]; +acadoWorkspace.H[39] = acadoWorkspace.H10[45]; +acadoWorkspace.H[40] = acadoWorkspace.H10[49]; +acadoWorkspace.H[41] = acadoWorkspace.H10[53]; +acadoWorkspace.H[42] = acadoWorkspace.H10[57]; +acadoWorkspace.H[43] = acadoWorkspace.H10[61]; +acadoWorkspace.H[44] = acadoWorkspace.H10[65]; +acadoWorkspace.H[45] = acadoWorkspace.H10[69]; +acadoWorkspace.H[46] = acadoWorkspace.H10[73]; +acadoWorkspace.H[47] = acadoWorkspace.H10[77]; +acadoWorkspace.H[52] = acadoWorkspace.H10[2]; +acadoWorkspace.H[53] = acadoWorkspace.H10[6]; +acadoWorkspace.H[54] = acadoWorkspace.H10[10]; +acadoWorkspace.H[55] = acadoWorkspace.H10[14]; +acadoWorkspace.H[56] = acadoWorkspace.H10[18]; +acadoWorkspace.H[57] = acadoWorkspace.H10[22]; +acadoWorkspace.H[58] = acadoWorkspace.H10[26]; +acadoWorkspace.H[59] = acadoWorkspace.H10[30]; +acadoWorkspace.H[60] = acadoWorkspace.H10[34]; +acadoWorkspace.H[61] = acadoWorkspace.H10[38]; +acadoWorkspace.H[62] = acadoWorkspace.H10[42]; +acadoWorkspace.H[63] = acadoWorkspace.H10[46]; +acadoWorkspace.H[64] = acadoWorkspace.H10[50]; +acadoWorkspace.H[65] = acadoWorkspace.H10[54]; +acadoWorkspace.H[66] = acadoWorkspace.H10[58]; +acadoWorkspace.H[67] = acadoWorkspace.H10[62]; +acadoWorkspace.H[68] = acadoWorkspace.H10[66]; +acadoWorkspace.H[69] = acadoWorkspace.H10[70]; +acadoWorkspace.H[70] = acadoWorkspace.H10[74]; +acadoWorkspace.H[71] = acadoWorkspace.H10[78]; +acadoWorkspace.H[76] = acadoWorkspace.H10[3]; +acadoWorkspace.H[77] = acadoWorkspace.H10[7]; +acadoWorkspace.H[78] = acadoWorkspace.H10[11]; +acadoWorkspace.H[79] = acadoWorkspace.H10[15]; +acadoWorkspace.H[80] = acadoWorkspace.H10[19]; +acadoWorkspace.H[81] = acadoWorkspace.H10[23]; +acadoWorkspace.H[82] = acadoWorkspace.H10[27]; +acadoWorkspace.H[83] = acadoWorkspace.H10[31]; +acadoWorkspace.H[84] = acadoWorkspace.H10[35]; +acadoWorkspace.H[85] = acadoWorkspace.H10[39]; +acadoWorkspace.H[86] = acadoWorkspace.H10[43]; +acadoWorkspace.H[87] = acadoWorkspace.H10[47]; +acadoWorkspace.H[88] = acadoWorkspace.H10[51]; +acadoWorkspace.H[89] = acadoWorkspace.H10[55]; +acadoWorkspace.H[90] = acadoWorkspace.H10[59]; +acadoWorkspace.H[91] = acadoWorkspace.H10[63]; +acadoWorkspace.H[92] = acadoWorkspace.H10[67]; +acadoWorkspace.H[93] = acadoWorkspace.H10[71]; +acadoWorkspace.H[94] = acadoWorkspace.H10[75]; +acadoWorkspace.H[95] = acadoWorkspace.H10[79]; + +acado_setBlockH11_R1( 0, 0, acadoWorkspace.R1 ); +acado_setBlockH11( 0, 0, acadoWorkspace.E, acadoWorkspace.QE ); +acado_setBlockH11( 0, 0, &(acadoWorkspace.E[ 4 ]), &(acadoWorkspace.QE[ 4 ]) ); +acado_setBlockH11( 0, 0, &(acadoWorkspace.E[ 12 ]), &(acadoWorkspace.QE[ 12 ]) ); +acado_setBlockH11( 0, 0, &(acadoWorkspace.E[ 24 ]), &(acadoWorkspace.QE[ 24 ]) ); +acado_setBlockH11( 0, 0, &(acadoWorkspace.E[ 40 ]), &(acadoWorkspace.QE[ 40 ]) ); +acado_setBlockH11( 0, 0, &(acadoWorkspace.E[ 60 ]), &(acadoWorkspace.QE[ 60 ]) ); +acado_setBlockH11( 0, 0, &(acadoWorkspace.E[ 84 ]), &(acadoWorkspace.QE[ 84 ]) ); +acado_setBlockH11( 0, 0, &(acadoWorkspace.E[ 112 ]), &(acadoWorkspace.QE[ 112 ]) ); +acado_setBlockH11( 0, 0, &(acadoWorkspace.E[ 144 ]), &(acadoWorkspace.QE[ 144 ]) ); +acado_setBlockH11( 0, 0, &(acadoWorkspace.E[ 180 ]), &(acadoWorkspace.QE[ 180 ]) ); +acado_setBlockH11( 0, 0, &(acadoWorkspace.E[ 220 ]), &(acadoWorkspace.QE[ 220 ]) ); +acado_setBlockH11( 0, 0, &(acadoWorkspace.E[ 264 ]), &(acadoWorkspace.QE[ 264 ]) ); +acado_setBlockH11( 0, 0, &(acadoWorkspace.E[ 312 ]), &(acadoWorkspace.QE[ 312 ]) ); +acado_setBlockH11( 0, 0, &(acadoWorkspace.E[ 364 ]), &(acadoWorkspace.QE[ 364 ]) ); +acado_setBlockH11( 0, 0, &(acadoWorkspace.E[ 420 ]), &(acadoWorkspace.QE[ 420 ]) ); +acado_setBlockH11( 0, 0, &(acadoWorkspace.E[ 480 ]), &(acadoWorkspace.QE[ 480 ]) ); +acado_setBlockH11( 0, 0, &(acadoWorkspace.E[ 544 ]), &(acadoWorkspace.QE[ 544 ]) ); +acado_setBlockH11( 0, 0, &(acadoWorkspace.E[ 612 ]), &(acadoWorkspace.QE[ 612 ]) ); +acado_setBlockH11( 0, 0, &(acadoWorkspace.E[ 684 ]), &(acadoWorkspace.QE[ 684 ]) ); +acado_setBlockH11( 0, 0, &(acadoWorkspace.E[ 760 ]), &(acadoWorkspace.QE[ 760 ]) ); + +acado_zeroBlockH11( 0, 1 ); +acado_setBlockH11( 0, 1, &(acadoWorkspace.E[ 4 ]), &(acadoWorkspace.QE[ 8 ]) ); +acado_setBlockH11( 0, 1, &(acadoWorkspace.E[ 12 ]), &(acadoWorkspace.QE[ 16 ]) ); +acado_setBlockH11( 0, 1, &(acadoWorkspace.E[ 24 ]), &(acadoWorkspace.QE[ 28 ]) ); +acado_setBlockH11( 0, 1, &(acadoWorkspace.E[ 40 ]), &(acadoWorkspace.QE[ 44 ]) ); +acado_setBlockH11( 0, 1, &(acadoWorkspace.E[ 60 ]), &(acadoWorkspace.QE[ 64 ]) ); +acado_setBlockH11( 0, 1, &(acadoWorkspace.E[ 84 ]), &(acadoWorkspace.QE[ 88 ]) ); +acado_setBlockH11( 0, 1, &(acadoWorkspace.E[ 112 ]), &(acadoWorkspace.QE[ 116 ]) ); +acado_setBlockH11( 0, 1, &(acadoWorkspace.E[ 144 ]), &(acadoWorkspace.QE[ 148 ]) ); +acado_setBlockH11( 0, 1, &(acadoWorkspace.E[ 180 ]), &(acadoWorkspace.QE[ 184 ]) ); +acado_setBlockH11( 0, 1, &(acadoWorkspace.E[ 220 ]), &(acadoWorkspace.QE[ 224 ]) ); +acado_setBlockH11( 0, 1, &(acadoWorkspace.E[ 264 ]), &(acadoWorkspace.QE[ 268 ]) ); +acado_setBlockH11( 0, 1, &(acadoWorkspace.E[ 312 ]), &(acadoWorkspace.QE[ 316 ]) ); +acado_setBlockH11( 0, 1, &(acadoWorkspace.E[ 364 ]), &(acadoWorkspace.QE[ 368 ]) ); +acado_setBlockH11( 0, 1, &(acadoWorkspace.E[ 420 ]), &(acadoWorkspace.QE[ 424 ]) ); +acado_setBlockH11( 0, 1, &(acadoWorkspace.E[ 480 ]), &(acadoWorkspace.QE[ 484 ]) ); +acado_setBlockH11( 0, 1, &(acadoWorkspace.E[ 544 ]), &(acadoWorkspace.QE[ 548 ]) ); +acado_setBlockH11( 0, 1, &(acadoWorkspace.E[ 612 ]), &(acadoWorkspace.QE[ 616 ]) ); +acado_setBlockH11( 0, 1, &(acadoWorkspace.E[ 684 ]), &(acadoWorkspace.QE[ 688 ]) ); +acado_setBlockH11( 0, 1, &(acadoWorkspace.E[ 760 ]), &(acadoWorkspace.QE[ 764 ]) ); + +acado_zeroBlockH11( 0, 2 ); +acado_setBlockH11( 0, 2, &(acadoWorkspace.E[ 12 ]), &(acadoWorkspace.QE[ 20 ]) ); +acado_setBlockH11( 0, 2, &(acadoWorkspace.E[ 24 ]), &(acadoWorkspace.QE[ 32 ]) ); +acado_setBlockH11( 0, 2, &(acadoWorkspace.E[ 40 ]), &(acadoWorkspace.QE[ 48 ]) ); +acado_setBlockH11( 0, 2, &(acadoWorkspace.E[ 60 ]), &(acadoWorkspace.QE[ 68 ]) ); +acado_setBlockH11( 0, 2, &(acadoWorkspace.E[ 84 ]), &(acadoWorkspace.QE[ 92 ]) ); +acado_setBlockH11( 0, 2, &(acadoWorkspace.E[ 112 ]), &(acadoWorkspace.QE[ 120 ]) ); +acado_setBlockH11( 0, 2, &(acadoWorkspace.E[ 144 ]), &(acadoWorkspace.QE[ 152 ]) ); +acado_setBlockH11( 0, 2, &(acadoWorkspace.E[ 180 ]), &(acadoWorkspace.QE[ 188 ]) ); +acado_setBlockH11( 0, 2, &(acadoWorkspace.E[ 220 ]), &(acadoWorkspace.QE[ 228 ]) ); +acado_setBlockH11( 0, 2, &(acadoWorkspace.E[ 264 ]), &(acadoWorkspace.QE[ 272 ]) ); +acado_setBlockH11( 0, 2, &(acadoWorkspace.E[ 312 ]), &(acadoWorkspace.QE[ 320 ]) ); +acado_setBlockH11( 0, 2, &(acadoWorkspace.E[ 364 ]), &(acadoWorkspace.QE[ 372 ]) ); +acado_setBlockH11( 0, 2, &(acadoWorkspace.E[ 420 ]), &(acadoWorkspace.QE[ 428 ]) ); +acado_setBlockH11( 0, 2, &(acadoWorkspace.E[ 480 ]), &(acadoWorkspace.QE[ 488 ]) ); +acado_setBlockH11( 0, 2, &(acadoWorkspace.E[ 544 ]), &(acadoWorkspace.QE[ 552 ]) ); +acado_setBlockH11( 0, 2, &(acadoWorkspace.E[ 612 ]), &(acadoWorkspace.QE[ 620 ]) ); +acado_setBlockH11( 0, 2, &(acadoWorkspace.E[ 684 ]), &(acadoWorkspace.QE[ 692 ]) ); +acado_setBlockH11( 0, 2, &(acadoWorkspace.E[ 760 ]), &(acadoWorkspace.QE[ 768 ]) ); + +acado_zeroBlockH11( 0, 3 ); +acado_setBlockH11( 0, 3, &(acadoWorkspace.E[ 24 ]), &(acadoWorkspace.QE[ 36 ]) ); +acado_setBlockH11( 0, 3, &(acadoWorkspace.E[ 40 ]), &(acadoWorkspace.QE[ 52 ]) ); +acado_setBlockH11( 0, 3, &(acadoWorkspace.E[ 60 ]), &(acadoWorkspace.QE[ 72 ]) ); +acado_setBlockH11( 0, 3, &(acadoWorkspace.E[ 84 ]), &(acadoWorkspace.QE[ 96 ]) ); +acado_setBlockH11( 0, 3, &(acadoWorkspace.E[ 112 ]), &(acadoWorkspace.QE[ 124 ]) ); +acado_setBlockH11( 0, 3, &(acadoWorkspace.E[ 144 ]), &(acadoWorkspace.QE[ 156 ]) ); +acado_setBlockH11( 0, 3, &(acadoWorkspace.E[ 180 ]), &(acadoWorkspace.QE[ 192 ]) ); +acado_setBlockH11( 0, 3, &(acadoWorkspace.E[ 220 ]), &(acadoWorkspace.QE[ 232 ]) ); +acado_setBlockH11( 0, 3, &(acadoWorkspace.E[ 264 ]), &(acadoWorkspace.QE[ 276 ]) ); +acado_setBlockH11( 0, 3, &(acadoWorkspace.E[ 312 ]), &(acadoWorkspace.QE[ 324 ]) ); +acado_setBlockH11( 0, 3, &(acadoWorkspace.E[ 364 ]), &(acadoWorkspace.QE[ 376 ]) ); +acado_setBlockH11( 0, 3, &(acadoWorkspace.E[ 420 ]), &(acadoWorkspace.QE[ 432 ]) ); +acado_setBlockH11( 0, 3, &(acadoWorkspace.E[ 480 ]), &(acadoWorkspace.QE[ 492 ]) ); +acado_setBlockH11( 0, 3, &(acadoWorkspace.E[ 544 ]), &(acadoWorkspace.QE[ 556 ]) ); +acado_setBlockH11( 0, 3, &(acadoWorkspace.E[ 612 ]), &(acadoWorkspace.QE[ 624 ]) ); +acado_setBlockH11( 0, 3, &(acadoWorkspace.E[ 684 ]), &(acadoWorkspace.QE[ 696 ]) ); +acado_setBlockH11( 0, 3, &(acadoWorkspace.E[ 760 ]), &(acadoWorkspace.QE[ 772 ]) ); + +acado_zeroBlockH11( 0, 4 ); +acado_setBlockH11( 0, 4, &(acadoWorkspace.E[ 40 ]), &(acadoWorkspace.QE[ 56 ]) ); +acado_setBlockH11( 0, 4, &(acadoWorkspace.E[ 60 ]), &(acadoWorkspace.QE[ 76 ]) ); +acado_setBlockH11( 0, 4, &(acadoWorkspace.E[ 84 ]), &(acadoWorkspace.QE[ 100 ]) ); +acado_setBlockH11( 0, 4, &(acadoWorkspace.E[ 112 ]), &(acadoWorkspace.QE[ 128 ]) ); +acado_setBlockH11( 0, 4, &(acadoWorkspace.E[ 144 ]), &(acadoWorkspace.QE[ 160 ]) ); +acado_setBlockH11( 0, 4, &(acadoWorkspace.E[ 180 ]), &(acadoWorkspace.QE[ 196 ]) ); +acado_setBlockH11( 0, 4, &(acadoWorkspace.E[ 220 ]), &(acadoWorkspace.QE[ 236 ]) ); +acado_setBlockH11( 0, 4, &(acadoWorkspace.E[ 264 ]), &(acadoWorkspace.QE[ 280 ]) ); +acado_setBlockH11( 0, 4, &(acadoWorkspace.E[ 312 ]), &(acadoWorkspace.QE[ 328 ]) ); +acado_setBlockH11( 0, 4, &(acadoWorkspace.E[ 364 ]), &(acadoWorkspace.QE[ 380 ]) ); +acado_setBlockH11( 0, 4, &(acadoWorkspace.E[ 420 ]), &(acadoWorkspace.QE[ 436 ]) ); +acado_setBlockH11( 0, 4, &(acadoWorkspace.E[ 480 ]), &(acadoWorkspace.QE[ 496 ]) ); +acado_setBlockH11( 0, 4, &(acadoWorkspace.E[ 544 ]), &(acadoWorkspace.QE[ 560 ]) ); +acado_setBlockH11( 0, 4, &(acadoWorkspace.E[ 612 ]), &(acadoWorkspace.QE[ 628 ]) ); +acado_setBlockH11( 0, 4, &(acadoWorkspace.E[ 684 ]), &(acadoWorkspace.QE[ 700 ]) ); +acado_setBlockH11( 0, 4, &(acadoWorkspace.E[ 760 ]), &(acadoWorkspace.QE[ 776 ]) ); + +acado_zeroBlockH11( 0, 5 ); +acado_setBlockH11( 0, 5, &(acadoWorkspace.E[ 60 ]), &(acadoWorkspace.QE[ 80 ]) ); +acado_setBlockH11( 0, 5, &(acadoWorkspace.E[ 84 ]), &(acadoWorkspace.QE[ 104 ]) ); +acado_setBlockH11( 0, 5, &(acadoWorkspace.E[ 112 ]), &(acadoWorkspace.QE[ 132 ]) ); +acado_setBlockH11( 0, 5, &(acadoWorkspace.E[ 144 ]), &(acadoWorkspace.QE[ 164 ]) ); +acado_setBlockH11( 0, 5, &(acadoWorkspace.E[ 180 ]), &(acadoWorkspace.QE[ 200 ]) ); +acado_setBlockH11( 0, 5, &(acadoWorkspace.E[ 220 ]), &(acadoWorkspace.QE[ 240 ]) ); +acado_setBlockH11( 0, 5, &(acadoWorkspace.E[ 264 ]), &(acadoWorkspace.QE[ 284 ]) ); +acado_setBlockH11( 0, 5, &(acadoWorkspace.E[ 312 ]), &(acadoWorkspace.QE[ 332 ]) ); +acado_setBlockH11( 0, 5, &(acadoWorkspace.E[ 364 ]), &(acadoWorkspace.QE[ 384 ]) ); +acado_setBlockH11( 0, 5, &(acadoWorkspace.E[ 420 ]), &(acadoWorkspace.QE[ 440 ]) ); +acado_setBlockH11( 0, 5, &(acadoWorkspace.E[ 480 ]), &(acadoWorkspace.QE[ 500 ]) ); +acado_setBlockH11( 0, 5, &(acadoWorkspace.E[ 544 ]), &(acadoWorkspace.QE[ 564 ]) ); +acado_setBlockH11( 0, 5, &(acadoWorkspace.E[ 612 ]), &(acadoWorkspace.QE[ 632 ]) ); +acado_setBlockH11( 0, 5, &(acadoWorkspace.E[ 684 ]), &(acadoWorkspace.QE[ 704 ]) ); +acado_setBlockH11( 0, 5, &(acadoWorkspace.E[ 760 ]), &(acadoWorkspace.QE[ 780 ]) ); + +acado_zeroBlockH11( 0, 6 ); +acado_setBlockH11( 0, 6, &(acadoWorkspace.E[ 84 ]), &(acadoWorkspace.QE[ 108 ]) ); +acado_setBlockH11( 0, 6, &(acadoWorkspace.E[ 112 ]), &(acadoWorkspace.QE[ 136 ]) ); +acado_setBlockH11( 0, 6, &(acadoWorkspace.E[ 144 ]), &(acadoWorkspace.QE[ 168 ]) ); +acado_setBlockH11( 0, 6, &(acadoWorkspace.E[ 180 ]), &(acadoWorkspace.QE[ 204 ]) ); +acado_setBlockH11( 0, 6, &(acadoWorkspace.E[ 220 ]), &(acadoWorkspace.QE[ 244 ]) ); +acado_setBlockH11( 0, 6, &(acadoWorkspace.E[ 264 ]), &(acadoWorkspace.QE[ 288 ]) ); +acado_setBlockH11( 0, 6, &(acadoWorkspace.E[ 312 ]), &(acadoWorkspace.QE[ 336 ]) ); +acado_setBlockH11( 0, 6, &(acadoWorkspace.E[ 364 ]), &(acadoWorkspace.QE[ 388 ]) ); +acado_setBlockH11( 0, 6, &(acadoWorkspace.E[ 420 ]), &(acadoWorkspace.QE[ 444 ]) ); +acado_setBlockH11( 0, 6, &(acadoWorkspace.E[ 480 ]), &(acadoWorkspace.QE[ 504 ]) ); +acado_setBlockH11( 0, 6, &(acadoWorkspace.E[ 544 ]), &(acadoWorkspace.QE[ 568 ]) ); +acado_setBlockH11( 0, 6, &(acadoWorkspace.E[ 612 ]), &(acadoWorkspace.QE[ 636 ]) ); +acado_setBlockH11( 0, 6, &(acadoWorkspace.E[ 684 ]), &(acadoWorkspace.QE[ 708 ]) ); +acado_setBlockH11( 0, 6, &(acadoWorkspace.E[ 760 ]), &(acadoWorkspace.QE[ 784 ]) ); + +acado_zeroBlockH11( 0, 7 ); +acado_setBlockH11( 0, 7, &(acadoWorkspace.E[ 112 ]), &(acadoWorkspace.QE[ 140 ]) ); +acado_setBlockH11( 0, 7, &(acadoWorkspace.E[ 144 ]), &(acadoWorkspace.QE[ 172 ]) ); +acado_setBlockH11( 0, 7, &(acadoWorkspace.E[ 180 ]), &(acadoWorkspace.QE[ 208 ]) ); +acado_setBlockH11( 0, 7, &(acadoWorkspace.E[ 220 ]), &(acadoWorkspace.QE[ 248 ]) ); +acado_setBlockH11( 0, 7, &(acadoWorkspace.E[ 264 ]), &(acadoWorkspace.QE[ 292 ]) ); +acado_setBlockH11( 0, 7, &(acadoWorkspace.E[ 312 ]), &(acadoWorkspace.QE[ 340 ]) ); +acado_setBlockH11( 0, 7, &(acadoWorkspace.E[ 364 ]), &(acadoWorkspace.QE[ 392 ]) ); +acado_setBlockH11( 0, 7, &(acadoWorkspace.E[ 420 ]), &(acadoWorkspace.QE[ 448 ]) ); +acado_setBlockH11( 0, 7, &(acadoWorkspace.E[ 480 ]), &(acadoWorkspace.QE[ 508 ]) ); +acado_setBlockH11( 0, 7, &(acadoWorkspace.E[ 544 ]), &(acadoWorkspace.QE[ 572 ]) ); +acado_setBlockH11( 0, 7, &(acadoWorkspace.E[ 612 ]), &(acadoWorkspace.QE[ 640 ]) ); +acado_setBlockH11( 0, 7, &(acadoWorkspace.E[ 684 ]), &(acadoWorkspace.QE[ 712 ]) ); +acado_setBlockH11( 0, 7, &(acadoWorkspace.E[ 760 ]), &(acadoWorkspace.QE[ 788 ]) ); + +acado_zeroBlockH11( 0, 8 ); +acado_setBlockH11( 0, 8, &(acadoWorkspace.E[ 144 ]), &(acadoWorkspace.QE[ 176 ]) ); +acado_setBlockH11( 0, 8, &(acadoWorkspace.E[ 180 ]), &(acadoWorkspace.QE[ 212 ]) ); +acado_setBlockH11( 0, 8, &(acadoWorkspace.E[ 220 ]), &(acadoWorkspace.QE[ 252 ]) ); +acado_setBlockH11( 0, 8, &(acadoWorkspace.E[ 264 ]), &(acadoWorkspace.QE[ 296 ]) ); +acado_setBlockH11( 0, 8, &(acadoWorkspace.E[ 312 ]), &(acadoWorkspace.QE[ 344 ]) ); +acado_setBlockH11( 0, 8, &(acadoWorkspace.E[ 364 ]), &(acadoWorkspace.QE[ 396 ]) ); +acado_setBlockH11( 0, 8, &(acadoWorkspace.E[ 420 ]), &(acadoWorkspace.QE[ 452 ]) ); +acado_setBlockH11( 0, 8, &(acadoWorkspace.E[ 480 ]), &(acadoWorkspace.QE[ 512 ]) ); +acado_setBlockH11( 0, 8, &(acadoWorkspace.E[ 544 ]), &(acadoWorkspace.QE[ 576 ]) ); +acado_setBlockH11( 0, 8, &(acadoWorkspace.E[ 612 ]), &(acadoWorkspace.QE[ 644 ]) ); +acado_setBlockH11( 0, 8, &(acadoWorkspace.E[ 684 ]), &(acadoWorkspace.QE[ 716 ]) ); +acado_setBlockH11( 0, 8, &(acadoWorkspace.E[ 760 ]), &(acadoWorkspace.QE[ 792 ]) ); + +acado_zeroBlockH11( 0, 9 ); +acado_setBlockH11( 0, 9, &(acadoWorkspace.E[ 180 ]), &(acadoWorkspace.QE[ 216 ]) ); +acado_setBlockH11( 0, 9, &(acadoWorkspace.E[ 220 ]), &(acadoWorkspace.QE[ 256 ]) ); +acado_setBlockH11( 0, 9, &(acadoWorkspace.E[ 264 ]), &(acadoWorkspace.QE[ 300 ]) ); +acado_setBlockH11( 0, 9, &(acadoWorkspace.E[ 312 ]), &(acadoWorkspace.QE[ 348 ]) ); +acado_setBlockH11( 0, 9, &(acadoWorkspace.E[ 364 ]), &(acadoWorkspace.QE[ 400 ]) ); +acado_setBlockH11( 0, 9, &(acadoWorkspace.E[ 420 ]), &(acadoWorkspace.QE[ 456 ]) ); +acado_setBlockH11( 0, 9, &(acadoWorkspace.E[ 480 ]), &(acadoWorkspace.QE[ 516 ]) ); +acado_setBlockH11( 0, 9, &(acadoWorkspace.E[ 544 ]), &(acadoWorkspace.QE[ 580 ]) ); +acado_setBlockH11( 0, 9, &(acadoWorkspace.E[ 612 ]), &(acadoWorkspace.QE[ 648 ]) ); +acado_setBlockH11( 0, 9, &(acadoWorkspace.E[ 684 ]), &(acadoWorkspace.QE[ 720 ]) ); +acado_setBlockH11( 0, 9, &(acadoWorkspace.E[ 760 ]), &(acadoWorkspace.QE[ 796 ]) ); + +acado_zeroBlockH11( 0, 10 ); +acado_setBlockH11( 0, 10, &(acadoWorkspace.E[ 220 ]), &(acadoWorkspace.QE[ 260 ]) ); +acado_setBlockH11( 0, 10, &(acadoWorkspace.E[ 264 ]), &(acadoWorkspace.QE[ 304 ]) ); +acado_setBlockH11( 0, 10, &(acadoWorkspace.E[ 312 ]), &(acadoWorkspace.QE[ 352 ]) ); +acado_setBlockH11( 0, 10, &(acadoWorkspace.E[ 364 ]), &(acadoWorkspace.QE[ 404 ]) ); +acado_setBlockH11( 0, 10, &(acadoWorkspace.E[ 420 ]), &(acadoWorkspace.QE[ 460 ]) ); +acado_setBlockH11( 0, 10, &(acadoWorkspace.E[ 480 ]), &(acadoWorkspace.QE[ 520 ]) ); +acado_setBlockH11( 0, 10, &(acadoWorkspace.E[ 544 ]), &(acadoWorkspace.QE[ 584 ]) ); +acado_setBlockH11( 0, 10, &(acadoWorkspace.E[ 612 ]), &(acadoWorkspace.QE[ 652 ]) ); +acado_setBlockH11( 0, 10, &(acadoWorkspace.E[ 684 ]), &(acadoWorkspace.QE[ 724 ]) ); +acado_setBlockH11( 0, 10, &(acadoWorkspace.E[ 760 ]), &(acadoWorkspace.QE[ 800 ]) ); + +acado_zeroBlockH11( 0, 11 ); +acado_setBlockH11( 0, 11, &(acadoWorkspace.E[ 264 ]), &(acadoWorkspace.QE[ 308 ]) ); +acado_setBlockH11( 0, 11, &(acadoWorkspace.E[ 312 ]), &(acadoWorkspace.QE[ 356 ]) ); +acado_setBlockH11( 0, 11, &(acadoWorkspace.E[ 364 ]), &(acadoWorkspace.QE[ 408 ]) ); +acado_setBlockH11( 0, 11, &(acadoWorkspace.E[ 420 ]), &(acadoWorkspace.QE[ 464 ]) ); +acado_setBlockH11( 0, 11, &(acadoWorkspace.E[ 480 ]), &(acadoWorkspace.QE[ 524 ]) ); +acado_setBlockH11( 0, 11, &(acadoWorkspace.E[ 544 ]), &(acadoWorkspace.QE[ 588 ]) ); +acado_setBlockH11( 0, 11, &(acadoWorkspace.E[ 612 ]), &(acadoWorkspace.QE[ 656 ]) ); +acado_setBlockH11( 0, 11, &(acadoWorkspace.E[ 684 ]), &(acadoWorkspace.QE[ 728 ]) ); +acado_setBlockH11( 0, 11, &(acadoWorkspace.E[ 760 ]), &(acadoWorkspace.QE[ 804 ]) ); + +acado_zeroBlockH11( 0, 12 ); +acado_setBlockH11( 0, 12, &(acadoWorkspace.E[ 312 ]), &(acadoWorkspace.QE[ 360 ]) ); +acado_setBlockH11( 0, 12, &(acadoWorkspace.E[ 364 ]), &(acadoWorkspace.QE[ 412 ]) ); +acado_setBlockH11( 0, 12, &(acadoWorkspace.E[ 420 ]), &(acadoWorkspace.QE[ 468 ]) ); +acado_setBlockH11( 0, 12, &(acadoWorkspace.E[ 480 ]), &(acadoWorkspace.QE[ 528 ]) ); +acado_setBlockH11( 0, 12, &(acadoWorkspace.E[ 544 ]), &(acadoWorkspace.QE[ 592 ]) ); +acado_setBlockH11( 0, 12, &(acadoWorkspace.E[ 612 ]), &(acadoWorkspace.QE[ 660 ]) ); +acado_setBlockH11( 0, 12, &(acadoWorkspace.E[ 684 ]), &(acadoWorkspace.QE[ 732 ]) ); +acado_setBlockH11( 0, 12, &(acadoWorkspace.E[ 760 ]), &(acadoWorkspace.QE[ 808 ]) ); + +acado_zeroBlockH11( 0, 13 ); +acado_setBlockH11( 0, 13, &(acadoWorkspace.E[ 364 ]), &(acadoWorkspace.QE[ 416 ]) ); +acado_setBlockH11( 0, 13, &(acadoWorkspace.E[ 420 ]), &(acadoWorkspace.QE[ 472 ]) ); +acado_setBlockH11( 0, 13, &(acadoWorkspace.E[ 480 ]), &(acadoWorkspace.QE[ 532 ]) ); +acado_setBlockH11( 0, 13, &(acadoWorkspace.E[ 544 ]), &(acadoWorkspace.QE[ 596 ]) ); +acado_setBlockH11( 0, 13, &(acadoWorkspace.E[ 612 ]), &(acadoWorkspace.QE[ 664 ]) ); +acado_setBlockH11( 0, 13, &(acadoWorkspace.E[ 684 ]), &(acadoWorkspace.QE[ 736 ]) ); +acado_setBlockH11( 0, 13, &(acadoWorkspace.E[ 760 ]), &(acadoWorkspace.QE[ 812 ]) ); + +acado_zeroBlockH11( 0, 14 ); +acado_setBlockH11( 0, 14, &(acadoWorkspace.E[ 420 ]), &(acadoWorkspace.QE[ 476 ]) ); +acado_setBlockH11( 0, 14, &(acadoWorkspace.E[ 480 ]), &(acadoWorkspace.QE[ 536 ]) ); +acado_setBlockH11( 0, 14, &(acadoWorkspace.E[ 544 ]), &(acadoWorkspace.QE[ 600 ]) ); +acado_setBlockH11( 0, 14, &(acadoWorkspace.E[ 612 ]), &(acadoWorkspace.QE[ 668 ]) ); +acado_setBlockH11( 0, 14, &(acadoWorkspace.E[ 684 ]), &(acadoWorkspace.QE[ 740 ]) ); +acado_setBlockH11( 0, 14, &(acadoWorkspace.E[ 760 ]), &(acadoWorkspace.QE[ 816 ]) ); + +acado_zeroBlockH11( 0, 15 ); +acado_setBlockH11( 0, 15, &(acadoWorkspace.E[ 480 ]), &(acadoWorkspace.QE[ 540 ]) ); +acado_setBlockH11( 0, 15, &(acadoWorkspace.E[ 544 ]), &(acadoWorkspace.QE[ 604 ]) ); +acado_setBlockH11( 0, 15, &(acadoWorkspace.E[ 612 ]), &(acadoWorkspace.QE[ 672 ]) ); +acado_setBlockH11( 0, 15, &(acadoWorkspace.E[ 684 ]), &(acadoWorkspace.QE[ 744 ]) ); +acado_setBlockH11( 0, 15, &(acadoWorkspace.E[ 760 ]), &(acadoWorkspace.QE[ 820 ]) ); + +acado_zeroBlockH11( 0, 16 ); +acado_setBlockH11( 0, 16, &(acadoWorkspace.E[ 544 ]), &(acadoWorkspace.QE[ 608 ]) ); +acado_setBlockH11( 0, 16, &(acadoWorkspace.E[ 612 ]), &(acadoWorkspace.QE[ 676 ]) ); +acado_setBlockH11( 0, 16, &(acadoWorkspace.E[ 684 ]), &(acadoWorkspace.QE[ 748 ]) ); +acado_setBlockH11( 0, 16, &(acadoWorkspace.E[ 760 ]), &(acadoWorkspace.QE[ 824 ]) ); + +acado_zeroBlockH11( 0, 17 ); +acado_setBlockH11( 0, 17, &(acadoWorkspace.E[ 612 ]), &(acadoWorkspace.QE[ 680 ]) ); +acado_setBlockH11( 0, 17, &(acadoWorkspace.E[ 684 ]), &(acadoWorkspace.QE[ 752 ]) ); +acado_setBlockH11( 0, 17, &(acadoWorkspace.E[ 760 ]), &(acadoWorkspace.QE[ 828 ]) ); + +acado_zeroBlockH11( 0, 18 ); +acado_setBlockH11( 0, 18, &(acadoWorkspace.E[ 684 ]), &(acadoWorkspace.QE[ 756 ]) ); +acado_setBlockH11( 0, 18, &(acadoWorkspace.E[ 760 ]), &(acadoWorkspace.QE[ 832 ]) ); + +acado_zeroBlockH11( 0, 19 ); +acado_setBlockH11( 0, 19, &(acadoWorkspace.E[ 760 ]), &(acadoWorkspace.QE[ 836 ]) ); + +acado_setBlockH11_R1( 1, 1, &(acadoWorkspace.R1[ 1 ]) ); +acado_setBlockH11( 1, 1, &(acadoWorkspace.E[ 8 ]), &(acadoWorkspace.QE[ 8 ]) ); +acado_setBlockH11( 1, 1, &(acadoWorkspace.E[ 16 ]), &(acadoWorkspace.QE[ 16 ]) ); +acado_setBlockH11( 1, 1, &(acadoWorkspace.E[ 28 ]), &(acadoWorkspace.QE[ 28 ]) ); +acado_setBlockH11( 1, 1, &(acadoWorkspace.E[ 44 ]), &(acadoWorkspace.QE[ 44 ]) ); +acado_setBlockH11( 1, 1, &(acadoWorkspace.E[ 64 ]), &(acadoWorkspace.QE[ 64 ]) ); +acado_setBlockH11( 1, 1, &(acadoWorkspace.E[ 88 ]), &(acadoWorkspace.QE[ 88 ]) ); +acado_setBlockH11( 1, 1, &(acadoWorkspace.E[ 116 ]), &(acadoWorkspace.QE[ 116 ]) ); +acado_setBlockH11( 1, 1, &(acadoWorkspace.E[ 148 ]), &(acadoWorkspace.QE[ 148 ]) ); +acado_setBlockH11( 1, 1, &(acadoWorkspace.E[ 184 ]), &(acadoWorkspace.QE[ 184 ]) ); +acado_setBlockH11( 1, 1, &(acadoWorkspace.E[ 224 ]), &(acadoWorkspace.QE[ 224 ]) ); +acado_setBlockH11( 1, 1, &(acadoWorkspace.E[ 268 ]), &(acadoWorkspace.QE[ 268 ]) ); +acado_setBlockH11( 1, 1, &(acadoWorkspace.E[ 316 ]), &(acadoWorkspace.QE[ 316 ]) ); +acado_setBlockH11( 1, 1, &(acadoWorkspace.E[ 368 ]), &(acadoWorkspace.QE[ 368 ]) ); +acado_setBlockH11( 1, 1, &(acadoWorkspace.E[ 424 ]), &(acadoWorkspace.QE[ 424 ]) ); +acado_setBlockH11( 1, 1, &(acadoWorkspace.E[ 484 ]), &(acadoWorkspace.QE[ 484 ]) ); +acado_setBlockH11( 1, 1, &(acadoWorkspace.E[ 548 ]), &(acadoWorkspace.QE[ 548 ]) ); +acado_setBlockH11( 1, 1, &(acadoWorkspace.E[ 616 ]), &(acadoWorkspace.QE[ 616 ]) ); +acado_setBlockH11( 1, 1, &(acadoWorkspace.E[ 688 ]), &(acadoWorkspace.QE[ 688 ]) ); +acado_setBlockH11( 1, 1, &(acadoWorkspace.E[ 764 ]), &(acadoWorkspace.QE[ 764 ]) ); + +acado_zeroBlockH11( 1, 2 ); +acado_setBlockH11( 1, 2, &(acadoWorkspace.E[ 16 ]), &(acadoWorkspace.QE[ 20 ]) ); +acado_setBlockH11( 1, 2, &(acadoWorkspace.E[ 28 ]), &(acadoWorkspace.QE[ 32 ]) ); +acado_setBlockH11( 1, 2, &(acadoWorkspace.E[ 44 ]), &(acadoWorkspace.QE[ 48 ]) ); +acado_setBlockH11( 1, 2, &(acadoWorkspace.E[ 64 ]), &(acadoWorkspace.QE[ 68 ]) ); +acado_setBlockH11( 1, 2, &(acadoWorkspace.E[ 88 ]), &(acadoWorkspace.QE[ 92 ]) ); +acado_setBlockH11( 1, 2, &(acadoWorkspace.E[ 116 ]), &(acadoWorkspace.QE[ 120 ]) ); +acado_setBlockH11( 1, 2, &(acadoWorkspace.E[ 148 ]), &(acadoWorkspace.QE[ 152 ]) ); +acado_setBlockH11( 1, 2, &(acadoWorkspace.E[ 184 ]), &(acadoWorkspace.QE[ 188 ]) ); +acado_setBlockH11( 1, 2, &(acadoWorkspace.E[ 224 ]), &(acadoWorkspace.QE[ 228 ]) ); +acado_setBlockH11( 1, 2, &(acadoWorkspace.E[ 268 ]), &(acadoWorkspace.QE[ 272 ]) ); +acado_setBlockH11( 1, 2, &(acadoWorkspace.E[ 316 ]), &(acadoWorkspace.QE[ 320 ]) ); +acado_setBlockH11( 1, 2, &(acadoWorkspace.E[ 368 ]), &(acadoWorkspace.QE[ 372 ]) ); +acado_setBlockH11( 1, 2, &(acadoWorkspace.E[ 424 ]), &(acadoWorkspace.QE[ 428 ]) ); +acado_setBlockH11( 1, 2, &(acadoWorkspace.E[ 484 ]), &(acadoWorkspace.QE[ 488 ]) ); +acado_setBlockH11( 1, 2, &(acadoWorkspace.E[ 548 ]), &(acadoWorkspace.QE[ 552 ]) ); +acado_setBlockH11( 1, 2, &(acadoWorkspace.E[ 616 ]), &(acadoWorkspace.QE[ 620 ]) ); +acado_setBlockH11( 1, 2, &(acadoWorkspace.E[ 688 ]), &(acadoWorkspace.QE[ 692 ]) ); +acado_setBlockH11( 1, 2, &(acadoWorkspace.E[ 764 ]), &(acadoWorkspace.QE[ 768 ]) ); + +acado_zeroBlockH11( 1, 3 ); +acado_setBlockH11( 1, 3, &(acadoWorkspace.E[ 28 ]), &(acadoWorkspace.QE[ 36 ]) ); +acado_setBlockH11( 1, 3, &(acadoWorkspace.E[ 44 ]), &(acadoWorkspace.QE[ 52 ]) ); +acado_setBlockH11( 1, 3, &(acadoWorkspace.E[ 64 ]), &(acadoWorkspace.QE[ 72 ]) ); +acado_setBlockH11( 1, 3, &(acadoWorkspace.E[ 88 ]), &(acadoWorkspace.QE[ 96 ]) ); +acado_setBlockH11( 1, 3, &(acadoWorkspace.E[ 116 ]), &(acadoWorkspace.QE[ 124 ]) ); +acado_setBlockH11( 1, 3, &(acadoWorkspace.E[ 148 ]), &(acadoWorkspace.QE[ 156 ]) ); +acado_setBlockH11( 1, 3, &(acadoWorkspace.E[ 184 ]), &(acadoWorkspace.QE[ 192 ]) ); +acado_setBlockH11( 1, 3, &(acadoWorkspace.E[ 224 ]), &(acadoWorkspace.QE[ 232 ]) ); +acado_setBlockH11( 1, 3, &(acadoWorkspace.E[ 268 ]), &(acadoWorkspace.QE[ 276 ]) ); +acado_setBlockH11( 1, 3, &(acadoWorkspace.E[ 316 ]), &(acadoWorkspace.QE[ 324 ]) ); +acado_setBlockH11( 1, 3, &(acadoWorkspace.E[ 368 ]), &(acadoWorkspace.QE[ 376 ]) ); +acado_setBlockH11( 1, 3, &(acadoWorkspace.E[ 424 ]), &(acadoWorkspace.QE[ 432 ]) ); +acado_setBlockH11( 1, 3, &(acadoWorkspace.E[ 484 ]), &(acadoWorkspace.QE[ 492 ]) ); +acado_setBlockH11( 1, 3, &(acadoWorkspace.E[ 548 ]), &(acadoWorkspace.QE[ 556 ]) ); +acado_setBlockH11( 1, 3, &(acadoWorkspace.E[ 616 ]), &(acadoWorkspace.QE[ 624 ]) ); +acado_setBlockH11( 1, 3, &(acadoWorkspace.E[ 688 ]), &(acadoWorkspace.QE[ 696 ]) ); +acado_setBlockH11( 1, 3, &(acadoWorkspace.E[ 764 ]), &(acadoWorkspace.QE[ 772 ]) ); + +acado_zeroBlockH11( 1, 4 ); +acado_setBlockH11( 1, 4, &(acadoWorkspace.E[ 44 ]), &(acadoWorkspace.QE[ 56 ]) ); +acado_setBlockH11( 1, 4, &(acadoWorkspace.E[ 64 ]), &(acadoWorkspace.QE[ 76 ]) ); +acado_setBlockH11( 1, 4, &(acadoWorkspace.E[ 88 ]), &(acadoWorkspace.QE[ 100 ]) ); +acado_setBlockH11( 1, 4, &(acadoWorkspace.E[ 116 ]), &(acadoWorkspace.QE[ 128 ]) ); +acado_setBlockH11( 1, 4, &(acadoWorkspace.E[ 148 ]), &(acadoWorkspace.QE[ 160 ]) ); +acado_setBlockH11( 1, 4, &(acadoWorkspace.E[ 184 ]), &(acadoWorkspace.QE[ 196 ]) ); +acado_setBlockH11( 1, 4, &(acadoWorkspace.E[ 224 ]), &(acadoWorkspace.QE[ 236 ]) ); +acado_setBlockH11( 1, 4, &(acadoWorkspace.E[ 268 ]), &(acadoWorkspace.QE[ 280 ]) ); +acado_setBlockH11( 1, 4, &(acadoWorkspace.E[ 316 ]), &(acadoWorkspace.QE[ 328 ]) ); +acado_setBlockH11( 1, 4, &(acadoWorkspace.E[ 368 ]), &(acadoWorkspace.QE[ 380 ]) ); +acado_setBlockH11( 1, 4, &(acadoWorkspace.E[ 424 ]), &(acadoWorkspace.QE[ 436 ]) ); +acado_setBlockH11( 1, 4, &(acadoWorkspace.E[ 484 ]), &(acadoWorkspace.QE[ 496 ]) ); +acado_setBlockH11( 1, 4, &(acadoWorkspace.E[ 548 ]), &(acadoWorkspace.QE[ 560 ]) ); +acado_setBlockH11( 1, 4, &(acadoWorkspace.E[ 616 ]), &(acadoWorkspace.QE[ 628 ]) ); +acado_setBlockH11( 1, 4, &(acadoWorkspace.E[ 688 ]), &(acadoWorkspace.QE[ 700 ]) ); +acado_setBlockH11( 1, 4, &(acadoWorkspace.E[ 764 ]), &(acadoWorkspace.QE[ 776 ]) ); + +acado_zeroBlockH11( 1, 5 ); +acado_setBlockH11( 1, 5, &(acadoWorkspace.E[ 64 ]), &(acadoWorkspace.QE[ 80 ]) ); +acado_setBlockH11( 1, 5, &(acadoWorkspace.E[ 88 ]), &(acadoWorkspace.QE[ 104 ]) ); +acado_setBlockH11( 1, 5, &(acadoWorkspace.E[ 116 ]), &(acadoWorkspace.QE[ 132 ]) ); +acado_setBlockH11( 1, 5, &(acadoWorkspace.E[ 148 ]), &(acadoWorkspace.QE[ 164 ]) ); +acado_setBlockH11( 1, 5, &(acadoWorkspace.E[ 184 ]), &(acadoWorkspace.QE[ 200 ]) ); +acado_setBlockH11( 1, 5, &(acadoWorkspace.E[ 224 ]), &(acadoWorkspace.QE[ 240 ]) ); +acado_setBlockH11( 1, 5, &(acadoWorkspace.E[ 268 ]), &(acadoWorkspace.QE[ 284 ]) ); +acado_setBlockH11( 1, 5, &(acadoWorkspace.E[ 316 ]), &(acadoWorkspace.QE[ 332 ]) ); +acado_setBlockH11( 1, 5, &(acadoWorkspace.E[ 368 ]), &(acadoWorkspace.QE[ 384 ]) ); +acado_setBlockH11( 1, 5, &(acadoWorkspace.E[ 424 ]), &(acadoWorkspace.QE[ 440 ]) ); +acado_setBlockH11( 1, 5, &(acadoWorkspace.E[ 484 ]), &(acadoWorkspace.QE[ 500 ]) ); +acado_setBlockH11( 1, 5, &(acadoWorkspace.E[ 548 ]), &(acadoWorkspace.QE[ 564 ]) ); +acado_setBlockH11( 1, 5, &(acadoWorkspace.E[ 616 ]), &(acadoWorkspace.QE[ 632 ]) ); +acado_setBlockH11( 1, 5, &(acadoWorkspace.E[ 688 ]), &(acadoWorkspace.QE[ 704 ]) ); +acado_setBlockH11( 1, 5, &(acadoWorkspace.E[ 764 ]), &(acadoWorkspace.QE[ 780 ]) ); + +acado_zeroBlockH11( 1, 6 ); +acado_setBlockH11( 1, 6, &(acadoWorkspace.E[ 88 ]), &(acadoWorkspace.QE[ 108 ]) ); +acado_setBlockH11( 1, 6, &(acadoWorkspace.E[ 116 ]), &(acadoWorkspace.QE[ 136 ]) ); +acado_setBlockH11( 1, 6, &(acadoWorkspace.E[ 148 ]), &(acadoWorkspace.QE[ 168 ]) ); +acado_setBlockH11( 1, 6, &(acadoWorkspace.E[ 184 ]), &(acadoWorkspace.QE[ 204 ]) ); +acado_setBlockH11( 1, 6, &(acadoWorkspace.E[ 224 ]), &(acadoWorkspace.QE[ 244 ]) ); +acado_setBlockH11( 1, 6, &(acadoWorkspace.E[ 268 ]), &(acadoWorkspace.QE[ 288 ]) ); +acado_setBlockH11( 1, 6, &(acadoWorkspace.E[ 316 ]), &(acadoWorkspace.QE[ 336 ]) ); +acado_setBlockH11( 1, 6, &(acadoWorkspace.E[ 368 ]), &(acadoWorkspace.QE[ 388 ]) ); +acado_setBlockH11( 1, 6, &(acadoWorkspace.E[ 424 ]), &(acadoWorkspace.QE[ 444 ]) ); +acado_setBlockH11( 1, 6, &(acadoWorkspace.E[ 484 ]), &(acadoWorkspace.QE[ 504 ]) ); +acado_setBlockH11( 1, 6, &(acadoWorkspace.E[ 548 ]), &(acadoWorkspace.QE[ 568 ]) ); +acado_setBlockH11( 1, 6, &(acadoWorkspace.E[ 616 ]), &(acadoWorkspace.QE[ 636 ]) ); +acado_setBlockH11( 1, 6, &(acadoWorkspace.E[ 688 ]), &(acadoWorkspace.QE[ 708 ]) ); +acado_setBlockH11( 1, 6, &(acadoWorkspace.E[ 764 ]), &(acadoWorkspace.QE[ 784 ]) ); + +acado_zeroBlockH11( 1, 7 ); +acado_setBlockH11( 1, 7, &(acadoWorkspace.E[ 116 ]), &(acadoWorkspace.QE[ 140 ]) ); +acado_setBlockH11( 1, 7, &(acadoWorkspace.E[ 148 ]), &(acadoWorkspace.QE[ 172 ]) ); +acado_setBlockH11( 1, 7, &(acadoWorkspace.E[ 184 ]), &(acadoWorkspace.QE[ 208 ]) ); +acado_setBlockH11( 1, 7, &(acadoWorkspace.E[ 224 ]), &(acadoWorkspace.QE[ 248 ]) ); +acado_setBlockH11( 1, 7, &(acadoWorkspace.E[ 268 ]), &(acadoWorkspace.QE[ 292 ]) ); +acado_setBlockH11( 1, 7, &(acadoWorkspace.E[ 316 ]), &(acadoWorkspace.QE[ 340 ]) ); +acado_setBlockH11( 1, 7, &(acadoWorkspace.E[ 368 ]), &(acadoWorkspace.QE[ 392 ]) ); +acado_setBlockH11( 1, 7, &(acadoWorkspace.E[ 424 ]), &(acadoWorkspace.QE[ 448 ]) ); +acado_setBlockH11( 1, 7, &(acadoWorkspace.E[ 484 ]), &(acadoWorkspace.QE[ 508 ]) ); +acado_setBlockH11( 1, 7, &(acadoWorkspace.E[ 548 ]), &(acadoWorkspace.QE[ 572 ]) ); +acado_setBlockH11( 1, 7, &(acadoWorkspace.E[ 616 ]), &(acadoWorkspace.QE[ 640 ]) ); +acado_setBlockH11( 1, 7, &(acadoWorkspace.E[ 688 ]), &(acadoWorkspace.QE[ 712 ]) ); +acado_setBlockH11( 1, 7, &(acadoWorkspace.E[ 764 ]), &(acadoWorkspace.QE[ 788 ]) ); + +acado_zeroBlockH11( 1, 8 ); +acado_setBlockH11( 1, 8, &(acadoWorkspace.E[ 148 ]), &(acadoWorkspace.QE[ 176 ]) ); +acado_setBlockH11( 1, 8, &(acadoWorkspace.E[ 184 ]), &(acadoWorkspace.QE[ 212 ]) ); +acado_setBlockH11( 1, 8, &(acadoWorkspace.E[ 224 ]), &(acadoWorkspace.QE[ 252 ]) ); +acado_setBlockH11( 1, 8, &(acadoWorkspace.E[ 268 ]), &(acadoWorkspace.QE[ 296 ]) ); +acado_setBlockH11( 1, 8, &(acadoWorkspace.E[ 316 ]), &(acadoWorkspace.QE[ 344 ]) ); +acado_setBlockH11( 1, 8, &(acadoWorkspace.E[ 368 ]), &(acadoWorkspace.QE[ 396 ]) ); +acado_setBlockH11( 1, 8, &(acadoWorkspace.E[ 424 ]), &(acadoWorkspace.QE[ 452 ]) ); +acado_setBlockH11( 1, 8, &(acadoWorkspace.E[ 484 ]), &(acadoWorkspace.QE[ 512 ]) ); +acado_setBlockH11( 1, 8, &(acadoWorkspace.E[ 548 ]), &(acadoWorkspace.QE[ 576 ]) ); +acado_setBlockH11( 1, 8, &(acadoWorkspace.E[ 616 ]), &(acadoWorkspace.QE[ 644 ]) ); +acado_setBlockH11( 1, 8, &(acadoWorkspace.E[ 688 ]), &(acadoWorkspace.QE[ 716 ]) ); +acado_setBlockH11( 1, 8, &(acadoWorkspace.E[ 764 ]), &(acadoWorkspace.QE[ 792 ]) ); + +acado_zeroBlockH11( 1, 9 ); +acado_setBlockH11( 1, 9, &(acadoWorkspace.E[ 184 ]), &(acadoWorkspace.QE[ 216 ]) ); +acado_setBlockH11( 1, 9, &(acadoWorkspace.E[ 224 ]), &(acadoWorkspace.QE[ 256 ]) ); +acado_setBlockH11( 1, 9, &(acadoWorkspace.E[ 268 ]), &(acadoWorkspace.QE[ 300 ]) ); +acado_setBlockH11( 1, 9, &(acadoWorkspace.E[ 316 ]), &(acadoWorkspace.QE[ 348 ]) ); +acado_setBlockH11( 1, 9, &(acadoWorkspace.E[ 368 ]), &(acadoWorkspace.QE[ 400 ]) ); +acado_setBlockH11( 1, 9, &(acadoWorkspace.E[ 424 ]), &(acadoWorkspace.QE[ 456 ]) ); +acado_setBlockH11( 1, 9, &(acadoWorkspace.E[ 484 ]), &(acadoWorkspace.QE[ 516 ]) ); +acado_setBlockH11( 1, 9, &(acadoWorkspace.E[ 548 ]), &(acadoWorkspace.QE[ 580 ]) ); +acado_setBlockH11( 1, 9, &(acadoWorkspace.E[ 616 ]), &(acadoWorkspace.QE[ 648 ]) ); +acado_setBlockH11( 1, 9, &(acadoWorkspace.E[ 688 ]), &(acadoWorkspace.QE[ 720 ]) ); +acado_setBlockH11( 1, 9, &(acadoWorkspace.E[ 764 ]), &(acadoWorkspace.QE[ 796 ]) ); + +acado_zeroBlockH11( 1, 10 ); +acado_setBlockH11( 1, 10, &(acadoWorkspace.E[ 224 ]), &(acadoWorkspace.QE[ 260 ]) ); +acado_setBlockH11( 1, 10, &(acadoWorkspace.E[ 268 ]), &(acadoWorkspace.QE[ 304 ]) ); +acado_setBlockH11( 1, 10, &(acadoWorkspace.E[ 316 ]), &(acadoWorkspace.QE[ 352 ]) ); +acado_setBlockH11( 1, 10, &(acadoWorkspace.E[ 368 ]), &(acadoWorkspace.QE[ 404 ]) ); +acado_setBlockH11( 1, 10, &(acadoWorkspace.E[ 424 ]), &(acadoWorkspace.QE[ 460 ]) ); +acado_setBlockH11( 1, 10, &(acadoWorkspace.E[ 484 ]), &(acadoWorkspace.QE[ 520 ]) ); +acado_setBlockH11( 1, 10, &(acadoWorkspace.E[ 548 ]), &(acadoWorkspace.QE[ 584 ]) ); +acado_setBlockH11( 1, 10, &(acadoWorkspace.E[ 616 ]), &(acadoWorkspace.QE[ 652 ]) ); +acado_setBlockH11( 1, 10, &(acadoWorkspace.E[ 688 ]), &(acadoWorkspace.QE[ 724 ]) ); +acado_setBlockH11( 1, 10, &(acadoWorkspace.E[ 764 ]), &(acadoWorkspace.QE[ 800 ]) ); + +acado_zeroBlockH11( 1, 11 ); +acado_setBlockH11( 1, 11, &(acadoWorkspace.E[ 268 ]), &(acadoWorkspace.QE[ 308 ]) ); +acado_setBlockH11( 1, 11, &(acadoWorkspace.E[ 316 ]), &(acadoWorkspace.QE[ 356 ]) ); +acado_setBlockH11( 1, 11, &(acadoWorkspace.E[ 368 ]), &(acadoWorkspace.QE[ 408 ]) ); +acado_setBlockH11( 1, 11, &(acadoWorkspace.E[ 424 ]), &(acadoWorkspace.QE[ 464 ]) ); +acado_setBlockH11( 1, 11, &(acadoWorkspace.E[ 484 ]), &(acadoWorkspace.QE[ 524 ]) ); +acado_setBlockH11( 1, 11, &(acadoWorkspace.E[ 548 ]), &(acadoWorkspace.QE[ 588 ]) ); +acado_setBlockH11( 1, 11, &(acadoWorkspace.E[ 616 ]), &(acadoWorkspace.QE[ 656 ]) ); +acado_setBlockH11( 1, 11, &(acadoWorkspace.E[ 688 ]), &(acadoWorkspace.QE[ 728 ]) ); +acado_setBlockH11( 1, 11, &(acadoWorkspace.E[ 764 ]), &(acadoWorkspace.QE[ 804 ]) ); + +acado_zeroBlockH11( 1, 12 ); +acado_setBlockH11( 1, 12, &(acadoWorkspace.E[ 316 ]), &(acadoWorkspace.QE[ 360 ]) ); +acado_setBlockH11( 1, 12, &(acadoWorkspace.E[ 368 ]), &(acadoWorkspace.QE[ 412 ]) ); +acado_setBlockH11( 1, 12, &(acadoWorkspace.E[ 424 ]), &(acadoWorkspace.QE[ 468 ]) ); +acado_setBlockH11( 1, 12, &(acadoWorkspace.E[ 484 ]), &(acadoWorkspace.QE[ 528 ]) ); +acado_setBlockH11( 1, 12, &(acadoWorkspace.E[ 548 ]), &(acadoWorkspace.QE[ 592 ]) ); +acado_setBlockH11( 1, 12, &(acadoWorkspace.E[ 616 ]), &(acadoWorkspace.QE[ 660 ]) ); +acado_setBlockH11( 1, 12, &(acadoWorkspace.E[ 688 ]), &(acadoWorkspace.QE[ 732 ]) ); +acado_setBlockH11( 1, 12, &(acadoWorkspace.E[ 764 ]), &(acadoWorkspace.QE[ 808 ]) ); + +acado_zeroBlockH11( 1, 13 ); +acado_setBlockH11( 1, 13, &(acadoWorkspace.E[ 368 ]), &(acadoWorkspace.QE[ 416 ]) ); +acado_setBlockH11( 1, 13, &(acadoWorkspace.E[ 424 ]), &(acadoWorkspace.QE[ 472 ]) ); +acado_setBlockH11( 1, 13, &(acadoWorkspace.E[ 484 ]), &(acadoWorkspace.QE[ 532 ]) ); +acado_setBlockH11( 1, 13, &(acadoWorkspace.E[ 548 ]), &(acadoWorkspace.QE[ 596 ]) ); +acado_setBlockH11( 1, 13, &(acadoWorkspace.E[ 616 ]), &(acadoWorkspace.QE[ 664 ]) ); +acado_setBlockH11( 1, 13, &(acadoWorkspace.E[ 688 ]), &(acadoWorkspace.QE[ 736 ]) ); +acado_setBlockH11( 1, 13, &(acadoWorkspace.E[ 764 ]), &(acadoWorkspace.QE[ 812 ]) ); + +acado_zeroBlockH11( 1, 14 ); +acado_setBlockH11( 1, 14, &(acadoWorkspace.E[ 424 ]), &(acadoWorkspace.QE[ 476 ]) ); +acado_setBlockH11( 1, 14, &(acadoWorkspace.E[ 484 ]), &(acadoWorkspace.QE[ 536 ]) ); +acado_setBlockH11( 1, 14, &(acadoWorkspace.E[ 548 ]), &(acadoWorkspace.QE[ 600 ]) ); +acado_setBlockH11( 1, 14, &(acadoWorkspace.E[ 616 ]), &(acadoWorkspace.QE[ 668 ]) ); +acado_setBlockH11( 1, 14, &(acadoWorkspace.E[ 688 ]), &(acadoWorkspace.QE[ 740 ]) ); +acado_setBlockH11( 1, 14, &(acadoWorkspace.E[ 764 ]), &(acadoWorkspace.QE[ 816 ]) ); + +acado_zeroBlockH11( 1, 15 ); +acado_setBlockH11( 1, 15, &(acadoWorkspace.E[ 484 ]), &(acadoWorkspace.QE[ 540 ]) ); +acado_setBlockH11( 1, 15, &(acadoWorkspace.E[ 548 ]), &(acadoWorkspace.QE[ 604 ]) ); +acado_setBlockH11( 1, 15, &(acadoWorkspace.E[ 616 ]), &(acadoWorkspace.QE[ 672 ]) ); +acado_setBlockH11( 1, 15, &(acadoWorkspace.E[ 688 ]), &(acadoWorkspace.QE[ 744 ]) ); +acado_setBlockH11( 1, 15, &(acadoWorkspace.E[ 764 ]), &(acadoWorkspace.QE[ 820 ]) ); + +acado_zeroBlockH11( 1, 16 ); +acado_setBlockH11( 1, 16, &(acadoWorkspace.E[ 548 ]), &(acadoWorkspace.QE[ 608 ]) ); +acado_setBlockH11( 1, 16, &(acadoWorkspace.E[ 616 ]), &(acadoWorkspace.QE[ 676 ]) ); +acado_setBlockH11( 1, 16, &(acadoWorkspace.E[ 688 ]), &(acadoWorkspace.QE[ 748 ]) ); +acado_setBlockH11( 1, 16, &(acadoWorkspace.E[ 764 ]), &(acadoWorkspace.QE[ 824 ]) ); + +acado_zeroBlockH11( 1, 17 ); +acado_setBlockH11( 1, 17, &(acadoWorkspace.E[ 616 ]), &(acadoWorkspace.QE[ 680 ]) ); +acado_setBlockH11( 1, 17, &(acadoWorkspace.E[ 688 ]), &(acadoWorkspace.QE[ 752 ]) ); +acado_setBlockH11( 1, 17, &(acadoWorkspace.E[ 764 ]), &(acadoWorkspace.QE[ 828 ]) ); + +acado_zeroBlockH11( 1, 18 ); +acado_setBlockH11( 1, 18, &(acadoWorkspace.E[ 688 ]), &(acadoWorkspace.QE[ 756 ]) ); +acado_setBlockH11( 1, 18, &(acadoWorkspace.E[ 764 ]), &(acadoWorkspace.QE[ 832 ]) ); + +acado_zeroBlockH11( 1, 19 ); +acado_setBlockH11( 1, 19, &(acadoWorkspace.E[ 764 ]), &(acadoWorkspace.QE[ 836 ]) ); + +acado_setBlockH11_R1( 2, 2, &(acadoWorkspace.R1[ 2 ]) ); +acado_setBlockH11( 2, 2, &(acadoWorkspace.E[ 20 ]), &(acadoWorkspace.QE[ 20 ]) ); +acado_setBlockH11( 2, 2, &(acadoWorkspace.E[ 32 ]), &(acadoWorkspace.QE[ 32 ]) ); +acado_setBlockH11( 2, 2, &(acadoWorkspace.E[ 48 ]), &(acadoWorkspace.QE[ 48 ]) ); +acado_setBlockH11( 2, 2, &(acadoWorkspace.E[ 68 ]), &(acadoWorkspace.QE[ 68 ]) ); +acado_setBlockH11( 2, 2, &(acadoWorkspace.E[ 92 ]), &(acadoWorkspace.QE[ 92 ]) ); +acado_setBlockH11( 2, 2, &(acadoWorkspace.E[ 120 ]), &(acadoWorkspace.QE[ 120 ]) ); +acado_setBlockH11( 2, 2, &(acadoWorkspace.E[ 152 ]), &(acadoWorkspace.QE[ 152 ]) ); +acado_setBlockH11( 2, 2, &(acadoWorkspace.E[ 188 ]), &(acadoWorkspace.QE[ 188 ]) ); +acado_setBlockH11( 2, 2, &(acadoWorkspace.E[ 228 ]), &(acadoWorkspace.QE[ 228 ]) ); +acado_setBlockH11( 2, 2, &(acadoWorkspace.E[ 272 ]), &(acadoWorkspace.QE[ 272 ]) ); +acado_setBlockH11( 2, 2, &(acadoWorkspace.E[ 320 ]), &(acadoWorkspace.QE[ 320 ]) ); +acado_setBlockH11( 2, 2, &(acadoWorkspace.E[ 372 ]), &(acadoWorkspace.QE[ 372 ]) ); +acado_setBlockH11( 2, 2, &(acadoWorkspace.E[ 428 ]), &(acadoWorkspace.QE[ 428 ]) ); +acado_setBlockH11( 2, 2, &(acadoWorkspace.E[ 488 ]), &(acadoWorkspace.QE[ 488 ]) ); +acado_setBlockH11( 2, 2, &(acadoWorkspace.E[ 552 ]), &(acadoWorkspace.QE[ 552 ]) ); +acado_setBlockH11( 2, 2, &(acadoWorkspace.E[ 620 ]), &(acadoWorkspace.QE[ 620 ]) ); +acado_setBlockH11( 2, 2, &(acadoWorkspace.E[ 692 ]), &(acadoWorkspace.QE[ 692 ]) ); +acado_setBlockH11( 2, 2, &(acadoWorkspace.E[ 768 ]), &(acadoWorkspace.QE[ 768 ]) ); + +acado_zeroBlockH11( 2, 3 ); +acado_setBlockH11( 2, 3, &(acadoWorkspace.E[ 32 ]), &(acadoWorkspace.QE[ 36 ]) ); +acado_setBlockH11( 2, 3, &(acadoWorkspace.E[ 48 ]), &(acadoWorkspace.QE[ 52 ]) ); +acado_setBlockH11( 2, 3, &(acadoWorkspace.E[ 68 ]), &(acadoWorkspace.QE[ 72 ]) ); +acado_setBlockH11( 2, 3, &(acadoWorkspace.E[ 92 ]), &(acadoWorkspace.QE[ 96 ]) ); +acado_setBlockH11( 2, 3, &(acadoWorkspace.E[ 120 ]), &(acadoWorkspace.QE[ 124 ]) ); +acado_setBlockH11( 2, 3, &(acadoWorkspace.E[ 152 ]), &(acadoWorkspace.QE[ 156 ]) ); +acado_setBlockH11( 2, 3, &(acadoWorkspace.E[ 188 ]), &(acadoWorkspace.QE[ 192 ]) ); +acado_setBlockH11( 2, 3, &(acadoWorkspace.E[ 228 ]), &(acadoWorkspace.QE[ 232 ]) ); +acado_setBlockH11( 2, 3, &(acadoWorkspace.E[ 272 ]), &(acadoWorkspace.QE[ 276 ]) ); +acado_setBlockH11( 2, 3, &(acadoWorkspace.E[ 320 ]), &(acadoWorkspace.QE[ 324 ]) ); +acado_setBlockH11( 2, 3, &(acadoWorkspace.E[ 372 ]), &(acadoWorkspace.QE[ 376 ]) ); +acado_setBlockH11( 2, 3, &(acadoWorkspace.E[ 428 ]), &(acadoWorkspace.QE[ 432 ]) ); +acado_setBlockH11( 2, 3, &(acadoWorkspace.E[ 488 ]), &(acadoWorkspace.QE[ 492 ]) ); +acado_setBlockH11( 2, 3, &(acadoWorkspace.E[ 552 ]), &(acadoWorkspace.QE[ 556 ]) ); +acado_setBlockH11( 2, 3, &(acadoWorkspace.E[ 620 ]), &(acadoWorkspace.QE[ 624 ]) ); +acado_setBlockH11( 2, 3, &(acadoWorkspace.E[ 692 ]), &(acadoWorkspace.QE[ 696 ]) ); +acado_setBlockH11( 2, 3, &(acadoWorkspace.E[ 768 ]), &(acadoWorkspace.QE[ 772 ]) ); + +acado_zeroBlockH11( 2, 4 ); +acado_setBlockH11( 2, 4, &(acadoWorkspace.E[ 48 ]), &(acadoWorkspace.QE[ 56 ]) ); +acado_setBlockH11( 2, 4, &(acadoWorkspace.E[ 68 ]), &(acadoWorkspace.QE[ 76 ]) ); +acado_setBlockH11( 2, 4, &(acadoWorkspace.E[ 92 ]), &(acadoWorkspace.QE[ 100 ]) ); +acado_setBlockH11( 2, 4, &(acadoWorkspace.E[ 120 ]), &(acadoWorkspace.QE[ 128 ]) ); +acado_setBlockH11( 2, 4, &(acadoWorkspace.E[ 152 ]), &(acadoWorkspace.QE[ 160 ]) ); +acado_setBlockH11( 2, 4, &(acadoWorkspace.E[ 188 ]), &(acadoWorkspace.QE[ 196 ]) ); +acado_setBlockH11( 2, 4, &(acadoWorkspace.E[ 228 ]), &(acadoWorkspace.QE[ 236 ]) ); +acado_setBlockH11( 2, 4, &(acadoWorkspace.E[ 272 ]), &(acadoWorkspace.QE[ 280 ]) ); +acado_setBlockH11( 2, 4, &(acadoWorkspace.E[ 320 ]), &(acadoWorkspace.QE[ 328 ]) ); +acado_setBlockH11( 2, 4, &(acadoWorkspace.E[ 372 ]), &(acadoWorkspace.QE[ 380 ]) ); +acado_setBlockH11( 2, 4, &(acadoWorkspace.E[ 428 ]), &(acadoWorkspace.QE[ 436 ]) ); +acado_setBlockH11( 2, 4, &(acadoWorkspace.E[ 488 ]), &(acadoWorkspace.QE[ 496 ]) ); +acado_setBlockH11( 2, 4, &(acadoWorkspace.E[ 552 ]), &(acadoWorkspace.QE[ 560 ]) ); +acado_setBlockH11( 2, 4, &(acadoWorkspace.E[ 620 ]), &(acadoWorkspace.QE[ 628 ]) ); +acado_setBlockH11( 2, 4, &(acadoWorkspace.E[ 692 ]), &(acadoWorkspace.QE[ 700 ]) ); +acado_setBlockH11( 2, 4, &(acadoWorkspace.E[ 768 ]), &(acadoWorkspace.QE[ 776 ]) ); + +acado_zeroBlockH11( 2, 5 ); +acado_setBlockH11( 2, 5, &(acadoWorkspace.E[ 68 ]), &(acadoWorkspace.QE[ 80 ]) ); +acado_setBlockH11( 2, 5, &(acadoWorkspace.E[ 92 ]), &(acadoWorkspace.QE[ 104 ]) ); +acado_setBlockH11( 2, 5, &(acadoWorkspace.E[ 120 ]), &(acadoWorkspace.QE[ 132 ]) ); +acado_setBlockH11( 2, 5, &(acadoWorkspace.E[ 152 ]), &(acadoWorkspace.QE[ 164 ]) ); +acado_setBlockH11( 2, 5, &(acadoWorkspace.E[ 188 ]), &(acadoWorkspace.QE[ 200 ]) ); +acado_setBlockH11( 2, 5, &(acadoWorkspace.E[ 228 ]), &(acadoWorkspace.QE[ 240 ]) ); +acado_setBlockH11( 2, 5, &(acadoWorkspace.E[ 272 ]), &(acadoWorkspace.QE[ 284 ]) ); +acado_setBlockH11( 2, 5, &(acadoWorkspace.E[ 320 ]), &(acadoWorkspace.QE[ 332 ]) ); +acado_setBlockH11( 2, 5, &(acadoWorkspace.E[ 372 ]), &(acadoWorkspace.QE[ 384 ]) ); +acado_setBlockH11( 2, 5, &(acadoWorkspace.E[ 428 ]), &(acadoWorkspace.QE[ 440 ]) ); +acado_setBlockH11( 2, 5, &(acadoWorkspace.E[ 488 ]), &(acadoWorkspace.QE[ 500 ]) ); +acado_setBlockH11( 2, 5, &(acadoWorkspace.E[ 552 ]), &(acadoWorkspace.QE[ 564 ]) ); +acado_setBlockH11( 2, 5, &(acadoWorkspace.E[ 620 ]), &(acadoWorkspace.QE[ 632 ]) ); +acado_setBlockH11( 2, 5, &(acadoWorkspace.E[ 692 ]), &(acadoWorkspace.QE[ 704 ]) ); +acado_setBlockH11( 2, 5, &(acadoWorkspace.E[ 768 ]), &(acadoWorkspace.QE[ 780 ]) ); + +acado_zeroBlockH11( 2, 6 ); +acado_setBlockH11( 2, 6, &(acadoWorkspace.E[ 92 ]), &(acadoWorkspace.QE[ 108 ]) ); +acado_setBlockH11( 2, 6, &(acadoWorkspace.E[ 120 ]), &(acadoWorkspace.QE[ 136 ]) ); +acado_setBlockH11( 2, 6, &(acadoWorkspace.E[ 152 ]), &(acadoWorkspace.QE[ 168 ]) ); +acado_setBlockH11( 2, 6, &(acadoWorkspace.E[ 188 ]), &(acadoWorkspace.QE[ 204 ]) ); +acado_setBlockH11( 2, 6, &(acadoWorkspace.E[ 228 ]), &(acadoWorkspace.QE[ 244 ]) ); +acado_setBlockH11( 2, 6, &(acadoWorkspace.E[ 272 ]), &(acadoWorkspace.QE[ 288 ]) ); +acado_setBlockH11( 2, 6, &(acadoWorkspace.E[ 320 ]), &(acadoWorkspace.QE[ 336 ]) ); +acado_setBlockH11( 2, 6, &(acadoWorkspace.E[ 372 ]), &(acadoWorkspace.QE[ 388 ]) ); +acado_setBlockH11( 2, 6, &(acadoWorkspace.E[ 428 ]), &(acadoWorkspace.QE[ 444 ]) ); +acado_setBlockH11( 2, 6, &(acadoWorkspace.E[ 488 ]), &(acadoWorkspace.QE[ 504 ]) ); +acado_setBlockH11( 2, 6, &(acadoWorkspace.E[ 552 ]), &(acadoWorkspace.QE[ 568 ]) ); +acado_setBlockH11( 2, 6, &(acadoWorkspace.E[ 620 ]), &(acadoWorkspace.QE[ 636 ]) ); +acado_setBlockH11( 2, 6, &(acadoWorkspace.E[ 692 ]), &(acadoWorkspace.QE[ 708 ]) ); +acado_setBlockH11( 2, 6, &(acadoWorkspace.E[ 768 ]), &(acadoWorkspace.QE[ 784 ]) ); + +acado_zeroBlockH11( 2, 7 ); +acado_setBlockH11( 2, 7, &(acadoWorkspace.E[ 120 ]), &(acadoWorkspace.QE[ 140 ]) ); +acado_setBlockH11( 2, 7, &(acadoWorkspace.E[ 152 ]), &(acadoWorkspace.QE[ 172 ]) ); +acado_setBlockH11( 2, 7, &(acadoWorkspace.E[ 188 ]), &(acadoWorkspace.QE[ 208 ]) ); +acado_setBlockH11( 2, 7, &(acadoWorkspace.E[ 228 ]), &(acadoWorkspace.QE[ 248 ]) ); +acado_setBlockH11( 2, 7, &(acadoWorkspace.E[ 272 ]), &(acadoWorkspace.QE[ 292 ]) ); +acado_setBlockH11( 2, 7, &(acadoWorkspace.E[ 320 ]), &(acadoWorkspace.QE[ 340 ]) ); +acado_setBlockH11( 2, 7, &(acadoWorkspace.E[ 372 ]), &(acadoWorkspace.QE[ 392 ]) ); +acado_setBlockH11( 2, 7, &(acadoWorkspace.E[ 428 ]), &(acadoWorkspace.QE[ 448 ]) ); +acado_setBlockH11( 2, 7, &(acadoWorkspace.E[ 488 ]), &(acadoWorkspace.QE[ 508 ]) ); +acado_setBlockH11( 2, 7, &(acadoWorkspace.E[ 552 ]), &(acadoWorkspace.QE[ 572 ]) ); +acado_setBlockH11( 2, 7, &(acadoWorkspace.E[ 620 ]), &(acadoWorkspace.QE[ 640 ]) ); +acado_setBlockH11( 2, 7, &(acadoWorkspace.E[ 692 ]), &(acadoWorkspace.QE[ 712 ]) ); +acado_setBlockH11( 2, 7, &(acadoWorkspace.E[ 768 ]), &(acadoWorkspace.QE[ 788 ]) ); + +acado_zeroBlockH11( 2, 8 ); +acado_setBlockH11( 2, 8, &(acadoWorkspace.E[ 152 ]), &(acadoWorkspace.QE[ 176 ]) ); +acado_setBlockH11( 2, 8, &(acadoWorkspace.E[ 188 ]), &(acadoWorkspace.QE[ 212 ]) ); +acado_setBlockH11( 2, 8, &(acadoWorkspace.E[ 228 ]), &(acadoWorkspace.QE[ 252 ]) ); +acado_setBlockH11( 2, 8, &(acadoWorkspace.E[ 272 ]), &(acadoWorkspace.QE[ 296 ]) ); +acado_setBlockH11( 2, 8, &(acadoWorkspace.E[ 320 ]), &(acadoWorkspace.QE[ 344 ]) ); +acado_setBlockH11( 2, 8, &(acadoWorkspace.E[ 372 ]), &(acadoWorkspace.QE[ 396 ]) ); +acado_setBlockH11( 2, 8, &(acadoWorkspace.E[ 428 ]), &(acadoWorkspace.QE[ 452 ]) ); +acado_setBlockH11( 2, 8, &(acadoWorkspace.E[ 488 ]), &(acadoWorkspace.QE[ 512 ]) ); +acado_setBlockH11( 2, 8, &(acadoWorkspace.E[ 552 ]), &(acadoWorkspace.QE[ 576 ]) ); +acado_setBlockH11( 2, 8, &(acadoWorkspace.E[ 620 ]), &(acadoWorkspace.QE[ 644 ]) ); +acado_setBlockH11( 2, 8, &(acadoWorkspace.E[ 692 ]), &(acadoWorkspace.QE[ 716 ]) ); +acado_setBlockH11( 2, 8, &(acadoWorkspace.E[ 768 ]), &(acadoWorkspace.QE[ 792 ]) ); + +acado_zeroBlockH11( 2, 9 ); +acado_setBlockH11( 2, 9, &(acadoWorkspace.E[ 188 ]), &(acadoWorkspace.QE[ 216 ]) ); +acado_setBlockH11( 2, 9, &(acadoWorkspace.E[ 228 ]), &(acadoWorkspace.QE[ 256 ]) ); +acado_setBlockH11( 2, 9, &(acadoWorkspace.E[ 272 ]), &(acadoWorkspace.QE[ 300 ]) ); +acado_setBlockH11( 2, 9, &(acadoWorkspace.E[ 320 ]), &(acadoWorkspace.QE[ 348 ]) ); +acado_setBlockH11( 2, 9, &(acadoWorkspace.E[ 372 ]), &(acadoWorkspace.QE[ 400 ]) ); +acado_setBlockH11( 2, 9, &(acadoWorkspace.E[ 428 ]), &(acadoWorkspace.QE[ 456 ]) ); +acado_setBlockH11( 2, 9, &(acadoWorkspace.E[ 488 ]), &(acadoWorkspace.QE[ 516 ]) ); +acado_setBlockH11( 2, 9, &(acadoWorkspace.E[ 552 ]), &(acadoWorkspace.QE[ 580 ]) ); +acado_setBlockH11( 2, 9, &(acadoWorkspace.E[ 620 ]), &(acadoWorkspace.QE[ 648 ]) ); +acado_setBlockH11( 2, 9, &(acadoWorkspace.E[ 692 ]), &(acadoWorkspace.QE[ 720 ]) ); +acado_setBlockH11( 2, 9, &(acadoWorkspace.E[ 768 ]), &(acadoWorkspace.QE[ 796 ]) ); + +acado_zeroBlockH11( 2, 10 ); +acado_setBlockH11( 2, 10, &(acadoWorkspace.E[ 228 ]), &(acadoWorkspace.QE[ 260 ]) ); +acado_setBlockH11( 2, 10, &(acadoWorkspace.E[ 272 ]), &(acadoWorkspace.QE[ 304 ]) ); +acado_setBlockH11( 2, 10, &(acadoWorkspace.E[ 320 ]), &(acadoWorkspace.QE[ 352 ]) ); +acado_setBlockH11( 2, 10, &(acadoWorkspace.E[ 372 ]), &(acadoWorkspace.QE[ 404 ]) ); +acado_setBlockH11( 2, 10, &(acadoWorkspace.E[ 428 ]), &(acadoWorkspace.QE[ 460 ]) ); +acado_setBlockH11( 2, 10, &(acadoWorkspace.E[ 488 ]), &(acadoWorkspace.QE[ 520 ]) ); +acado_setBlockH11( 2, 10, &(acadoWorkspace.E[ 552 ]), &(acadoWorkspace.QE[ 584 ]) ); +acado_setBlockH11( 2, 10, &(acadoWorkspace.E[ 620 ]), &(acadoWorkspace.QE[ 652 ]) ); +acado_setBlockH11( 2, 10, &(acadoWorkspace.E[ 692 ]), &(acadoWorkspace.QE[ 724 ]) ); +acado_setBlockH11( 2, 10, &(acadoWorkspace.E[ 768 ]), &(acadoWorkspace.QE[ 800 ]) ); + +acado_zeroBlockH11( 2, 11 ); +acado_setBlockH11( 2, 11, &(acadoWorkspace.E[ 272 ]), &(acadoWorkspace.QE[ 308 ]) ); +acado_setBlockH11( 2, 11, &(acadoWorkspace.E[ 320 ]), &(acadoWorkspace.QE[ 356 ]) ); +acado_setBlockH11( 2, 11, &(acadoWorkspace.E[ 372 ]), &(acadoWorkspace.QE[ 408 ]) ); +acado_setBlockH11( 2, 11, &(acadoWorkspace.E[ 428 ]), &(acadoWorkspace.QE[ 464 ]) ); +acado_setBlockH11( 2, 11, &(acadoWorkspace.E[ 488 ]), &(acadoWorkspace.QE[ 524 ]) ); +acado_setBlockH11( 2, 11, &(acadoWorkspace.E[ 552 ]), &(acadoWorkspace.QE[ 588 ]) ); +acado_setBlockH11( 2, 11, &(acadoWorkspace.E[ 620 ]), &(acadoWorkspace.QE[ 656 ]) ); +acado_setBlockH11( 2, 11, &(acadoWorkspace.E[ 692 ]), &(acadoWorkspace.QE[ 728 ]) ); +acado_setBlockH11( 2, 11, &(acadoWorkspace.E[ 768 ]), &(acadoWorkspace.QE[ 804 ]) ); + +acado_zeroBlockH11( 2, 12 ); +acado_setBlockH11( 2, 12, &(acadoWorkspace.E[ 320 ]), &(acadoWorkspace.QE[ 360 ]) ); +acado_setBlockH11( 2, 12, &(acadoWorkspace.E[ 372 ]), &(acadoWorkspace.QE[ 412 ]) ); +acado_setBlockH11( 2, 12, &(acadoWorkspace.E[ 428 ]), &(acadoWorkspace.QE[ 468 ]) ); +acado_setBlockH11( 2, 12, &(acadoWorkspace.E[ 488 ]), &(acadoWorkspace.QE[ 528 ]) ); +acado_setBlockH11( 2, 12, &(acadoWorkspace.E[ 552 ]), &(acadoWorkspace.QE[ 592 ]) ); +acado_setBlockH11( 2, 12, &(acadoWorkspace.E[ 620 ]), &(acadoWorkspace.QE[ 660 ]) ); +acado_setBlockH11( 2, 12, &(acadoWorkspace.E[ 692 ]), &(acadoWorkspace.QE[ 732 ]) ); +acado_setBlockH11( 2, 12, &(acadoWorkspace.E[ 768 ]), &(acadoWorkspace.QE[ 808 ]) ); + +acado_zeroBlockH11( 2, 13 ); +acado_setBlockH11( 2, 13, &(acadoWorkspace.E[ 372 ]), &(acadoWorkspace.QE[ 416 ]) ); +acado_setBlockH11( 2, 13, &(acadoWorkspace.E[ 428 ]), &(acadoWorkspace.QE[ 472 ]) ); +acado_setBlockH11( 2, 13, &(acadoWorkspace.E[ 488 ]), &(acadoWorkspace.QE[ 532 ]) ); +acado_setBlockH11( 2, 13, &(acadoWorkspace.E[ 552 ]), &(acadoWorkspace.QE[ 596 ]) ); +acado_setBlockH11( 2, 13, &(acadoWorkspace.E[ 620 ]), &(acadoWorkspace.QE[ 664 ]) ); +acado_setBlockH11( 2, 13, &(acadoWorkspace.E[ 692 ]), &(acadoWorkspace.QE[ 736 ]) ); +acado_setBlockH11( 2, 13, &(acadoWorkspace.E[ 768 ]), &(acadoWorkspace.QE[ 812 ]) ); + +acado_zeroBlockH11( 2, 14 ); +acado_setBlockH11( 2, 14, &(acadoWorkspace.E[ 428 ]), &(acadoWorkspace.QE[ 476 ]) ); +acado_setBlockH11( 2, 14, &(acadoWorkspace.E[ 488 ]), &(acadoWorkspace.QE[ 536 ]) ); +acado_setBlockH11( 2, 14, &(acadoWorkspace.E[ 552 ]), &(acadoWorkspace.QE[ 600 ]) ); +acado_setBlockH11( 2, 14, &(acadoWorkspace.E[ 620 ]), &(acadoWorkspace.QE[ 668 ]) ); +acado_setBlockH11( 2, 14, &(acadoWorkspace.E[ 692 ]), &(acadoWorkspace.QE[ 740 ]) ); +acado_setBlockH11( 2, 14, &(acadoWorkspace.E[ 768 ]), &(acadoWorkspace.QE[ 816 ]) ); + +acado_zeroBlockH11( 2, 15 ); +acado_setBlockH11( 2, 15, &(acadoWorkspace.E[ 488 ]), &(acadoWorkspace.QE[ 540 ]) ); +acado_setBlockH11( 2, 15, &(acadoWorkspace.E[ 552 ]), &(acadoWorkspace.QE[ 604 ]) ); +acado_setBlockH11( 2, 15, &(acadoWorkspace.E[ 620 ]), &(acadoWorkspace.QE[ 672 ]) ); +acado_setBlockH11( 2, 15, &(acadoWorkspace.E[ 692 ]), &(acadoWorkspace.QE[ 744 ]) ); +acado_setBlockH11( 2, 15, &(acadoWorkspace.E[ 768 ]), &(acadoWorkspace.QE[ 820 ]) ); + +acado_zeroBlockH11( 2, 16 ); +acado_setBlockH11( 2, 16, &(acadoWorkspace.E[ 552 ]), &(acadoWorkspace.QE[ 608 ]) ); +acado_setBlockH11( 2, 16, &(acadoWorkspace.E[ 620 ]), &(acadoWorkspace.QE[ 676 ]) ); +acado_setBlockH11( 2, 16, &(acadoWorkspace.E[ 692 ]), &(acadoWorkspace.QE[ 748 ]) ); +acado_setBlockH11( 2, 16, &(acadoWorkspace.E[ 768 ]), &(acadoWorkspace.QE[ 824 ]) ); + +acado_zeroBlockH11( 2, 17 ); +acado_setBlockH11( 2, 17, &(acadoWorkspace.E[ 620 ]), &(acadoWorkspace.QE[ 680 ]) ); +acado_setBlockH11( 2, 17, &(acadoWorkspace.E[ 692 ]), &(acadoWorkspace.QE[ 752 ]) ); +acado_setBlockH11( 2, 17, &(acadoWorkspace.E[ 768 ]), &(acadoWorkspace.QE[ 828 ]) ); + +acado_zeroBlockH11( 2, 18 ); +acado_setBlockH11( 2, 18, &(acadoWorkspace.E[ 692 ]), &(acadoWorkspace.QE[ 756 ]) ); +acado_setBlockH11( 2, 18, &(acadoWorkspace.E[ 768 ]), &(acadoWorkspace.QE[ 832 ]) ); + +acado_zeroBlockH11( 2, 19 ); +acado_setBlockH11( 2, 19, &(acadoWorkspace.E[ 768 ]), &(acadoWorkspace.QE[ 836 ]) ); + +acado_setBlockH11_R1( 3, 3, &(acadoWorkspace.R1[ 3 ]) ); +acado_setBlockH11( 3, 3, &(acadoWorkspace.E[ 36 ]), &(acadoWorkspace.QE[ 36 ]) ); +acado_setBlockH11( 3, 3, &(acadoWorkspace.E[ 52 ]), &(acadoWorkspace.QE[ 52 ]) ); +acado_setBlockH11( 3, 3, &(acadoWorkspace.E[ 72 ]), &(acadoWorkspace.QE[ 72 ]) ); +acado_setBlockH11( 3, 3, &(acadoWorkspace.E[ 96 ]), &(acadoWorkspace.QE[ 96 ]) ); +acado_setBlockH11( 3, 3, &(acadoWorkspace.E[ 124 ]), &(acadoWorkspace.QE[ 124 ]) ); +acado_setBlockH11( 3, 3, &(acadoWorkspace.E[ 156 ]), &(acadoWorkspace.QE[ 156 ]) ); +acado_setBlockH11( 3, 3, &(acadoWorkspace.E[ 192 ]), &(acadoWorkspace.QE[ 192 ]) ); +acado_setBlockH11( 3, 3, &(acadoWorkspace.E[ 232 ]), &(acadoWorkspace.QE[ 232 ]) ); +acado_setBlockH11( 3, 3, &(acadoWorkspace.E[ 276 ]), &(acadoWorkspace.QE[ 276 ]) ); +acado_setBlockH11( 3, 3, &(acadoWorkspace.E[ 324 ]), &(acadoWorkspace.QE[ 324 ]) ); +acado_setBlockH11( 3, 3, &(acadoWorkspace.E[ 376 ]), &(acadoWorkspace.QE[ 376 ]) ); +acado_setBlockH11( 3, 3, &(acadoWorkspace.E[ 432 ]), &(acadoWorkspace.QE[ 432 ]) ); +acado_setBlockH11( 3, 3, &(acadoWorkspace.E[ 492 ]), &(acadoWorkspace.QE[ 492 ]) ); +acado_setBlockH11( 3, 3, &(acadoWorkspace.E[ 556 ]), &(acadoWorkspace.QE[ 556 ]) ); +acado_setBlockH11( 3, 3, &(acadoWorkspace.E[ 624 ]), &(acadoWorkspace.QE[ 624 ]) ); +acado_setBlockH11( 3, 3, &(acadoWorkspace.E[ 696 ]), &(acadoWorkspace.QE[ 696 ]) ); +acado_setBlockH11( 3, 3, &(acadoWorkspace.E[ 772 ]), &(acadoWorkspace.QE[ 772 ]) ); + +acado_zeroBlockH11( 3, 4 ); +acado_setBlockH11( 3, 4, &(acadoWorkspace.E[ 52 ]), &(acadoWorkspace.QE[ 56 ]) ); +acado_setBlockH11( 3, 4, &(acadoWorkspace.E[ 72 ]), &(acadoWorkspace.QE[ 76 ]) ); +acado_setBlockH11( 3, 4, &(acadoWorkspace.E[ 96 ]), &(acadoWorkspace.QE[ 100 ]) ); +acado_setBlockH11( 3, 4, &(acadoWorkspace.E[ 124 ]), &(acadoWorkspace.QE[ 128 ]) ); +acado_setBlockH11( 3, 4, &(acadoWorkspace.E[ 156 ]), &(acadoWorkspace.QE[ 160 ]) ); +acado_setBlockH11( 3, 4, &(acadoWorkspace.E[ 192 ]), &(acadoWorkspace.QE[ 196 ]) ); +acado_setBlockH11( 3, 4, &(acadoWorkspace.E[ 232 ]), &(acadoWorkspace.QE[ 236 ]) ); +acado_setBlockH11( 3, 4, &(acadoWorkspace.E[ 276 ]), &(acadoWorkspace.QE[ 280 ]) ); +acado_setBlockH11( 3, 4, &(acadoWorkspace.E[ 324 ]), &(acadoWorkspace.QE[ 328 ]) ); +acado_setBlockH11( 3, 4, &(acadoWorkspace.E[ 376 ]), &(acadoWorkspace.QE[ 380 ]) ); +acado_setBlockH11( 3, 4, &(acadoWorkspace.E[ 432 ]), &(acadoWorkspace.QE[ 436 ]) ); +acado_setBlockH11( 3, 4, &(acadoWorkspace.E[ 492 ]), &(acadoWorkspace.QE[ 496 ]) ); +acado_setBlockH11( 3, 4, &(acadoWorkspace.E[ 556 ]), &(acadoWorkspace.QE[ 560 ]) ); +acado_setBlockH11( 3, 4, &(acadoWorkspace.E[ 624 ]), &(acadoWorkspace.QE[ 628 ]) ); +acado_setBlockH11( 3, 4, &(acadoWorkspace.E[ 696 ]), &(acadoWorkspace.QE[ 700 ]) ); +acado_setBlockH11( 3, 4, &(acadoWorkspace.E[ 772 ]), &(acadoWorkspace.QE[ 776 ]) ); + +acado_zeroBlockH11( 3, 5 ); +acado_setBlockH11( 3, 5, &(acadoWorkspace.E[ 72 ]), &(acadoWorkspace.QE[ 80 ]) ); +acado_setBlockH11( 3, 5, &(acadoWorkspace.E[ 96 ]), &(acadoWorkspace.QE[ 104 ]) ); +acado_setBlockH11( 3, 5, &(acadoWorkspace.E[ 124 ]), &(acadoWorkspace.QE[ 132 ]) ); +acado_setBlockH11( 3, 5, &(acadoWorkspace.E[ 156 ]), &(acadoWorkspace.QE[ 164 ]) ); +acado_setBlockH11( 3, 5, &(acadoWorkspace.E[ 192 ]), &(acadoWorkspace.QE[ 200 ]) ); +acado_setBlockH11( 3, 5, &(acadoWorkspace.E[ 232 ]), &(acadoWorkspace.QE[ 240 ]) ); +acado_setBlockH11( 3, 5, &(acadoWorkspace.E[ 276 ]), &(acadoWorkspace.QE[ 284 ]) ); +acado_setBlockH11( 3, 5, &(acadoWorkspace.E[ 324 ]), &(acadoWorkspace.QE[ 332 ]) ); +acado_setBlockH11( 3, 5, &(acadoWorkspace.E[ 376 ]), &(acadoWorkspace.QE[ 384 ]) ); +acado_setBlockH11( 3, 5, &(acadoWorkspace.E[ 432 ]), &(acadoWorkspace.QE[ 440 ]) ); +acado_setBlockH11( 3, 5, &(acadoWorkspace.E[ 492 ]), &(acadoWorkspace.QE[ 500 ]) ); +acado_setBlockH11( 3, 5, &(acadoWorkspace.E[ 556 ]), &(acadoWorkspace.QE[ 564 ]) ); +acado_setBlockH11( 3, 5, &(acadoWorkspace.E[ 624 ]), &(acadoWorkspace.QE[ 632 ]) ); +acado_setBlockH11( 3, 5, &(acadoWorkspace.E[ 696 ]), &(acadoWorkspace.QE[ 704 ]) ); +acado_setBlockH11( 3, 5, &(acadoWorkspace.E[ 772 ]), &(acadoWorkspace.QE[ 780 ]) ); + +acado_zeroBlockH11( 3, 6 ); +acado_setBlockH11( 3, 6, &(acadoWorkspace.E[ 96 ]), &(acadoWorkspace.QE[ 108 ]) ); +acado_setBlockH11( 3, 6, &(acadoWorkspace.E[ 124 ]), &(acadoWorkspace.QE[ 136 ]) ); +acado_setBlockH11( 3, 6, &(acadoWorkspace.E[ 156 ]), &(acadoWorkspace.QE[ 168 ]) ); +acado_setBlockH11( 3, 6, &(acadoWorkspace.E[ 192 ]), &(acadoWorkspace.QE[ 204 ]) ); +acado_setBlockH11( 3, 6, &(acadoWorkspace.E[ 232 ]), &(acadoWorkspace.QE[ 244 ]) ); +acado_setBlockH11( 3, 6, &(acadoWorkspace.E[ 276 ]), &(acadoWorkspace.QE[ 288 ]) ); +acado_setBlockH11( 3, 6, &(acadoWorkspace.E[ 324 ]), &(acadoWorkspace.QE[ 336 ]) ); +acado_setBlockH11( 3, 6, &(acadoWorkspace.E[ 376 ]), &(acadoWorkspace.QE[ 388 ]) ); +acado_setBlockH11( 3, 6, &(acadoWorkspace.E[ 432 ]), &(acadoWorkspace.QE[ 444 ]) ); +acado_setBlockH11( 3, 6, &(acadoWorkspace.E[ 492 ]), &(acadoWorkspace.QE[ 504 ]) ); +acado_setBlockH11( 3, 6, &(acadoWorkspace.E[ 556 ]), &(acadoWorkspace.QE[ 568 ]) ); +acado_setBlockH11( 3, 6, &(acadoWorkspace.E[ 624 ]), &(acadoWorkspace.QE[ 636 ]) ); +acado_setBlockH11( 3, 6, &(acadoWorkspace.E[ 696 ]), &(acadoWorkspace.QE[ 708 ]) ); +acado_setBlockH11( 3, 6, &(acadoWorkspace.E[ 772 ]), &(acadoWorkspace.QE[ 784 ]) ); + +acado_zeroBlockH11( 3, 7 ); +acado_setBlockH11( 3, 7, &(acadoWorkspace.E[ 124 ]), &(acadoWorkspace.QE[ 140 ]) ); +acado_setBlockH11( 3, 7, &(acadoWorkspace.E[ 156 ]), &(acadoWorkspace.QE[ 172 ]) ); +acado_setBlockH11( 3, 7, &(acadoWorkspace.E[ 192 ]), &(acadoWorkspace.QE[ 208 ]) ); +acado_setBlockH11( 3, 7, &(acadoWorkspace.E[ 232 ]), &(acadoWorkspace.QE[ 248 ]) ); +acado_setBlockH11( 3, 7, &(acadoWorkspace.E[ 276 ]), &(acadoWorkspace.QE[ 292 ]) ); +acado_setBlockH11( 3, 7, &(acadoWorkspace.E[ 324 ]), &(acadoWorkspace.QE[ 340 ]) ); +acado_setBlockH11( 3, 7, &(acadoWorkspace.E[ 376 ]), &(acadoWorkspace.QE[ 392 ]) ); +acado_setBlockH11( 3, 7, &(acadoWorkspace.E[ 432 ]), &(acadoWorkspace.QE[ 448 ]) ); +acado_setBlockH11( 3, 7, &(acadoWorkspace.E[ 492 ]), &(acadoWorkspace.QE[ 508 ]) ); +acado_setBlockH11( 3, 7, &(acadoWorkspace.E[ 556 ]), &(acadoWorkspace.QE[ 572 ]) ); +acado_setBlockH11( 3, 7, &(acadoWorkspace.E[ 624 ]), &(acadoWorkspace.QE[ 640 ]) ); +acado_setBlockH11( 3, 7, &(acadoWorkspace.E[ 696 ]), &(acadoWorkspace.QE[ 712 ]) ); +acado_setBlockH11( 3, 7, &(acadoWorkspace.E[ 772 ]), &(acadoWorkspace.QE[ 788 ]) ); + +acado_zeroBlockH11( 3, 8 ); +acado_setBlockH11( 3, 8, &(acadoWorkspace.E[ 156 ]), &(acadoWorkspace.QE[ 176 ]) ); +acado_setBlockH11( 3, 8, &(acadoWorkspace.E[ 192 ]), &(acadoWorkspace.QE[ 212 ]) ); +acado_setBlockH11( 3, 8, &(acadoWorkspace.E[ 232 ]), &(acadoWorkspace.QE[ 252 ]) ); +acado_setBlockH11( 3, 8, &(acadoWorkspace.E[ 276 ]), &(acadoWorkspace.QE[ 296 ]) ); +acado_setBlockH11( 3, 8, &(acadoWorkspace.E[ 324 ]), &(acadoWorkspace.QE[ 344 ]) ); +acado_setBlockH11( 3, 8, &(acadoWorkspace.E[ 376 ]), &(acadoWorkspace.QE[ 396 ]) ); +acado_setBlockH11( 3, 8, &(acadoWorkspace.E[ 432 ]), &(acadoWorkspace.QE[ 452 ]) ); +acado_setBlockH11( 3, 8, &(acadoWorkspace.E[ 492 ]), &(acadoWorkspace.QE[ 512 ]) ); +acado_setBlockH11( 3, 8, &(acadoWorkspace.E[ 556 ]), &(acadoWorkspace.QE[ 576 ]) ); +acado_setBlockH11( 3, 8, &(acadoWorkspace.E[ 624 ]), &(acadoWorkspace.QE[ 644 ]) ); +acado_setBlockH11( 3, 8, &(acadoWorkspace.E[ 696 ]), &(acadoWorkspace.QE[ 716 ]) ); +acado_setBlockH11( 3, 8, &(acadoWorkspace.E[ 772 ]), &(acadoWorkspace.QE[ 792 ]) ); + +acado_zeroBlockH11( 3, 9 ); +acado_setBlockH11( 3, 9, &(acadoWorkspace.E[ 192 ]), &(acadoWorkspace.QE[ 216 ]) ); +acado_setBlockH11( 3, 9, &(acadoWorkspace.E[ 232 ]), &(acadoWorkspace.QE[ 256 ]) ); +acado_setBlockH11( 3, 9, &(acadoWorkspace.E[ 276 ]), &(acadoWorkspace.QE[ 300 ]) ); +acado_setBlockH11( 3, 9, &(acadoWorkspace.E[ 324 ]), &(acadoWorkspace.QE[ 348 ]) ); +acado_setBlockH11( 3, 9, &(acadoWorkspace.E[ 376 ]), &(acadoWorkspace.QE[ 400 ]) ); +acado_setBlockH11( 3, 9, &(acadoWorkspace.E[ 432 ]), &(acadoWorkspace.QE[ 456 ]) ); +acado_setBlockH11( 3, 9, &(acadoWorkspace.E[ 492 ]), &(acadoWorkspace.QE[ 516 ]) ); +acado_setBlockH11( 3, 9, &(acadoWorkspace.E[ 556 ]), &(acadoWorkspace.QE[ 580 ]) ); +acado_setBlockH11( 3, 9, &(acadoWorkspace.E[ 624 ]), &(acadoWorkspace.QE[ 648 ]) ); +acado_setBlockH11( 3, 9, &(acadoWorkspace.E[ 696 ]), &(acadoWorkspace.QE[ 720 ]) ); +acado_setBlockH11( 3, 9, &(acadoWorkspace.E[ 772 ]), &(acadoWorkspace.QE[ 796 ]) ); + +acado_zeroBlockH11( 3, 10 ); +acado_setBlockH11( 3, 10, &(acadoWorkspace.E[ 232 ]), &(acadoWorkspace.QE[ 260 ]) ); +acado_setBlockH11( 3, 10, &(acadoWorkspace.E[ 276 ]), &(acadoWorkspace.QE[ 304 ]) ); +acado_setBlockH11( 3, 10, &(acadoWorkspace.E[ 324 ]), &(acadoWorkspace.QE[ 352 ]) ); +acado_setBlockH11( 3, 10, &(acadoWorkspace.E[ 376 ]), &(acadoWorkspace.QE[ 404 ]) ); +acado_setBlockH11( 3, 10, &(acadoWorkspace.E[ 432 ]), &(acadoWorkspace.QE[ 460 ]) ); +acado_setBlockH11( 3, 10, &(acadoWorkspace.E[ 492 ]), &(acadoWorkspace.QE[ 520 ]) ); +acado_setBlockH11( 3, 10, &(acadoWorkspace.E[ 556 ]), &(acadoWorkspace.QE[ 584 ]) ); +acado_setBlockH11( 3, 10, &(acadoWorkspace.E[ 624 ]), &(acadoWorkspace.QE[ 652 ]) ); +acado_setBlockH11( 3, 10, &(acadoWorkspace.E[ 696 ]), &(acadoWorkspace.QE[ 724 ]) ); +acado_setBlockH11( 3, 10, &(acadoWorkspace.E[ 772 ]), &(acadoWorkspace.QE[ 800 ]) ); + +acado_zeroBlockH11( 3, 11 ); +acado_setBlockH11( 3, 11, &(acadoWorkspace.E[ 276 ]), &(acadoWorkspace.QE[ 308 ]) ); +acado_setBlockH11( 3, 11, &(acadoWorkspace.E[ 324 ]), &(acadoWorkspace.QE[ 356 ]) ); +acado_setBlockH11( 3, 11, &(acadoWorkspace.E[ 376 ]), &(acadoWorkspace.QE[ 408 ]) ); +acado_setBlockH11( 3, 11, &(acadoWorkspace.E[ 432 ]), &(acadoWorkspace.QE[ 464 ]) ); +acado_setBlockH11( 3, 11, &(acadoWorkspace.E[ 492 ]), &(acadoWorkspace.QE[ 524 ]) ); +acado_setBlockH11( 3, 11, &(acadoWorkspace.E[ 556 ]), &(acadoWorkspace.QE[ 588 ]) ); +acado_setBlockH11( 3, 11, &(acadoWorkspace.E[ 624 ]), &(acadoWorkspace.QE[ 656 ]) ); +acado_setBlockH11( 3, 11, &(acadoWorkspace.E[ 696 ]), &(acadoWorkspace.QE[ 728 ]) ); +acado_setBlockH11( 3, 11, &(acadoWorkspace.E[ 772 ]), &(acadoWorkspace.QE[ 804 ]) ); + +acado_zeroBlockH11( 3, 12 ); +acado_setBlockH11( 3, 12, &(acadoWorkspace.E[ 324 ]), &(acadoWorkspace.QE[ 360 ]) ); +acado_setBlockH11( 3, 12, &(acadoWorkspace.E[ 376 ]), &(acadoWorkspace.QE[ 412 ]) ); +acado_setBlockH11( 3, 12, &(acadoWorkspace.E[ 432 ]), &(acadoWorkspace.QE[ 468 ]) ); +acado_setBlockH11( 3, 12, &(acadoWorkspace.E[ 492 ]), &(acadoWorkspace.QE[ 528 ]) ); +acado_setBlockH11( 3, 12, &(acadoWorkspace.E[ 556 ]), &(acadoWorkspace.QE[ 592 ]) ); +acado_setBlockH11( 3, 12, &(acadoWorkspace.E[ 624 ]), &(acadoWorkspace.QE[ 660 ]) ); +acado_setBlockH11( 3, 12, &(acadoWorkspace.E[ 696 ]), &(acadoWorkspace.QE[ 732 ]) ); +acado_setBlockH11( 3, 12, &(acadoWorkspace.E[ 772 ]), &(acadoWorkspace.QE[ 808 ]) ); + +acado_zeroBlockH11( 3, 13 ); +acado_setBlockH11( 3, 13, &(acadoWorkspace.E[ 376 ]), &(acadoWorkspace.QE[ 416 ]) ); +acado_setBlockH11( 3, 13, &(acadoWorkspace.E[ 432 ]), &(acadoWorkspace.QE[ 472 ]) ); +acado_setBlockH11( 3, 13, &(acadoWorkspace.E[ 492 ]), &(acadoWorkspace.QE[ 532 ]) ); +acado_setBlockH11( 3, 13, &(acadoWorkspace.E[ 556 ]), &(acadoWorkspace.QE[ 596 ]) ); +acado_setBlockH11( 3, 13, &(acadoWorkspace.E[ 624 ]), &(acadoWorkspace.QE[ 664 ]) ); +acado_setBlockH11( 3, 13, &(acadoWorkspace.E[ 696 ]), &(acadoWorkspace.QE[ 736 ]) ); +acado_setBlockH11( 3, 13, &(acadoWorkspace.E[ 772 ]), &(acadoWorkspace.QE[ 812 ]) ); + +acado_zeroBlockH11( 3, 14 ); +acado_setBlockH11( 3, 14, &(acadoWorkspace.E[ 432 ]), &(acadoWorkspace.QE[ 476 ]) ); +acado_setBlockH11( 3, 14, &(acadoWorkspace.E[ 492 ]), &(acadoWorkspace.QE[ 536 ]) ); +acado_setBlockH11( 3, 14, &(acadoWorkspace.E[ 556 ]), &(acadoWorkspace.QE[ 600 ]) ); +acado_setBlockH11( 3, 14, &(acadoWorkspace.E[ 624 ]), &(acadoWorkspace.QE[ 668 ]) ); +acado_setBlockH11( 3, 14, &(acadoWorkspace.E[ 696 ]), &(acadoWorkspace.QE[ 740 ]) ); +acado_setBlockH11( 3, 14, &(acadoWorkspace.E[ 772 ]), &(acadoWorkspace.QE[ 816 ]) ); + +acado_zeroBlockH11( 3, 15 ); +acado_setBlockH11( 3, 15, &(acadoWorkspace.E[ 492 ]), &(acadoWorkspace.QE[ 540 ]) ); +acado_setBlockH11( 3, 15, &(acadoWorkspace.E[ 556 ]), &(acadoWorkspace.QE[ 604 ]) ); +acado_setBlockH11( 3, 15, &(acadoWorkspace.E[ 624 ]), &(acadoWorkspace.QE[ 672 ]) ); +acado_setBlockH11( 3, 15, &(acadoWorkspace.E[ 696 ]), &(acadoWorkspace.QE[ 744 ]) ); +acado_setBlockH11( 3, 15, &(acadoWorkspace.E[ 772 ]), &(acadoWorkspace.QE[ 820 ]) ); + +acado_zeroBlockH11( 3, 16 ); +acado_setBlockH11( 3, 16, &(acadoWorkspace.E[ 556 ]), &(acadoWorkspace.QE[ 608 ]) ); +acado_setBlockH11( 3, 16, &(acadoWorkspace.E[ 624 ]), &(acadoWorkspace.QE[ 676 ]) ); +acado_setBlockH11( 3, 16, &(acadoWorkspace.E[ 696 ]), &(acadoWorkspace.QE[ 748 ]) ); +acado_setBlockH11( 3, 16, &(acadoWorkspace.E[ 772 ]), &(acadoWorkspace.QE[ 824 ]) ); + +acado_zeroBlockH11( 3, 17 ); +acado_setBlockH11( 3, 17, &(acadoWorkspace.E[ 624 ]), &(acadoWorkspace.QE[ 680 ]) ); +acado_setBlockH11( 3, 17, &(acadoWorkspace.E[ 696 ]), &(acadoWorkspace.QE[ 752 ]) ); +acado_setBlockH11( 3, 17, &(acadoWorkspace.E[ 772 ]), &(acadoWorkspace.QE[ 828 ]) ); + +acado_zeroBlockH11( 3, 18 ); +acado_setBlockH11( 3, 18, &(acadoWorkspace.E[ 696 ]), &(acadoWorkspace.QE[ 756 ]) ); +acado_setBlockH11( 3, 18, &(acadoWorkspace.E[ 772 ]), &(acadoWorkspace.QE[ 832 ]) ); + +acado_zeroBlockH11( 3, 19 ); +acado_setBlockH11( 3, 19, &(acadoWorkspace.E[ 772 ]), &(acadoWorkspace.QE[ 836 ]) ); + +acado_setBlockH11_R1( 4, 4, &(acadoWorkspace.R1[ 4 ]) ); +acado_setBlockH11( 4, 4, &(acadoWorkspace.E[ 56 ]), &(acadoWorkspace.QE[ 56 ]) ); +acado_setBlockH11( 4, 4, &(acadoWorkspace.E[ 76 ]), &(acadoWorkspace.QE[ 76 ]) ); +acado_setBlockH11( 4, 4, &(acadoWorkspace.E[ 100 ]), &(acadoWorkspace.QE[ 100 ]) ); +acado_setBlockH11( 4, 4, &(acadoWorkspace.E[ 128 ]), &(acadoWorkspace.QE[ 128 ]) ); +acado_setBlockH11( 4, 4, &(acadoWorkspace.E[ 160 ]), &(acadoWorkspace.QE[ 160 ]) ); +acado_setBlockH11( 4, 4, &(acadoWorkspace.E[ 196 ]), &(acadoWorkspace.QE[ 196 ]) ); +acado_setBlockH11( 4, 4, &(acadoWorkspace.E[ 236 ]), &(acadoWorkspace.QE[ 236 ]) ); +acado_setBlockH11( 4, 4, &(acadoWorkspace.E[ 280 ]), &(acadoWorkspace.QE[ 280 ]) ); +acado_setBlockH11( 4, 4, &(acadoWorkspace.E[ 328 ]), &(acadoWorkspace.QE[ 328 ]) ); +acado_setBlockH11( 4, 4, &(acadoWorkspace.E[ 380 ]), &(acadoWorkspace.QE[ 380 ]) ); +acado_setBlockH11( 4, 4, &(acadoWorkspace.E[ 436 ]), &(acadoWorkspace.QE[ 436 ]) ); +acado_setBlockH11( 4, 4, &(acadoWorkspace.E[ 496 ]), &(acadoWorkspace.QE[ 496 ]) ); +acado_setBlockH11( 4, 4, &(acadoWorkspace.E[ 560 ]), &(acadoWorkspace.QE[ 560 ]) ); +acado_setBlockH11( 4, 4, &(acadoWorkspace.E[ 628 ]), &(acadoWorkspace.QE[ 628 ]) ); +acado_setBlockH11( 4, 4, &(acadoWorkspace.E[ 700 ]), &(acadoWorkspace.QE[ 700 ]) ); +acado_setBlockH11( 4, 4, &(acadoWorkspace.E[ 776 ]), &(acadoWorkspace.QE[ 776 ]) ); + +acado_zeroBlockH11( 4, 5 ); +acado_setBlockH11( 4, 5, &(acadoWorkspace.E[ 76 ]), &(acadoWorkspace.QE[ 80 ]) ); +acado_setBlockH11( 4, 5, &(acadoWorkspace.E[ 100 ]), &(acadoWorkspace.QE[ 104 ]) ); +acado_setBlockH11( 4, 5, &(acadoWorkspace.E[ 128 ]), &(acadoWorkspace.QE[ 132 ]) ); +acado_setBlockH11( 4, 5, &(acadoWorkspace.E[ 160 ]), &(acadoWorkspace.QE[ 164 ]) ); +acado_setBlockH11( 4, 5, &(acadoWorkspace.E[ 196 ]), &(acadoWorkspace.QE[ 200 ]) ); +acado_setBlockH11( 4, 5, &(acadoWorkspace.E[ 236 ]), &(acadoWorkspace.QE[ 240 ]) ); +acado_setBlockH11( 4, 5, &(acadoWorkspace.E[ 280 ]), &(acadoWorkspace.QE[ 284 ]) ); +acado_setBlockH11( 4, 5, &(acadoWorkspace.E[ 328 ]), &(acadoWorkspace.QE[ 332 ]) ); +acado_setBlockH11( 4, 5, &(acadoWorkspace.E[ 380 ]), &(acadoWorkspace.QE[ 384 ]) ); +acado_setBlockH11( 4, 5, &(acadoWorkspace.E[ 436 ]), &(acadoWorkspace.QE[ 440 ]) ); +acado_setBlockH11( 4, 5, &(acadoWorkspace.E[ 496 ]), &(acadoWorkspace.QE[ 500 ]) ); +acado_setBlockH11( 4, 5, &(acadoWorkspace.E[ 560 ]), &(acadoWorkspace.QE[ 564 ]) ); +acado_setBlockH11( 4, 5, &(acadoWorkspace.E[ 628 ]), &(acadoWorkspace.QE[ 632 ]) ); +acado_setBlockH11( 4, 5, &(acadoWorkspace.E[ 700 ]), &(acadoWorkspace.QE[ 704 ]) ); +acado_setBlockH11( 4, 5, &(acadoWorkspace.E[ 776 ]), &(acadoWorkspace.QE[ 780 ]) ); + +acado_zeroBlockH11( 4, 6 ); +acado_setBlockH11( 4, 6, &(acadoWorkspace.E[ 100 ]), &(acadoWorkspace.QE[ 108 ]) ); +acado_setBlockH11( 4, 6, &(acadoWorkspace.E[ 128 ]), &(acadoWorkspace.QE[ 136 ]) ); +acado_setBlockH11( 4, 6, &(acadoWorkspace.E[ 160 ]), &(acadoWorkspace.QE[ 168 ]) ); +acado_setBlockH11( 4, 6, &(acadoWorkspace.E[ 196 ]), &(acadoWorkspace.QE[ 204 ]) ); +acado_setBlockH11( 4, 6, &(acadoWorkspace.E[ 236 ]), &(acadoWorkspace.QE[ 244 ]) ); +acado_setBlockH11( 4, 6, &(acadoWorkspace.E[ 280 ]), &(acadoWorkspace.QE[ 288 ]) ); +acado_setBlockH11( 4, 6, &(acadoWorkspace.E[ 328 ]), &(acadoWorkspace.QE[ 336 ]) ); +acado_setBlockH11( 4, 6, &(acadoWorkspace.E[ 380 ]), &(acadoWorkspace.QE[ 388 ]) ); +acado_setBlockH11( 4, 6, &(acadoWorkspace.E[ 436 ]), &(acadoWorkspace.QE[ 444 ]) ); +acado_setBlockH11( 4, 6, &(acadoWorkspace.E[ 496 ]), &(acadoWorkspace.QE[ 504 ]) ); +acado_setBlockH11( 4, 6, &(acadoWorkspace.E[ 560 ]), &(acadoWorkspace.QE[ 568 ]) ); +acado_setBlockH11( 4, 6, &(acadoWorkspace.E[ 628 ]), &(acadoWorkspace.QE[ 636 ]) ); +acado_setBlockH11( 4, 6, &(acadoWorkspace.E[ 700 ]), &(acadoWorkspace.QE[ 708 ]) ); +acado_setBlockH11( 4, 6, &(acadoWorkspace.E[ 776 ]), &(acadoWorkspace.QE[ 784 ]) ); + +acado_zeroBlockH11( 4, 7 ); +acado_setBlockH11( 4, 7, &(acadoWorkspace.E[ 128 ]), &(acadoWorkspace.QE[ 140 ]) ); +acado_setBlockH11( 4, 7, &(acadoWorkspace.E[ 160 ]), &(acadoWorkspace.QE[ 172 ]) ); +acado_setBlockH11( 4, 7, &(acadoWorkspace.E[ 196 ]), &(acadoWorkspace.QE[ 208 ]) ); +acado_setBlockH11( 4, 7, &(acadoWorkspace.E[ 236 ]), &(acadoWorkspace.QE[ 248 ]) ); +acado_setBlockH11( 4, 7, &(acadoWorkspace.E[ 280 ]), &(acadoWorkspace.QE[ 292 ]) ); +acado_setBlockH11( 4, 7, &(acadoWorkspace.E[ 328 ]), &(acadoWorkspace.QE[ 340 ]) ); +acado_setBlockH11( 4, 7, &(acadoWorkspace.E[ 380 ]), &(acadoWorkspace.QE[ 392 ]) ); +acado_setBlockH11( 4, 7, &(acadoWorkspace.E[ 436 ]), &(acadoWorkspace.QE[ 448 ]) ); +acado_setBlockH11( 4, 7, &(acadoWorkspace.E[ 496 ]), &(acadoWorkspace.QE[ 508 ]) ); +acado_setBlockH11( 4, 7, &(acadoWorkspace.E[ 560 ]), &(acadoWorkspace.QE[ 572 ]) ); +acado_setBlockH11( 4, 7, &(acadoWorkspace.E[ 628 ]), &(acadoWorkspace.QE[ 640 ]) ); +acado_setBlockH11( 4, 7, &(acadoWorkspace.E[ 700 ]), &(acadoWorkspace.QE[ 712 ]) ); +acado_setBlockH11( 4, 7, &(acadoWorkspace.E[ 776 ]), &(acadoWorkspace.QE[ 788 ]) ); + +acado_zeroBlockH11( 4, 8 ); +acado_setBlockH11( 4, 8, &(acadoWorkspace.E[ 160 ]), &(acadoWorkspace.QE[ 176 ]) ); +acado_setBlockH11( 4, 8, &(acadoWorkspace.E[ 196 ]), &(acadoWorkspace.QE[ 212 ]) ); +acado_setBlockH11( 4, 8, &(acadoWorkspace.E[ 236 ]), &(acadoWorkspace.QE[ 252 ]) ); +acado_setBlockH11( 4, 8, &(acadoWorkspace.E[ 280 ]), &(acadoWorkspace.QE[ 296 ]) ); +acado_setBlockH11( 4, 8, &(acadoWorkspace.E[ 328 ]), &(acadoWorkspace.QE[ 344 ]) ); +acado_setBlockH11( 4, 8, &(acadoWorkspace.E[ 380 ]), &(acadoWorkspace.QE[ 396 ]) ); +acado_setBlockH11( 4, 8, &(acadoWorkspace.E[ 436 ]), &(acadoWorkspace.QE[ 452 ]) ); +acado_setBlockH11( 4, 8, &(acadoWorkspace.E[ 496 ]), &(acadoWorkspace.QE[ 512 ]) ); +acado_setBlockH11( 4, 8, &(acadoWorkspace.E[ 560 ]), &(acadoWorkspace.QE[ 576 ]) ); +acado_setBlockH11( 4, 8, &(acadoWorkspace.E[ 628 ]), &(acadoWorkspace.QE[ 644 ]) ); +acado_setBlockH11( 4, 8, &(acadoWorkspace.E[ 700 ]), &(acadoWorkspace.QE[ 716 ]) ); +acado_setBlockH11( 4, 8, &(acadoWorkspace.E[ 776 ]), &(acadoWorkspace.QE[ 792 ]) ); + +acado_zeroBlockH11( 4, 9 ); +acado_setBlockH11( 4, 9, &(acadoWorkspace.E[ 196 ]), &(acadoWorkspace.QE[ 216 ]) ); +acado_setBlockH11( 4, 9, &(acadoWorkspace.E[ 236 ]), &(acadoWorkspace.QE[ 256 ]) ); +acado_setBlockH11( 4, 9, &(acadoWorkspace.E[ 280 ]), &(acadoWorkspace.QE[ 300 ]) ); +acado_setBlockH11( 4, 9, &(acadoWorkspace.E[ 328 ]), &(acadoWorkspace.QE[ 348 ]) ); +acado_setBlockH11( 4, 9, &(acadoWorkspace.E[ 380 ]), &(acadoWorkspace.QE[ 400 ]) ); +acado_setBlockH11( 4, 9, &(acadoWorkspace.E[ 436 ]), &(acadoWorkspace.QE[ 456 ]) ); +acado_setBlockH11( 4, 9, &(acadoWorkspace.E[ 496 ]), &(acadoWorkspace.QE[ 516 ]) ); +acado_setBlockH11( 4, 9, &(acadoWorkspace.E[ 560 ]), &(acadoWorkspace.QE[ 580 ]) ); +acado_setBlockH11( 4, 9, &(acadoWorkspace.E[ 628 ]), &(acadoWorkspace.QE[ 648 ]) ); +acado_setBlockH11( 4, 9, &(acadoWorkspace.E[ 700 ]), &(acadoWorkspace.QE[ 720 ]) ); +acado_setBlockH11( 4, 9, &(acadoWorkspace.E[ 776 ]), &(acadoWorkspace.QE[ 796 ]) ); + +acado_zeroBlockH11( 4, 10 ); +acado_setBlockH11( 4, 10, &(acadoWorkspace.E[ 236 ]), &(acadoWorkspace.QE[ 260 ]) ); +acado_setBlockH11( 4, 10, &(acadoWorkspace.E[ 280 ]), &(acadoWorkspace.QE[ 304 ]) ); +acado_setBlockH11( 4, 10, &(acadoWorkspace.E[ 328 ]), &(acadoWorkspace.QE[ 352 ]) ); +acado_setBlockH11( 4, 10, &(acadoWorkspace.E[ 380 ]), &(acadoWorkspace.QE[ 404 ]) ); +acado_setBlockH11( 4, 10, &(acadoWorkspace.E[ 436 ]), &(acadoWorkspace.QE[ 460 ]) ); +acado_setBlockH11( 4, 10, &(acadoWorkspace.E[ 496 ]), &(acadoWorkspace.QE[ 520 ]) ); +acado_setBlockH11( 4, 10, &(acadoWorkspace.E[ 560 ]), &(acadoWorkspace.QE[ 584 ]) ); +acado_setBlockH11( 4, 10, &(acadoWorkspace.E[ 628 ]), &(acadoWorkspace.QE[ 652 ]) ); +acado_setBlockH11( 4, 10, &(acadoWorkspace.E[ 700 ]), &(acadoWorkspace.QE[ 724 ]) ); +acado_setBlockH11( 4, 10, &(acadoWorkspace.E[ 776 ]), &(acadoWorkspace.QE[ 800 ]) ); + +acado_zeroBlockH11( 4, 11 ); +acado_setBlockH11( 4, 11, &(acadoWorkspace.E[ 280 ]), &(acadoWorkspace.QE[ 308 ]) ); +acado_setBlockH11( 4, 11, &(acadoWorkspace.E[ 328 ]), &(acadoWorkspace.QE[ 356 ]) ); +acado_setBlockH11( 4, 11, &(acadoWorkspace.E[ 380 ]), &(acadoWorkspace.QE[ 408 ]) ); +acado_setBlockH11( 4, 11, &(acadoWorkspace.E[ 436 ]), &(acadoWorkspace.QE[ 464 ]) ); +acado_setBlockH11( 4, 11, &(acadoWorkspace.E[ 496 ]), &(acadoWorkspace.QE[ 524 ]) ); +acado_setBlockH11( 4, 11, &(acadoWorkspace.E[ 560 ]), &(acadoWorkspace.QE[ 588 ]) ); +acado_setBlockH11( 4, 11, &(acadoWorkspace.E[ 628 ]), &(acadoWorkspace.QE[ 656 ]) ); +acado_setBlockH11( 4, 11, &(acadoWorkspace.E[ 700 ]), &(acadoWorkspace.QE[ 728 ]) ); +acado_setBlockH11( 4, 11, &(acadoWorkspace.E[ 776 ]), &(acadoWorkspace.QE[ 804 ]) ); + +acado_zeroBlockH11( 4, 12 ); +acado_setBlockH11( 4, 12, &(acadoWorkspace.E[ 328 ]), &(acadoWorkspace.QE[ 360 ]) ); +acado_setBlockH11( 4, 12, &(acadoWorkspace.E[ 380 ]), &(acadoWorkspace.QE[ 412 ]) ); +acado_setBlockH11( 4, 12, &(acadoWorkspace.E[ 436 ]), &(acadoWorkspace.QE[ 468 ]) ); +acado_setBlockH11( 4, 12, &(acadoWorkspace.E[ 496 ]), &(acadoWorkspace.QE[ 528 ]) ); +acado_setBlockH11( 4, 12, &(acadoWorkspace.E[ 560 ]), &(acadoWorkspace.QE[ 592 ]) ); +acado_setBlockH11( 4, 12, &(acadoWorkspace.E[ 628 ]), &(acadoWorkspace.QE[ 660 ]) ); +acado_setBlockH11( 4, 12, &(acadoWorkspace.E[ 700 ]), &(acadoWorkspace.QE[ 732 ]) ); +acado_setBlockH11( 4, 12, &(acadoWorkspace.E[ 776 ]), &(acadoWorkspace.QE[ 808 ]) ); + +acado_zeroBlockH11( 4, 13 ); +acado_setBlockH11( 4, 13, &(acadoWorkspace.E[ 380 ]), &(acadoWorkspace.QE[ 416 ]) ); +acado_setBlockH11( 4, 13, &(acadoWorkspace.E[ 436 ]), &(acadoWorkspace.QE[ 472 ]) ); +acado_setBlockH11( 4, 13, &(acadoWorkspace.E[ 496 ]), &(acadoWorkspace.QE[ 532 ]) ); +acado_setBlockH11( 4, 13, &(acadoWorkspace.E[ 560 ]), &(acadoWorkspace.QE[ 596 ]) ); +acado_setBlockH11( 4, 13, &(acadoWorkspace.E[ 628 ]), &(acadoWorkspace.QE[ 664 ]) ); +acado_setBlockH11( 4, 13, &(acadoWorkspace.E[ 700 ]), &(acadoWorkspace.QE[ 736 ]) ); +acado_setBlockH11( 4, 13, &(acadoWorkspace.E[ 776 ]), &(acadoWorkspace.QE[ 812 ]) ); + +acado_zeroBlockH11( 4, 14 ); +acado_setBlockH11( 4, 14, &(acadoWorkspace.E[ 436 ]), &(acadoWorkspace.QE[ 476 ]) ); +acado_setBlockH11( 4, 14, &(acadoWorkspace.E[ 496 ]), &(acadoWorkspace.QE[ 536 ]) ); +acado_setBlockH11( 4, 14, &(acadoWorkspace.E[ 560 ]), &(acadoWorkspace.QE[ 600 ]) ); +acado_setBlockH11( 4, 14, &(acadoWorkspace.E[ 628 ]), &(acadoWorkspace.QE[ 668 ]) ); +acado_setBlockH11( 4, 14, &(acadoWorkspace.E[ 700 ]), &(acadoWorkspace.QE[ 740 ]) ); +acado_setBlockH11( 4, 14, &(acadoWorkspace.E[ 776 ]), &(acadoWorkspace.QE[ 816 ]) ); + +acado_zeroBlockH11( 4, 15 ); +acado_setBlockH11( 4, 15, &(acadoWorkspace.E[ 496 ]), &(acadoWorkspace.QE[ 540 ]) ); +acado_setBlockH11( 4, 15, &(acadoWorkspace.E[ 560 ]), &(acadoWorkspace.QE[ 604 ]) ); +acado_setBlockH11( 4, 15, &(acadoWorkspace.E[ 628 ]), &(acadoWorkspace.QE[ 672 ]) ); +acado_setBlockH11( 4, 15, &(acadoWorkspace.E[ 700 ]), &(acadoWorkspace.QE[ 744 ]) ); +acado_setBlockH11( 4, 15, &(acadoWorkspace.E[ 776 ]), &(acadoWorkspace.QE[ 820 ]) ); + +acado_zeroBlockH11( 4, 16 ); +acado_setBlockH11( 4, 16, &(acadoWorkspace.E[ 560 ]), &(acadoWorkspace.QE[ 608 ]) ); +acado_setBlockH11( 4, 16, &(acadoWorkspace.E[ 628 ]), &(acadoWorkspace.QE[ 676 ]) ); +acado_setBlockH11( 4, 16, &(acadoWorkspace.E[ 700 ]), &(acadoWorkspace.QE[ 748 ]) ); +acado_setBlockH11( 4, 16, &(acadoWorkspace.E[ 776 ]), &(acadoWorkspace.QE[ 824 ]) ); + +acado_zeroBlockH11( 4, 17 ); +acado_setBlockH11( 4, 17, &(acadoWorkspace.E[ 628 ]), &(acadoWorkspace.QE[ 680 ]) ); +acado_setBlockH11( 4, 17, &(acadoWorkspace.E[ 700 ]), &(acadoWorkspace.QE[ 752 ]) ); +acado_setBlockH11( 4, 17, &(acadoWorkspace.E[ 776 ]), &(acadoWorkspace.QE[ 828 ]) ); + +acado_zeroBlockH11( 4, 18 ); +acado_setBlockH11( 4, 18, &(acadoWorkspace.E[ 700 ]), &(acadoWorkspace.QE[ 756 ]) ); +acado_setBlockH11( 4, 18, &(acadoWorkspace.E[ 776 ]), &(acadoWorkspace.QE[ 832 ]) ); + +acado_zeroBlockH11( 4, 19 ); +acado_setBlockH11( 4, 19, &(acadoWorkspace.E[ 776 ]), &(acadoWorkspace.QE[ 836 ]) ); + +acado_setBlockH11_R1( 5, 5, &(acadoWorkspace.R1[ 5 ]) ); +acado_setBlockH11( 5, 5, &(acadoWorkspace.E[ 80 ]), &(acadoWorkspace.QE[ 80 ]) ); +acado_setBlockH11( 5, 5, &(acadoWorkspace.E[ 104 ]), &(acadoWorkspace.QE[ 104 ]) ); +acado_setBlockH11( 5, 5, &(acadoWorkspace.E[ 132 ]), &(acadoWorkspace.QE[ 132 ]) ); +acado_setBlockH11( 5, 5, &(acadoWorkspace.E[ 164 ]), &(acadoWorkspace.QE[ 164 ]) ); +acado_setBlockH11( 5, 5, &(acadoWorkspace.E[ 200 ]), &(acadoWorkspace.QE[ 200 ]) ); +acado_setBlockH11( 5, 5, &(acadoWorkspace.E[ 240 ]), &(acadoWorkspace.QE[ 240 ]) ); +acado_setBlockH11( 5, 5, &(acadoWorkspace.E[ 284 ]), &(acadoWorkspace.QE[ 284 ]) ); +acado_setBlockH11( 5, 5, &(acadoWorkspace.E[ 332 ]), &(acadoWorkspace.QE[ 332 ]) ); +acado_setBlockH11( 5, 5, &(acadoWorkspace.E[ 384 ]), &(acadoWorkspace.QE[ 384 ]) ); +acado_setBlockH11( 5, 5, &(acadoWorkspace.E[ 440 ]), &(acadoWorkspace.QE[ 440 ]) ); +acado_setBlockH11( 5, 5, &(acadoWorkspace.E[ 500 ]), &(acadoWorkspace.QE[ 500 ]) ); +acado_setBlockH11( 5, 5, &(acadoWorkspace.E[ 564 ]), &(acadoWorkspace.QE[ 564 ]) ); +acado_setBlockH11( 5, 5, &(acadoWorkspace.E[ 632 ]), &(acadoWorkspace.QE[ 632 ]) ); +acado_setBlockH11( 5, 5, &(acadoWorkspace.E[ 704 ]), &(acadoWorkspace.QE[ 704 ]) ); +acado_setBlockH11( 5, 5, &(acadoWorkspace.E[ 780 ]), &(acadoWorkspace.QE[ 780 ]) ); + +acado_zeroBlockH11( 5, 6 ); +acado_setBlockH11( 5, 6, &(acadoWorkspace.E[ 104 ]), &(acadoWorkspace.QE[ 108 ]) ); +acado_setBlockH11( 5, 6, &(acadoWorkspace.E[ 132 ]), &(acadoWorkspace.QE[ 136 ]) ); +acado_setBlockH11( 5, 6, &(acadoWorkspace.E[ 164 ]), &(acadoWorkspace.QE[ 168 ]) ); +acado_setBlockH11( 5, 6, &(acadoWorkspace.E[ 200 ]), &(acadoWorkspace.QE[ 204 ]) ); +acado_setBlockH11( 5, 6, &(acadoWorkspace.E[ 240 ]), &(acadoWorkspace.QE[ 244 ]) ); +acado_setBlockH11( 5, 6, &(acadoWorkspace.E[ 284 ]), &(acadoWorkspace.QE[ 288 ]) ); +acado_setBlockH11( 5, 6, &(acadoWorkspace.E[ 332 ]), &(acadoWorkspace.QE[ 336 ]) ); +acado_setBlockH11( 5, 6, &(acadoWorkspace.E[ 384 ]), &(acadoWorkspace.QE[ 388 ]) ); +acado_setBlockH11( 5, 6, &(acadoWorkspace.E[ 440 ]), &(acadoWorkspace.QE[ 444 ]) ); +acado_setBlockH11( 5, 6, &(acadoWorkspace.E[ 500 ]), &(acadoWorkspace.QE[ 504 ]) ); +acado_setBlockH11( 5, 6, &(acadoWorkspace.E[ 564 ]), &(acadoWorkspace.QE[ 568 ]) ); +acado_setBlockH11( 5, 6, &(acadoWorkspace.E[ 632 ]), &(acadoWorkspace.QE[ 636 ]) ); +acado_setBlockH11( 5, 6, &(acadoWorkspace.E[ 704 ]), &(acadoWorkspace.QE[ 708 ]) ); +acado_setBlockH11( 5, 6, &(acadoWorkspace.E[ 780 ]), &(acadoWorkspace.QE[ 784 ]) ); + +acado_zeroBlockH11( 5, 7 ); +acado_setBlockH11( 5, 7, &(acadoWorkspace.E[ 132 ]), &(acadoWorkspace.QE[ 140 ]) ); +acado_setBlockH11( 5, 7, &(acadoWorkspace.E[ 164 ]), &(acadoWorkspace.QE[ 172 ]) ); +acado_setBlockH11( 5, 7, &(acadoWorkspace.E[ 200 ]), &(acadoWorkspace.QE[ 208 ]) ); +acado_setBlockH11( 5, 7, &(acadoWorkspace.E[ 240 ]), &(acadoWorkspace.QE[ 248 ]) ); +acado_setBlockH11( 5, 7, &(acadoWorkspace.E[ 284 ]), &(acadoWorkspace.QE[ 292 ]) ); +acado_setBlockH11( 5, 7, &(acadoWorkspace.E[ 332 ]), &(acadoWorkspace.QE[ 340 ]) ); +acado_setBlockH11( 5, 7, &(acadoWorkspace.E[ 384 ]), &(acadoWorkspace.QE[ 392 ]) ); +acado_setBlockH11( 5, 7, &(acadoWorkspace.E[ 440 ]), &(acadoWorkspace.QE[ 448 ]) ); +acado_setBlockH11( 5, 7, &(acadoWorkspace.E[ 500 ]), &(acadoWorkspace.QE[ 508 ]) ); +acado_setBlockH11( 5, 7, &(acadoWorkspace.E[ 564 ]), &(acadoWorkspace.QE[ 572 ]) ); +acado_setBlockH11( 5, 7, &(acadoWorkspace.E[ 632 ]), &(acadoWorkspace.QE[ 640 ]) ); +acado_setBlockH11( 5, 7, &(acadoWorkspace.E[ 704 ]), &(acadoWorkspace.QE[ 712 ]) ); +acado_setBlockH11( 5, 7, &(acadoWorkspace.E[ 780 ]), &(acadoWorkspace.QE[ 788 ]) ); + +acado_zeroBlockH11( 5, 8 ); +acado_setBlockH11( 5, 8, &(acadoWorkspace.E[ 164 ]), &(acadoWorkspace.QE[ 176 ]) ); +acado_setBlockH11( 5, 8, &(acadoWorkspace.E[ 200 ]), &(acadoWorkspace.QE[ 212 ]) ); +acado_setBlockH11( 5, 8, &(acadoWorkspace.E[ 240 ]), &(acadoWorkspace.QE[ 252 ]) ); +acado_setBlockH11( 5, 8, &(acadoWorkspace.E[ 284 ]), &(acadoWorkspace.QE[ 296 ]) ); +acado_setBlockH11( 5, 8, &(acadoWorkspace.E[ 332 ]), &(acadoWorkspace.QE[ 344 ]) ); +acado_setBlockH11( 5, 8, &(acadoWorkspace.E[ 384 ]), &(acadoWorkspace.QE[ 396 ]) ); +acado_setBlockH11( 5, 8, &(acadoWorkspace.E[ 440 ]), &(acadoWorkspace.QE[ 452 ]) ); +acado_setBlockH11( 5, 8, &(acadoWorkspace.E[ 500 ]), &(acadoWorkspace.QE[ 512 ]) ); +acado_setBlockH11( 5, 8, &(acadoWorkspace.E[ 564 ]), &(acadoWorkspace.QE[ 576 ]) ); +acado_setBlockH11( 5, 8, &(acadoWorkspace.E[ 632 ]), &(acadoWorkspace.QE[ 644 ]) ); +acado_setBlockH11( 5, 8, &(acadoWorkspace.E[ 704 ]), &(acadoWorkspace.QE[ 716 ]) ); +acado_setBlockH11( 5, 8, &(acadoWorkspace.E[ 780 ]), &(acadoWorkspace.QE[ 792 ]) ); + +acado_zeroBlockH11( 5, 9 ); +acado_setBlockH11( 5, 9, &(acadoWorkspace.E[ 200 ]), &(acadoWorkspace.QE[ 216 ]) ); +acado_setBlockH11( 5, 9, &(acadoWorkspace.E[ 240 ]), &(acadoWorkspace.QE[ 256 ]) ); +acado_setBlockH11( 5, 9, &(acadoWorkspace.E[ 284 ]), &(acadoWorkspace.QE[ 300 ]) ); +acado_setBlockH11( 5, 9, &(acadoWorkspace.E[ 332 ]), &(acadoWorkspace.QE[ 348 ]) ); +acado_setBlockH11( 5, 9, &(acadoWorkspace.E[ 384 ]), &(acadoWorkspace.QE[ 400 ]) ); +acado_setBlockH11( 5, 9, &(acadoWorkspace.E[ 440 ]), &(acadoWorkspace.QE[ 456 ]) ); +acado_setBlockH11( 5, 9, &(acadoWorkspace.E[ 500 ]), &(acadoWorkspace.QE[ 516 ]) ); +acado_setBlockH11( 5, 9, &(acadoWorkspace.E[ 564 ]), &(acadoWorkspace.QE[ 580 ]) ); +acado_setBlockH11( 5, 9, &(acadoWorkspace.E[ 632 ]), &(acadoWorkspace.QE[ 648 ]) ); +acado_setBlockH11( 5, 9, &(acadoWorkspace.E[ 704 ]), &(acadoWorkspace.QE[ 720 ]) ); +acado_setBlockH11( 5, 9, &(acadoWorkspace.E[ 780 ]), &(acadoWorkspace.QE[ 796 ]) ); + +acado_zeroBlockH11( 5, 10 ); +acado_setBlockH11( 5, 10, &(acadoWorkspace.E[ 240 ]), &(acadoWorkspace.QE[ 260 ]) ); +acado_setBlockH11( 5, 10, &(acadoWorkspace.E[ 284 ]), &(acadoWorkspace.QE[ 304 ]) ); +acado_setBlockH11( 5, 10, &(acadoWorkspace.E[ 332 ]), &(acadoWorkspace.QE[ 352 ]) ); +acado_setBlockH11( 5, 10, &(acadoWorkspace.E[ 384 ]), &(acadoWorkspace.QE[ 404 ]) ); +acado_setBlockH11( 5, 10, &(acadoWorkspace.E[ 440 ]), &(acadoWorkspace.QE[ 460 ]) ); +acado_setBlockH11( 5, 10, &(acadoWorkspace.E[ 500 ]), &(acadoWorkspace.QE[ 520 ]) ); +acado_setBlockH11( 5, 10, &(acadoWorkspace.E[ 564 ]), &(acadoWorkspace.QE[ 584 ]) ); +acado_setBlockH11( 5, 10, &(acadoWorkspace.E[ 632 ]), &(acadoWorkspace.QE[ 652 ]) ); +acado_setBlockH11( 5, 10, &(acadoWorkspace.E[ 704 ]), &(acadoWorkspace.QE[ 724 ]) ); +acado_setBlockH11( 5, 10, &(acadoWorkspace.E[ 780 ]), &(acadoWorkspace.QE[ 800 ]) ); + +acado_zeroBlockH11( 5, 11 ); +acado_setBlockH11( 5, 11, &(acadoWorkspace.E[ 284 ]), &(acadoWorkspace.QE[ 308 ]) ); +acado_setBlockH11( 5, 11, &(acadoWorkspace.E[ 332 ]), &(acadoWorkspace.QE[ 356 ]) ); +acado_setBlockH11( 5, 11, &(acadoWorkspace.E[ 384 ]), &(acadoWorkspace.QE[ 408 ]) ); +acado_setBlockH11( 5, 11, &(acadoWorkspace.E[ 440 ]), &(acadoWorkspace.QE[ 464 ]) ); +acado_setBlockH11( 5, 11, &(acadoWorkspace.E[ 500 ]), &(acadoWorkspace.QE[ 524 ]) ); +acado_setBlockH11( 5, 11, &(acadoWorkspace.E[ 564 ]), &(acadoWorkspace.QE[ 588 ]) ); +acado_setBlockH11( 5, 11, &(acadoWorkspace.E[ 632 ]), &(acadoWorkspace.QE[ 656 ]) ); +acado_setBlockH11( 5, 11, &(acadoWorkspace.E[ 704 ]), &(acadoWorkspace.QE[ 728 ]) ); +acado_setBlockH11( 5, 11, &(acadoWorkspace.E[ 780 ]), &(acadoWorkspace.QE[ 804 ]) ); + +acado_zeroBlockH11( 5, 12 ); +acado_setBlockH11( 5, 12, &(acadoWorkspace.E[ 332 ]), &(acadoWorkspace.QE[ 360 ]) ); +acado_setBlockH11( 5, 12, &(acadoWorkspace.E[ 384 ]), &(acadoWorkspace.QE[ 412 ]) ); +acado_setBlockH11( 5, 12, &(acadoWorkspace.E[ 440 ]), &(acadoWorkspace.QE[ 468 ]) ); +acado_setBlockH11( 5, 12, &(acadoWorkspace.E[ 500 ]), &(acadoWorkspace.QE[ 528 ]) ); +acado_setBlockH11( 5, 12, &(acadoWorkspace.E[ 564 ]), &(acadoWorkspace.QE[ 592 ]) ); +acado_setBlockH11( 5, 12, &(acadoWorkspace.E[ 632 ]), &(acadoWorkspace.QE[ 660 ]) ); +acado_setBlockH11( 5, 12, &(acadoWorkspace.E[ 704 ]), &(acadoWorkspace.QE[ 732 ]) ); +acado_setBlockH11( 5, 12, &(acadoWorkspace.E[ 780 ]), &(acadoWorkspace.QE[ 808 ]) ); + +acado_zeroBlockH11( 5, 13 ); +acado_setBlockH11( 5, 13, &(acadoWorkspace.E[ 384 ]), &(acadoWorkspace.QE[ 416 ]) ); +acado_setBlockH11( 5, 13, &(acadoWorkspace.E[ 440 ]), &(acadoWorkspace.QE[ 472 ]) ); +acado_setBlockH11( 5, 13, &(acadoWorkspace.E[ 500 ]), &(acadoWorkspace.QE[ 532 ]) ); +acado_setBlockH11( 5, 13, &(acadoWorkspace.E[ 564 ]), &(acadoWorkspace.QE[ 596 ]) ); +acado_setBlockH11( 5, 13, &(acadoWorkspace.E[ 632 ]), &(acadoWorkspace.QE[ 664 ]) ); +acado_setBlockH11( 5, 13, &(acadoWorkspace.E[ 704 ]), &(acadoWorkspace.QE[ 736 ]) ); +acado_setBlockH11( 5, 13, &(acadoWorkspace.E[ 780 ]), &(acadoWorkspace.QE[ 812 ]) ); + +acado_zeroBlockH11( 5, 14 ); +acado_setBlockH11( 5, 14, &(acadoWorkspace.E[ 440 ]), &(acadoWorkspace.QE[ 476 ]) ); +acado_setBlockH11( 5, 14, &(acadoWorkspace.E[ 500 ]), &(acadoWorkspace.QE[ 536 ]) ); +acado_setBlockH11( 5, 14, &(acadoWorkspace.E[ 564 ]), &(acadoWorkspace.QE[ 600 ]) ); +acado_setBlockH11( 5, 14, &(acadoWorkspace.E[ 632 ]), &(acadoWorkspace.QE[ 668 ]) ); +acado_setBlockH11( 5, 14, &(acadoWorkspace.E[ 704 ]), &(acadoWorkspace.QE[ 740 ]) ); +acado_setBlockH11( 5, 14, &(acadoWorkspace.E[ 780 ]), &(acadoWorkspace.QE[ 816 ]) ); + +acado_zeroBlockH11( 5, 15 ); +acado_setBlockH11( 5, 15, &(acadoWorkspace.E[ 500 ]), &(acadoWorkspace.QE[ 540 ]) ); +acado_setBlockH11( 5, 15, &(acadoWorkspace.E[ 564 ]), &(acadoWorkspace.QE[ 604 ]) ); +acado_setBlockH11( 5, 15, &(acadoWorkspace.E[ 632 ]), &(acadoWorkspace.QE[ 672 ]) ); +acado_setBlockH11( 5, 15, &(acadoWorkspace.E[ 704 ]), &(acadoWorkspace.QE[ 744 ]) ); +acado_setBlockH11( 5, 15, &(acadoWorkspace.E[ 780 ]), &(acadoWorkspace.QE[ 820 ]) ); + +acado_zeroBlockH11( 5, 16 ); +acado_setBlockH11( 5, 16, &(acadoWorkspace.E[ 564 ]), &(acadoWorkspace.QE[ 608 ]) ); +acado_setBlockH11( 5, 16, &(acadoWorkspace.E[ 632 ]), &(acadoWorkspace.QE[ 676 ]) ); +acado_setBlockH11( 5, 16, &(acadoWorkspace.E[ 704 ]), &(acadoWorkspace.QE[ 748 ]) ); +acado_setBlockH11( 5, 16, &(acadoWorkspace.E[ 780 ]), &(acadoWorkspace.QE[ 824 ]) ); + +acado_zeroBlockH11( 5, 17 ); +acado_setBlockH11( 5, 17, &(acadoWorkspace.E[ 632 ]), &(acadoWorkspace.QE[ 680 ]) ); +acado_setBlockH11( 5, 17, &(acadoWorkspace.E[ 704 ]), &(acadoWorkspace.QE[ 752 ]) ); +acado_setBlockH11( 5, 17, &(acadoWorkspace.E[ 780 ]), &(acadoWorkspace.QE[ 828 ]) ); + +acado_zeroBlockH11( 5, 18 ); +acado_setBlockH11( 5, 18, &(acadoWorkspace.E[ 704 ]), &(acadoWorkspace.QE[ 756 ]) ); +acado_setBlockH11( 5, 18, &(acadoWorkspace.E[ 780 ]), &(acadoWorkspace.QE[ 832 ]) ); + +acado_zeroBlockH11( 5, 19 ); +acado_setBlockH11( 5, 19, &(acadoWorkspace.E[ 780 ]), &(acadoWorkspace.QE[ 836 ]) ); + +acado_setBlockH11_R1( 6, 6, &(acadoWorkspace.R1[ 6 ]) ); +acado_setBlockH11( 6, 6, &(acadoWorkspace.E[ 108 ]), &(acadoWorkspace.QE[ 108 ]) ); +acado_setBlockH11( 6, 6, &(acadoWorkspace.E[ 136 ]), &(acadoWorkspace.QE[ 136 ]) ); +acado_setBlockH11( 6, 6, &(acadoWorkspace.E[ 168 ]), &(acadoWorkspace.QE[ 168 ]) ); +acado_setBlockH11( 6, 6, &(acadoWorkspace.E[ 204 ]), &(acadoWorkspace.QE[ 204 ]) ); +acado_setBlockH11( 6, 6, &(acadoWorkspace.E[ 244 ]), &(acadoWorkspace.QE[ 244 ]) ); +acado_setBlockH11( 6, 6, &(acadoWorkspace.E[ 288 ]), &(acadoWorkspace.QE[ 288 ]) ); +acado_setBlockH11( 6, 6, &(acadoWorkspace.E[ 336 ]), &(acadoWorkspace.QE[ 336 ]) ); +acado_setBlockH11( 6, 6, &(acadoWorkspace.E[ 388 ]), &(acadoWorkspace.QE[ 388 ]) ); +acado_setBlockH11( 6, 6, &(acadoWorkspace.E[ 444 ]), &(acadoWorkspace.QE[ 444 ]) ); +acado_setBlockH11( 6, 6, &(acadoWorkspace.E[ 504 ]), &(acadoWorkspace.QE[ 504 ]) ); +acado_setBlockH11( 6, 6, &(acadoWorkspace.E[ 568 ]), &(acadoWorkspace.QE[ 568 ]) ); +acado_setBlockH11( 6, 6, &(acadoWorkspace.E[ 636 ]), &(acadoWorkspace.QE[ 636 ]) ); +acado_setBlockH11( 6, 6, &(acadoWorkspace.E[ 708 ]), &(acadoWorkspace.QE[ 708 ]) ); +acado_setBlockH11( 6, 6, &(acadoWorkspace.E[ 784 ]), &(acadoWorkspace.QE[ 784 ]) ); + +acado_zeroBlockH11( 6, 7 ); +acado_setBlockH11( 6, 7, &(acadoWorkspace.E[ 136 ]), &(acadoWorkspace.QE[ 140 ]) ); +acado_setBlockH11( 6, 7, &(acadoWorkspace.E[ 168 ]), &(acadoWorkspace.QE[ 172 ]) ); +acado_setBlockH11( 6, 7, &(acadoWorkspace.E[ 204 ]), &(acadoWorkspace.QE[ 208 ]) ); +acado_setBlockH11( 6, 7, &(acadoWorkspace.E[ 244 ]), &(acadoWorkspace.QE[ 248 ]) ); +acado_setBlockH11( 6, 7, &(acadoWorkspace.E[ 288 ]), &(acadoWorkspace.QE[ 292 ]) ); +acado_setBlockH11( 6, 7, &(acadoWorkspace.E[ 336 ]), &(acadoWorkspace.QE[ 340 ]) ); +acado_setBlockH11( 6, 7, &(acadoWorkspace.E[ 388 ]), &(acadoWorkspace.QE[ 392 ]) ); +acado_setBlockH11( 6, 7, &(acadoWorkspace.E[ 444 ]), &(acadoWorkspace.QE[ 448 ]) ); +acado_setBlockH11( 6, 7, &(acadoWorkspace.E[ 504 ]), &(acadoWorkspace.QE[ 508 ]) ); +acado_setBlockH11( 6, 7, &(acadoWorkspace.E[ 568 ]), &(acadoWorkspace.QE[ 572 ]) ); +acado_setBlockH11( 6, 7, &(acadoWorkspace.E[ 636 ]), &(acadoWorkspace.QE[ 640 ]) ); +acado_setBlockH11( 6, 7, &(acadoWorkspace.E[ 708 ]), &(acadoWorkspace.QE[ 712 ]) ); +acado_setBlockH11( 6, 7, &(acadoWorkspace.E[ 784 ]), &(acadoWorkspace.QE[ 788 ]) ); + +acado_zeroBlockH11( 6, 8 ); +acado_setBlockH11( 6, 8, &(acadoWorkspace.E[ 168 ]), &(acadoWorkspace.QE[ 176 ]) ); +acado_setBlockH11( 6, 8, &(acadoWorkspace.E[ 204 ]), &(acadoWorkspace.QE[ 212 ]) ); +acado_setBlockH11( 6, 8, &(acadoWorkspace.E[ 244 ]), &(acadoWorkspace.QE[ 252 ]) ); +acado_setBlockH11( 6, 8, &(acadoWorkspace.E[ 288 ]), &(acadoWorkspace.QE[ 296 ]) ); +acado_setBlockH11( 6, 8, &(acadoWorkspace.E[ 336 ]), &(acadoWorkspace.QE[ 344 ]) ); +acado_setBlockH11( 6, 8, &(acadoWorkspace.E[ 388 ]), &(acadoWorkspace.QE[ 396 ]) ); +acado_setBlockH11( 6, 8, &(acadoWorkspace.E[ 444 ]), &(acadoWorkspace.QE[ 452 ]) ); +acado_setBlockH11( 6, 8, &(acadoWorkspace.E[ 504 ]), &(acadoWorkspace.QE[ 512 ]) ); +acado_setBlockH11( 6, 8, &(acadoWorkspace.E[ 568 ]), &(acadoWorkspace.QE[ 576 ]) ); +acado_setBlockH11( 6, 8, &(acadoWorkspace.E[ 636 ]), &(acadoWorkspace.QE[ 644 ]) ); +acado_setBlockH11( 6, 8, &(acadoWorkspace.E[ 708 ]), &(acadoWorkspace.QE[ 716 ]) ); +acado_setBlockH11( 6, 8, &(acadoWorkspace.E[ 784 ]), &(acadoWorkspace.QE[ 792 ]) ); + +acado_zeroBlockH11( 6, 9 ); +acado_setBlockH11( 6, 9, &(acadoWorkspace.E[ 204 ]), &(acadoWorkspace.QE[ 216 ]) ); +acado_setBlockH11( 6, 9, &(acadoWorkspace.E[ 244 ]), &(acadoWorkspace.QE[ 256 ]) ); +acado_setBlockH11( 6, 9, &(acadoWorkspace.E[ 288 ]), &(acadoWorkspace.QE[ 300 ]) ); +acado_setBlockH11( 6, 9, &(acadoWorkspace.E[ 336 ]), &(acadoWorkspace.QE[ 348 ]) ); +acado_setBlockH11( 6, 9, &(acadoWorkspace.E[ 388 ]), &(acadoWorkspace.QE[ 400 ]) ); +acado_setBlockH11( 6, 9, &(acadoWorkspace.E[ 444 ]), &(acadoWorkspace.QE[ 456 ]) ); +acado_setBlockH11( 6, 9, &(acadoWorkspace.E[ 504 ]), &(acadoWorkspace.QE[ 516 ]) ); +acado_setBlockH11( 6, 9, &(acadoWorkspace.E[ 568 ]), &(acadoWorkspace.QE[ 580 ]) ); +acado_setBlockH11( 6, 9, &(acadoWorkspace.E[ 636 ]), &(acadoWorkspace.QE[ 648 ]) ); +acado_setBlockH11( 6, 9, &(acadoWorkspace.E[ 708 ]), &(acadoWorkspace.QE[ 720 ]) ); +acado_setBlockH11( 6, 9, &(acadoWorkspace.E[ 784 ]), &(acadoWorkspace.QE[ 796 ]) ); + +acado_zeroBlockH11( 6, 10 ); +acado_setBlockH11( 6, 10, &(acadoWorkspace.E[ 244 ]), &(acadoWorkspace.QE[ 260 ]) ); +acado_setBlockH11( 6, 10, &(acadoWorkspace.E[ 288 ]), &(acadoWorkspace.QE[ 304 ]) ); +acado_setBlockH11( 6, 10, &(acadoWorkspace.E[ 336 ]), &(acadoWorkspace.QE[ 352 ]) ); +acado_setBlockH11( 6, 10, &(acadoWorkspace.E[ 388 ]), &(acadoWorkspace.QE[ 404 ]) ); +acado_setBlockH11( 6, 10, &(acadoWorkspace.E[ 444 ]), &(acadoWorkspace.QE[ 460 ]) ); +acado_setBlockH11( 6, 10, &(acadoWorkspace.E[ 504 ]), &(acadoWorkspace.QE[ 520 ]) ); +acado_setBlockH11( 6, 10, &(acadoWorkspace.E[ 568 ]), &(acadoWorkspace.QE[ 584 ]) ); +acado_setBlockH11( 6, 10, &(acadoWorkspace.E[ 636 ]), &(acadoWorkspace.QE[ 652 ]) ); +acado_setBlockH11( 6, 10, &(acadoWorkspace.E[ 708 ]), &(acadoWorkspace.QE[ 724 ]) ); +acado_setBlockH11( 6, 10, &(acadoWorkspace.E[ 784 ]), &(acadoWorkspace.QE[ 800 ]) ); + +acado_zeroBlockH11( 6, 11 ); +acado_setBlockH11( 6, 11, &(acadoWorkspace.E[ 288 ]), &(acadoWorkspace.QE[ 308 ]) ); +acado_setBlockH11( 6, 11, &(acadoWorkspace.E[ 336 ]), &(acadoWorkspace.QE[ 356 ]) ); +acado_setBlockH11( 6, 11, &(acadoWorkspace.E[ 388 ]), &(acadoWorkspace.QE[ 408 ]) ); +acado_setBlockH11( 6, 11, &(acadoWorkspace.E[ 444 ]), &(acadoWorkspace.QE[ 464 ]) ); +acado_setBlockH11( 6, 11, &(acadoWorkspace.E[ 504 ]), &(acadoWorkspace.QE[ 524 ]) ); +acado_setBlockH11( 6, 11, &(acadoWorkspace.E[ 568 ]), &(acadoWorkspace.QE[ 588 ]) ); +acado_setBlockH11( 6, 11, &(acadoWorkspace.E[ 636 ]), &(acadoWorkspace.QE[ 656 ]) ); +acado_setBlockH11( 6, 11, &(acadoWorkspace.E[ 708 ]), &(acadoWorkspace.QE[ 728 ]) ); +acado_setBlockH11( 6, 11, &(acadoWorkspace.E[ 784 ]), &(acadoWorkspace.QE[ 804 ]) ); + +acado_zeroBlockH11( 6, 12 ); +acado_setBlockH11( 6, 12, &(acadoWorkspace.E[ 336 ]), &(acadoWorkspace.QE[ 360 ]) ); +acado_setBlockH11( 6, 12, &(acadoWorkspace.E[ 388 ]), &(acadoWorkspace.QE[ 412 ]) ); +acado_setBlockH11( 6, 12, &(acadoWorkspace.E[ 444 ]), &(acadoWorkspace.QE[ 468 ]) ); +acado_setBlockH11( 6, 12, &(acadoWorkspace.E[ 504 ]), &(acadoWorkspace.QE[ 528 ]) ); +acado_setBlockH11( 6, 12, &(acadoWorkspace.E[ 568 ]), &(acadoWorkspace.QE[ 592 ]) ); +acado_setBlockH11( 6, 12, &(acadoWorkspace.E[ 636 ]), &(acadoWorkspace.QE[ 660 ]) ); +acado_setBlockH11( 6, 12, &(acadoWorkspace.E[ 708 ]), &(acadoWorkspace.QE[ 732 ]) ); +acado_setBlockH11( 6, 12, &(acadoWorkspace.E[ 784 ]), &(acadoWorkspace.QE[ 808 ]) ); + +acado_zeroBlockH11( 6, 13 ); +acado_setBlockH11( 6, 13, &(acadoWorkspace.E[ 388 ]), &(acadoWorkspace.QE[ 416 ]) ); +acado_setBlockH11( 6, 13, &(acadoWorkspace.E[ 444 ]), &(acadoWorkspace.QE[ 472 ]) ); +acado_setBlockH11( 6, 13, &(acadoWorkspace.E[ 504 ]), &(acadoWorkspace.QE[ 532 ]) ); +acado_setBlockH11( 6, 13, &(acadoWorkspace.E[ 568 ]), &(acadoWorkspace.QE[ 596 ]) ); +acado_setBlockH11( 6, 13, &(acadoWorkspace.E[ 636 ]), &(acadoWorkspace.QE[ 664 ]) ); +acado_setBlockH11( 6, 13, &(acadoWorkspace.E[ 708 ]), &(acadoWorkspace.QE[ 736 ]) ); +acado_setBlockH11( 6, 13, &(acadoWorkspace.E[ 784 ]), &(acadoWorkspace.QE[ 812 ]) ); + +acado_zeroBlockH11( 6, 14 ); +acado_setBlockH11( 6, 14, &(acadoWorkspace.E[ 444 ]), &(acadoWorkspace.QE[ 476 ]) ); +acado_setBlockH11( 6, 14, &(acadoWorkspace.E[ 504 ]), &(acadoWorkspace.QE[ 536 ]) ); +acado_setBlockH11( 6, 14, &(acadoWorkspace.E[ 568 ]), &(acadoWorkspace.QE[ 600 ]) ); +acado_setBlockH11( 6, 14, &(acadoWorkspace.E[ 636 ]), &(acadoWorkspace.QE[ 668 ]) ); +acado_setBlockH11( 6, 14, &(acadoWorkspace.E[ 708 ]), &(acadoWorkspace.QE[ 740 ]) ); +acado_setBlockH11( 6, 14, &(acadoWorkspace.E[ 784 ]), &(acadoWorkspace.QE[ 816 ]) ); + +acado_zeroBlockH11( 6, 15 ); +acado_setBlockH11( 6, 15, &(acadoWorkspace.E[ 504 ]), &(acadoWorkspace.QE[ 540 ]) ); +acado_setBlockH11( 6, 15, &(acadoWorkspace.E[ 568 ]), &(acadoWorkspace.QE[ 604 ]) ); +acado_setBlockH11( 6, 15, &(acadoWorkspace.E[ 636 ]), &(acadoWorkspace.QE[ 672 ]) ); +acado_setBlockH11( 6, 15, &(acadoWorkspace.E[ 708 ]), &(acadoWorkspace.QE[ 744 ]) ); +acado_setBlockH11( 6, 15, &(acadoWorkspace.E[ 784 ]), &(acadoWorkspace.QE[ 820 ]) ); + +acado_zeroBlockH11( 6, 16 ); +acado_setBlockH11( 6, 16, &(acadoWorkspace.E[ 568 ]), &(acadoWorkspace.QE[ 608 ]) ); +acado_setBlockH11( 6, 16, &(acadoWorkspace.E[ 636 ]), &(acadoWorkspace.QE[ 676 ]) ); +acado_setBlockH11( 6, 16, &(acadoWorkspace.E[ 708 ]), &(acadoWorkspace.QE[ 748 ]) ); +acado_setBlockH11( 6, 16, &(acadoWorkspace.E[ 784 ]), &(acadoWorkspace.QE[ 824 ]) ); + +acado_zeroBlockH11( 6, 17 ); +acado_setBlockH11( 6, 17, &(acadoWorkspace.E[ 636 ]), &(acadoWorkspace.QE[ 680 ]) ); +acado_setBlockH11( 6, 17, &(acadoWorkspace.E[ 708 ]), &(acadoWorkspace.QE[ 752 ]) ); +acado_setBlockH11( 6, 17, &(acadoWorkspace.E[ 784 ]), &(acadoWorkspace.QE[ 828 ]) ); + +acado_zeroBlockH11( 6, 18 ); +acado_setBlockH11( 6, 18, &(acadoWorkspace.E[ 708 ]), &(acadoWorkspace.QE[ 756 ]) ); +acado_setBlockH11( 6, 18, &(acadoWorkspace.E[ 784 ]), &(acadoWorkspace.QE[ 832 ]) ); + +acado_zeroBlockH11( 6, 19 ); +acado_setBlockH11( 6, 19, &(acadoWorkspace.E[ 784 ]), &(acadoWorkspace.QE[ 836 ]) ); + +acado_setBlockH11_R1( 7, 7, &(acadoWorkspace.R1[ 7 ]) ); +acado_setBlockH11( 7, 7, &(acadoWorkspace.E[ 140 ]), &(acadoWorkspace.QE[ 140 ]) ); +acado_setBlockH11( 7, 7, &(acadoWorkspace.E[ 172 ]), &(acadoWorkspace.QE[ 172 ]) ); +acado_setBlockH11( 7, 7, &(acadoWorkspace.E[ 208 ]), &(acadoWorkspace.QE[ 208 ]) ); +acado_setBlockH11( 7, 7, &(acadoWorkspace.E[ 248 ]), &(acadoWorkspace.QE[ 248 ]) ); +acado_setBlockH11( 7, 7, &(acadoWorkspace.E[ 292 ]), &(acadoWorkspace.QE[ 292 ]) ); +acado_setBlockH11( 7, 7, &(acadoWorkspace.E[ 340 ]), &(acadoWorkspace.QE[ 340 ]) ); +acado_setBlockH11( 7, 7, &(acadoWorkspace.E[ 392 ]), &(acadoWorkspace.QE[ 392 ]) ); +acado_setBlockH11( 7, 7, &(acadoWorkspace.E[ 448 ]), &(acadoWorkspace.QE[ 448 ]) ); +acado_setBlockH11( 7, 7, &(acadoWorkspace.E[ 508 ]), &(acadoWorkspace.QE[ 508 ]) ); +acado_setBlockH11( 7, 7, &(acadoWorkspace.E[ 572 ]), &(acadoWorkspace.QE[ 572 ]) ); +acado_setBlockH11( 7, 7, &(acadoWorkspace.E[ 640 ]), &(acadoWorkspace.QE[ 640 ]) ); +acado_setBlockH11( 7, 7, &(acadoWorkspace.E[ 712 ]), &(acadoWorkspace.QE[ 712 ]) ); +acado_setBlockH11( 7, 7, &(acadoWorkspace.E[ 788 ]), &(acadoWorkspace.QE[ 788 ]) ); + +acado_zeroBlockH11( 7, 8 ); +acado_setBlockH11( 7, 8, &(acadoWorkspace.E[ 172 ]), &(acadoWorkspace.QE[ 176 ]) ); +acado_setBlockH11( 7, 8, &(acadoWorkspace.E[ 208 ]), &(acadoWorkspace.QE[ 212 ]) ); +acado_setBlockH11( 7, 8, &(acadoWorkspace.E[ 248 ]), &(acadoWorkspace.QE[ 252 ]) ); +acado_setBlockH11( 7, 8, &(acadoWorkspace.E[ 292 ]), &(acadoWorkspace.QE[ 296 ]) ); +acado_setBlockH11( 7, 8, &(acadoWorkspace.E[ 340 ]), &(acadoWorkspace.QE[ 344 ]) ); +acado_setBlockH11( 7, 8, &(acadoWorkspace.E[ 392 ]), &(acadoWorkspace.QE[ 396 ]) ); +acado_setBlockH11( 7, 8, &(acadoWorkspace.E[ 448 ]), &(acadoWorkspace.QE[ 452 ]) ); +acado_setBlockH11( 7, 8, &(acadoWorkspace.E[ 508 ]), &(acadoWorkspace.QE[ 512 ]) ); +acado_setBlockH11( 7, 8, &(acadoWorkspace.E[ 572 ]), &(acadoWorkspace.QE[ 576 ]) ); +acado_setBlockH11( 7, 8, &(acadoWorkspace.E[ 640 ]), &(acadoWorkspace.QE[ 644 ]) ); +acado_setBlockH11( 7, 8, &(acadoWorkspace.E[ 712 ]), &(acadoWorkspace.QE[ 716 ]) ); +acado_setBlockH11( 7, 8, &(acadoWorkspace.E[ 788 ]), &(acadoWorkspace.QE[ 792 ]) ); + +acado_zeroBlockH11( 7, 9 ); +acado_setBlockH11( 7, 9, &(acadoWorkspace.E[ 208 ]), &(acadoWorkspace.QE[ 216 ]) ); +acado_setBlockH11( 7, 9, &(acadoWorkspace.E[ 248 ]), &(acadoWorkspace.QE[ 256 ]) ); +acado_setBlockH11( 7, 9, &(acadoWorkspace.E[ 292 ]), &(acadoWorkspace.QE[ 300 ]) ); +acado_setBlockH11( 7, 9, &(acadoWorkspace.E[ 340 ]), &(acadoWorkspace.QE[ 348 ]) ); +acado_setBlockH11( 7, 9, &(acadoWorkspace.E[ 392 ]), &(acadoWorkspace.QE[ 400 ]) ); +acado_setBlockH11( 7, 9, &(acadoWorkspace.E[ 448 ]), &(acadoWorkspace.QE[ 456 ]) ); +acado_setBlockH11( 7, 9, &(acadoWorkspace.E[ 508 ]), &(acadoWorkspace.QE[ 516 ]) ); +acado_setBlockH11( 7, 9, &(acadoWorkspace.E[ 572 ]), &(acadoWorkspace.QE[ 580 ]) ); +acado_setBlockH11( 7, 9, &(acadoWorkspace.E[ 640 ]), &(acadoWorkspace.QE[ 648 ]) ); +acado_setBlockH11( 7, 9, &(acadoWorkspace.E[ 712 ]), &(acadoWorkspace.QE[ 720 ]) ); +acado_setBlockH11( 7, 9, &(acadoWorkspace.E[ 788 ]), &(acadoWorkspace.QE[ 796 ]) ); + +acado_zeroBlockH11( 7, 10 ); +acado_setBlockH11( 7, 10, &(acadoWorkspace.E[ 248 ]), &(acadoWorkspace.QE[ 260 ]) ); +acado_setBlockH11( 7, 10, &(acadoWorkspace.E[ 292 ]), &(acadoWorkspace.QE[ 304 ]) ); +acado_setBlockH11( 7, 10, &(acadoWorkspace.E[ 340 ]), &(acadoWorkspace.QE[ 352 ]) ); +acado_setBlockH11( 7, 10, &(acadoWorkspace.E[ 392 ]), &(acadoWorkspace.QE[ 404 ]) ); +acado_setBlockH11( 7, 10, &(acadoWorkspace.E[ 448 ]), &(acadoWorkspace.QE[ 460 ]) ); +acado_setBlockH11( 7, 10, &(acadoWorkspace.E[ 508 ]), &(acadoWorkspace.QE[ 520 ]) ); +acado_setBlockH11( 7, 10, &(acadoWorkspace.E[ 572 ]), &(acadoWorkspace.QE[ 584 ]) ); +acado_setBlockH11( 7, 10, &(acadoWorkspace.E[ 640 ]), &(acadoWorkspace.QE[ 652 ]) ); +acado_setBlockH11( 7, 10, &(acadoWorkspace.E[ 712 ]), &(acadoWorkspace.QE[ 724 ]) ); +acado_setBlockH11( 7, 10, &(acadoWorkspace.E[ 788 ]), &(acadoWorkspace.QE[ 800 ]) ); + +acado_zeroBlockH11( 7, 11 ); +acado_setBlockH11( 7, 11, &(acadoWorkspace.E[ 292 ]), &(acadoWorkspace.QE[ 308 ]) ); +acado_setBlockH11( 7, 11, &(acadoWorkspace.E[ 340 ]), &(acadoWorkspace.QE[ 356 ]) ); +acado_setBlockH11( 7, 11, &(acadoWorkspace.E[ 392 ]), &(acadoWorkspace.QE[ 408 ]) ); +acado_setBlockH11( 7, 11, &(acadoWorkspace.E[ 448 ]), &(acadoWorkspace.QE[ 464 ]) ); +acado_setBlockH11( 7, 11, &(acadoWorkspace.E[ 508 ]), &(acadoWorkspace.QE[ 524 ]) ); +acado_setBlockH11( 7, 11, &(acadoWorkspace.E[ 572 ]), &(acadoWorkspace.QE[ 588 ]) ); +acado_setBlockH11( 7, 11, &(acadoWorkspace.E[ 640 ]), &(acadoWorkspace.QE[ 656 ]) ); +acado_setBlockH11( 7, 11, &(acadoWorkspace.E[ 712 ]), &(acadoWorkspace.QE[ 728 ]) ); +acado_setBlockH11( 7, 11, &(acadoWorkspace.E[ 788 ]), &(acadoWorkspace.QE[ 804 ]) ); + +acado_zeroBlockH11( 7, 12 ); +acado_setBlockH11( 7, 12, &(acadoWorkspace.E[ 340 ]), &(acadoWorkspace.QE[ 360 ]) ); +acado_setBlockH11( 7, 12, &(acadoWorkspace.E[ 392 ]), &(acadoWorkspace.QE[ 412 ]) ); +acado_setBlockH11( 7, 12, &(acadoWorkspace.E[ 448 ]), &(acadoWorkspace.QE[ 468 ]) ); +acado_setBlockH11( 7, 12, &(acadoWorkspace.E[ 508 ]), &(acadoWorkspace.QE[ 528 ]) ); +acado_setBlockH11( 7, 12, &(acadoWorkspace.E[ 572 ]), &(acadoWorkspace.QE[ 592 ]) ); +acado_setBlockH11( 7, 12, &(acadoWorkspace.E[ 640 ]), &(acadoWorkspace.QE[ 660 ]) ); +acado_setBlockH11( 7, 12, &(acadoWorkspace.E[ 712 ]), &(acadoWorkspace.QE[ 732 ]) ); +acado_setBlockH11( 7, 12, &(acadoWorkspace.E[ 788 ]), &(acadoWorkspace.QE[ 808 ]) ); + +acado_zeroBlockH11( 7, 13 ); +acado_setBlockH11( 7, 13, &(acadoWorkspace.E[ 392 ]), &(acadoWorkspace.QE[ 416 ]) ); +acado_setBlockH11( 7, 13, &(acadoWorkspace.E[ 448 ]), &(acadoWorkspace.QE[ 472 ]) ); +acado_setBlockH11( 7, 13, &(acadoWorkspace.E[ 508 ]), &(acadoWorkspace.QE[ 532 ]) ); +acado_setBlockH11( 7, 13, &(acadoWorkspace.E[ 572 ]), &(acadoWorkspace.QE[ 596 ]) ); +acado_setBlockH11( 7, 13, &(acadoWorkspace.E[ 640 ]), &(acadoWorkspace.QE[ 664 ]) ); +acado_setBlockH11( 7, 13, &(acadoWorkspace.E[ 712 ]), &(acadoWorkspace.QE[ 736 ]) ); +acado_setBlockH11( 7, 13, &(acadoWorkspace.E[ 788 ]), &(acadoWorkspace.QE[ 812 ]) ); + +acado_zeroBlockH11( 7, 14 ); +acado_setBlockH11( 7, 14, &(acadoWorkspace.E[ 448 ]), &(acadoWorkspace.QE[ 476 ]) ); +acado_setBlockH11( 7, 14, &(acadoWorkspace.E[ 508 ]), &(acadoWorkspace.QE[ 536 ]) ); +acado_setBlockH11( 7, 14, &(acadoWorkspace.E[ 572 ]), &(acadoWorkspace.QE[ 600 ]) ); +acado_setBlockH11( 7, 14, &(acadoWorkspace.E[ 640 ]), &(acadoWorkspace.QE[ 668 ]) ); +acado_setBlockH11( 7, 14, &(acadoWorkspace.E[ 712 ]), &(acadoWorkspace.QE[ 740 ]) ); +acado_setBlockH11( 7, 14, &(acadoWorkspace.E[ 788 ]), &(acadoWorkspace.QE[ 816 ]) ); + +acado_zeroBlockH11( 7, 15 ); +acado_setBlockH11( 7, 15, &(acadoWorkspace.E[ 508 ]), &(acadoWorkspace.QE[ 540 ]) ); +acado_setBlockH11( 7, 15, &(acadoWorkspace.E[ 572 ]), &(acadoWorkspace.QE[ 604 ]) ); +acado_setBlockH11( 7, 15, &(acadoWorkspace.E[ 640 ]), &(acadoWorkspace.QE[ 672 ]) ); +acado_setBlockH11( 7, 15, &(acadoWorkspace.E[ 712 ]), &(acadoWorkspace.QE[ 744 ]) ); +acado_setBlockH11( 7, 15, &(acadoWorkspace.E[ 788 ]), &(acadoWorkspace.QE[ 820 ]) ); + +acado_zeroBlockH11( 7, 16 ); +acado_setBlockH11( 7, 16, &(acadoWorkspace.E[ 572 ]), &(acadoWorkspace.QE[ 608 ]) ); +acado_setBlockH11( 7, 16, &(acadoWorkspace.E[ 640 ]), &(acadoWorkspace.QE[ 676 ]) ); +acado_setBlockH11( 7, 16, &(acadoWorkspace.E[ 712 ]), &(acadoWorkspace.QE[ 748 ]) ); +acado_setBlockH11( 7, 16, &(acadoWorkspace.E[ 788 ]), &(acadoWorkspace.QE[ 824 ]) ); + +acado_zeroBlockH11( 7, 17 ); +acado_setBlockH11( 7, 17, &(acadoWorkspace.E[ 640 ]), &(acadoWorkspace.QE[ 680 ]) ); +acado_setBlockH11( 7, 17, &(acadoWorkspace.E[ 712 ]), &(acadoWorkspace.QE[ 752 ]) ); +acado_setBlockH11( 7, 17, &(acadoWorkspace.E[ 788 ]), &(acadoWorkspace.QE[ 828 ]) ); + +acado_zeroBlockH11( 7, 18 ); +acado_setBlockH11( 7, 18, &(acadoWorkspace.E[ 712 ]), &(acadoWorkspace.QE[ 756 ]) ); +acado_setBlockH11( 7, 18, &(acadoWorkspace.E[ 788 ]), &(acadoWorkspace.QE[ 832 ]) ); + +acado_zeroBlockH11( 7, 19 ); +acado_setBlockH11( 7, 19, &(acadoWorkspace.E[ 788 ]), &(acadoWorkspace.QE[ 836 ]) ); + +acado_setBlockH11_R1( 8, 8, &(acadoWorkspace.R1[ 8 ]) ); +acado_setBlockH11( 8, 8, &(acadoWorkspace.E[ 176 ]), &(acadoWorkspace.QE[ 176 ]) ); +acado_setBlockH11( 8, 8, &(acadoWorkspace.E[ 212 ]), &(acadoWorkspace.QE[ 212 ]) ); +acado_setBlockH11( 8, 8, &(acadoWorkspace.E[ 252 ]), &(acadoWorkspace.QE[ 252 ]) ); +acado_setBlockH11( 8, 8, &(acadoWorkspace.E[ 296 ]), &(acadoWorkspace.QE[ 296 ]) ); +acado_setBlockH11( 8, 8, &(acadoWorkspace.E[ 344 ]), &(acadoWorkspace.QE[ 344 ]) ); +acado_setBlockH11( 8, 8, &(acadoWorkspace.E[ 396 ]), &(acadoWorkspace.QE[ 396 ]) ); +acado_setBlockH11( 8, 8, &(acadoWorkspace.E[ 452 ]), &(acadoWorkspace.QE[ 452 ]) ); +acado_setBlockH11( 8, 8, &(acadoWorkspace.E[ 512 ]), &(acadoWorkspace.QE[ 512 ]) ); +acado_setBlockH11( 8, 8, &(acadoWorkspace.E[ 576 ]), &(acadoWorkspace.QE[ 576 ]) ); +acado_setBlockH11( 8, 8, &(acadoWorkspace.E[ 644 ]), &(acadoWorkspace.QE[ 644 ]) ); +acado_setBlockH11( 8, 8, &(acadoWorkspace.E[ 716 ]), &(acadoWorkspace.QE[ 716 ]) ); +acado_setBlockH11( 8, 8, &(acadoWorkspace.E[ 792 ]), &(acadoWorkspace.QE[ 792 ]) ); + +acado_zeroBlockH11( 8, 9 ); +acado_setBlockH11( 8, 9, &(acadoWorkspace.E[ 212 ]), &(acadoWorkspace.QE[ 216 ]) ); +acado_setBlockH11( 8, 9, &(acadoWorkspace.E[ 252 ]), &(acadoWorkspace.QE[ 256 ]) ); +acado_setBlockH11( 8, 9, &(acadoWorkspace.E[ 296 ]), &(acadoWorkspace.QE[ 300 ]) ); +acado_setBlockH11( 8, 9, &(acadoWorkspace.E[ 344 ]), &(acadoWorkspace.QE[ 348 ]) ); +acado_setBlockH11( 8, 9, &(acadoWorkspace.E[ 396 ]), &(acadoWorkspace.QE[ 400 ]) ); +acado_setBlockH11( 8, 9, &(acadoWorkspace.E[ 452 ]), &(acadoWorkspace.QE[ 456 ]) ); +acado_setBlockH11( 8, 9, &(acadoWorkspace.E[ 512 ]), &(acadoWorkspace.QE[ 516 ]) ); +acado_setBlockH11( 8, 9, &(acadoWorkspace.E[ 576 ]), &(acadoWorkspace.QE[ 580 ]) ); +acado_setBlockH11( 8, 9, &(acadoWorkspace.E[ 644 ]), &(acadoWorkspace.QE[ 648 ]) ); +acado_setBlockH11( 8, 9, &(acadoWorkspace.E[ 716 ]), &(acadoWorkspace.QE[ 720 ]) ); +acado_setBlockH11( 8, 9, &(acadoWorkspace.E[ 792 ]), &(acadoWorkspace.QE[ 796 ]) ); + +acado_zeroBlockH11( 8, 10 ); +acado_setBlockH11( 8, 10, &(acadoWorkspace.E[ 252 ]), &(acadoWorkspace.QE[ 260 ]) ); +acado_setBlockH11( 8, 10, &(acadoWorkspace.E[ 296 ]), &(acadoWorkspace.QE[ 304 ]) ); +acado_setBlockH11( 8, 10, &(acadoWorkspace.E[ 344 ]), &(acadoWorkspace.QE[ 352 ]) ); +acado_setBlockH11( 8, 10, &(acadoWorkspace.E[ 396 ]), &(acadoWorkspace.QE[ 404 ]) ); +acado_setBlockH11( 8, 10, &(acadoWorkspace.E[ 452 ]), &(acadoWorkspace.QE[ 460 ]) ); +acado_setBlockH11( 8, 10, &(acadoWorkspace.E[ 512 ]), &(acadoWorkspace.QE[ 520 ]) ); +acado_setBlockH11( 8, 10, &(acadoWorkspace.E[ 576 ]), &(acadoWorkspace.QE[ 584 ]) ); +acado_setBlockH11( 8, 10, &(acadoWorkspace.E[ 644 ]), &(acadoWorkspace.QE[ 652 ]) ); +acado_setBlockH11( 8, 10, &(acadoWorkspace.E[ 716 ]), &(acadoWorkspace.QE[ 724 ]) ); +acado_setBlockH11( 8, 10, &(acadoWorkspace.E[ 792 ]), &(acadoWorkspace.QE[ 800 ]) ); + +acado_zeroBlockH11( 8, 11 ); +acado_setBlockH11( 8, 11, &(acadoWorkspace.E[ 296 ]), &(acadoWorkspace.QE[ 308 ]) ); +acado_setBlockH11( 8, 11, &(acadoWorkspace.E[ 344 ]), &(acadoWorkspace.QE[ 356 ]) ); +acado_setBlockH11( 8, 11, &(acadoWorkspace.E[ 396 ]), &(acadoWorkspace.QE[ 408 ]) ); +acado_setBlockH11( 8, 11, &(acadoWorkspace.E[ 452 ]), &(acadoWorkspace.QE[ 464 ]) ); +acado_setBlockH11( 8, 11, &(acadoWorkspace.E[ 512 ]), &(acadoWorkspace.QE[ 524 ]) ); +acado_setBlockH11( 8, 11, &(acadoWorkspace.E[ 576 ]), &(acadoWorkspace.QE[ 588 ]) ); +acado_setBlockH11( 8, 11, &(acadoWorkspace.E[ 644 ]), &(acadoWorkspace.QE[ 656 ]) ); +acado_setBlockH11( 8, 11, &(acadoWorkspace.E[ 716 ]), &(acadoWorkspace.QE[ 728 ]) ); +acado_setBlockH11( 8, 11, &(acadoWorkspace.E[ 792 ]), &(acadoWorkspace.QE[ 804 ]) ); + +acado_zeroBlockH11( 8, 12 ); +acado_setBlockH11( 8, 12, &(acadoWorkspace.E[ 344 ]), &(acadoWorkspace.QE[ 360 ]) ); +acado_setBlockH11( 8, 12, &(acadoWorkspace.E[ 396 ]), &(acadoWorkspace.QE[ 412 ]) ); +acado_setBlockH11( 8, 12, &(acadoWorkspace.E[ 452 ]), &(acadoWorkspace.QE[ 468 ]) ); +acado_setBlockH11( 8, 12, &(acadoWorkspace.E[ 512 ]), &(acadoWorkspace.QE[ 528 ]) ); +acado_setBlockH11( 8, 12, &(acadoWorkspace.E[ 576 ]), &(acadoWorkspace.QE[ 592 ]) ); +acado_setBlockH11( 8, 12, &(acadoWorkspace.E[ 644 ]), &(acadoWorkspace.QE[ 660 ]) ); +acado_setBlockH11( 8, 12, &(acadoWorkspace.E[ 716 ]), &(acadoWorkspace.QE[ 732 ]) ); +acado_setBlockH11( 8, 12, &(acadoWorkspace.E[ 792 ]), &(acadoWorkspace.QE[ 808 ]) ); + +acado_zeroBlockH11( 8, 13 ); +acado_setBlockH11( 8, 13, &(acadoWorkspace.E[ 396 ]), &(acadoWorkspace.QE[ 416 ]) ); +acado_setBlockH11( 8, 13, &(acadoWorkspace.E[ 452 ]), &(acadoWorkspace.QE[ 472 ]) ); +acado_setBlockH11( 8, 13, &(acadoWorkspace.E[ 512 ]), &(acadoWorkspace.QE[ 532 ]) ); +acado_setBlockH11( 8, 13, &(acadoWorkspace.E[ 576 ]), &(acadoWorkspace.QE[ 596 ]) ); +acado_setBlockH11( 8, 13, &(acadoWorkspace.E[ 644 ]), &(acadoWorkspace.QE[ 664 ]) ); +acado_setBlockH11( 8, 13, &(acadoWorkspace.E[ 716 ]), &(acadoWorkspace.QE[ 736 ]) ); +acado_setBlockH11( 8, 13, &(acadoWorkspace.E[ 792 ]), &(acadoWorkspace.QE[ 812 ]) ); + +acado_zeroBlockH11( 8, 14 ); +acado_setBlockH11( 8, 14, &(acadoWorkspace.E[ 452 ]), &(acadoWorkspace.QE[ 476 ]) ); +acado_setBlockH11( 8, 14, &(acadoWorkspace.E[ 512 ]), &(acadoWorkspace.QE[ 536 ]) ); +acado_setBlockH11( 8, 14, &(acadoWorkspace.E[ 576 ]), &(acadoWorkspace.QE[ 600 ]) ); +acado_setBlockH11( 8, 14, &(acadoWorkspace.E[ 644 ]), &(acadoWorkspace.QE[ 668 ]) ); +acado_setBlockH11( 8, 14, &(acadoWorkspace.E[ 716 ]), &(acadoWorkspace.QE[ 740 ]) ); +acado_setBlockH11( 8, 14, &(acadoWorkspace.E[ 792 ]), &(acadoWorkspace.QE[ 816 ]) ); + +acado_zeroBlockH11( 8, 15 ); +acado_setBlockH11( 8, 15, &(acadoWorkspace.E[ 512 ]), &(acadoWorkspace.QE[ 540 ]) ); +acado_setBlockH11( 8, 15, &(acadoWorkspace.E[ 576 ]), &(acadoWorkspace.QE[ 604 ]) ); +acado_setBlockH11( 8, 15, &(acadoWorkspace.E[ 644 ]), &(acadoWorkspace.QE[ 672 ]) ); +acado_setBlockH11( 8, 15, &(acadoWorkspace.E[ 716 ]), &(acadoWorkspace.QE[ 744 ]) ); +acado_setBlockH11( 8, 15, &(acadoWorkspace.E[ 792 ]), &(acadoWorkspace.QE[ 820 ]) ); + +acado_zeroBlockH11( 8, 16 ); +acado_setBlockH11( 8, 16, &(acadoWorkspace.E[ 576 ]), &(acadoWorkspace.QE[ 608 ]) ); +acado_setBlockH11( 8, 16, &(acadoWorkspace.E[ 644 ]), &(acadoWorkspace.QE[ 676 ]) ); +acado_setBlockH11( 8, 16, &(acadoWorkspace.E[ 716 ]), &(acadoWorkspace.QE[ 748 ]) ); +acado_setBlockH11( 8, 16, &(acadoWorkspace.E[ 792 ]), &(acadoWorkspace.QE[ 824 ]) ); + +acado_zeroBlockH11( 8, 17 ); +acado_setBlockH11( 8, 17, &(acadoWorkspace.E[ 644 ]), &(acadoWorkspace.QE[ 680 ]) ); +acado_setBlockH11( 8, 17, &(acadoWorkspace.E[ 716 ]), &(acadoWorkspace.QE[ 752 ]) ); +acado_setBlockH11( 8, 17, &(acadoWorkspace.E[ 792 ]), &(acadoWorkspace.QE[ 828 ]) ); + +acado_zeroBlockH11( 8, 18 ); +acado_setBlockH11( 8, 18, &(acadoWorkspace.E[ 716 ]), &(acadoWorkspace.QE[ 756 ]) ); +acado_setBlockH11( 8, 18, &(acadoWorkspace.E[ 792 ]), &(acadoWorkspace.QE[ 832 ]) ); + +acado_zeroBlockH11( 8, 19 ); +acado_setBlockH11( 8, 19, &(acadoWorkspace.E[ 792 ]), &(acadoWorkspace.QE[ 836 ]) ); + +acado_setBlockH11_R1( 9, 9, &(acadoWorkspace.R1[ 9 ]) ); +acado_setBlockH11( 9, 9, &(acadoWorkspace.E[ 216 ]), &(acadoWorkspace.QE[ 216 ]) ); +acado_setBlockH11( 9, 9, &(acadoWorkspace.E[ 256 ]), &(acadoWorkspace.QE[ 256 ]) ); +acado_setBlockH11( 9, 9, &(acadoWorkspace.E[ 300 ]), &(acadoWorkspace.QE[ 300 ]) ); +acado_setBlockH11( 9, 9, &(acadoWorkspace.E[ 348 ]), &(acadoWorkspace.QE[ 348 ]) ); +acado_setBlockH11( 9, 9, &(acadoWorkspace.E[ 400 ]), &(acadoWorkspace.QE[ 400 ]) ); +acado_setBlockH11( 9, 9, &(acadoWorkspace.E[ 456 ]), &(acadoWorkspace.QE[ 456 ]) ); +acado_setBlockH11( 9, 9, &(acadoWorkspace.E[ 516 ]), &(acadoWorkspace.QE[ 516 ]) ); +acado_setBlockH11( 9, 9, &(acadoWorkspace.E[ 580 ]), &(acadoWorkspace.QE[ 580 ]) ); +acado_setBlockH11( 9, 9, &(acadoWorkspace.E[ 648 ]), &(acadoWorkspace.QE[ 648 ]) ); +acado_setBlockH11( 9, 9, &(acadoWorkspace.E[ 720 ]), &(acadoWorkspace.QE[ 720 ]) ); +acado_setBlockH11( 9, 9, &(acadoWorkspace.E[ 796 ]), &(acadoWorkspace.QE[ 796 ]) ); + +acado_zeroBlockH11( 9, 10 ); +acado_setBlockH11( 9, 10, &(acadoWorkspace.E[ 256 ]), &(acadoWorkspace.QE[ 260 ]) ); +acado_setBlockH11( 9, 10, &(acadoWorkspace.E[ 300 ]), &(acadoWorkspace.QE[ 304 ]) ); +acado_setBlockH11( 9, 10, &(acadoWorkspace.E[ 348 ]), &(acadoWorkspace.QE[ 352 ]) ); +acado_setBlockH11( 9, 10, &(acadoWorkspace.E[ 400 ]), &(acadoWorkspace.QE[ 404 ]) ); +acado_setBlockH11( 9, 10, &(acadoWorkspace.E[ 456 ]), &(acadoWorkspace.QE[ 460 ]) ); +acado_setBlockH11( 9, 10, &(acadoWorkspace.E[ 516 ]), &(acadoWorkspace.QE[ 520 ]) ); +acado_setBlockH11( 9, 10, &(acadoWorkspace.E[ 580 ]), &(acadoWorkspace.QE[ 584 ]) ); +acado_setBlockH11( 9, 10, &(acadoWorkspace.E[ 648 ]), &(acadoWorkspace.QE[ 652 ]) ); +acado_setBlockH11( 9, 10, &(acadoWorkspace.E[ 720 ]), &(acadoWorkspace.QE[ 724 ]) ); +acado_setBlockH11( 9, 10, &(acadoWorkspace.E[ 796 ]), &(acadoWorkspace.QE[ 800 ]) ); + +acado_zeroBlockH11( 9, 11 ); +acado_setBlockH11( 9, 11, &(acadoWorkspace.E[ 300 ]), &(acadoWorkspace.QE[ 308 ]) ); +acado_setBlockH11( 9, 11, &(acadoWorkspace.E[ 348 ]), &(acadoWorkspace.QE[ 356 ]) ); +acado_setBlockH11( 9, 11, &(acadoWorkspace.E[ 400 ]), &(acadoWorkspace.QE[ 408 ]) ); +acado_setBlockH11( 9, 11, &(acadoWorkspace.E[ 456 ]), &(acadoWorkspace.QE[ 464 ]) ); +acado_setBlockH11( 9, 11, &(acadoWorkspace.E[ 516 ]), &(acadoWorkspace.QE[ 524 ]) ); +acado_setBlockH11( 9, 11, &(acadoWorkspace.E[ 580 ]), &(acadoWorkspace.QE[ 588 ]) ); +acado_setBlockH11( 9, 11, &(acadoWorkspace.E[ 648 ]), &(acadoWorkspace.QE[ 656 ]) ); +acado_setBlockH11( 9, 11, &(acadoWorkspace.E[ 720 ]), &(acadoWorkspace.QE[ 728 ]) ); +acado_setBlockH11( 9, 11, &(acadoWorkspace.E[ 796 ]), &(acadoWorkspace.QE[ 804 ]) ); + +acado_zeroBlockH11( 9, 12 ); +acado_setBlockH11( 9, 12, &(acadoWorkspace.E[ 348 ]), &(acadoWorkspace.QE[ 360 ]) ); +acado_setBlockH11( 9, 12, &(acadoWorkspace.E[ 400 ]), &(acadoWorkspace.QE[ 412 ]) ); +acado_setBlockH11( 9, 12, &(acadoWorkspace.E[ 456 ]), &(acadoWorkspace.QE[ 468 ]) ); +acado_setBlockH11( 9, 12, &(acadoWorkspace.E[ 516 ]), &(acadoWorkspace.QE[ 528 ]) ); +acado_setBlockH11( 9, 12, &(acadoWorkspace.E[ 580 ]), &(acadoWorkspace.QE[ 592 ]) ); +acado_setBlockH11( 9, 12, &(acadoWorkspace.E[ 648 ]), &(acadoWorkspace.QE[ 660 ]) ); +acado_setBlockH11( 9, 12, &(acadoWorkspace.E[ 720 ]), &(acadoWorkspace.QE[ 732 ]) ); +acado_setBlockH11( 9, 12, &(acadoWorkspace.E[ 796 ]), &(acadoWorkspace.QE[ 808 ]) ); + +acado_zeroBlockH11( 9, 13 ); +acado_setBlockH11( 9, 13, &(acadoWorkspace.E[ 400 ]), &(acadoWorkspace.QE[ 416 ]) ); +acado_setBlockH11( 9, 13, &(acadoWorkspace.E[ 456 ]), &(acadoWorkspace.QE[ 472 ]) ); +acado_setBlockH11( 9, 13, &(acadoWorkspace.E[ 516 ]), &(acadoWorkspace.QE[ 532 ]) ); +acado_setBlockH11( 9, 13, &(acadoWorkspace.E[ 580 ]), &(acadoWorkspace.QE[ 596 ]) ); +acado_setBlockH11( 9, 13, &(acadoWorkspace.E[ 648 ]), &(acadoWorkspace.QE[ 664 ]) ); +acado_setBlockH11( 9, 13, &(acadoWorkspace.E[ 720 ]), &(acadoWorkspace.QE[ 736 ]) ); +acado_setBlockH11( 9, 13, &(acadoWorkspace.E[ 796 ]), &(acadoWorkspace.QE[ 812 ]) ); + +acado_zeroBlockH11( 9, 14 ); +acado_setBlockH11( 9, 14, &(acadoWorkspace.E[ 456 ]), &(acadoWorkspace.QE[ 476 ]) ); +acado_setBlockH11( 9, 14, &(acadoWorkspace.E[ 516 ]), &(acadoWorkspace.QE[ 536 ]) ); +acado_setBlockH11( 9, 14, &(acadoWorkspace.E[ 580 ]), &(acadoWorkspace.QE[ 600 ]) ); +acado_setBlockH11( 9, 14, &(acadoWorkspace.E[ 648 ]), &(acadoWorkspace.QE[ 668 ]) ); +acado_setBlockH11( 9, 14, &(acadoWorkspace.E[ 720 ]), &(acadoWorkspace.QE[ 740 ]) ); +acado_setBlockH11( 9, 14, &(acadoWorkspace.E[ 796 ]), &(acadoWorkspace.QE[ 816 ]) ); + +acado_zeroBlockH11( 9, 15 ); +acado_setBlockH11( 9, 15, &(acadoWorkspace.E[ 516 ]), &(acadoWorkspace.QE[ 540 ]) ); +acado_setBlockH11( 9, 15, &(acadoWorkspace.E[ 580 ]), &(acadoWorkspace.QE[ 604 ]) ); +acado_setBlockH11( 9, 15, &(acadoWorkspace.E[ 648 ]), &(acadoWorkspace.QE[ 672 ]) ); +acado_setBlockH11( 9, 15, &(acadoWorkspace.E[ 720 ]), &(acadoWorkspace.QE[ 744 ]) ); +acado_setBlockH11( 9, 15, &(acadoWorkspace.E[ 796 ]), &(acadoWorkspace.QE[ 820 ]) ); + +acado_zeroBlockH11( 9, 16 ); +acado_setBlockH11( 9, 16, &(acadoWorkspace.E[ 580 ]), &(acadoWorkspace.QE[ 608 ]) ); +acado_setBlockH11( 9, 16, &(acadoWorkspace.E[ 648 ]), &(acadoWorkspace.QE[ 676 ]) ); +acado_setBlockH11( 9, 16, &(acadoWorkspace.E[ 720 ]), &(acadoWorkspace.QE[ 748 ]) ); +acado_setBlockH11( 9, 16, &(acadoWorkspace.E[ 796 ]), &(acadoWorkspace.QE[ 824 ]) ); + +acado_zeroBlockH11( 9, 17 ); +acado_setBlockH11( 9, 17, &(acadoWorkspace.E[ 648 ]), &(acadoWorkspace.QE[ 680 ]) ); +acado_setBlockH11( 9, 17, &(acadoWorkspace.E[ 720 ]), &(acadoWorkspace.QE[ 752 ]) ); +acado_setBlockH11( 9, 17, &(acadoWorkspace.E[ 796 ]), &(acadoWorkspace.QE[ 828 ]) ); + +acado_zeroBlockH11( 9, 18 ); +acado_setBlockH11( 9, 18, &(acadoWorkspace.E[ 720 ]), &(acadoWorkspace.QE[ 756 ]) ); +acado_setBlockH11( 9, 18, &(acadoWorkspace.E[ 796 ]), &(acadoWorkspace.QE[ 832 ]) ); + +acado_zeroBlockH11( 9, 19 ); +acado_setBlockH11( 9, 19, &(acadoWorkspace.E[ 796 ]), &(acadoWorkspace.QE[ 836 ]) ); + +acado_setBlockH11_R1( 10, 10, &(acadoWorkspace.R1[ 10 ]) ); +acado_setBlockH11( 10, 10, &(acadoWorkspace.E[ 260 ]), &(acadoWorkspace.QE[ 260 ]) ); +acado_setBlockH11( 10, 10, &(acadoWorkspace.E[ 304 ]), &(acadoWorkspace.QE[ 304 ]) ); +acado_setBlockH11( 10, 10, &(acadoWorkspace.E[ 352 ]), &(acadoWorkspace.QE[ 352 ]) ); +acado_setBlockH11( 10, 10, &(acadoWorkspace.E[ 404 ]), &(acadoWorkspace.QE[ 404 ]) ); +acado_setBlockH11( 10, 10, &(acadoWorkspace.E[ 460 ]), &(acadoWorkspace.QE[ 460 ]) ); +acado_setBlockH11( 10, 10, &(acadoWorkspace.E[ 520 ]), &(acadoWorkspace.QE[ 520 ]) ); +acado_setBlockH11( 10, 10, &(acadoWorkspace.E[ 584 ]), &(acadoWorkspace.QE[ 584 ]) ); +acado_setBlockH11( 10, 10, &(acadoWorkspace.E[ 652 ]), &(acadoWorkspace.QE[ 652 ]) ); +acado_setBlockH11( 10, 10, &(acadoWorkspace.E[ 724 ]), &(acadoWorkspace.QE[ 724 ]) ); +acado_setBlockH11( 10, 10, &(acadoWorkspace.E[ 800 ]), &(acadoWorkspace.QE[ 800 ]) ); + +acado_zeroBlockH11( 10, 11 ); +acado_setBlockH11( 10, 11, &(acadoWorkspace.E[ 304 ]), &(acadoWorkspace.QE[ 308 ]) ); +acado_setBlockH11( 10, 11, &(acadoWorkspace.E[ 352 ]), &(acadoWorkspace.QE[ 356 ]) ); +acado_setBlockH11( 10, 11, &(acadoWorkspace.E[ 404 ]), &(acadoWorkspace.QE[ 408 ]) ); +acado_setBlockH11( 10, 11, &(acadoWorkspace.E[ 460 ]), &(acadoWorkspace.QE[ 464 ]) ); +acado_setBlockH11( 10, 11, &(acadoWorkspace.E[ 520 ]), &(acadoWorkspace.QE[ 524 ]) ); +acado_setBlockH11( 10, 11, &(acadoWorkspace.E[ 584 ]), &(acadoWorkspace.QE[ 588 ]) ); +acado_setBlockH11( 10, 11, &(acadoWorkspace.E[ 652 ]), &(acadoWorkspace.QE[ 656 ]) ); +acado_setBlockH11( 10, 11, &(acadoWorkspace.E[ 724 ]), &(acadoWorkspace.QE[ 728 ]) ); +acado_setBlockH11( 10, 11, &(acadoWorkspace.E[ 800 ]), &(acadoWorkspace.QE[ 804 ]) ); + +acado_zeroBlockH11( 10, 12 ); +acado_setBlockH11( 10, 12, &(acadoWorkspace.E[ 352 ]), &(acadoWorkspace.QE[ 360 ]) ); +acado_setBlockH11( 10, 12, &(acadoWorkspace.E[ 404 ]), &(acadoWorkspace.QE[ 412 ]) ); +acado_setBlockH11( 10, 12, &(acadoWorkspace.E[ 460 ]), &(acadoWorkspace.QE[ 468 ]) ); +acado_setBlockH11( 10, 12, &(acadoWorkspace.E[ 520 ]), &(acadoWorkspace.QE[ 528 ]) ); +acado_setBlockH11( 10, 12, &(acadoWorkspace.E[ 584 ]), &(acadoWorkspace.QE[ 592 ]) ); +acado_setBlockH11( 10, 12, &(acadoWorkspace.E[ 652 ]), &(acadoWorkspace.QE[ 660 ]) ); +acado_setBlockH11( 10, 12, &(acadoWorkspace.E[ 724 ]), &(acadoWorkspace.QE[ 732 ]) ); +acado_setBlockH11( 10, 12, &(acadoWorkspace.E[ 800 ]), &(acadoWorkspace.QE[ 808 ]) ); + +acado_zeroBlockH11( 10, 13 ); +acado_setBlockH11( 10, 13, &(acadoWorkspace.E[ 404 ]), &(acadoWorkspace.QE[ 416 ]) ); +acado_setBlockH11( 10, 13, &(acadoWorkspace.E[ 460 ]), &(acadoWorkspace.QE[ 472 ]) ); +acado_setBlockH11( 10, 13, &(acadoWorkspace.E[ 520 ]), &(acadoWorkspace.QE[ 532 ]) ); +acado_setBlockH11( 10, 13, &(acadoWorkspace.E[ 584 ]), &(acadoWorkspace.QE[ 596 ]) ); +acado_setBlockH11( 10, 13, &(acadoWorkspace.E[ 652 ]), &(acadoWorkspace.QE[ 664 ]) ); +acado_setBlockH11( 10, 13, &(acadoWorkspace.E[ 724 ]), &(acadoWorkspace.QE[ 736 ]) ); +acado_setBlockH11( 10, 13, &(acadoWorkspace.E[ 800 ]), &(acadoWorkspace.QE[ 812 ]) ); + +acado_zeroBlockH11( 10, 14 ); +acado_setBlockH11( 10, 14, &(acadoWorkspace.E[ 460 ]), &(acadoWorkspace.QE[ 476 ]) ); +acado_setBlockH11( 10, 14, &(acadoWorkspace.E[ 520 ]), &(acadoWorkspace.QE[ 536 ]) ); +acado_setBlockH11( 10, 14, &(acadoWorkspace.E[ 584 ]), &(acadoWorkspace.QE[ 600 ]) ); +acado_setBlockH11( 10, 14, &(acadoWorkspace.E[ 652 ]), &(acadoWorkspace.QE[ 668 ]) ); +acado_setBlockH11( 10, 14, &(acadoWorkspace.E[ 724 ]), &(acadoWorkspace.QE[ 740 ]) ); +acado_setBlockH11( 10, 14, &(acadoWorkspace.E[ 800 ]), &(acadoWorkspace.QE[ 816 ]) ); + +acado_zeroBlockH11( 10, 15 ); +acado_setBlockH11( 10, 15, &(acadoWorkspace.E[ 520 ]), &(acadoWorkspace.QE[ 540 ]) ); +acado_setBlockH11( 10, 15, &(acadoWorkspace.E[ 584 ]), &(acadoWorkspace.QE[ 604 ]) ); +acado_setBlockH11( 10, 15, &(acadoWorkspace.E[ 652 ]), &(acadoWorkspace.QE[ 672 ]) ); +acado_setBlockH11( 10, 15, &(acadoWorkspace.E[ 724 ]), &(acadoWorkspace.QE[ 744 ]) ); +acado_setBlockH11( 10, 15, &(acadoWorkspace.E[ 800 ]), &(acadoWorkspace.QE[ 820 ]) ); + +acado_zeroBlockH11( 10, 16 ); +acado_setBlockH11( 10, 16, &(acadoWorkspace.E[ 584 ]), &(acadoWorkspace.QE[ 608 ]) ); +acado_setBlockH11( 10, 16, &(acadoWorkspace.E[ 652 ]), &(acadoWorkspace.QE[ 676 ]) ); +acado_setBlockH11( 10, 16, &(acadoWorkspace.E[ 724 ]), &(acadoWorkspace.QE[ 748 ]) ); +acado_setBlockH11( 10, 16, &(acadoWorkspace.E[ 800 ]), &(acadoWorkspace.QE[ 824 ]) ); + +acado_zeroBlockH11( 10, 17 ); +acado_setBlockH11( 10, 17, &(acadoWorkspace.E[ 652 ]), &(acadoWorkspace.QE[ 680 ]) ); +acado_setBlockH11( 10, 17, &(acadoWorkspace.E[ 724 ]), &(acadoWorkspace.QE[ 752 ]) ); +acado_setBlockH11( 10, 17, &(acadoWorkspace.E[ 800 ]), &(acadoWorkspace.QE[ 828 ]) ); + +acado_zeroBlockH11( 10, 18 ); +acado_setBlockH11( 10, 18, &(acadoWorkspace.E[ 724 ]), &(acadoWorkspace.QE[ 756 ]) ); +acado_setBlockH11( 10, 18, &(acadoWorkspace.E[ 800 ]), &(acadoWorkspace.QE[ 832 ]) ); + +acado_zeroBlockH11( 10, 19 ); +acado_setBlockH11( 10, 19, &(acadoWorkspace.E[ 800 ]), &(acadoWorkspace.QE[ 836 ]) ); + +acado_setBlockH11_R1( 11, 11, &(acadoWorkspace.R1[ 11 ]) ); +acado_setBlockH11( 11, 11, &(acadoWorkspace.E[ 308 ]), &(acadoWorkspace.QE[ 308 ]) ); +acado_setBlockH11( 11, 11, &(acadoWorkspace.E[ 356 ]), &(acadoWorkspace.QE[ 356 ]) ); +acado_setBlockH11( 11, 11, &(acadoWorkspace.E[ 408 ]), &(acadoWorkspace.QE[ 408 ]) ); +acado_setBlockH11( 11, 11, &(acadoWorkspace.E[ 464 ]), &(acadoWorkspace.QE[ 464 ]) ); +acado_setBlockH11( 11, 11, &(acadoWorkspace.E[ 524 ]), &(acadoWorkspace.QE[ 524 ]) ); +acado_setBlockH11( 11, 11, &(acadoWorkspace.E[ 588 ]), &(acadoWorkspace.QE[ 588 ]) ); +acado_setBlockH11( 11, 11, &(acadoWorkspace.E[ 656 ]), &(acadoWorkspace.QE[ 656 ]) ); +acado_setBlockH11( 11, 11, &(acadoWorkspace.E[ 728 ]), &(acadoWorkspace.QE[ 728 ]) ); +acado_setBlockH11( 11, 11, &(acadoWorkspace.E[ 804 ]), &(acadoWorkspace.QE[ 804 ]) ); + +acado_zeroBlockH11( 11, 12 ); +acado_setBlockH11( 11, 12, &(acadoWorkspace.E[ 356 ]), &(acadoWorkspace.QE[ 360 ]) ); +acado_setBlockH11( 11, 12, &(acadoWorkspace.E[ 408 ]), &(acadoWorkspace.QE[ 412 ]) ); +acado_setBlockH11( 11, 12, &(acadoWorkspace.E[ 464 ]), &(acadoWorkspace.QE[ 468 ]) ); +acado_setBlockH11( 11, 12, &(acadoWorkspace.E[ 524 ]), &(acadoWorkspace.QE[ 528 ]) ); +acado_setBlockH11( 11, 12, &(acadoWorkspace.E[ 588 ]), &(acadoWorkspace.QE[ 592 ]) ); +acado_setBlockH11( 11, 12, &(acadoWorkspace.E[ 656 ]), &(acadoWorkspace.QE[ 660 ]) ); +acado_setBlockH11( 11, 12, &(acadoWorkspace.E[ 728 ]), &(acadoWorkspace.QE[ 732 ]) ); +acado_setBlockH11( 11, 12, &(acadoWorkspace.E[ 804 ]), &(acadoWorkspace.QE[ 808 ]) ); + +acado_zeroBlockH11( 11, 13 ); +acado_setBlockH11( 11, 13, &(acadoWorkspace.E[ 408 ]), &(acadoWorkspace.QE[ 416 ]) ); +acado_setBlockH11( 11, 13, &(acadoWorkspace.E[ 464 ]), &(acadoWorkspace.QE[ 472 ]) ); +acado_setBlockH11( 11, 13, &(acadoWorkspace.E[ 524 ]), &(acadoWorkspace.QE[ 532 ]) ); +acado_setBlockH11( 11, 13, &(acadoWorkspace.E[ 588 ]), &(acadoWorkspace.QE[ 596 ]) ); +acado_setBlockH11( 11, 13, &(acadoWorkspace.E[ 656 ]), &(acadoWorkspace.QE[ 664 ]) ); +acado_setBlockH11( 11, 13, &(acadoWorkspace.E[ 728 ]), &(acadoWorkspace.QE[ 736 ]) ); +acado_setBlockH11( 11, 13, &(acadoWorkspace.E[ 804 ]), &(acadoWorkspace.QE[ 812 ]) ); + +acado_zeroBlockH11( 11, 14 ); +acado_setBlockH11( 11, 14, &(acadoWorkspace.E[ 464 ]), &(acadoWorkspace.QE[ 476 ]) ); +acado_setBlockH11( 11, 14, &(acadoWorkspace.E[ 524 ]), &(acadoWorkspace.QE[ 536 ]) ); +acado_setBlockH11( 11, 14, &(acadoWorkspace.E[ 588 ]), &(acadoWorkspace.QE[ 600 ]) ); +acado_setBlockH11( 11, 14, &(acadoWorkspace.E[ 656 ]), &(acadoWorkspace.QE[ 668 ]) ); +acado_setBlockH11( 11, 14, &(acadoWorkspace.E[ 728 ]), &(acadoWorkspace.QE[ 740 ]) ); +acado_setBlockH11( 11, 14, &(acadoWorkspace.E[ 804 ]), &(acadoWorkspace.QE[ 816 ]) ); + +acado_zeroBlockH11( 11, 15 ); +acado_setBlockH11( 11, 15, &(acadoWorkspace.E[ 524 ]), &(acadoWorkspace.QE[ 540 ]) ); +acado_setBlockH11( 11, 15, &(acadoWorkspace.E[ 588 ]), &(acadoWorkspace.QE[ 604 ]) ); +acado_setBlockH11( 11, 15, &(acadoWorkspace.E[ 656 ]), &(acadoWorkspace.QE[ 672 ]) ); +acado_setBlockH11( 11, 15, &(acadoWorkspace.E[ 728 ]), &(acadoWorkspace.QE[ 744 ]) ); +acado_setBlockH11( 11, 15, &(acadoWorkspace.E[ 804 ]), &(acadoWorkspace.QE[ 820 ]) ); + +acado_zeroBlockH11( 11, 16 ); +acado_setBlockH11( 11, 16, &(acadoWorkspace.E[ 588 ]), &(acadoWorkspace.QE[ 608 ]) ); +acado_setBlockH11( 11, 16, &(acadoWorkspace.E[ 656 ]), &(acadoWorkspace.QE[ 676 ]) ); +acado_setBlockH11( 11, 16, &(acadoWorkspace.E[ 728 ]), &(acadoWorkspace.QE[ 748 ]) ); +acado_setBlockH11( 11, 16, &(acadoWorkspace.E[ 804 ]), &(acadoWorkspace.QE[ 824 ]) ); + +acado_zeroBlockH11( 11, 17 ); +acado_setBlockH11( 11, 17, &(acadoWorkspace.E[ 656 ]), &(acadoWorkspace.QE[ 680 ]) ); +acado_setBlockH11( 11, 17, &(acadoWorkspace.E[ 728 ]), &(acadoWorkspace.QE[ 752 ]) ); +acado_setBlockH11( 11, 17, &(acadoWorkspace.E[ 804 ]), &(acadoWorkspace.QE[ 828 ]) ); + +acado_zeroBlockH11( 11, 18 ); +acado_setBlockH11( 11, 18, &(acadoWorkspace.E[ 728 ]), &(acadoWorkspace.QE[ 756 ]) ); +acado_setBlockH11( 11, 18, &(acadoWorkspace.E[ 804 ]), &(acadoWorkspace.QE[ 832 ]) ); + +acado_zeroBlockH11( 11, 19 ); +acado_setBlockH11( 11, 19, &(acadoWorkspace.E[ 804 ]), &(acadoWorkspace.QE[ 836 ]) ); + +acado_setBlockH11_R1( 12, 12, &(acadoWorkspace.R1[ 12 ]) ); +acado_setBlockH11( 12, 12, &(acadoWorkspace.E[ 360 ]), &(acadoWorkspace.QE[ 360 ]) ); +acado_setBlockH11( 12, 12, &(acadoWorkspace.E[ 412 ]), &(acadoWorkspace.QE[ 412 ]) ); +acado_setBlockH11( 12, 12, &(acadoWorkspace.E[ 468 ]), &(acadoWorkspace.QE[ 468 ]) ); +acado_setBlockH11( 12, 12, &(acadoWorkspace.E[ 528 ]), &(acadoWorkspace.QE[ 528 ]) ); +acado_setBlockH11( 12, 12, &(acadoWorkspace.E[ 592 ]), &(acadoWorkspace.QE[ 592 ]) ); +acado_setBlockH11( 12, 12, &(acadoWorkspace.E[ 660 ]), &(acadoWorkspace.QE[ 660 ]) ); +acado_setBlockH11( 12, 12, &(acadoWorkspace.E[ 732 ]), &(acadoWorkspace.QE[ 732 ]) ); +acado_setBlockH11( 12, 12, &(acadoWorkspace.E[ 808 ]), &(acadoWorkspace.QE[ 808 ]) ); + +acado_zeroBlockH11( 12, 13 ); +acado_setBlockH11( 12, 13, &(acadoWorkspace.E[ 412 ]), &(acadoWorkspace.QE[ 416 ]) ); +acado_setBlockH11( 12, 13, &(acadoWorkspace.E[ 468 ]), &(acadoWorkspace.QE[ 472 ]) ); +acado_setBlockH11( 12, 13, &(acadoWorkspace.E[ 528 ]), &(acadoWorkspace.QE[ 532 ]) ); +acado_setBlockH11( 12, 13, &(acadoWorkspace.E[ 592 ]), &(acadoWorkspace.QE[ 596 ]) ); +acado_setBlockH11( 12, 13, &(acadoWorkspace.E[ 660 ]), &(acadoWorkspace.QE[ 664 ]) ); +acado_setBlockH11( 12, 13, &(acadoWorkspace.E[ 732 ]), &(acadoWorkspace.QE[ 736 ]) ); +acado_setBlockH11( 12, 13, &(acadoWorkspace.E[ 808 ]), &(acadoWorkspace.QE[ 812 ]) ); + +acado_zeroBlockH11( 12, 14 ); +acado_setBlockH11( 12, 14, &(acadoWorkspace.E[ 468 ]), &(acadoWorkspace.QE[ 476 ]) ); +acado_setBlockH11( 12, 14, &(acadoWorkspace.E[ 528 ]), &(acadoWorkspace.QE[ 536 ]) ); +acado_setBlockH11( 12, 14, &(acadoWorkspace.E[ 592 ]), &(acadoWorkspace.QE[ 600 ]) ); +acado_setBlockH11( 12, 14, &(acadoWorkspace.E[ 660 ]), &(acadoWorkspace.QE[ 668 ]) ); +acado_setBlockH11( 12, 14, &(acadoWorkspace.E[ 732 ]), &(acadoWorkspace.QE[ 740 ]) ); +acado_setBlockH11( 12, 14, &(acadoWorkspace.E[ 808 ]), &(acadoWorkspace.QE[ 816 ]) ); + +acado_zeroBlockH11( 12, 15 ); +acado_setBlockH11( 12, 15, &(acadoWorkspace.E[ 528 ]), &(acadoWorkspace.QE[ 540 ]) ); +acado_setBlockH11( 12, 15, &(acadoWorkspace.E[ 592 ]), &(acadoWorkspace.QE[ 604 ]) ); +acado_setBlockH11( 12, 15, &(acadoWorkspace.E[ 660 ]), &(acadoWorkspace.QE[ 672 ]) ); +acado_setBlockH11( 12, 15, &(acadoWorkspace.E[ 732 ]), &(acadoWorkspace.QE[ 744 ]) ); +acado_setBlockH11( 12, 15, &(acadoWorkspace.E[ 808 ]), &(acadoWorkspace.QE[ 820 ]) ); + +acado_zeroBlockH11( 12, 16 ); +acado_setBlockH11( 12, 16, &(acadoWorkspace.E[ 592 ]), &(acadoWorkspace.QE[ 608 ]) ); +acado_setBlockH11( 12, 16, &(acadoWorkspace.E[ 660 ]), &(acadoWorkspace.QE[ 676 ]) ); +acado_setBlockH11( 12, 16, &(acadoWorkspace.E[ 732 ]), &(acadoWorkspace.QE[ 748 ]) ); +acado_setBlockH11( 12, 16, &(acadoWorkspace.E[ 808 ]), &(acadoWorkspace.QE[ 824 ]) ); + +acado_zeroBlockH11( 12, 17 ); +acado_setBlockH11( 12, 17, &(acadoWorkspace.E[ 660 ]), &(acadoWorkspace.QE[ 680 ]) ); +acado_setBlockH11( 12, 17, &(acadoWorkspace.E[ 732 ]), &(acadoWorkspace.QE[ 752 ]) ); +acado_setBlockH11( 12, 17, &(acadoWorkspace.E[ 808 ]), &(acadoWorkspace.QE[ 828 ]) ); + +acado_zeroBlockH11( 12, 18 ); +acado_setBlockH11( 12, 18, &(acadoWorkspace.E[ 732 ]), &(acadoWorkspace.QE[ 756 ]) ); +acado_setBlockH11( 12, 18, &(acadoWorkspace.E[ 808 ]), &(acadoWorkspace.QE[ 832 ]) ); + +acado_zeroBlockH11( 12, 19 ); +acado_setBlockH11( 12, 19, &(acadoWorkspace.E[ 808 ]), &(acadoWorkspace.QE[ 836 ]) ); + +acado_setBlockH11_R1( 13, 13, &(acadoWorkspace.R1[ 13 ]) ); +acado_setBlockH11( 13, 13, &(acadoWorkspace.E[ 416 ]), &(acadoWorkspace.QE[ 416 ]) ); +acado_setBlockH11( 13, 13, &(acadoWorkspace.E[ 472 ]), &(acadoWorkspace.QE[ 472 ]) ); +acado_setBlockH11( 13, 13, &(acadoWorkspace.E[ 532 ]), &(acadoWorkspace.QE[ 532 ]) ); +acado_setBlockH11( 13, 13, &(acadoWorkspace.E[ 596 ]), &(acadoWorkspace.QE[ 596 ]) ); +acado_setBlockH11( 13, 13, &(acadoWorkspace.E[ 664 ]), &(acadoWorkspace.QE[ 664 ]) ); +acado_setBlockH11( 13, 13, &(acadoWorkspace.E[ 736 ]), &(acadoWorkspace.QE[ 736 ]) ); +acado_setBlockH11( 13, 13, &(acadoWorkspace.E[ 812 ]), &(acadoWorkspace.QE[ 812 ]) ); + +acado_zeroBlockH11( 13, 14 ); +acado_setBlockH11( 13, 14, &(acadoWorkspace.E[ 472 ]), &(acadoWorkspace.QE[ 476 ]) ); +acado_setBlockH11( 13, 14, &(acadoWorkspace.E[ 532 ]), &(acadoWorkspace.QE[ 536 ]) ); +acado_setBlockH11( 13, 14, &(acadoWorkspace.E[ 596 ]), &(acadoWorkspace.QE[ 600 ]) ); +acado_setBlockH11( 13, 14, &(acadoWorkspace.E[ 664 ]), &(acadoWorkspace.QE[ 668 ]) ); +acado_setBlockH11( 13, 14, &(acadoWorkspace.E[ 736 ]), &(acadoWorkspace.QE[ 740 ]) ); +acado_setBlockH11( 13, 14, &(acadoWorkspace.E[ 812 ]), &(acadoWorkspace.QE[ 816 ]) ); + +acado_zeroBlockH11( 13, 15 ); +acado_setBlockH11( 13, 15, &(acadoWorkspace.E[ 532 ]), &(acadoWorkspace.QE[ 540 ]) ); +acado_setBlockH11( 13, 15, &(acadoWorkspace.E[ 596 ]), &(acadoWorkspace.QE[ 604 ]) ); +acado_setBlockH11( 13, 15, &(acadoWorkspace.E[ 664 ]), &(acadoWorkspace.QE[ 672 ]) ); +acado_setBlockH11( 13, 15, &(acadoWorkspace.E[ 736 ]), &(acadoWorkspace.QE[ 744 ]) ); +acado_setBlockH11( 13, 15, &(acadoWorkspace.E[ 812 ]), &(acadoWorkspace.QE[ 820 ]) ); + +acado_zeroBlockH11( 13, 16 ); +acado_setBlockH11( 13, 16, &(acadoWorkspace.E[ 596 ]), &(acadoWorkspace.QE[ 608 ]) ); +acado_setBlockH11( 13, 16, &(acadoWorkspace.E[ 664 ]), &(acadoWorkspace.QE[ 676 ]) ); +acado_setBlockH11( 13, 16, &(acadoWorkspace.E[ 736 ]), &(acadoWorkspace.QE[ 748 ]) ); +acado_setBlockH11( 13, 16, &(acadoWorkspace.E[ 812 ]), &(acadoWorkspace.QE[ 824 ]) ); + +acado_zeroBlockH11( 13, 17 ); +acado_setBlockH11( 13, 17, &(acadoWorkspace.E[ 664 ]), &(acadoWorkspace.QE[ 680 ]) ); +acado_setBlockH11( 13, 17, &(acadoWorkspace.E[ 736 ]), &(acadoWorkspace.QE[ 752 ]) ); +acado_setBlockH11( 13, 17, &(acadoWorkspace.E[ 812 ]), &(acadoWorkspace.QE[ 828 ]) ); + +acado_zeroBlockH11( 13, 18 ); +acado_setBlockH11( 13, 18, &(acadoWorkspace.E[ 736 ]), &(acadoWorkspace.QE[ 756 ]) ); +acado_setBlockH11( 13, 18, &(acadoWorkspace.E[ 812 ]), &(acadoWorkspace.QE[ 832 ]) ); + +acado_zeroBlockH11( 13, 19 ); +acado_setBlockH11( 13, 19, &(acadoWorkspace.E[ 812 ]), &(acadoWorkspace.QE[ 836 ]) ); + +acado_setBlockH11_R1( 14, 14, &(acadoWorkspace.R1[ 14 ]) ); +acado_setBlockH11( 14, 14, &(acadoWorkspace.E[ 476 ]), &(acadoWorkspace.QE[ 476 ]) ); +acado_setBlockH11( 14, 14, &(acadoWorkspace.E[ 536 ]), &(acadoWorkspace.QE[ 536 ]) ); +acado_setBlockH11( 14, 14, &(acadoWorkspace.E[ 600 ]), &(acadoWorkspace.QE[ 600 ]) ); +acado_setBlockH11( 14, 14, &(acadoWorkspace.E[ 668 ]), &(acadoWorkspace.QE[ 668 ]) ); +acado_setBlockH11( 14, 14, &(acadoWorkspace.E[ 740 ]), &(acadoWorkspace.QE[ 740 ]) ); +acado_setBlockH11( 14, 14, &(acadoWorkspace.E[ 816 ]), &(acadoWorkspace.QE[ 816 ]) ); + +acado_zeroBlockH11( 14, 15 ); +acado_setBlockH11( 14, 15, &(acadoWorkspace.E[ 536 ]), &(acadoWorkspace.QE[ 540 ]) ); +acado_setBlockH11( 14, 15, &(acadoWorkspace.E[ 600 ]), &(acadoWorkspace.QE[ 604 ]) ); +acado_setBlockH11( 14, 15, &(acadoWorkspace.E[ 668 ]), &(acadoWorkspace.QE[ 672 ]) ); +acado_setBlockH11( 14, 15, &(acadoWorkspace.E[ 740 ]), &(acadoWorkspace.QE[ 744 ]) ); +acado_setBlockH11( 14, 15, &(acadoWorkspace.E[ 816 ]), &(acadoWorkspace.QE[ 820 ]) ); + +acado_zeroBlockH11( 14, 16 ); +acado_setBlockH11( 14, 16, &(acadoWorkspace.E[ 600 ]), &(acadoWorkspace.QE[ 608 ]) ); +acado_setBlockH11( 14, 16, &(acadoWorkspace.E[ 668 ]), &(acadoWorkspace.QE[ 676 ]) ); +acado_setBlockH11( 14, 16, &(acadoWorkspace.E[ 740 ]), &(acadoWorkspace.QE[ 748 ]) ); +acado_setBlockH11( 14, 16, &(acadoWorkspace.E[ 816 ]), &(acadoWorkspace.QE[ 824 ]) ); + +acado_zeroBlockH11( 14, 17 ); +acado_setBlockH11( 14, 17, &(acadoWorkspace.E[ 668 ]), &(acadoWorkspace.QE[ 680 ]) ); +acado_setBlockH11( 14, 17, &(acadoWorkspace.E[ 740 ]), &(acadoWorkspace.QE[ 752 ]) ); +acado_setBlockH11( 14, 17, &(acadoWorkspace.E[ 816 ]), &(acadoWorkspace.QE[ 828 ]) ); + +acado_zeroBlockH11( 14, 18 ); +acado_setBlockH11( 14, 18, &(acadoWorkspace.E[ 740 ]), &(acadoWorkspace.QE[ 756 ]) ); +acado_setBlockH11( 14, 18, &(acadoWorkspace.E[ 816 ]), &(acadoWorkspace.QE[ 832 ]) ); + +acado_zeroBlockH11( 14, 19 ); +acado_setBlockH11( 14, 19, &(acadoWorkspace.E[ 816 ]), &(acadoWorkspace.QE[ 836 ]) ); + +acado_setBlockH11_R1( 15, 15, &(acadoWorkspace.R1[ 15 ]) ); +acado_setBlockH11( 15, 15, &(acadoWorkspace.E[ 540 ]), &(acadoWorkspace.QE[ 540 ]) ); +acado_setBlockH11( 15, 15, &(acadoWorkspace.E[ 604 ]), &(acadoWorkspace.QE[ 604 ]) ); +acado_setBlockH11( 15, 15, &(acadoWorkspace.E[ 672 ]), &(acadoWorkspace.QE[ 672 ]) ); +acado_setBlockH11( 15, 15, &(acadoWorkspace.E[ 744 ]), &(acadoWorkspace.QE[ 744 ]) ); +acado_setBlockH11( 15, 15, &(acadoWorkspace.E[ 820 ]), &(acadoWorkspace.QE[ 820 ]) ); + +acado_zeroBlockH11( 15, 16 ); +acado_setBlockH11( 15, 16, &(acadoWorkspace.E[ 604 ]), &(acadoWorkspace.QE[ 608 ]) ); +acado_setBlockH11( 15, 16, &(acadoWorkspace.E[ 672 ]), &(acadoWorkspace.QE[ 676 ]) ); +acado_setBlockH11( 15, 16, &(acadoWorkspace.E[ 744 ]), &(acadoWorkspace.QE[ 748 ]) ); +acado_setBlockH11( 15, 16, &(acadoWorkspace.E[ 820 ]), &(acadoWorkspace.QE[ 824 ]) ); + +acado_zeroBlockH11( 15, 17 ); +acado_setBlockH11( 15, 17, &(acadoWorkspace.E[ 672 ]), &(acadoWorkspace.QE[ 680 ]) ); +acado_setBlockH11( 15, 17, &(acadoWorkspace.E[ 744 ]), &(acadoWorkspace.QE[ 752 ]) ); +acado_setBlockH11( 15, 17, &(acadoWorkspace.E[ 820 ]), &(acadoWorkspace.QE[ 828 ]) ); + +acado_zeroBlockH11( 15, 18 ); +acado_setBlockH11( 15, 18, &(acadoWorkspace.E[ 744 ]), &(acadoWorkspace.QE[ 756 ]) ); +acado_setBlockH11( 15, 18, &(acadoWorkspace.E[ 820 ]), &(acadoWorkspace.QE[ 832 ]) ); + +acado_zeroBlockH11( 15, 19 ); +acado_setBlockH11( 15, 19, &(acadoWorkspace.E[ 820 ]), &(acadoWorkspace.QE[ 836 ]) ); + +acado_setBlockH11_R1( 16, 16, &(acadoWorkspace.R1[ 16 ]) ); +acado_setBlockH11( 16, 16, &(acadoWorkspace.E[ 608 ]), &(acadoWorkspace.QE[ 608 ]) ); +acado_setBlockH11( 16, 16, &(acadoWorkspace.E[ 676 ]), &(acadoWorkspace.QE[ 676 ]) ); +acado_setBlockH11( 16, 16, &(acadoWorkspace.E[ 748 ]), &(acadoWorkspace.QE[ 748 ]) ); +acado_setBlockH11( 16, 16, &(acadoWorkspace.E[ 824 ]), &(acadoWorkspace.QE[ 824 ]) ); + +acado_zeroBlockH11( 16, 17 ); +acado_setBlockH11( 16, 17, &(acadoWorkspace.E[ 676 ]), &(acadoWorkspace.QE[ 680 ]) ); +acado_setBlockH11( 16, 17, &(acadoWorkspace.E[ 748 ]), &(acadoWorkspace.QE[ 752 ]) ); +acado_setBlockH11( 16, 17, &(acadoWorkspace.E[ 824 ]), &(acadoWorkspace.QE[ 828 ]) ); + +acado_zeroBlockH11( 16, 18 ); +acado_setBlockH11( 16, 18, &(acadoWorkspace.E[ 748 ]), &(acadoWorkspace.QE[ 756 ]) ); +acado_setBlockH11( 16, 18, &(acadoWorkspace.E[ 824 ]), &(acadoWorkspace.QE[ 832 ]) ); + +acado_zeroBlockH11( 16, 19 ); +acado_setBlockH11( 16, 19, &(acadoWorkspace.E[ 824 ]), &(acadoWorkspace.QE[ 836 ]) ); + +acado_setBlockH11_R1( 17, 17, &(acadoWorkspace.R1[ 17 ]) ); +acado_setBlockH11( 17, 17, &(acadoWorkspace.E[ 680 ]), &(acadoWorkspace.QE[ 680 ]) ); +acado_setBlockH11( 17, 17, &(acadoWorkspace.E[ 752 ]), &(acadoWorkspace.QE[ 752 ]) ); +acado_setBlockH11( 17, 17, &(acadoWorkspace.E[ 828 ]), &(acadoWorkspace.QE[ 828 ]) ); + +acado_zeroBlockH11( 17, 18 ); +acado_setBlockH11( 17, 18, &(acadoWorkspace.E[ 752 ]), &(acadoWorkspace.QE[ 756 ]) ); +acado_setBlockH11( 17, 18, &(acadoWorkspace.E[ 828 ]), &(acadoWorkspace.QE[ 832 ]) ); + +acado_zeroBlockH11( 17, 19 ); +acado_setBlockH11( 17, 19, &(acadoWorkspace.E[ 828 ]), &(acadoWorkspace.QE[ 836 ]) ); + +acado_setBlockH11_R1( 18, 18, &(acadoWorkspace.R1[ 18 ]) ); +acado_setBlockH11( 18, 18, &(acadoWorkspace.E[ 756 ]), &(acadoWorkspace.QE[ 756 ]) ); +acado_setBlockH11( 18, 18, &(acadoWorkspace.E[ 832 ]), &(acadoWorkspace.QE[ 832 ]) ); + +acado_zeroBlockH11( 18, 19 ); +acado_setBlockH11( 18, 19, &(acadoWorkspace.E[ 832 ]), &(acadoWorkspace.QE[ 836 ]) ); + +acado_setBlockH11_R1( 19, 19, &(acadoWorkspace.R1[ 19 ]) ); +acado_setBlockH11( 19, 19, &(acadoWorkspace.E[ 836 ]), &(acadoWorkspace.QE[ 836 ]) ); + + +acado_copyHTH( 1, 0 ); +acado_copyHTH( 2, 0 ); +acado_copyHTH( 2, 1 ); +acado_copyHTH( 3, 0 ); +acado_copyHTH( 3, 1 ); +acado_copyHTH( 3, 2 ); +acado_copyHTH( 4, 0 ); +acado_copyHTH( 4, 1 ); +acado_copyHTH( 4, 2 ); +acado_copyHTH( 4, 3 ); +acado_copyHTH( 5, 0 ); +acado_copyHTH( 5, 1 ); +acado_copyHTH( 5, 2 ); +acado_copyHTH( 5, 3 ); +acado_copyHTH( 5, 4 ); +acado_copyHTH( 6, 0 ); +acado_copyHTH( 6, 1 ); +acado_copyHTH( 6, 2 ); +acado_copyHTH( 6, 3 ); +acado_copyHTH( 6, 4 ); +acado_copyHTH( 6, 5 ); +acado_copyHTH( 7, 0 ); +acado_copyHTH( 7, 1 ); +acado_copyHTH( 7, 2 ); +acado_copyHTH( 7, 3 ); +acado_copyHTH( 7, 4 ); +acado_copyHTH( 7, 5 ); +acado_copyHTH( 7, 6 ); +acado_copyHTH( 8, 0 ); +acado_copyHTH( 8, 1 ); +acado_copyHTH( 8, 2 ); +acado_copyHTH( 8, 3 ); +acado_copyHTH( 8, 4 ); +acado_copyHTH( 8, 5 ); +acado_copyHTH( 8, 6 ); +acado_copyHTH( 8, 7 ); +acado_copyHTH( 9, 0 ); +acado_copyHTH( 9, 1 ); +acado_copyHTH( 9, 2 ); +acado_copyHTH( 9, 3 ); +acado_copyHTH( 9, 4 ); +acado_copyHTH( 9, 5 ); +acado_copyHTH( 9, 6 ); +acado_copyHTH( 9, 7 ); +acado_copyHTH( 9, 8 ); +acado_copyHTH( 10, 0 ); +acado_copyHTH( 10, 1 ); +acado_copyHTH( 10, 2 ); +acado_copyHTH( 10, 3 ); +acado_copyHTH( 10, 4 ); +acado_copyHTH( 10, 5 ); +acado_copyHTH( 10, 6 ); +acado_copyHTH( 10, 7 ); +acado_copyHTH( 10, 8 ); +acado_copyHTH( 10, 9 ); +acado_copyHTH( 11, 0 ); +acado_copyHTH( 11, 1 ); +acado_copyHTH( 11, 2 ); +acado_copyHTH( 11, 3 ); +acado_copyHTH( 11, 4 ); +acado_copyHTH( 11, 5 ); +acado_copyHTH( 11, 6 ); +acado_copyHTH( 11, 7 ); +acado_copyHTH( 11, 8 ); +acado_copyHTH( 11, 9 ); +acado_copyHTH( 11, 10 ); +acado_copyHTH( 12, 0 ); +acado_copyHTH( 12, 1 ); +acado_copyHTH( 12, 2 ); +acado_copyHTH( 12, 3 ); +acado_copyHTH( 12, 4 ); +acado_copyHTH( 12, 5 ); +acado_copyHTH( 12, 6 ); +acado_copyHTH( 12, 7 ); +acado_copyHTH( 12, 8 ); +acado_copyHTH( 12, 9 ); +acado_copyHTH( 12, 10 ); +acado_copyHTH( 12, 11 ); +acado_copyHTH( 13, 0 ); +acado_copyHTH( 13, 1 ); +acado_copyHTH( 13, 2 ); +acado_copyHTH( 13, 3 ); +acado_copyHTH( 13, 4 ); +acado_copyHTH( 13, 5 ); +acado_copyHTH( 13, 6 ); +acado_copyHTH( 13, 7 ); +acado_copyHTH( 13, 8 ); +acado_copyHTH( 13, 9 ); +acado_copyHTH( 13, 10 ); +acado_copyHTH( 13, 11 ); +acado_copyHTH( 13, 12 ); +acado_copyHTH( 14, 0 ); +acado_copyHTH( 14, 1 ); +acado_copyHTH( 14, 2 ); +acado_copyHTH( 14, 3 ); +acado_copyHTH( 14, 4 ); +acado_copyHTH( 14, 5 ); +acado_copyHTH( 14, 6 ); +acado_copyHTH( 14, 7 ); +acado_copyHTH( 14, 8 ); +acado_copyHTH( 14, 9 ); +acado_copyHTH( 14, 10 ); +acado_copyHTH( 14, 11 ); +acado_copyHTH( 14, 12 ); +acado_copyHTH( 14, 13 ); +acado_copyHTH( 15, 0 ); +acado_copyHTH( 15, 1 ); +acado_copyHTH( 15, 2 ); +acado_copyHTH( 15, 3 ); +acado_copyHTH( 15, 4 ); +acado_copyHTH( 15, 5 ); +acado_copyHTH( 15, 6 ); +acado_copyHTH( 15, 7 ); +acado_copyHTH( 15, 8 ); +acado_copyHTH( 15, 9 ); +acado_copyHTH( 15, 10 ); +acado_copyHTH( 15, 11 ); +acado_copyHTH( 15, 12 ); +acado_copyHTH( 15, 13 ); +acado_copyHTH( 15, 14 ); +acado_copyHTH( 16, 0 ); +acado_copyHTH( 16, 1 ); +acado_copyHTH( 16, 2 ); +acado_copyHTH( 16, 3 ); +acado_copyHTH( 16, 4 ); +acado_copyHTH( 16, 5 ); +acado_copyHTH( 16, 6 ); +acado_copyHTH( 16, 7 ); +acado_copyHTH( 16, 8 ); +acado_copyHTH( 16, 9 ); +acado_copyHTH( 16, 10 ); +acado_copyHTH( 16, 11 ); +acado_copyHTH( 16, 12 ); +acado_copyHTH( 16, 13 ); +acado_copyHTH( 16, 14 ); +acado_copyHTH( 16, 15 ); +acado_copyHTH( 17, 0 ); +acado_copyHTH( 17, 1 ); +acado_copyHTH( 17, 2 ); +acado_copyHTH( 17, 3 ); +acado_copyHTH( 17, 4 ); +acado_copyHTH( 17, 5 ); +acado_copyHTH( 17, 6 ); +acado_copyHTH( 17, 7 ); +acado_copyHTH( 17, 8 ); +acado_copyHTH( 17, 9 ); +acado_copyHTH( 17, 10 ); +acado_copyHTH( 17, 11 ); +acado_copyHTH( 17, 12 ); +acado_copyHTH( 17, 13 ); +acado_copyHTH( 17, 14 ); +acado_copyHTH( 17, 15 ); +acado_copyHTH( 17, 16 ); +acado_copyHTH( 18, 0 ); +acado_copyHTH( 18, 1 ); +acado_copyHTH( 18, 2 ); +acado_copyHTH( 18, 3 ); +acado_copyHTH( 18, 4 ); +acado_copyHTH( 18, 5 ); +acado_copyHTH( 18, 6 ); +acado_copyHTH( 18, 7 ); +acado_copyHTH( 18, 8 ); +acado_copyHTH( 18, 9 ); +acado_copyHTH( 18, 10 ); +acado_copyHTH( 18, 11 ); +acado_copyHTH( 18, 12 ); +acado_copyHTH( 18, 13 ); +acado_copyHTH( 18, 14 ); +acado_copyHTH( 18, 15 ); +acado_copyHTH( 18, 16 ); +acado_copyHTH( 18, 17 ); +acado_copyHTH( 19, 0 ); +acado_copyHTH( 19, 1 ); +acado_copyHTH( 19, 2 ); +acado_copyHTH( 19, 3 ); +acado_copyHTH( 19, 4 ); +acado_copyHTH( 19, 5 ); +acado_copyHTH( 19, 6 ); +acado_copyHTH( 19, 7 ); +acado_copyHTH( 19, 8 ); +acado_copyHTH( 19, 9 ); +acado_copyHTH( 19, 10 ); +acado_copyHTH( 19, 11 ); +acado_copyHTH( 19, 12 ); +acado_copyHTH( 19, 13 ); +acado_copyHTH( 19, 14 ); +acado_copyHTH( 19, 15 ); +acado_copyHTH( 19, 16 ); +acado_copyHTH( 19, 17 ); +acado_copyHTH( 19, 18 ); + +acadoWorkspace.H[96] = acadoWorkspace.H10[0]; +acadoWorkspace.H[97] = acadoWorkspace.H10[1]; +acadoWorkspace.H[98] = acadoWorkspace.H10[2]; +acadoWorkspace.H[99] = acadoWorkspace.H10[3]; +acadoWorkspace.H[120] = acadoWorkspace.H10[4]; +acadoWorkspace.H[121] = acadoWorkspace.H10[5]; +acadoWorkspace.H[122] = acadoWorkspace.H10[6]; +acadoWorkspace.H[123] = acadoWorkspace.H10[7]; +acadoWorkspace.H[144] = acadoWorkspace.H10[8]; +acadoWorkspace.H[145] = acadoWorkspace.H10[9]; +acadoWorkspace.H[146] = acadoWorkspace.H10[10]; +acadoWorkspace.H[147] = acadoWorkspace.H10[11]; +acadoWorkspace.H[168] = acadoWorkspace.H10[12]; +acadoWorkspace.H[169] = acadoWorkspace.H10[13]; +acadoWorkspace.H[170] = acadoWorkspace.H10[14]; +acadoWorkspace.H[171] = acadoWorkspace.H10[15]; +acadoWorkspace.H[192] = acadoWorkspace.H10[16]; +acadoWorkspace.H[193] = acadoWorkspace.H10[17]; +acadoWorkspace.H[194] = acadoWorkspace.H10[18]; +acadoWorkspace.H[195] = acadoWorkspace.H10[19]; +acadoWorkspace.H[216] = acadoWorkspace.H10[20]; +acadoWorkspace.H[217] = acadoWorkspace.H10[21]; +acadoWorkspace.H[218] = acadoWorkspace.H10[22]; +acadoWorkspace.H[219] = acadoWorkspace.H10[23]; +acadoWorkspace.H[240] = acadoWorkspace.H10[24]; +acadoWorkspace.H[241] = acadoWorkspace.H10[25]; +acadoWorkspace.H[242] = acadoWorkspace.H10[26]; +acadoWorkspace.H[243] = acadoWorkspace.H10[27]; +acadoWorkspace.H[264] = acadoWorkspace.H10[28]; +acadoWorkspace.H[265] = acadoWorkspace.H10[29]; +acadoWorkspace.H[266] = acadoWorkspace.H10[30]; +acadoWorkspace.H[267] = acadoWorkspace.H10[31]; +acadoWorkspace.H[288] = acadoWorkspace.H10[32]; +acadoWorkspace.H[289] = acadoWorkspace.H10[33]; +acadoWorkspace.H[290] = acadoWorkspace.H10[34]; +acadoWorkspace.H[291] = acadoWorkspace.H10[35]; +acadoWorkspace.H[312] = acadoWorkspace.H10[36]; +acadoWorkspace.H[313] = acadoWorkspace.H10[37]; +acadoWorkspace.H[314] = acadoWorkspace.H10[38]; +acadoWorkspace.H[315] = acadoWorkspace.H10[39]; +acadoWorkspace.H[336] = acadoWorkspace.H10[40]; +acadoWorkspace.H[337] = acadoWorkspace.H10[41]; +acadoWorkspace.H[338] = acadoWorkspace.H10[42]; +acadoWorkspace.H[339] = acadoWorkspace.H10[43]; +acadoWorkspace.H[360] = acadoWorkspace.H10[44]; +acadoWorkspace.H[361] = acadoWorkspace.H10[45]; +acadoWorkspace.H[362] = acadoWorkspace.H10[46]; +acadoWorkspace.H[363] = acadoWorkspace.H10[47]; +acadoWorkspace.H[384] = acadoWorkspace.H10[48]; +acadoWorkspace.H[385] = acadoWorkspace.H10[49]; +acadoWorkspace.H[386] = acadoWorkspace.H10[50]; +acadoWorkspace.H[387] = acadoWorkspace.H10[51]; +acadoWorkspace.H[408] = acadoWorkspace.H10[52]; +acadoWorkspace.H[409] = acadoWorkspace.H10[53]; +acadoWorkspace.H[410] = acadoWorkspace.H10[54]; +acadoWorkspace.H[411] = acadoWorkspace.H10[55]; +acadoWorkspace.H[432] = acadoWorkspace.H10[56]; +acadoWorkspace.H[433] = acadoWorkspace.H10[57]; +acadoWorkspace.H[434] = acadoWorkspace.H10[58]; +acadoWorkspace.H[435] = acadoWorkspace.H10[59]; +acadoWorkspace.H[456] = acadoWorkspace.H10[60]; +acadoWorkspace.H[457] = acadoWorkspace.H10[61]; +acadoWorkspace.H[458] = acadoWorkspace.H10[62]; +acadoWorkspace.H[459] = acadoWorkspace.H10[63]; +acadoWorkspace.H[480] = acadoWorkspace.H10[64]; +acadoWorkspace.H[481] = acadoWorkspace.H10[65]; +acadoWorkspace.H[482] = acadoWorkspace.H10[66]; +acadoWorkspace.H[483] = acadoWorkspace.H10[67]; +acadoWorkspace.H[504] = acadoWorkspace.H10[68]; +acadoWorkspace.H[505] = acadoWorkspace.H10[69]; +acadoWorkspace.H[506] = acadoWorkspace.H10[70]; +acadoWorkspace.H[507] = acadoWorkspace.H10[71]; +acadoWorkspace.H[528] = acadoWorkspace.H10[72]; +acadoWorkspace.H[529] = acadoWorkspace.H10[73]; +acadoWorkspace.H[530] = acadoWorkspace.H10[74]; +acadoWorkspace.H[531] = acadoWorkspace.H10[75]; +acadoWorkspace.H[552] = acadoWorkspace.H10[76]; +acadoWorkspace.H[553] = acadoWorkspace.H10[77]; +acadoWorkspace.H[554] = acadoWorkspace.H10[78]; +acadoWorkspace.H[555] = acadoWorkspace.H10[79]; + +acado_multQ1d( &(acadoWorkspace.Q1[ 16 ]), acadoWorkspace.d, acadoWorkspace.Qd ); +acado_multQ1d( &(acadoWorkspace.Q1[ 32 ]), &(acadoWorkspace.d[ 4 ]), &(acadoWorkspace.Qd[ 4 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 48 ]), &(acadoWorkspace.d[ 8 ]), &(acadoWorkspace.Qd[ 8 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 64 ]), &(acadoWorkspace.d[ 12 ]), &(acadoWorkspace.Qd[ 12 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 80 ]), &(acadoWorkspace.d[ 16 ]), &(acadoWorkspace.Qd[ 16 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 96 ]), &(acadoWorkspace.d[ 20 ]), &(acadoWorkspace.Qd[ 20 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 112 ]), &(acadoWorkspace.d[ 24 ]), &(acadoWorkspace.Qd[ 24 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 128 ]), &(acadoWorkspace.d[ 28 ]), &(acadoWorkspace.Qd[ 28 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 144 ]), &(acadoWorkspace.d[ 32 ]), &(acadoWorkspace.Qd[ 32 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 160 ]), &(acadoWorkspace.d[ 36 ]), &(acadoWorkspace.Qd[ 36 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 176 ]), &(acadoWorkspace.d[ 40 ]), &(acadoWorkspace.Qd[ 40 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 192 ]), &(acadoWorkspace.d[ 44 ]), &(acadoWorkspace.Qd[ 44 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 208 ]), &(acadoWorkspace.d[ 48 ]), &(acadoWorkspace.Qd[ 48 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 224 ]), &(acadoWorkspace.d[ 52 ]), &(acadoWorkspace.Qd[ 52 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 240 ]), &(acadoWorkspace.d[ 56 ]), &(acadoWorkspace.Qd[ 56 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 256 ]), &(acadoWorkspace.d[ 60 ]), &(acadoWorkspace.Qd[ 60 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 272 ]), &(acadoWorkspace.d[ 64 ]), &(acadoWorkspace.Qd[ 64 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 288 ]), &(acadoWorkspace.d[ 68 ]), &(acadoWorkspace.Qd[ 68 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 304 ]), &(acadoWorkspace.d[ 72 ]), &(acadoWorkspace.Qd[ 72 ]) ); +acado_multQN1d( acadoWorkspace.QN1, &(acadoWorkspace.d[ 76 ]), &(acadoWorkspace.Qd[ 76 ]) ); + +acado_macCTSlx( acadoWorkspace.evGx, acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 16 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 32 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 48 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 64 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 80 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 96 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 112 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 128 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 144 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 160 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 176 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 192 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 208 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 224 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 240 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 256 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 272 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 288 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 304 ]), acadoWorkspace.g ); +acado_macETSlu( acadoWorkspace.QE, &(acadoWorkspace.g[ 4 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 4 ]), &(acadoWorkspace.g[ 4 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 12 ]), &(acadoWorkspace.g[ 4 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 24 ]), &(acadoWorkspace.g[ 4 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 40 ]), &(acadoWorkspace.g[ 4 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 60 ]), &(acadoWorkspace.g[ 4 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 84 ]), &(acadoWorkspace.g[ 4 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 112 ]), &(acadoWorkspace.g[ 4 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 144 ]), &(acadoWorkspace.g[ 4 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 180 ]), &(acadoWorkspace.g[ 4 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 220 ]), &(acadoWorkspace.g[ 4 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 264 ]), &(acadoWorkspace.g[ 4 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 312 ]), &(acadoWorkspace.g[ 4 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 364 ]), &(acadoWorkspace.g[ 4 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 420 ]), &(acadoWorkspace.g[ 4 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 480 ]), &(acadoWorkspace.g[ 4 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 544 ]), &(acadoWorkspace.g[ 4 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 612 ]), &(acadoWorkspace.g[ 4 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 684 ]), &(acadoWorkspace.g[ 4 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 760 ]), &(acadoWorkspace.g[ 4 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 8 ]), &(acadoWorkspace.g[ 5 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 16 ]), &(acadoWorkspace.g[ 5 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 28 ]), &(acadoWorkspace.g[ 5 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 44 ]), &(acadoWorkspace.g[ 5 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 64 ]), &(acadoWorkspace.g[ 5 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 88 ]), &(acadoWorkspace.g[ 5 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 116 ]), &(acadoWorkspace.g[ 5 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 148 ]), &(acadoWorkspace.g[ 5 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 184 ]), &(acadoWorkspace.g[ 5 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 224 ]), &(acadoWorkspace.g[ 5 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 268 ]), &(acadoWorkspace.g[ 5 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 316 ]), &(acadoWorkspace.g[ 5 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 368 ]), &(acadoWorkspace.g[ 5 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 424 ]), &(acadoWorkspace.g[ 5 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 484 ]), &(acadoWorkspace.g[ 5 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 548 ]), &(acadoWorkspace.g[ 5 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 616 ]), &(acadoWorkspace.g[ 5 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 688 ]), &(acadoWorkspace.g[ 5 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 764 ]), &(acadoWorkspace.g[ 5 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 20 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 32 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 48 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 68 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 92 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 120 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 152 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 188 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 228 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 272 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 320 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 372 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 428 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 488 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 552 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 620 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 692 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 768 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 36 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 52 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 72 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 96 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 124 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 156 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 192 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 232 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 276 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 324 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 376 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 432 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 492 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 556 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 624 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 696 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 772 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 56 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 76 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 100 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 128 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 160 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 196 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 236 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 280 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 328 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 380 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 436 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 496 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 560 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 628 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 700 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 776 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 80 ]), &(acadoWorkspace.g[ 9 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 104 ]), &(acadoWorkspace.g[ 9 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 132 ]), &(acadoWorkspace.g[ 9 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 164 ]), &(acadoWorkspace.g[ 9 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 200 ]), &(acadoWorkspace.g[ 9 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 240 ]), &(acadoWorkspace.g[ 9 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 284 ]), &(acadoWorkspace.g[ 9 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 332 ]), &(acadoWorkspace.g[ 9 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 384 ]), &(acadoWorkspace.g[ 9 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 440 ]), &(acadoWorkspace.g[ 9 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 500 ]), &(acadoWorkspace.g[ 9 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 564 ]), &(acadoWorkspace.g[ 9 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 632 ]), &(acadoWorkspace.g[ 9 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 704 ]), &(acadoWorkspace.g[ 9 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 780 ]), &(acadoWorkspace.g[ 9 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 108 ]), &(acadoWorkspace.g[ 10 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 136 ]), &(acadoWorkspace.g[ 10 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 168 ]), &(acadoWorkspace.g[ 10 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 204 ]), &(acadoWorkspace.g[ 10 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 244 ]), &(acadoWorkspace.g[ 10 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 288 ]), &(acadoWorkspace.g[ 10 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 336 ]), &(acadoWorkspace.g[ 10 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 388 ]), &(acadoWorkspace.g[ 10 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 444 ]), &(acadoWorkspace.g[ 10 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 504 ]), &(acadoWorkspace.g[ 10 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 568 ]), &(acadoWorkspace.g[ 10 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 636 ]), &(acadoWorkspace.g[ 10 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 708 ]), &(acadoWorkspace.g[ 10 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 784 ]), &(acadoWorkspace.g[ 10 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 140 ]), &(acadoWorkspace.g[ 11 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 172 ]), &(acadoWorkspace.g[ 11 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 208 ]), &(acadoWorkspace.g[ 11 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 248 ]), &(acadoWorkspace.g[ 11 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 292 ]), &(acadoWorkspace.g[ 11 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 340 ]), &(acadoWorkspace.g[ 11 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 392 ]), &(acadoWorkspace.g[ 11 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 448 ]), &(acadoWorkspace.g[ 11 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 508 ]), &(acadoWorkspace.g[ 11 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 572 ]), &(acadoWorkspace.g[ 11 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 640 ]), &(acadoWorkspace.g[ 11 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 712 ]), &(acadoWorkspace.g[ 11 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 788 ]), &(acadoWorkspace.g[ 11 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 176 ]), &(acadoWorkspace.g[ 12 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 212 ]), &(acadoWorkspace.g[ 12 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 252 ]), &(acadoWorkspace.g[ 12 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 296 ]), &(acadoWorkspace.g[ 12 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 344 ]), &(acadoWorkspace.g[ 12 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 396 ]), &(acadoWorkspace.g[ 12 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 452 ]), &(acadoWorkspace.g[ 12 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 512 ]), &(acadoWorkspace.g[ 12 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 576 ]), &(acadoWorkspace.g[ 12 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 644 ]), &(acadoWorkspace.g[ 12 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 716 ]), &(acadoWorkspace.g[ 12 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 792 ]), &(acadoWorkspace.g[ 12 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 216 ]), &(acadoWorkspace.g[ 13 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 256 ]), &(acadoWorkspace.g[ 13 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 300 ]), &(acadoWorkspace.g[ 13 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 348 ]), &(acadoWorkspace.g[ 13 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 400 ]), &(acadoWorkspace.g[ 13 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 456 ]), &(acadoWorkspace.g[ 13 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 516 ]), &(acadoWorkspace.g[ 13 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 580 ]), &(acadoWorkspace.g[ 13 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 648 ]), &(acadoWorkspace.g[ 13 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 720 ]), &(acadoWorkspace.g[ 13 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 796 ]), &(acadoWorkspace.g[ 13 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 260 ]), &(acadoWorkspace.g[ 14 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 304 ]), &(acadoWorkspace.g[ 14 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 352 ]), &(acadoWorkspace.g[ 14 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 404 ]), &(acadoWorkspace.g[ 14 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 460 ]), &(acadoWorkspace.g[ 14 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 520 ]), &(acadoWorkspace.g[ 14 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 584 ]), &(acadoWorkspace.g[ 14 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 652 ]), &(acadoWorkspace.g[ 14 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 724 ]), &(acadoWorkspace.g[ 14 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 800 ]), &(acadoWorkspace.g[ 14 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 308 ]), &(acadoWorkspace.g[ 15 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 356 ]), &(acadoWorkspace.g[ 15 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 408 ]), &(acadoWorkspace.g[ 15 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 464 ]), &(acadoWorkspace.g[ 15 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 524 ]), &(acadoWorkspace.g[ 15 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 588 ]), &(acadoWorkspace.g[ 15 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 656 ]), &(acadoWorkspace.g[ 15 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 728 ]), &(acadoWorkspace.g[ 15 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 804 ]), &(acadoWorkspace.g[ 15 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 360 ]), &(acadoWorkspace.g[ 16 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 412 ]), &(acadoWorkspace.g[ 16 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 468 ]), &(acadoWorkspace.g[ 16 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 528 ]), &(acadoWorkspace.g[ 16 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 592 ]), &(acadoWorkspace.g[ 16 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 660 ]), &(acadoWorkspace.g[ 16 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 732 ]), &(acadoWorkspace.g[ 16 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 808 ]), &(acadoWorkspace.g[ 16 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 416 ]), &(acadoWorkspace.g[ 17 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 472 ]), &(acadoWorkspace.g[ 17 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 532 ]), &(acadoWorkspace.g[ 17 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 596 ]), &(acadoWorkspace.g[ 17 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 664 ]), &(acadoWorkspace.g[ 17 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 736 ]), &(acadoWorkspace.g[ 17 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 812 ]), &(acadoWorkspace.g[ 17 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 476 ]), &(acadoWorkspace.g[ 18 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 536 ]), &(acadoWorkspace.g[ 18 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 600 ]), &(acadoWorkspace.g[ 18 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 668 ]), &(acadoWorkspace.g[ 18 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 740 ]), &(acadoWorkspace.g[ 18 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 816 ]), &(acadoWorkspace.g[ 18 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 540 ]), &(acadoWorkspace.g[ 19 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 604 ]), &(acadoWorkspace.g[ 19 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 672 ]), &(acadoWorkspace.g[ 19 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 744 ]), &(acadoWorkspace.g[ 19 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 820 ]), &(acadoWorkspace.g[ 19 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 608 ]), &(acadoWorkspace.g[ 20 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 676 ]), &(acadoWorkspace.g[ 20 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 748 ]), &(acadoWorkspace.g[ 20 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 824 ]), &(acadoWorkspace.g[ 20 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 680 ]), &(acadoWorkspace.g[ 21 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 752 ]), &(acadoWorkspace.g[ 21 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 828 ]), &(acadoWorkspace.g[ 21 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 756 ]), &(acadoWorkspace.g[ 22 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 832 ]), &(acadoWorkspace.g[ 22 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 836 ]), &(acadoWorkspace.g[ 23 ]) ); +acadoWorkspace.lb[4] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[0]; +acadoWorkspace.lb[5] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[1]; +acadoWorkspace.lb[6] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[2]; +acadoWorkspace.lb[7] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[3]; +acadoWorkspace.lb[8] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[4]; +acadoWorkspace.lb[9] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[5]; +acadoWorkspace.lb[10] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[6]; +acadoWorkspace.lb[11] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[7]; +acadoWorkspace.lb[12] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[8]; +acadoWorkspace.lb[13] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[9]; +acadoWorkspace.lb[14] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[10]; +acadoWorkspace.lb[15] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[11]; +acadoWorkspace.lb[16] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[12]; +acadoWorkspace.lb[17] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[13]; +acadoWorkspace.lb[18] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[14]; +acadoWorkspace.lb[19] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[15]; +acadoWorkspace.lb[20] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[16]; +acadoWorkspace.lb[21] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[17]; +acadoWorkspace.lb[22] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[18]; +acadoWorkspace.lb[23] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[19]; +acadoWorkspace.ub[4] = (real_t)1.0000000000000000e+12 - acadoVariables.u[0]; +acadoWorkspace.ub[5] = (real_t)1.0000000000000000e+12 - acadoVariables.u[1]; +acadoWorkspace.ub[6] = (real_t)1.0000000000000000e+12 - acadoVariables.u[2]; +acadoWorkspace.ub[7] = (real_t)1.0000000000000000e+12 - acadoVariables.u[3]; +acadoWorkspace.ub[8] = (real_t)1.0000000000000000e+12 - acadoVariables.u[4]; +acadoWorkspace.ub[9] = (real_t)1.0000000000000000e+12 - acadoVariables.u[5]; +acadoWorkspace.ub[10] = (real_t)1.0000000000000000e+12 - acadoVariables.u[6]; +acadoWorkspace.ub[11] = (real_t)1.0000000000000000e+12 - acadoVariables.u[7]; +acadoWorkspace.ub[12] = (real_t)1.0000000000000000e+12 - acadoVariables.u[8]; +acadoWorkspace.ub[13] = (real_t)1.0000000000000000e+12 - acadoVariables.u[9]; +acadoWorkspace.ub[14] = (real_t)1.0000000000000000e+12 - acadoVariables.u[10]; +acadoWorkspace.ub[15] = (real_t)1.0000000000000000e+12 - acadoVariables.u[11]; +acadoWorkspace.ub[16] = (real_t)1.0000000000000000e+12 - acadoVariables.u[12]; +acadoWorkspace.ub[17] = (real_t)1.0000000000000000e+12 - acadoVariables.u[13]; +acadoWorkspace.ub[18] = (real_t)1.0000000000000000e+12 - acadoVariables.u[14]; +acadoWorkspace.ub[19] = (real_t)1.0000000000000000e+12 - acadoVariables.u[15]; +acadoWorkspace.ub[20] = (real_t)1.0000000000000000e+12 - acadoVariables.u[16]; +acadoWorkspace.ub[21] = (real_t)1.0000000000000000e+12 - acadoVariables.u[17]; +acadoWorkspace.ub[22] = (real_t)1.0000000000000000e+12 - acadoVariables.u[18]; +acadoWorkspace.ub[23] = (real_t)1.0000000000000000e+12 - acadoVariables.u[19]; + +for (lRun1 = 0; lRun1 < 40; ++lRun1) +{ +lRun3 = xBoundIndices[ lRun1 ] - 4; +lRun4 = ((lRun3) / (4)) + (1); +acadoWorkspace.A[lRun1 * 24] = acadoWorkspace.evGx[lRun3 * 4]; +acadoWorkspace.A[lRun1 * 24 + 1] = acadoWorkspace.evGx[lRun3 * 4 + 1]; +acadoWorkspace.A[lRun1 * 24 + 2] = acadoWorkspace.evGx[lRun3 * 4 + 2]; +acadoWorkspace.A[lRun1 * 24 + 3] = acadoWorkspace.evGx[lRun3 * 4 + 3]; +for (lRun2 = 0; lRun2 < lRun4; ++lRun2) +{ +lRun5 = (((((lRun4) * (lRun4-1)) / (2)) + (lRun2)) * (4)) + ((lRun3) % (4)); +acadoWorkspace.A[(lRun1 * 24) + (lRun2 + 4)] = acadoWorkspace.E[lRun5]; +} +} + +} + +void acado_condenseFdb( ) +{ +real_t tmp; + +acadoWorkspace.Dx0[0] = acadoVariables.x0[0] - acadoVariables.x[0]; +acadoWorkspace.Dx0[1] = acadoVariables.x0[1] - acadoVariables.x[1]; +acadoWorkspace.Dx0[2] = acadoVariables.x0[2] - acadoVariables.x[2]; +acadoWorkspace.Dx0[3] = acadoVariables.x0[3] - acadoVariables.x[3]; + +acadoWorkspace.Dy[0] -= acadoVariables.y[0]; +acadoWorkspace.Dy[1] -= acadoVariables.y[1]; +acadoWorkspace.Dy[2] -= acadoVariables.y[2]; +acadoWorkspace.Dy[3] -= acadoVariables.y[3]; +acadoWorkspace.Dy[4] -= acadoVariables.y[4]; +acadoWorkspace.Dy[5] -= acadoVariables.y[5]; +acadoWorkspace.Dy[6] -= acadoVariables.y[6]; +acadoWorkspace.Dy[7] -= acadoVariables.y[7]; +acadoWorkspace.Dy[8] -= acadoVariables.y[8]; +acadoWorkspace.Dy[9] -= acadoVariables.y[9]; +acadoWorkspace.Dy[10] -= acadoVariables.y[10]; +acadoWorkspace.Dy[11] -= acadoVariables.y[11]; +acadoWorkspace.Dy[12] -= acadoVariables.y[12]; +acadoWorkspace.Dy[13] -= acadoVariables.y[13]; +acadoWorkspace.Dy[14] -= acadoVariables.y[14]; +acadoWorkspace.Dy[15] -= acadoVariables.y[15]; +acadoWorkspace.Dy[16] -= acadoVariables.y[16]; +acadoWorkspace.Dy[17] -= acadoVariables.y[17]; +acadoWorkspace.Dy[18] -= acadoVariables.y[18]; +acadoWorkspace.Dy[19] -= acadoVariables.y[19]; +acadoWorkspace.Dy[20] -= acadoVariables.y[20]; +acadoWorkspace.Dy[21] -= acadoVariables.y[21]; +acadoWorkspace.Dy[22] -= acadoVariables.y[22]; +acadoWorkspace.Dy[23] -= acadoVariables.y[23]; +acadoWorkspace.Dy[24] -= acadoVariables.y[24]; +acadoWorkspace.Dy[25] -= acadoVariables.y[25]; +acadoWorkspace.Dy[26] -= acadoVariables.y[26]; +acadoWorkspace.Dy[27] -= acadoVariables.y[27]; +acadoWorkspace.Dy[28] -= acadoVariables.y[28]; +acadoWorkspace.Dy[29] -= acadoVariables.y[29]; +acadoWorkspace.Dy[30] -= acadoVariables.y[30]; +acadoWorkspace.Dy[31] -= acadoVariables.y[31]; +acadoWorkspace.Dy[32] -= acadoVariables.y[32]; +acadoWorkspace.Dy[33] -= acadoVariables.y[33]; +acadoWorkspace.Dy[34] -= acadoVariables.y[34]; +acadoWorkspace.Dy[35] -= acadoVariables.y[35]; +acadoWorkspace.Dy[36] -= acadoVariables.y[36]; +acadoWorkspace.Dy[37] -= acadoVariables.y[37]; +acadoWorkspace.Dy[38] -= acadoVariables.y[38]; +acadoWorkspace.Dy[39] -= acadoVariables.y[39]; +acadoWorkspace.Dy[40] -= acadoVariables.y[40]; +acadoWorkspace.Dy[41] -= acadoVariables.y[41]; +acadoWorkspace.Dy[42] -= acadoVariables.y[42]; +acadoWorkspace.Dy[43] -= acadoVariables.y[43]; +acadoWorkspace.Dy[44] -= acadoVariables.y[44]; +acadoWorkspace.Dy[45] -= acadoVariables.y[45]; +acadoWorkspace.Dy[46] -= acadoVariables.y[46]; +acadoWorkspace.Dy[47] -= acadoVariables.y[47]; +acadoWorkspace.Dy[48] -= acadoVariables.y[48]; +acadoWorkspace.Dy[49] -= acadoVariables.y[49]; +acadoWorkspace.Dy[50] -= acadoVariables.y[50]; +acadoWorkspace.Dy[51] -= acadoVariables.y[51]; +acadoWorkspace.Dy[52] -= acadoVariables.y[52]; +acadoWorkspace.Dy[53] -= acadoVariables.y[53]; +acadoWorkspace.Dy[54] -= acadoVariables.y[54]; +acadoWorkspace.Dy[55] -= acadoVariables.y[55]; +acadoWorkspace.Dy[56] -= acadoVariables.y[56]; +acadoWorkspace.Dy[57] -= acadoVariables.y[57]; +acadoWorkspace.Dy[58] -= acadoVariables.y[58]; +acadoWorkspace.Dy[59] -= acadoVariables.y[59]; +acadoWorkspace.Dy[60] -= acadoVariables.y[60]; +acadoWorkspace.Dy[61] -= acadoVariables.y[61]; +acadoWorkspace.Dy[62] -= acadoVariables.y[62]; +acadoWorkspace.Dy[63] -= acadoVariables.y[63]; +acadoWorkspace.Dy[64] -= acadoVariables.y[64]; +acadoWorkspace.Dy[65] -= acadoVariables.y[65]; +acadoWorkspace.Dy[66] -= acadoVariables.y[66]; +acadoWorkspace.Dy[67] -= acadoVariables.y[67]; +acadoWorkspace.Dy[68] -= acadoVariables.y[68]; +acadoWorkspace.Dy[69] -= acadoVariables.y[69]; +acadoWorkspace.Dy[70] -= acadoVariables.y[70]; +acadoWorkspace.Dy[71] -= acadoVariables.y[71]; +acadoWorkspace.Dy[72] -= acadoVariables.y[72]; +acadoWorkspace.Dy[73] -= acadoVariables.y[73]; +acadoWorkspace.Dy[74] -= acadoVariables.y[74]; +acadoWorkspace.Dy[75] -= acadoVariables.y[75]; +acadoWorkspace.Dy[76] -= acadoVariables.y[76]; +acadoWorkspace.Dy[77] -= acadoVariables.y[77]; +acadoWorkspace.Dy[78] -= acadoVariables.y[78]; +acadoWorkspace.Dy[79] -= acadoVariables.y[79]; +acadoWorkspace.Dy[80] -= acadoVariables.y[80]; +acadoWorkspace.Dy[81] -= acadoVariables.y[81]; +acadoWorkspace.Dy[82] -= acadoVariables.y[82]; +acadoWorkspace.Dy[83] -= acadoVariables.y[83]; +acadoWorkspace.Dy[84] -= acadoVariables.y[84]; +acadoWorkspace.Dy[85] -= acadoVariables.y[85]; +acadoWorkspace.Dy[86] -= acadoVariables.y[86]; +acadoWorkspace.Dy[87] -= acadoVariables.y[87]; +acadoWorkspace.Dy[88] -= acadoVariables.y[88]; +acadoWorkspace.Dy[89] -= acadoVariables.y[89]; +acadoWorkspace.Dy[90] -= acadoVariables.y[90]; +acadoWorkspace.Dy[91] -= acadoVariables.y[91]; +acadoWorkspace.Dy[92] -= acadoVariables.y[92]; +acadoWorkspace.Dy[93] -= acadoVariables.y[93]; +acadoWorkspace.Dy[94] -= acadoVariables.y[94]; +acadoWorkspace.Dy[95] -= acadoVariables.y[95]; +acadoWorkspace.Dy[96] -= acadoVariables.y[96]; +acadoWorkspace.Dy[97] -= acadoVariables.y[97]; +acadoWorkspace.Dy[98] -= acadoVariables.y[98]; +acadoWorkspace.Dy[99] -= acadoVariables.y[99]; +acadoWorkspace.DyN[0] -= acadoVariables.yN[0]; +acadoWorkspace.DyN[1] -= acadoVariables.yN[1]; +acadoWorkspace.DyN[2] -= acadoVariables.yN[2]; +acadoWorkspace.DyN[3] -= acadoVariables.yN[3]; + +acado_multRDy( acadoWorkspace.R2, acadoWorkspace.Dy, &(acadoWorkspace.g[ 4 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 5 ]), &(acadoWorkspace.Dy[ 5 ]), &(acadoWorkspace.g[ 5 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 10 ]), &(acadoWorkspace.Dy[ 10 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 15 ]), &(acadoWorkspace.Dy[ 15 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 20 ]), &(acadoWorkspace.Dy[ 20 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 25 ]), &(acadoWorkspace.Dy[ 25 ]), &(acadoWorkspace.g[ 9 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 30 ]), &(acadoWorkspace.Dy[ 30 ]), &(acadoWorkspace.g[ 10 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 35 ]), &(acadoWorkspace.Dy[ 35 ]), &(acadoWorkspace.g[ 11 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 40 ]), &(acadoWorkspace.Dy[ 40 ]), &(acadoWorkspace.g[ 12 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 45 ]), &(acadoWorkspace.Dy[ 45 ]), &(acadoWorkspace.g[ 13 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 50 ]), &(acadoWorkspace.Dy[ 50 ]), &(acadoWorkspace.g[ 14 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 55 ]), &(acadoWorkspace.Dy[ 55 ]), &(acadoWorkspace.g[ 15 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 60 ]), &(acadoWorkspace.Dy[ 60 ]), &(acadoWorkspace.g[ 16 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 65 ]), &(acadoWorkspace.Dy[ 65 ]), &(acadoWorkspace.g[ 17 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 70 ]), &(acadoWorkspace.Dy[ 70 ]), &(acadoWorkspace.g[ 18 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 75 ]), &(acadoWorkspace.Dy[ 75 ]), &(acadoWorkspace.g[ 19 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 80 ]), &(acadoWorkspace.Dy[ 80 ]), &(acadoWorkspace.g[ 20 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 85 ]), &(acadoWorkspace.Dy[ 85 ]), &(acadoWorkspace.g[ 21 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 90 ]), &(acadoWorkspace.Dy[ 90 ]), &(acadoWorkspace.g[ 22 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 95 ]), &(acadoWorkspace.Dy[ 95 ]), &(acadoWorkspace.g[ 23 ]) ); + +acado_multQDy( acadoWorkspace.Q2, acadoWorkspace.Dy, acadoWorkspace.QDy ); +acado_multQDy( &(acadoWorkspace.Q2[ 20 ]), &(acadoWorkspace.Dy[ 5 ]), &(acadoWorkspace.QDy[ 4 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 40 ]), &(acadoWorkspace.Dy[ 10 ]), &(acadoWorkspace.QDy[ 8 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 60 ]), &(acadoWorkspace.Dy[ 15 ]), &(acadoWorkspace.QDy[ 12 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 80 ]), &(acadoWorkspace.Dy[ 20 ]), &(acadoWorkspace.QDy[ 16 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 100 ]), &(acadoWorkspace.Dy[ 25 ]), &(acadoWorkspace.QDy[ 20 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 120 ]), &(acadoWorkspace.Dy[ 30 ]), &(acadoWorkspace.QDy[ 24 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 140 ]), &(acadoWorkspace.Dy[ 35 ]), &(acadoWorkspace.QDy[ 28 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 160 ]), &(acadoWorkspace.Dy[ 40 ]), &(acadoWorkspace.QDy[ 32 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 180 ]), &(acadoWorkspace.Dy[ 45 ]), &(acadoWorkspace.QDy[ 36 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 200 ]), &(acadoWorkspace.Dy[ 50 ]), &(acadoWorkspace.QDy[ 40 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 220 ]), &(acadoWorkspace.Dy[ 55 ]), &(acadoWorkspace.QDy[ 44 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 240 ]), &(acadoWorkspace.Dy[ 60 ]), &(acadoWorkspace.QDy[ 48 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 260 ]), &(acadoWorkspace.Dy[ 65 ]), &(acadoWorkspace.QDy[ 52 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 280 ]), &(acadoWorkspace.Dy[ 70 ]), &(acadoWorkspace.QDy[ 56 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 300 ]), &(acadoWorkspace.Dy[ 75 ]), &(acadoWorkspace.QDy[ 60 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 320 ]), &(acadoWorkspace.Dy[ 80 ]), &(acadoWorkspace.QDy[ 64 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 340 ]), &(acadoWorkspace.Dy[ 85 ]), &(acadoWorkspace.QDy[ 68 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 360 ]), &(acadoWorkspace.Dy[ 90 ]), &(acadoWorkspace.QDy[ 72 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 380 ]), &(acadoWorkspace.Dy[ 95 ]), &(acadoWorkspace.QDy[ 76 ]) ); + +acadoWorkspace.QDy[80] = + acadoWorkspace.QN2[0]*acadoWorkspace.DyN[0] + acadoWorkspace.QN2[1]*acadoWorkspace.DyN[1] + acadoWorkspace.QN2[2]*acadoWorkspace.DyN[2] + acadoWorkspace.QN2[3]*acadoWorkspace.DyN[3]; +acadoWorkspace.QDy[81] = + acadoWorkspace.QN2[4]*acadoWorkspace.DyN[0] + acadoWorkspace.QN2[5]*acadoWorkspace.DyN[1] + acadoWorkspace.QN2[6]*acadoWorkspace.DyN[2] + acadoWorkspace.QN2[7]*acadoWorkspace.DyN[3]; +acadoWorkspace.QDy[82] = + acadoWorkspace.QN2[8]*acadoWorkspace.DyN[0] + acadoWorkspace.QN2[9]*acadoWorkspace.DyN[1] + acadoWorkspace.QN2[10]*acadoWorkspace.DyN[2] + acadoWorkspace.QN2[11]*acadoWorkspace.DyN[3]; +acadoWorkspace.QDy[83] = + acadoWorkspace.QN2[12]*acadoWorkspace.DyN[0] + acadoWorkspace.QN2[13]*acadoWorkspace.DyN[1] + acadoWorkspace.QN2[14]*acadoWorkspace.DyN[2] + acadoWorkspace.QN2[15]*acadoWorkspace.DyN[3]; + +acadoWorkspace.QDy[4] += acadoWorkspace.Qd[0]; +acadoWorkspace.QDy[5] += acadoWorkspace.Qd[1]; +acadoWorkspace.QDy[6] += acadoWorkspace.Qd[2]; +acadoWorkspace.QDy[7] += acadoWorkspace.Qd[3]; +acadoWorkspace.QDy[8] += acadoWorkspace.Qd[4]; +acadoWorkspace.QDy[9] += acadoWorkspace.Qd[5]; +acadoWorkspace.QDy[10] += acadoWorkspace.Qd[6]; +acadoWorkspace.QDy[11] += acadoWorkspace.Qd[7]; +acadoWorkspace.QDy[12] += acadoWorkspace.Qd[8]; +acadoWorkspace.QDy[13] += acadoWorkspace.Qd[9]; +acadoWorkspace.QDy[14] += acadoWorkspace.Qd[10]; +acadoWorkspace.QDy[15] += acadoWorkspace.Qd[11]; +acadoWorkspace.QDy[16] += acadoWorkspace.Qd[12]; +acadoWorkspace.QDy[17] += acadoWorkspace.Qd[13]; +acadoWorkspace.QDy[18] += acadoWorkspace.Qd[14]; +acadoWorkspace.QDy[19] += acadoWorkspace.Qd[15]; +acadoWorkspace.QDy[20] += acadoWorkspace.Qd[16]; +acadoWorkspace.QDy[21] += acadoWorkspace.Qd[17]; +acadoWorkspace.QDy[22] += acadoWorkspace.Qd[18]; +acadoWorkspace.QDy[23] += acadoWorkspace.Qd[19]; +acadoWorkspace.QDy[24] += acadoWorkspace.Qd[20]; +acadoWorkspace.QDy[25] += acadoWorkspace.Qd[21]; +acadoWorkspace.QDy[26] += acadoWorkspace.Qd[22]; +acadoWorkspace.QDy[27] += acadoWorkspace.Qd[23]; +acadoWorkspace.QDy[28] += acadoWorkspace.Qd[24]; +acadoWorkspace.QDy[29] += acadoWorkspace.Qd[25]; +acadoWorkspace.QDy[30] += acadoWorkspace.Qd[26]; +acadoWorkspace.QDy[31] += acadoWorkspace.Qd[27]; +acadoWorkspace.QDy[32] += acadoWorkspace.Qd[28]; +acadoWorkspace.QDy[33] += acadoWorkspace.Qd[29]; +acadoWorkspace.QDy[34] += acadoWorkspace.Qd[30]; +acadoWorkspace.QDy[35] += acadoWorkspace.Qd[31]; +acadoWorkspace.QDy[36] += acadoWorkspace.Qd[32]; +acadoWorkspace.QDy[37] += acadoWorkspace.Qd[33]; +acadoWorkspace.QDy[38] += acadoWorkspace.Qd[34]; +acadoWorkspace.QDy[39] += acadoWorkspace.Qd[35]; +acadoWorkspace.QDy[40] += acadoWorkspace.Qd[36]; +acadoWorkspace.QDy[41] += acadoWorkspace.Qd[37]; +acadoWorkspace.QDy[42] += acadoWorkspace.Qd[38]; +acadoWorkspace.QDy[43] += acadoWorkspace.Qd[39]; +acadoWorkspace.QDy[44] += acadoWorkspace.Qd[40]; +acadoWorkspace.QDy[45] += acadoWorkspace.Qd[41]; +acadoWorkspace.QDy[46] += acadoWorkspace.Qd[42]; +acadoWorkspace.QDy[47] += acadoWorkspace.Qd[43]; +acadoWorkspace.QDy[48] += acadoWorkspace.Qd[44]; +acadoWorkspace.QDy[49] += acadoWorkspace.Qd[45]; +acadoWorkspace.QDy[50] += acadoWorkspace.Qd[46]; +acadoWorkspace.QDy[51] += acadoWorkspace.Qd[47]; +acadoWorkspace.QDy[52] += acadoWorkspace.Qd[48]; +acadoWorkspace.QDy[53] += acadoWorkspace.Qd[49]; +acadoWorkspace.QDy[54] += acadoWorkspace.Qd[50]; +acadoWorkspace.QDy[55] += acadoWorkspace.Qd[51]; +acadoWorkspace.QDy[56] += acadoWorkspace.Qd[52]; +acadoWorkspace.QDy[57] += acadoWorkspace.Qd[53]; +acadoWorkspace.QDy[58] += acadoWorkspace.Qd[54]; +acadoWorkspace.QDy[59] += acadoWorkspace.Qd[55]; +acadoWorkspace.QDy[60] += acadoWorkspace.Qd[56]; +acadoWorkspace.QDy[61] += acadoWorkspace.Qd[57]; +acadoWorkspace.QDy[62] += acadoWorkspace.Qd[58]; +acadoWorkspace.QDy[63] += acadoWorkspace.Qd[59]; +acadoWorkspace.QDy[64] += acadoWorkspace.Qd[60]; +acadoWorkspace.QDy[65] += acadoWorkspace.Qd[61]; +acadoWorkspace.QDy[66] += acadoWorkspace.Qd[62]; +acadoWorkspace.QDy[67] += acadoWorkspace.Qd[63]; +acadoWorkspace.QDy[68] += acadoWorkspace.Qd[64]; +acadoWorkspace.QDy[69] += acadoWorkspace.Qd[65]; +acadoWorkspace.QDy[70] += acadoWorkspace.Qd[66]; +acadoWorkspace.QDy[71] += acadoWorkspace.Qd[67]; +acadoWorkspace.QDy[72] += acadoWorkspace.Qd[68]; +acadoWorkspace.QDy[73] += acadoWorkspace.Qd[69]; +acadoWorkspace.QDy[74] += acadoWorkspace.Qd[70]; +acadoWorkspace.QDy[75] += acadoWorkspace.Qd[71]; +acadoWorkspace.QDy[76] += acadoWorkspace.Qd[72]; +acadoWorkspace.QDy[77] += acadoWorkspace.Qd[73]; +acadoWorkspace.QDy[78] += acadoWorkspace.Qd[74]; +acadoWorkspace.QDy[79] += acadoWorkspace.Qd[75]; +acadoWorkspace.QDy[80] += acadoWorkspace.Qd[76]; +acadoWorkspace.QDy[81] += acadoWorkspace.Qd[77]; +acadoWorkspace.QDy[82] += acadoWorkspace.Qd[78]; +acadoWorkspace.QDy[83] += acadoWorkspace.Qd[79]; + +acadoWorkspace.g[0] = + acadoWorkspace.evGx[0]*acadoWorkspace.QDy[4] + acadoWorkspace.evGx[4]*acadoWorkspace.QDy[5] + acadoWorkspace.evGx[8]*acadoWorkspace.QDy[6] + acadoWorkspace.evGx[12]*acadoWorkspace.QDy[7] + acadoWorkspace.evGx[16]*acadoWorkspace.QDy[8] + acadoWorkspace.evGx[20]*acadoWorkspace.QDy[9] + acadoWorkspace.evGx[24]*acadoWorkspace.QDy[10] + acadoWorkspace.evGx[28]*acadoWorkspace.QDy[11] + acadoWorkspace.evGx[32]*acadoWorkspace.QDy[12] + acadoWorkspace.evGx[36]*acadoWorkspace.QDy[13] + acadoWorkspace.evGx[40]*acadoWorkspace.QDy[14] + acadoWorkspace.evGx[44]*acadoWorkspace.QDy[15] + acadoWorkspace.evGx[48]*acadoWorkspace.QDy[16] + acadoWorkspace.evGx[52]*acadoWorkspace.QDy[17] + acadoWorkspace.evGx[56]*acadoWorkspace.QDy[18] + acadoWorkspace.evGx[60]*acadoWorkspace.QDy[19] + acadoWorkspace.evGx[64]*acadoWorkspace.QDy[20] + acadoWorkspace.evGx[68]*acadoWorkspace.QDy[21] + acadoWorkspace.evGx[72]*acadoWorkspace.QDy[22] + acadoWorkspace.evGx[76]*acadoWorkspace.QDy[23] + acadoWorkspace.evGx[80]*acadoWorkspace.QDy[24] + acadoWorkspace.evGx[84]*acadoWorkspace.QDy[25] + acadoWorkspace.evGx[88]*acadoWorkspace.QDy[26] + acadoWorkspace.evGx[92]*acadoWorkspace.QDy[27] + acadoWorkspace.evGx[96]*acadoWorkspace.QDy[28] + acadoWorkspace.evGx[100]*acadoWorkspace.QDy[29] + acadoWorkspace.evGx[104]*acadoWorkspace.QDy[30] + acadoWorkspace.evGx[108]*acadoWorkspace.QDy[31] + acadoWorkspace.evGx[112]*acadoWorkspace.QDy[32] + acadoWorkspace.evGx[116]*acadoWorkspace.QDy[33] + acadoWorkspace.evGx[120]*acadoWorkspace.QDy[34] + acadoWorkspace.evGx[124]*acadoWorkspace.QDy[35] + acadoWorkspace.evGx[128]*acadoWorkspace.QDy[36] + acadoWorkspace.evGx[132]*acadoWorkspace.QDy[37] + acadoWorkspace.evGx[136]*acadoWorkspace.QDy[38] + acadoWorkspace.evGx[140]*acadoWorkspace.QDy[39] + acadoWorkspace.evGx[144]*acadoWorkspace.QDy[40] + acadoWorkspace.evGx[148]*acadoWorkspace.QDy[41] + acadoWorkspace.evGx[152]*acadoWorkspace.QDy[42] + acadoWorkspace.evGx[156]*acadoWorkspace.QDy[43] + acadoWorkspace.evGx[160]*acadoWorkspace.QDy[44] + acadoWorkspace.evGx[164]*acadoWorkspace.QDy[45] + acadoWorkspace.evGx[168]*acadoWorkspace.QDy[46] + acadoWorkspace.evGx[172]*acadoWorkspace.QDy[47] + acadoWorkspace.evGx[176]*acadoWorkspace.QDy[48] + acadoWorkspace.evGx[180]*acadoWorkspace.QDy[49] + acadoWorkspace.evGx[184]*acadoWorkspace.QDy[50] + acadoWorkspace.evGx[188]*acadoWorkspace.QDy[51] + acadoWorkspace.evGx[192]*acadoWorkspace.QDy[52] + acadoWorkspace.evGx[196]*acadoWorkspace.QDy[53] + acadoWorkspace.evGx[200]*acadoWorkspace.QDy[54] + acadoWorkspace.evGx[204]*acadoWorkspace.QDy[55] + acadoWorkspace.evGx[208]*acadoWorkspace.QDy[56] + acadoWorkspace.evGx[212]*acadoWorkspace.QDy[57] + acadoWorkspace.evGx[216]*acadoWorkspace.QDy[58] + acadoWorkspace.evGx[220]*acadoWorkspace.QDy[59] + acadoWorkspace.evGx[224]*acadoWorkspace.QDy[60] + acadoWorkspace.evGx[228]*acadoWorkspace.QDy[61] + acadoWorkspace.evGx[232]*acadoWorkspace.QDy[62] + acadoWorkspace.evGx[236]*acadoWorkspace.QDy[63] + acadoWorkspace.evGx[240]*acadoWorkspace.QDy[64] + acadoWorkspace.evGx[244]*acadoWorkspace.QDy[65] + acadoWorkspace.evGx[248]*acadoWorkspace.QDy[66] + acadoWorkspace.evGx[252]*acadoWorkspace.QDy[67] + acadoWorkspace.evGx[256]*acadoWorkspace.QDy[68] + acadoWorkspace.evGx[260]*acadoWorkspace.QDy[69] + acadoWorkspace.evGx[264]*acadoWorkspace.QDy[70] + acadoWorkspace.evGx[268]*acadoWorkspace.QDy[71] + acadoWorkspace.evGx[272]*acadoWorkspace.QDy[72] + acadoWorkspace.evGx[276]*acadoWorkspace.QDy[73] + acadoWorkspace.evGx[280]*acadoWorkspace.QDy[74] + acadoWorkspace.evGx[284]*acadoWorkspace.QDy[75] + acadoWorkspace.evGx[288]*acadoWorkspace.QDy[76] + acadoWorkspace.evGx[292]*acadoWorkspace.QDy[77] + acadoWorkspace.evGx[296]*acadoWorkspace.QDy[78] + acadoWorkspace.evGx[300]*acadoWorkspace.QDy[79] + acadoWorkspace.evGx[304]*acadoWorkspace.QDy[80] + acadoWorkspace.evGx[308]*acadoWorkspace.QDy[81] + acadoWorkspace.evGx[312]*acadoWorkspace.QDy[82] + acadoWorkspace.evGx[316]*acadoWorkspace.QDy[83]; +acadoWorkspace.g[1] = + acadoWorkspace.evGx[1]*acadoWorkspace.QDy[4] + acadoWorkspace.evGx[5]*acadoWorkspace.QDy[5] + acadoWorkspace.evGx[9]*acadoWorkspace.QDy[6] + acadoWorkspace.evGx[13]*acadoWorkspace.QDy[7] + acadoWorkspace.evGx[17]*acadoWorkspace.QDy[8] + acadoWorkspace.evGx[21]*acadoWorkspace.QDy[9] + acadoWorkspace.evGx[25]*acadoWorkspace.QDy[10] + acadoWorkspace.evGx[29]*acadoWorkspace.QDy[11] + acadoWorkspace.evGx[33]*acadoWorkspace.QDy[12] + acadoWorkspace.evGx[37]*acadoWorkspace.QDy[13] + acadoWorkspace.evGx[41]*acadoWorkspace.QDy[14] + acadoWorkspace.evGx[45]*acadoWorkspace.QDy[15] + acadoWorkspace.evGx[49]*acadoWorkspace.QDy[16] + acadoWorkspace.evGx[53]*acadoWorkspace.QDy[17] + acadoWorkspace.evGx[57]*acadoWorkspace.QDy[18] + acadoWorkspace.evGx[61]*acadoWorkspace.QDy[19] + acadoWorkspace.evGx[65]*acadoWorkspace.QDy[20] + acadoWorkspace.evGx[69]*acadoWorkspace.QDy[21] + acadoWorkspace.evGx[73]*acadoWorkspace.QDy[22] + acadoWorkspace.evGx[77]*acadoWorkspace.QDy[23] + acadoWorkspace.evGx[81]*acadoWorkspace.QDy[24] + acadoWorkspace.evGx[85]*acadoWorkspace.QDy[25] + acadoWorkspace.evGx[89]*acadoWorkspace.QDy[26] + acadoWorkspace.evGx[93]*acadoWorkspace.QDy[27] + acadoWorkspace.evGx[97]*acadoWorkspace.QDy[28] + acadoWorkspace.evGx[101]*acadoWorkspace.QDy[29] + acadoWorkspace.evGx[105]*acadoWorkspace.QDy[30] + acadoWorkspace.evGx[109]*acadoWorkspace.QDy[31] + acadoWorkspace.evGx[113]*acadoWorkspace.QDy[32] + acadoWorkspace.evGx[117]*acadoWorkspace.QDy[33] + acadoWorkspace.evGx[121]*acadoWorkspace.QDy[34] + acadoWorkspace.evGx[125]*acadoWorkspace.QDy[35] + acadoWorkspace.evGx[129]*acadoWorkspace.QDy[36] + acadoWorkspace.evGx[133]*acadoWorkspace.QDy[37] + acadoWorkspace.evGx[137]*acadoWorkspace.QDy[38] + acadoWorkspace.evGx[141]*acadoWorkspace.QDy[39] + acadoWorkspace.evGx[145]*acadoWorkspace.QDy[40] + acadoWorkspace.evGx[149]*acadoWorkspace.QDy[41] + acadoWorkspace.evGx[153]*acadoWorkspace.QDy[42] + acadoWorkspace.evGx[157]*acadoWorkspace.QDy[43] + acadoWorkspace.evGx[161]*acadoWorkspace.QDy[44] + acadoWorkspace.evGx[165]*acadoWorkspace.QDy[45] + acadoWorkspace.evGx[169]*acadoWorkspace.QDy[46] + acadoWorkspace.evGx[173]*acadoWorkspace.QDy[47] + acadoWorkspace.evGx[177]*acadoWorkspace.QDy[48] + acadoWorkspace.evGx[181]*acadoWorkspace.QDy[49] + acadoWorkspace.evGx[185]*acadoWorkspace.QDy[50] + acadoWorkspace.evGx[189]*acadoWorkspace.QDy[51] + acadoWorkspace.evGx[193]*acadoWorkspace.QDy[52] + acadoWorkspace.evGx[197]*acadoWorkspace.QDy[53] + acadoWorkspace.evGx[201]*acadoWorkspace.QDy[54] + acadoWorkspace.evGx[205]*acadoWorkspace.QDy[55] + acadoWorkspace.evGx[209]*acadoWorkspace.QDy[56] + acadoWorkspace.evGx[213]*acadoWorkspace.QDy[57] + acadoWorkspace.evGx[217]*acadoWorkspace.QDy[58] + acadoWorkspace.evGx[221]*acadoWorkspace.QDy[59] + acadoWorkspace.evGx[225]*acadoWorkspace.QDy[60] + acadoWorkspace.evGx[229]*acadoWorkspace.QDy[61] + acadoWorkspace.evGx[233]*acadoWorkspace.QDy[62] + acadoWorkspace.evGx[237]*acadoWorkspace.QDy[63] + acadoWorkspace.evGx[241]*acadoWorkspace.QDy[64] + acadoWorkspace.evGx[245]*acadoWorkspace.QDy[65] + acadoWorkspace.evGx[249]*acadoWorkspace.QDy[66] + acadoWorkspace.evGx[253]*acadoWorkspace.QDy[67] + acadoWorkspace.evGx[257]*acadoWorkspace.QDy[68] + acadoWorkspace.evGx[261]*acadoWorkspace.QDy[69] + acadoWorkspace.evGx[265]*acadoWorkspace.QDy[70] + acadoWorkspace.evGx[269]*acadoWorkspace.QDy[71] + acadoWorkspace.evGx[273]*acadoWorkspace.QDy[72] + acadoWorkspace.evGx[277]*acadoWorkspace.QDy[73] + acadoWorkspace.evGx[281]*acadoWorkspace.QDy[74] + acadoWorkspace.evGx[285]*acadoWorkspace.QDy[75] + acadoWorkspace.evGx[289]*acadoWorkspace.QDy[76] + acadoWorkspace.evGx[293]*acadoWorkspace.QDy[77] + acadoWorkspace.evGx[297]*acadoWorkspace.QDy[78] + acadoWorkspace.evGx[301]*acadoWorkspace.QDy[79] + acadoWorkspace.evGx[305]*acadoWorkspace.QDy[80] + acadoWorkspace.evGx[309]*acadoWorkspace.QDy[81] + acadoWorkspace.evGx[313]*acadoWorkspace.QDy[82] + acadoWorkspace.evGx[317]*acadoWorkspace.QDy[83]; +acadoWorkspace.g[2] = + acadoWorkspace.evGx[2]*acadoWorkspace.QDy[4] + acadoWorkspace.evGx[6]*acadoWorkspace.QDy[5] + acadoWorkspace.evGx[10]*acadoWorkspace.QDy[6] + acadoWorkspace.evGx[14]*acadoWorkspace.QDy[7] + acadoWorkspace.evGx[18]*acadoWorkspace.QDy[8] + acadoWorkspace.evGx[22]*acadoWorkspace.QDy[9] + acadoWorkspace.evGx[26]*acadoWorkspace.QDy[10] + acadoWorkspace.evGx[30]*acadoWorkspace.QDy[11] + acadoWorkspace.evGx[34]*acadoWorkspace.QDy[12] + acadoWorkspace.evGx[38]*acadoWorkspace.QDy[13] + acadoWorkspace.evGx[42]*acadoWorkspace.QDy[14] + acadoWorkspace.evGx[46]*acadoWorkspace.QDy[15] + acadoWorkspace.evGx[50]*acadoWorkspace.QDy[16] + acadoWorkspace.evGx[54]*acadoWorkspace.QDy[17] + acadoWorkspace.evGx[58]*acadoWorkspace.QDy[18] + acadoWorkspace.evGx[62]*acadoWorkspace.QDy[19] + acadoWorkspace.evGx[66]*acadoWorkspace.QDy[20] + acadoWorkspace.evGx[70]*acadoWorkspace.QDy[21] + acadoWorkspace.evGx[74]*acadoWorkspace.QDy[22] + acadoWorkspace.evGx[78]*acadoWorkspace.QDy[23] + acadoWorkspace.evGx[82]*acadoWorkspace.QDy[24] + acadoWorkspace.evGx[86]*acadoWorkspace.QDy[25] + acadoWorkspace.evGx[90]*acadoWorkspace.QDy[26] + acadoWorkspace.evGx[94]*acadoWorkspace.QDy[27] + acadoWorkspace.evGx[98]*acadoWorkspace.QDy[28] + acadoWorkspace.evGx[102]*acadoWorkspace.QDy[29] + acadoWorkspace.evGx[106]*acadoWorkspace.QDy[30] + acadoWorkspace.evGx[110]*acadoWorkspace.QDy[31] + acadoWorkspace.evGx[114]*acadoWorkspace.QDy[32] + acadoWorkspace.evGx[118]*acadoWorkspace.QDy[33] + acadoWorkspace.evGx[122]*acadoWorkspace.QDy[34] + acadoWorkspace.evGx[126]*acadoWorkspace.QDy[35] + acadoWorkspace.evGx[130]*acadoWorkspace.QDy[36] + acadoWorkspace.evGx[134]*acadoWorkspace.QDy[37] + acadoWorkspace.evGx[138]*acadoWorkspace.QDy[38] + acadoWorkspace.evGx[142]*acadoWorkspace.QDy[39] + acadoWorkspace.evGx[146]*acadoWorkspace.QDy[40] + acadoWorkspace.evGx[150]*acadoWorkspace.QDy[41] + acadoWorkspace.evGx[154]*acadoWorkspace.QDy[42] + acadoWorkspace.evGx[158]*acadoWorkspace.QDy[43] + acadoWorkspace.evGx[162]*acadoWorkspace.QDy[44] + acadoWorkspace.evGx[166]*acadoWorkspace.QDy[45] + acadoWorkspace.evGx[170]*acadoWorkspace.QDy[46] + acadoWorkspace.evGx[174]*acadoWorkspace.QDy[47] + acadoWorkspace.evGx[178]*acadoWorkspace.QDy[48] + acadoWorkspace.evGx[182]*acadoWorkspace.QDy[49] + acadoWorkspace.evGx[186]*acadoWorkspace.QDy[50] + acadoWorkspace.evGx[190]*acadoWorkspace.QDy[51] + acadoWorkspace.evGx[194]*acadoWorkspace.QDy[52] + acadoWorkspace.evGx[198]*acadoWorkspace.QDy[53] + acadoWorkspace.evGx[202]*acadoWorkspace.QDy[54] + acadoWorkspace.evGx[206]*acadoWorkspace.QDy[55] + acadoWorkspace.evGx[210]*acadoWorkspace.QDy[56] + acadoWorkspace.evGx[214]*acadoWorkspace.QDy[57] + acadoWorkspace.evGx[218]*acadoWorkspace.QDy[58] + acadoWorkspace.evGx[222]*acadoWorkspace.QDy[59] + acadoWorkspace.evGx[226]*acadoWorkspace.QDy[60] + acadoWorkspace.evGx[230]*acadoWorkspace.QDy[61] + acadoWorkspace.evGx[234]*acadoWorkspace.QDy[62] + acadoWorkspace.evGx[238]*acadoWorkspace.QDy[63] + acadoWorkspace.evGx[242]*acadoWorkspace.QDy[64] + acadoWorkspace.evGx[246]*acadoWorkspace.QDy[65] + acadoWorkspace.evGx[250]*acadoWorkspace.QDy[66] + acadoWorkspace.evGx[254]*acadoWorkspace.QDy[67] + acadoWorkspace.evGx[258]*acadoWorkspace.QDy[68] + acadoWorkspace.evGx[262]*acadoWorkspace.QDy[69] + acadoWorkspace.evGx[266]*acadoWorkspace.QDy[70] + acadoWorkspace.evGx[270]*acadoWorkspace.QDy[71] + acadoWorkspace.evGx[274]*acadoWorkspace.QDy[72] + acadoWorkspace.evGx[278]*acadoWorkspace.QDy[73] + acadoWorkspace.evGx[282]*acadoWorkspace.QDy[74] + acadoWorkspace.evGx[286]*acadoWorkspace.QDy[75] + acadoWorkspace.evGx[290]*acadoWorkspace.QDy[76] + acadoWorkspace.evGx[294]*acadoWorkspace.QDy[77] + acadoWorkspace.evGx[298]*acadoWorkspace.QDy[78] + acadoWorkspace.evGx[302]*acadoWorkspace.QDy[79] + acadoWorkspace.evGx[306]*acadoWorkspace.QDy[80] + acadoWorkspace.evGx[310]*acadoWorkspace.QDy[81] + acadoWorkspace.evGx[314]*acadoWorkspace.QDy[82] + acadoWorkspace.evGx[318]*acadoWorkspace.QDy[83]; +acadoWorkspace.g[3] = + acadoWorkspace.evGx[3]*acadoWorkspace.QDy[4] + acadoWorkspace.evGx[7]*acadoWorkspace.QDy[5] + acadoWorkspace.evGx[11]*acadoWorkspace.QDy[6] + acadoWorkspace.evGx[15]*acadoWorkspace.QDy[7] + acadoWorkspace.evGx[19]*acadoWorkspace.QDy[8] + acadoWorkspace.evGx[23]*acadoWorkspace.QDy[9] + acadoWorkspace.evGx[27]*acadoWorkspace.QDy[10] + acadoWorkspace.evGx[31]*acadoWorkspace.QDy[11] + acadoWorkspace.evGx[35]*acadoWorkspace.QDy[12] + acadoWorkspace.evGx[39]*acadoWorkspace.QDy[13] + acadoWorkspace.evGx[43]*acadoWorkspace.QDy[14] + acadoWorkspace.evGx[47]*acadoWorkspace.QDy[15] + acadoWorkspace.evGx[51]*acadoWorkspace.QDy[16] + acadoWorkspace.evGx[55]*acadoWorkspace.QDy[17] + acadoWorkspace.evGx[59]*acadoWorkspace.QDy[18] + acadoWorkspace.evGx[63]*acadoWorkspace.QDy[19] + acadoWorkspace.evGx[67]*acadoWorkspace.QDy[20] + acadoWorkspace.evGx[71]*acadoWorkspace.QDy[21] + acadoWorkspace.evGx[75]*acadoWorkspace.QDy[22] + acadoWorkspace.evGx[79]*acadoWorkspace.QDy[23] + acadoWorkspace.evGx[83]*acadoWorkspace.QDy[24] + acadoWorkspace.evGx[87]*acadoWorkspace.QDy[25] + acadoWorkspace.evGx[91]*acadoWorkspace.QDy[26] + acadoWorkspace.evGx[95]*acadoWorkspace.QDy[27] + acadoWorkspace.evGx[99]*acadoWorkspace.QDy[28] + acadoWorkspace.evGx[103]*acadoWorkspace.QDy[29] + acadoWorkspace.evGx[107]*acadoWorkspace.QDy[30] + acadoWorkspace.evGx[111]*acadoWorkspace.QDy[31] + acadoWorkspace.evGx[115]*acadoWorkspace.QDy[32] + acadoWorkspace.evGx[119]*acadoWorkspace.QDy[33] + acadoWorkspace.evGx[123]*acadoWorkspace.QDy[34] + acadoWorkspace.evGx[127]*acadoWorkspace.QDy[35] + acadoWorkspace.evGx[131]*acadoWorkspace.QDy[36] + acadoWorkspace.evGx[135]*acadoWorkspace.QDy[37] + acadoWorkspace.evGx[139]*acadoWorkspace.QDy[38] + acadoWorkspace.evGx[143]*acadoWorkspace.QDy[39] + acadoWorkspace.evGx[147]*acadoWorkspace.QDy[40] + acadoWorkspace.evGx[151]*acadoWorkspace.QDy[41] + acadoWorkspace.evGx[155]*acadoWorkspace.QDy[42] + acadoWorkspace.evGx[159]*acadoWorkspace.QDy[43] + acadoWorkspace.evGx[163]*acadoWorkspace.QDy[44] + acadoWorkspace.evGx[167]*acadoWorkspace.QDy[45] + acadoWorkspace.evGx[171]*acadoWorkspace.QDy[46] + acadoWorkspace.evGx[175]*acadoWorkspace.QDy[47] + acadoWorkspace.evGx[179]*acadoWorkspace.QDy[48] + acadoWorkspace.evGx[183]*acadoWorkspace.QDy[49] + acadoWorkspace.evGx[187]*acadoWorkspace.QDy[50] + acadoWorkspace.evGx[191]*acadoWorkspace.QDy[51] + acadoWorkspace.evGx[195]*acadoWorkspace.QDy[52] + acadoWorkspace.evGx[199]*acadoWorkspace.QDy[53] + acadoWorkspace.evGx[203]*acadoWorkspace.QDy[54] + acadoWorkspace.evGx[207]*acadoWorkspace.QDy[55] + acadoWorkspace.evGx[211]*acadoWorkspace.QDy[56] + acadoWorkspace.evGx[215]*acadoWorkspace.QDy[57] + acadoWorkspace.evGx[219]*acadoWorkspace.QDy[58] + acadoWorkspace.evGx[223]*acadoWorkspace.QDy[59] + acadoWorkspace.evGx[227]*acadoWorkspace.QDy[60] + acadoWorkspace.evGx[231]*acadoWorkspace.QDy[61] + acadoWorkspace.evGx[235]*acadoWorkspace.QDy[62] + acadoWorkspace.evGx[239]*acadoWorkspace.QDy[63] + acadoWorkspace.evGx[243]*acadoWorkspace.QDy[64] + acadoWorkspace.evGx[247]*acadoWorkspace.QDy[65] + acadoWorkspace.evGx[251]*acadoWorkspace.QDy[66] + acadoWorkspace.evGx[255]*acadoWorkspace.QDy[67] + acadoWorkspace.evGx[259]*acadoWorkspace.QDy[68] + acadoWorkspace.evGx[263]*acadoWorkspace.QDy[69] + acadoWorkspace.evGx[267]*acadoWorkspace.QDy[70] + acadoWorkspace.evGx[271]*acadoWorkspace.QDy[71] + acadoWorkspace.evGx[275]*acadoWorkspace.QDy[72] + acadoWorkspace.evGx[279]*acadoWorkspace.QDy[73] + acadoWorkspace.evGx[283]*acadoWorkspace.QDy[74] + acadoWorkspace.evGx[287]*acadoWorkspace.QDy[75] + acadoWorkspace.evGx[291]*acadoWorkspace.QDy[76] + acadoWorkspace.evGx[295]*acadoWorkspace.QDy[77] + acadoWorkspace.evGx[299]*acadoWorkspace.QDy[78] + acadoWorkspace.evGx[303]*acadoWorkspace.QDy[79] + acadoWorkspace.evGx[307]*acadoWorkspace.QDy[80] + acadoWorkspace.evGx[311]*acadoWorkspace.QDy[81] + acadoWorkspace.evGx[315]*acadoWorkspace.QDy[82] + acadoWorkspace.evGx[319]*acadoWorkspace.QDy[83]; + + +acado_multEQDy( acadoWorkspace.E, &(acadoWorkspace.QDy[ 4 ]), &(acadoWorkspace.g[ 4 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 4 ]), &(acadoWorkspace.QDy[ 8 ]), &(acadoWorkspace.g[ 4 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 12 ]), &(acadoWorkspace.QDy[ 12 ]), &(acadoWorkspace.g[ 4 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 24 ]), &(acadoWorkspace.QDy[ 16 ]), &(acadoWorkspace.g[ 4 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 40 ]), &(acadoWorkspace.QDy[ 20 ]), &(acadoWorkspace.g[ 4 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 60 ]), &(acadoWorkspace.QDy[ 24 ]), &(acadoWorkspace.g[ 4 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 84 ]), &(acadoWorkspace.QDy[ 28 ]), &(acadoWorkspace.g[ 4 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 112 ]), &(acadoWorkspace.QDy[ 32 ]), &(acadoWorkspace.g[ 4 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 144 ]), &(acadoWorkspace.QDy[ 36 ]), &(acadoWorkspace.g[ 4 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 180 ]), &(acadoWorkspace.QDy[ 40 ]), &(acadoWorkspace.g[ 4 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 220 ]), &(acadoWorkspace.QDy[ 44 ]), &(acadoWorkspace.g[ 4 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 264 ]), &(acadoWorkspace.QDy[ 48 ]), &(acadoWorkspace.g[ 4 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 312 ]), &(acadoWorkspace.QDy[ 52 ]), &(acadoWorkspace.g[ 4 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 364 ]), &(acadoWorkspace.QDy[ 56 ]), &(acadoWorkspace.g[ 4 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 420 ]), &(acadoWorkspace.QDy[ 60 ]), &(acadoWorkspace.g[ 4 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 480 ]), &(acadoWorkspace.QDy[ 64 ]), &(acadoWorkspace.g[ 4 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 544 ]), &(acadoWorkspace.QDy[ 68 ]), &(acadoWorkspace.g[ 4 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 612 ]), &(acadoWorkspace.QDy[ 72 ]), &(acadoWorkspace.g[ 4 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 684 ]), &(acadoWorkspace.QDy[ 76 ]), &(acadoWorkspace.g[ 4 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 760 ]), &(acadoWorkspace.QDy[ 80 ]), &(acadoWorkspace.g[ 4 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 8 ]), &(acadoWorkspace.QDy[ 8 ]), &(acadoWorkspace.g[ 5 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 16 ]), &(acadoWorkspace.QDy[ 12 ]), &(acadoWorkspace.g[ 5 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 28 ]), &(acadoWorkspace.QDy[ 16 ]), &(acadoWorkspace.g[ 5 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 44 ]), &(acadoWorkspace.QDy[ 20 ]), &(acadoWorkspace.g[ 5 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 64 ]), &(acadoWorkspace.QDy[ 24 ]), &(acadoWorkspace.g[ 5 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 88 ]), &(acadoWorkspace.QDy[ 28 ]), &(acadoWorkspace.g[ 5 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 116 ]), &(acadoWorkspace.QDy[ 32 ]), &(acadoWorkspace.g[ 5 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 148 ]), &(acadoWorkspace.QDy[ 36 ]), &(acadoWorkspace.g[ 5 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 184 ]), &(acadoWorkspace.QDy[ 40 ]), &(acadoWorkspace.g[ 5 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 224 ]), &(acadoWorkspace.QDy[ 44 ]), &(acadoWorkspace.g[ 5 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 268 ]), &(acadoWorkspace.QDy[ 48 ]), &(acadoWorkspace.g[ 5 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 316 ]), &(acadoWorkspace.QDy[ 52 ]), &(acadoWorkspace.g[ 5 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 368 ]), &(acadoWorkspace.QDy[ 56 ]), &(acadoWorkspace.g[ 5 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 424 ]), &(acadoWorkspace.QDy[ 60 ]), &(acadoWorkspace.g[ 5 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 484 ]), &(acadoWorkspace.QDy[ 64 ]), &(acadoWorkspace.g[ 5 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 548 ]), &(acadoWorkspace.QDy[ 68 ]), &(acadoWorkspace.g[ 5 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 616 ]), &(acadoWorkspace.QDy[ 72 ]), &(acadoWorkspace.g[ 5 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 688 ]), &(acadoWorkspace.QDy[ 76 ]), &(acadoWorkspace.g[ 5 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 764 ]), &(acadoWorkspace.QDy[ 80 ]), &(acadoWorkspace.g[ 5 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 20 ]), &(acadoWorkspace.QDy[ 12 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 32 ]), &(acadoWorkspace.QDy[ 16 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 48 ]), &(acadoWorkspace.QDy[ 20 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 68 ]), &(acadoWorkspace.QDy[ 24 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 92 ]), &(acadoWorkspace.QDy[ 28 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 120 ]), &(acadoWorkspace.QDy[ 32 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 152 ]), &(acadoWorkspace.QDy[ 36 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 188 ]), &(acadoWorkspace.QDy[ 40 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 228 ]), &(acadoWorkspace.QDy[ 44 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 272 ]), &(acadoWorkspace.QDy[ 48 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 320 ]), &(acadoWorkspace.QDy[ 52 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 372 ]), &(acadoWorkspace.QDy[ 56 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 428 ]), &(acadoWorkspace.QDy[ 60 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 488 ]), &(acadoWorkspace.QDy[ 64 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 552 ]), &(acadoWorkspace.QDy[ 68 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 620 ]), &(acadoWorkspace.QDy[ 72 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 692 ]), &(acadoWorkspace.QDy[ 76 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 768 ]), &(acadoWorkspace.QDy[ 80 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 36 ]), &(acadoWorkspace.QDy[ 16 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 52 ]), &(acadoWorkspace.QDy[ 20 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 72 ]), &(acadoWorkspace.QDy[ 24 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 96 ]), &(acadoWorkspace.QDy[ 28 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 124 ]), &(acadoWorkspace.QDy[ 32 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 156 ]), &(acadoWorkspace.QDy[ 36 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 192 ]), &(acadoWorkspace.QDy[ 40 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 232 ]), &(acadoWorkspace.QDy[ 44 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 276 ]), &(acadoWorkspace.QDy[ 48 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 324 ]), &(acadoWorkspace.QDy[ 52 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 376 ]), &(acadoWorkspace.QDy[ 56 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 432 ]), &(acadoWorkspace.QDy[ 60 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 492 ]), &(acadoWorkspace.QDy[ 64 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 556 ]), &(acadoWorkspace.QDy[ 68 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 624 ]), &(acadoWorkspace.QDy[ 72 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 696 ]), &(acadoWorkspace.QDy[ 76 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 772 ]), &(acadoWorkspace.QDy[ 80 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 56 ]), &(acadoWorkspace.QDy[ 20 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 76 ]), &(acadoWorkspace.QDy[ 24 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 100 ]), &(acadoWorkspace.QDy[ 28 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 128 ]), &(acadoWorkspace.QDy[ 32 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 160 ]), &(acadoWorkspace.QDy[ 36 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 196 ]), &(acadoWorkspace.QDy[ 40 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 236 ]), &(acadoWorkspace.QDy[ 44 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 280 ]), &(acadoWorkspace.QDy[ 48 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 328 ]), &(acadoWorkspace.QDy[ 52 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 380 ]), &(acadoWorkspace.QDy[ 56 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 436 ]), &(acadoWorkspace.QDy[ 60 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 496 ]), &(acadoWorkspace.QDy[ 64 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 560 ]), &(acadoWorkspace.QDy[ 68 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 628 ]), &(acadoWorkspace.QDy[ 72 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 700 ]), &(acadoWorkspace.QDy[ 76 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 776 ]), &(acadoWorkspace.QDy[ 80 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 80 ]), &(acadoWorkspace.QDy[ 24 ]), &(acadoWorkspace.g[ 9 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 104 ]), &(acadoWorkspace.QDy[ 28 ]), &(acadoWorkspace.g[ 9 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 132 ]), &(acadoWorkspace.QDy[ 32 ]), &(acadoWorkspace.g[ 9 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 164 ]), &(acadoWorkspace.QDy[ 36 ]), &(acadoWorkspace.g[ 9 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 200 ]), &(acadoWorkspace.QDy[ 40 ]), &(acadoWorkspace.g[ 9 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 240 ]), &(acadoWorkspace.QDy[ 44 ]), &(acadoWorkspace.g[ 9 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 284 ]), &(acadoWorkspace.QDy[ 48 ]), &(acadoWorkspace.g[ 9 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 332 ]), &(acadoWorkspace.QDy[ 52 ]), &(acadoWorkspace.g[ 9 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 384 ]), &(acadoWorkspace.QDy[ 56 ]), &(acadoWorkspace.g[ 9 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 440 ]), &(acadoWorkspace.QDy[ 60 ]), &(acadoWorkspace.g[ 9 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 500 ]), &(acadoWorkspace.QDy[ 64 ]), &(acadoWorkspace.g[ 9 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 564 ]), &(acadoWorkspace.QDy[ 68 ]), &(acadoWorkspace.g[ 9 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 632 ]), &(acadoWorkspace.QDy[ 72 ]), &(acadoWorkspace.g[ 9 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 704 ]), &(acadoWorkspace.QDy[ 76 ]), &(acadoWorkspace.g[ 9 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 780 ]), &(acadoWorkspace.QDy[ 80 ]), &(acadoWorkspace.g[ 9 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 108 ]), &(acadoWorkspace.QDy[ 28 ]), &(acadoWorkspace.g[ 10 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 136 ]), &(acadoWorkspace.QDy[ 32 ]), &(acadoWorkspace.g[ 10 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 168 ]), &(acadoWorkspace.QDy[ 36 ]), &(acadoWorkspace.g[ 10 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 204 ]), &(acadoWorkspace.QDy[ 40 ]), &(acadoWorkspace.g[ 10 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 244 ]), &(acadoWorkspace.QDy[ 44 ]), &(acadoWorkspace.g[ 10 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 288 ]), &(acadoWorkspace.QDy[ 48 ]), &(acadoWorkspace.g[ 10 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 336 ]), &(acadoWorkspace.QDy[ 52 ]), &(acadoWorkspace.g[ 10 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 388 ]), &(acadoWorkspace.QDy[ 56 ]), &(acadoWorkspace.g[ 10 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 444 ]), &(acadoWorkspace.QDy[ 60 ]), &(acadoWorkspace.g[ 10 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 504 ]), &(acadoWorkspace.QDy[ 64 ]), &(acadoWorkspace.g[ 10 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 568 ]), &(acadoWorkspace.QDy[ 68 ]), &(acadoWorkspace.g[ 10 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 636 ]), &(acadoWorkspace.QDy[ 72 ]), &(acadoWorkspace.g[ 10 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 708 ]), &(acadoWorkspace.QDy[ 76 ]), &(acadoWorkspace.g[ 10 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 784 ]), &(acadoWorkspace.QDy[ 80 ]), &(acadoWorkspace.g[ 10 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 140 ]), &(acadoWorkspace.QDy[ 32 ]), &(acadoWorkspace.g[ 11 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 172 ]), &(acadoWorkspace.QDy[ 36 ]), &(acadoWorkspace.g[ 11 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 208 ]), &(acadoWorkspace.QDy[ 40 ]), &(acadoWorkspace.g[ 11 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 248 ]), &(acadoWorkspace.QDy[ 44 ]), &(acadoWorkspace.g[ 11 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 292 ]), &(acadoWorkspace.QDy[ 48 ]), &(acadoWorkspace.g[ 11 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 340 ]), &(acadoWorkspace.QDy[ 52 ]), &(acadoWorkspace.g[ 11 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 392 ]), &(acadoWorkspace.QDy[ 56 ]), &(acadoWorkspace.g[ 11 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 448 ]), &(acadoWorkspace.QDy[ 60 ]), &(acadoWorkspace.g[ 11 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 508 ]), &(acadoWorkspace.QDy[ 64 ]), &(acadoWorkspace.g[ 11 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 572 ]), &(acadoWorkspace.QDy[ 68 ]), &(acadoWorkspace.g[ 11 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 640 ]), &(acadoWorkspace.QDy[ 72 ]), &(acadoWorkspace.g[ 11 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 712 ]), &(acadoWorkspace.QDy[ 76 ]), &(acadoWorkspace.g[ 11 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 788 ]), &(acadoWorkspace.QDy[ 80 ]), &(acadoWorkspace.g[ 11 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 176 ]), &(acadoWorkspace.QDy[ 36 ]), &(acadoWorkspace.g[ 12 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 212 ]), &(acadoWorkspace.QDy[ 40 ]), &(acadoWorkspace.g[ 12 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 252 ]), &(acadoWorkspace.QDy[ 44 ]), &(acadoWorkspace.g[ 12 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 296 ]), &(acadoWorkspace.QDy[ 48 ]), &(acadoWorkspace.g[ 12 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 344 ]), &(acadoWorkspace.QDy[ 52 ]), &(acadoWorkspace.g[ 12 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 396 ]), &(acadoWorkspace.QDy[ 56 ]), &(acadoWorkspace.g[ 12 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 452 ]), &(acadoWorkspace.QDy[ 60 ]), &(acadoWorkspace.g[ 12 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 512 ]), &(acadoWorkspace.QDy[ 64 ]), &(acadoWorkspace.g[ 12 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 576 ]), &(acadoWorkspace.QDy[ 68 ]), &(acadoWorkspace.g[ 12 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 644 ]), &(acadoWorkspace.QDy[ 72 ]), &(acadoWorkspace.g[ 12 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 716 ]), &(acadoWorkspace.QDy[ 76 ]), &(acadoWorkspace.g[ 12 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 792 ]), &(acadoWorkspace.QDy[ 80 ]), &(acadoWorkspace.g[ 12 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 216 ]), &(acadoWorkspace.QDy[ 40 ]), &(acadoWorkspace.g[ 13 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 256 ]), &(acadoWorkspace.QDy[ 44 ]), &(acadoWorkspace.g[ 13 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 300 ]), &(acadoWorkspace.QDy[ 48 ]), &(acadoWorkspace.g[ 13 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 348 ]), &(acadoWorkspace.QDy[ 52 ]), &(acadoWorkspace.g[ 13 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 400 ]), &(acadoWorkspace.QDy[ 56 ]), &(acadoWorkspace.g[ 13 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 456 ]), &(acadoWorkspace.QDy[ 60 ]), &(acadoWorkspace.g[ 13 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 516 ]), &(acadoWorkspace.QDy[ 64 ]), &(acadoWorkspace.g[ 13 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 580 ]), &(acadoWorkspace.QDy[ 68 ]), &(acadoWorkspace.g[ 13 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 648 ]), &(acadoWorkspace.QDy[ 72 ]), &(acadoWorkspace.g[ 13 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 720 ]), &(acadoWorkspace.QDy[ 76 ]), &(acadoWorkspace.g[ 13 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 796 ]), &(acadoWorkspace.QDy[ 80 ]), &(acadoWorkspace.g[ 13 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 260 ]), &(acadoWorkspace.QDy[ 44 ]), &(acadoWorkspace.g[ 14 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 304 ]), &(acadoWorkspace.QDy[ 48 ]), &(acadoWorkspace.g[ 14 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 352 ]), &(acadoWorkspace.QDy[ 52 ]), &(acadoWorkspace.g[ 14 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 404 ]), &(acadoWorkspace.QDy[ 56 ]), &(acadoWorkspace.g[ 14 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 460 ]), &(acadoWorkspace.QDy[ 60 ]), &(acadoWorkspace.g[ 14 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 520 ]), &(acadoWorkspace.QDy[ 64 ]), &(acadoWorkspace.g[ 14 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 584 ]), &(acadoWorkspace.QDy[ 68 ]), &(acadoWorkspace.g[ 14 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 652 ]), &(acadoWorkspace.QDy[ 72 ]), &(acadoWorkspace.g[ 14 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 724 ]), &(acadoWorkspace.QDy[ 76 ]), &(acadoWorkspace.g[ 14 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 800 ]), &(acadoWorkspace.QDy[ 80 ]), &(acadoWorkspace.g[ 14 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 308 ]), &(acadoWorkspace.QDy[ 48 ]), &(acadoWorkspace.g[ 15 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 356 ]), &(acadoWorkspace.QDy[ 52 ]), &(acadoWorkspace.g[ 15 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 408 ]), &(acadoWorkspace.QDy[ 56 ]), &(acadoWorkspace.g[ 15 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 464 ]), &(acadoWorkspace.QDy[ 60 ]), &(acadoWorkspace.g[ 15 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 524 ]), &(acadoWorkspace.QDy[ 64 ]), &(acadoWorkspace.g[ 15 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 588 ]), &(acadoWorkspace.QDy[ 68 ]), &(acadoWorkspace.g[ 15 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 656 ]), &(acadoWorkspace.QDy[ 72 ]), &(acadoWorkspace.g[ 15 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 728 ]), &(acadoWorkspace.QDy[ 76 ]), &(acadoWorkspace.g[ 15 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 804 ]), &(acadoWorkspace.QDy[ 80 ]), &(acadoWorkspace.g[ 15 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 360 ]), &(acadoWorkspace.QDy[ 52 ]), &(acadoWorkspace.g[ 16 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 412 ]), &(acadoWorkspace.QDy[ 56 ]), &(acadoWorkspace.g[ 16 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 468 ]), &(acadoWorkspace.QDy[ 60 ]), &(acadoWorkspace.g[ 16 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 528 ]), &(acadoWorkspace.QDy[ 64 ]), &(acadoWorkspace.g[ 16 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 592 ]), &(acadoWorkspace.QDy[ 68 ]), &(acadoWorkspace.g[ 16 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 660 ]), &(acadoWorkspace.QDy[ 72 ]), &(acadoWorkspace.g[ 16 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 732 ]), &(acadoWorkspace.QDy[ 76 ]), &(acadoWorkspace.g[ 16 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 808 ]), &(acadoWorkspace.QDy[ 80 ]), &(acadoWorkspace.g[ 16 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 416 ]), &(acadoWorkspace.QDy[ 56 ]), &(acadoWorkspace.g[ 17 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 472 ]), &(acadoWorkspace.QDy[ 60 ]), &(acadoWorkspace.g[ 17 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 532 ]), &(acadoWorkspace.QDy[ 64 ]), &(acadoWorkspace.g[ 17 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 596 ]), &(acadoWorkspace.QDy[ 68 ]), &(acadoWorkspace.g[ 17 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 664 ]), &(acadoWorkspace.QDy[ 72 ]), &(acadoWorkspace.g[ 17 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 736 ]), &(acadoWorkspace.QDy[ 76 ]), &(acadoWorkspace.g[ 17 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 812 ]), &(acadoWorkspace.QDy[ 80 ]), &(acadoWorkspace.g[ 17 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 476 ]), &(acadoWorkspace.QDy[ 60 ]), &(acadoWorkspace.g[ 18 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 536 ]), &(acadoWorkspace.QDy[ 64 ]), &(acadoWorkspace.g[ 18 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 600 ]), &(acadoWorkspace.QDy[ 68 ]), &(acadoWorkspace.g[ 18 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 668 ]), &(acadoWorkspace.QDy[ 72 ]), &(acadoWorkspace.g[ 18 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 740 ]), &(acadoWorkspace.QDy[ 76 ]), &(acadoWorkspace.g[ 18 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 816 ]), &(acadoWorkspace.QDy[ 80 ]), &(acadoWorkspace.g[ 18 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 540 ]), &(acadoWorkspace.QDy[ 64 ]), &(acadoWorkspace.g[ 19 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 604 ]), &(acadoWorkspace.QDy[ 68 ]), &(acadoWorkspace.g[ 19 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 672 ]), &(acadoWorkspace.QDy[ 72 ]), &(acadoWorkspace.g[ 19 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 744 ]), &(acadoWorkspace.QDy[ 76 ]), &(acadoWorkspace.g[ 19 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 820 ]), &(acadoWorkspace.QDy[ 80 ]), &(acadoWorkspace.g[ 19 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 608 ]), &(acadoWorkspace.QDy[ 68 ]), &(acadoWorkspace.g[ 20 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 676 ]), &(acadoWorkspace.QDy[ 72 ]), &(acadoWorkspace.g[ 20 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 748 ]), &(acadoWorkspace.QDy[ 76 ]), &(acadoWorkspace.g[ 20 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 824 ]), &(acadoWorkspace.QDy[ 80 ]), &(acadoWorkspace.g[ 20 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 680 ]), &(acadoWorkspace.QDy[ 72 ]), &(acadoWorkspace.g[ 21 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 752 ]), &(acadoWorkspace.QDy[ 76 ]), &(acadoWorkspace.g[ 21 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 828 ]), &(acadoWorkspace.QDy[ 80 ]), &(acadoWorkspace.g[ 21 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 756 ]), &(acadoWorkspace.QDy[ 76 ]), &(acadoWorkspace.g[ 22 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 832 ]), &(acadoWorkspace.QDy[ 80 ]), &(acadoWorkspace.g[ 22 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 836 ]), &(acadoWorkspace.QDy[ 80 ]), &(acadoWorkspace.g[ 23 ]) ); + +acadoWorkspace.lb[0] = acadoWorkspace.Dx0[0]; +acadoWorkspace.lb[1] = acadoWorkspace.Dx0[1]; +acadoWorkspace.lb[2] = acadoWorkspace.Dx0[2]; +acadoWorkspace.lb[3] = acadoWorkspace.Dx0[3]; +acadoWorkspace.ub[0] = acadoWorkspace.Dx0[0]; +acadoWorkspace.ub[1] = acadoWorkspace.Dx0[1]; +acadoWorkspace.ub[2] = acadoWorkspace.Dx0[2]; +acadoWorkspace.ub[3] = acadoWorkspace.Dx0[3]; +tmp = acadoVariables.x[6] + acadoWorkspace.d[2]; +acadoWorkspace.lbA[0] = (real_t)-1.5707963268000000e+00 - tmp; +acadoWorkspace.ubA[0] = (real_t)1.5707963268000000e+00 - tmp; +tmp = acadoVariables.x[7] + acadoWorkspace.d[3]; +acadoWorkspace.lbA[1] = (real_t)-8.7266462600000005e-01 - tmp; +acadoWorkspace.ubA[1] = (real_t)8.7266462600000005e-01 - tmp; +tmp = acadoVariables.x[10] + acadoWorkspace.d[6]; +acadoWorkspace.lbA[2] = (real_t)-1.5707963268000000e+00 - tmp; +acadoWorkspace.ubA[2] = (real_t)1.5707963268000000e+00 - tmp; +tmp = acadoVariables.x[11] + acadoWorkspace.d[7]; +acadoWorkspace.lbA[3] = (real_t)-8.7266462600000005e-01 - tmp; +acadoWorkspace.ubA[3] = (real_t)8.7266462600000005e-01 - tmp; +tmp = acadoVariables.x[14] + acadoWorkspace.d[10]; +acadoWorkspace.lbA[4] = (real_t)-1.5707963268000000e+00 - tmp; +acadoWorkspace.ubA[4] = (real_t)1.5707963268000000e+00 - tmp; +tmp = acadoVariables.x[15] + acadoWorkspace.d[11]; +acadoWorkspace.lbA[5] = (real_t)-8.7266462600000005e-01 - tmp; +acadoWorkspace.ubA[5] = (real_t)8.7266462600000005e-01 - tmp; +tmp = acadoVariables.x[18] + acadoWorkspace.d[14]; +acadoWorkspace.lbA[6] = (real_t)-1.5707963268000000e+00 - tmp; +acadoWorkspace.ubA[6] = (real_t)1.5707963268000000e+00 - tmp; +tmp = acadoVariables.x[19] + acadoWorkspace.d[15]; +acadoWorkspace.lbA[7] = (real_t)-8.7266462600000005e-01 - tmp; +acadoWorkspace.ubA[7] = (real_t)8.7266462600000005e-01 - tmp; +tmp = acadoVariables.x[22] + acadoWorkspace.d[18]; +acadoWorkspace.lbA[8] = (real_t)-1.5707963268000000e+00 - tmp; +acadoWorkspace.ubA[8] = (real_t)1.5707963268000000e+00 - tmp; +tmp = acadoVariables.x[23] + acadoWorkspace.d[19]; +acadoWorkspace.lbA[9] = (real_t)-8.7266462600000005e-01 - tmp; +acadoWorkspace.ubA[9] = (real_t)8.7266462600000005e-01 - tmp; +tmp = acadoVariables.x[26] + acadoWorkspace.d[22]; +acadoWorkspace.lbA[10] = (real_t)-1.5707963268000000e+00 - tmp; +acadoWorkspace.ubA[10] = (real_t)1.5707963268000000e+00 - tmp; +tmp = acadoVariables.x[27] + acadoWorkspace.d[23]; +acadoWorkspace.lbA[11] = (real_t)-8.7266462600000005e-01 - tmp; +acadoWorkspace.ubA[11] = (real_t)8.7266462600000005e-01 - tmp; +tmp = acadoVariables.x[30] + acadoWorkspace.d[26]; +acadoWorkspace.lbA[12] = (real_t)-1.5707963268000000e+00 - tmp; +acadoWorkspace.ubA[12] = (real_t)1.5707963268000000e+00 - tmp; +tmp = acadoVariables.x[31] + acadoWorkspace.d[27]; +acadoWorkspace.lbA[13] = (real_t)-8.7266462600000005e-01 - tmp; +acadoWorkspace.ubA[13] = (real_t)8.7266462600000005e-01 - tmp; +tmp = acadoVariables.x[34] + acadoWorkspace.d[30]; +acadoWorkspace.lbA[14] = (real_t)-1.5707963268000000e+00 - tmp; +acadoWorkspace.ubA[14] = (real_t)1.5707963268000000e+00 - tmp; +tmp = acadoVariables.x[35] + acadoWorkspace.d[31]; +acadoWorkspace.lbA[15] = (real_t)-8.7266462600000005e-01 - tmp; +acadoWorkspace.ubA[15] = (real_t)8.7266462600000005e-01 - tmp; +tmp = acadoVariables.x[38] + acadoWorkspace.d[34]; +acadoWorkspace.lbA[16] = (real_t)-1.5707963268000000e+00 - tmp; +acadoWorkspace.ubA[16] = (real_t)1.5707963268000000e+00 - tmp; +tmp = acadoVariables.x[39] + acadoWorkspace.d[35]; +acadoWorkspace.lbA[17] = (real_t)-8.7266462600000005e-01 - tmp; +acadoWorkspace.ubA[17] = (real_t)8.7266462600000005e-01 - tmp; +tmp = acadoVariables.x[42] + acadoWorkspace.d[38]; +acadoWorkspace.lbA[18] = (real_t)-1.5707963268000000e+00 - tmp; +acadoWorkspace.ubA[18] = (real_t)1.5707963268000000e+00 - tmp; +tmp = acadoVariables.x[43] + acadoWorkspace.d[39]; +acadoWorkspace.lbA[19] = (real_t)-8.7266462600000005e-01 - tmp; +acadoWorkspace.ubA[19] = (real_t)8.7266462600000005e-01 - tmp; +tmp = acadoVariables.x[46] + acadoWorkspace.d[42]; +acadoWorkspace.lbA[20] = (real_t)-1.5707963268000000e+00 - tmp; +acadoWorkspace.ubA[20] = (real_t)1.5707963268000000e+00 - tmp; +tmp = acadoVariables.x[47] + acadoWorkspace.d[43]; +acadoWorkspace.lbA[21] = (real_t)-8.7266462600000005e-01 - tmp; +acadoWorkspace.ubA[21] = (real_t)8.7266462600000005e-01 - tmp; +tmp = acadoVariables.x[50] + acadoWorkspace.d[46]; +acadoWorkspace.lbA[22] = (real_t)-1.5707963268000000e+00 - tmp; +acadoWorkspace.ubA[22] = (real_t)1.5707963268000000e+00 - tmp; +tmp = acadoVariables.x[51] + acadoWorkspace.d[47]; +acadoWorkspace.lbA[23] = (real_t)-8.7266462600000005e-01 - tmp; +acadoWorkspace.ubA[23] = (real_t)8.7266462600000005e-01 - tmp; +tmp = acadoVariables.x[54] + acadoWorkspace.d[50]; +acadoWorkspace.lbA[24] = (real_t)-1.5707963268000000e+00 - tmp; +acadoWorkspace.ubA[24] = (real_t)1.5707963268000000e+00 - tmp; +tmp = acadoVariables.x[55] + acadoWorkspace.d[51]; +acadoWorkspace.lbA[25] = (real_t)-8.7266462600000005e-01 - tmp; +acadoWorkspace.ubA[25] = (real_t)8.7266462600000005e-01 - tmp; +tmp = acadoVariables.x[58] + acadoWorkspace.d[54]; +acadoWorkspace.lbA[26] = (real_t)-1.5707963268000000e+00 - tmp; +acadoWorkspace.ubA[26] = (real_t)1.5707963268000000e+00 - tmp; +tmp = acadoVariables.x[59] + acadoWorkspace.d[55]; +acadoWorkspace.lbA[27] = (real_t)-8.7266462600000005e-01 - tmp; +acadoWorkspace.ubA[27] = (real_t)8.7266462600000005e-01 - tmp; +tmp = acadoVariables.x[62] + acadoWorkspace.d[58]; +acadoWorkspace.lbA[28] = (real_t)-1.5707963268000000e+00 - tmp; +acadoWorkspace.ubA[28] = (real_t)1.5707963268000000e+00 - tmp; +tmp = acadoVariables.x[63] + acadoWorkspace.d[59]; +acadoWorkspace.lbA[29] = (real_t)-8.7266462600000005e-01 - tmp; +acadoWorkspace.ubA[29] = (real_t)8.7266462600000005e-01 - tmp; +tmp = acadoVariables.x[66] + acadoWorkspace.d[62]; +acadoWorkspace.lbA[30] = (real_t)-1.5707963268000000e+00 - tmp; +acadoWorkspace.ubA[30] = (real_t)1.5707963268000000e+00 - tmp; +tmp = acadoVariables.x[67] + acadoWorkspace.d[63]; +acadoWorkspace.lbA[31] = (real_t)-8.7266462600000005e-01 - tmp; +acadoWorkspace.ubA[31] = (real_t)8.7266462600000005e-01 - tmp; +tmp = acadoVariables.x[70] + acadoWorkspace.d[66]; +acadoWorkspace.lbA[32] = (real_t)-1.5707963268000000e+00 - tmp; +acadoWorkspace.ubA[32] = (real_t)1.5707963268000000e+00 - tmp; +tmp = acadoVariables.x[71] + acadoWorkspace.d[67]; +acadoWorkspace.lbA[33] = (real_t)-8.7266462600000005e-01 - tmp; +acadoWorkspace.ubA[33] = (real_t)8.7266462600000005e-01 - tmp; +tmp = acadoVariables.x[74] + acadoWorkspace.d[70]; +acadoWorkspace.lbA[34] = (real_t)-1.5707963268000000e+00 - tmp; +acadoWorkspace.ubA[34] = (real_t)1.5707963268000000e+00 - tmp; +tmp = acadoVariables.x[75] + acadoWorkspace.d[71]; +acadoWorkspace.lbA[35] = (real_t)-8.7266462600000005e-01 - tmp; +acadoWorkspace.ubA[35] = (real_t)8.7266462600000005e-01 - tmp; +tmp = acadoVariables.x[78] + acadoWorkspace.d[74]; +acadoWorkspace.lbA[36] = (real_t)-1.5707963268000000e+00 - tmp; +acadoWorkspace.ubA[36] = (real_t)1.5707963268000000e+00 - tmp; +tmp = acadoVariables.x[79] + acadoWorkspace.d[75]; +acadoWorkspace.lbA[37] = (real_t)-8.7266462600000005e-01 - tmp; +acadoWorkspace.ubA[37] = (real_t)8.7266462600000005e-01 - tmp; +tmp = acadoVariables.x[82] + acadoWorkspace.d[78]; +acadoWorkspace.lbA[38] = (real_t)-1.5707963268000000e+00 - tmp; +acadoWorkspace.ubA[38] = (real_t)1.5707963268000000e+00 - tmp; +tmp = acadoVariables.x[83] + acadoWorkspace.d[79]; +acadoWorkspace.lbA[39] = (real_t)-8.7266462600000005e-01 - tmp; +acadoWorkspace.ubA[39] = (real_t)8.7266462600000005e-01 - tmp; + +} + +void acado_expand( ) +{ +acadoVariables.x[0] += acadoWorkspace.x[0]; +acadoVariables.x[1] += acadoWorkspace.x[1]; +acadoVariables.x[2] += acadoWorkspace.x[2]; +acadoVariables.x[3] += acadoWorkspace.x[3]; + +acadoVariables.u[0] += acadoWorkspace.x[4]; +acadoVariables.u[1] += acadoWorkspace.x[5]; +acadoVariables.u[2] += acadoWorkspace.x[6]; +acadoVariables.u[3] += acadoWorkspace.x[7]; +acadoVariables.u[4] += acadoWorkspace.x[8]; +acadoVariables.u[5] += acadoWorkspace.x[9]; +acadoVariables.u[6] += acadoWorkspace.x[10]; +acadoVariables.u[7] += acadoWorkspace.x[11]; +acadoVariables.u[8] += acadoWorkspace.x[12]; +acadoVariables.u[9] += acadoWorkspace.x[13]; +acadoVariables.u[10] += acadoWorkspace.x[14]; +acadoVariables.u[11] += acadoWorkspace.x[15]; +acadoVariables.u[12] += acadoWorkspace.x[16]; +acadoVariables.u[13] += acadoWorkspace.x[17]; +acadoVariables.u[14] += acadoWorkspace.x[18]; +acadoVariables.u[15] += acadoWorkspace.x[19]; +acadoVariables.u[16] += acadoWorkspace.x[20]; +acadoVariables.u[17] += acadoWorkspace.x[21]; +acadoVariables.u[18] += acadoWorkspace.x[22]; +acadoVariables.u[19] += acadoWorkspace.x[23]; + +acadoVariables.x[4] += + acadoWorkspace.evGx[0]*acadoWorkspace.x[0] + acadoWorkspace.evGx[1]*acadoWorkspace.x[1] + acadoWorkspace.evGx[2]*acadoWorkspace.x[2] + acadoWorkspace.evGx[3]*acadoWorkspace.x[3] + acadoWorkspace.d[0]; +acadoVariables.x[5] += + acadoWorkspace.evGx[4]*acadoWorkspace.x[0] + acadoWorkspace.evGx[5]*acadoWorkspace.x[1] + acadoWorkspace.evGx[6]*acadoWorkspace.x[2] + acadoWorkspace.evGx[7]*acadoWorkspace.x[3] + acadoWorkspace.d[1]; +acadoVariables.x[6] += + acadoWorkspace.evGx[8]*acadoWorkspace.x[0] + acadoWorkspace.evGx[9]*acadoWorkspace.x[1] + acadoWorkspace.evGx[10]*acadoWorkspace.x[2] + acadoWorkspace.evGx[11]*acadoWorkspace.x[3] + acadoWorkspace.d[2]; +acadoVariables.x[7] += + acadoWorkspace.evGx[12]*acadoWorkspace.x[0] + acadoWorkspace.evGx[13]*acadoWorkspace.x[1] + acadoWorkspace.evGx[14]*acadoWorkspace.x[2] + acadoWorkspace.evGx[15]*acadoWorkspace.x[3] + acadoWorkspace.d[3]; +acadoVariables.x[8] += + acadoWorkspace.evGx[16]*acadoWorkspace.x[0] + acadoWorkspace.evGx[17]*acadoWorkspace.x[1] + acadoWorkspace.evGx[18]*acadoWorkspace.x[2] + acadoWorkspace.evGx[19]*acadoWorkspace.x[3] + acadoWorkspace.d[4]; +acadoVariables.x[9] += + acadoWorkspace.evGx[20]*acadoWorkspace.x[0] + acadoWorkspace.evGx[21]*acadoWorkspace.x[1] + acadoWorkspace.evGx[22]*acadoWorkspace.x[2] + acadoWorkspace.evGx[23]*acadoWorkspace.x[3] + acadoWorkspace.d[5]; +acadoVariables.x[10] += + acadoWorkspace.evGx[24]*acadoWorkspace.x[0] + acadoWorkspace.evGx[25]*acadoWorkspace.x[1] + acadoWorkspace.evGx[26]*acadoWorkspace.x[2] + acadoWorkspace.evGx[27]*acadoWorkspace.x[3] + acadoWorkspace.d[6]; +acadoVariables.x[11] += + acadoWorkspace.evGx[28]*acadoWorkspace.x[0] + acadoWorkspace.evGx[29]*acadoWorkspace.x[1] + acadoWorkspace.evGx[30]*acadoWorkspace.x[2] + acadoWorkspace.evGx[31]*acadoWorkspace.x[3] + acadoWorkspace.d[7]; +acadoVariables.x[12] += + acadoWorkspace.evGx[32]*acadoWorkspace.x[0] + acadoWorkspace.evGx[33]*acadoWorkspace.x[1] + acadoWorkspace.evGx[34]*acadoWorkspace.x[2] + acadoWorkspace.evGx[35]*acadoWorkspace.x[3] + acadoWorkspace.d[8]; +acadoVariables.x[13] += + acadoWorkspace.evGx[36]*acadoWorkspace.x[0] + acadoWorkspace.evGx[37]*acadoWorkspace.x[1] + acadoWorkspace.evGx[38]*acadoWorkspace.x[2] + acadoWorkspace.evGx[39]*acadoWorkspace.x[3] + acadoWorkspace.d[9]; +acadoVariables.x[14] += + acadoWorkspace.evGx[40]*acadoWorkspace.x[0] + acadoWorkspace.evGx[41]*acadoWorkspace.x[1] + acadoWorkspace.evGx[42]*acadoWorkspace.x[2] + acadoWorkspace.evGx[43]*acadoWorkspace.x[3] + acadoWorkspace.d[10]; +acadoVariables.x[15] += + acadoWorkspace.evGx[44]*acadoWorkspace.x[0] + acadoWorkspace.evGx[45]*acadoWorkspace.x[1] + acadoWorkspace.evGx[46]*acadoWorkspace.x[2] + acadoWorkspace.evGx[47]*acadoWorkspace.x[3] + acadoWorkspace.d[11]; +acadoVariables.x[16] += + acadoWorkspace.evGx[48]*acadoWorkspace.x[0] + acadoWorkspace.evGx[49]*acadoWorkspace.x[1] + acadoWorkspace.evGx[50]*acadoWorkspace.x[2] + acadoWorkspace.evGx[51]*acadoWorkspace.x[3] + acadoWorkspace.d[12]; +acadoVariables.x[17] += + acadoWorkspace.evGx[52]*acadoWorkspace.x[0] + acadoWorkspace.evGx[53]*acadoWorkspace.x[1] + acadoWorkspace.evGx[54]*acadoWorkspace.x[2] + acadoWorkspace.evGx[55]*acadoWorkspace.x[3] + acadoWorkspace.d[13]; +acadoVariables.x[18] += + acadoWorkspace.evGx[56]*acadoWorkspace.x[0] + acadoWorkspace.evGx[57]*acadoWorkspace.x[1] + acadoWorkspace.evGx[58]*acadoWorkspace.x[2] + acadoWorkspace.evGx[59]*acadoWorkspace.x[3] + acadoWorkspace.d[14]; +acadoVariables.x[19] += + acadoWorkspace.evGx[60]*acadoWorkspace.x[0] + acadoWorkspace.evGx[61]*acadoWorkspace.x[1] + acadoWorkspace.evGx[62]*acadoWorkspace.x[2] + acadoWorkspace.evGx[63]*acadoWorkspace.x[3] + acadoWorkspace.d[15]; +acadoVariables.x[20] += + acadoWorkspace.evGx[64]*acadoWorkspace.x[0] + acadoWorkspace.evGx[65]*acadoWorkspace.x[1] + acadoWorkspace.evGx[66]*acadoWorkspace.x[2] + acadoWorkspace.evGx[67]*acadoWorkspace.x[3] + acadoWorkspace.d[16]; +acadoVariables.x[21] += + acadoWorkspace.evGx[68]*acadoWorkspace.x[0] + acadoWorkspace.evGx[69]*acadoWorkspace.x[1] + acadoWorkspace.evGx[70]*acadoWorkspace.x[2] + acadoWorkspace.evGx[71]*acadoWorkspace.x[3] + acadoWorkspace.d[17]; +acadoVariables.x[22] += + acadoWorkspace.evGx[72]*acadoWorkspace.x[0] + acadoWorkspace.evGx[73]*acadoWorkspace.x[1] + acadoWorkspace.evGx[74]*acadoWorkspace.x[2] + acadoWorkspace.evGx[75]*acadoWorkspace.x[3] + acadoWorkspace.d[18]; +acadoVariables.x[23] += + acadoWorkspace.evGx[76]*acadoWorkspace.x[0] + acadoWorkspace.evGx[77]*acadoWorkspace.x[1] + acadoWorkspace.evGx[78]*acadoWorkspace.x[2] + acadoWorkspace.evGx[79]*acadoWorkspace.x[3] + acadoWorkspace.d[19]; +acadoVariables.x[24] += + acadoWorkspace.evGx[80]*acadoWorkspace.x[0] + acadoWorkspace.evGx[81]*acadoWorkspace.x[1] + acadoWorkspace.evGx[82]*acadoWorkspace.x[2] + acadoWorkspace.evGx[83]*acadoWorkspace.x[3] + acadoWorkspace.d[20]; +acadoVariables.x[25] += + acadoWorkspace.evGx[84]*acadoWorkspace.x[0] + acadoWorkspace.evGx[85]*acadoWorkspace.x[1] + acadoWorkspace.evGx[86]*acadoWorkspace.x[2] + acadoWorkspace.evGx[87]*acadoWorkspace.x[3] + acadoWorkspace.d[21]; +acadoVariables.x[26] += + acadoWorkspace.evGx[88]*acadoWorkspace.x[0] + acadoWorkspace.evGx[89]*acadoWorkspace.x[1] + acadoWorkspace.evGx[90]*acadoWorkspace.x[2] + acadoWorkspace.evGx[91]*acadoWorkspace.x[3] + acadoWorkspace.d[22]; +acadoVariables.x[27] += + acadoWorkspace.evGx[92]*acadoWorkspace.x[0] + acadoWorkspace.evGx[93]*acadoWorkspace.x[1] + acadoWorkspace.evGx[94]*acadoWorkspace.x[2] + acadoWorkspace.evGx[95]*acadoWorkspace.x[3] + acadoWorkspace.d[23]; +acadoVariables.x[28] += + acadoWorkspace.evGx[96]*acadoWorkspace.x[0] + acadoWorkspace.evGx[97]*acadoWorkspace.x[1] + acadoWorkspace.evGx[98]*acadoWorkspace.x[2] + acadoWorkspace.evGx[99]*acadoWorkspace.x[3] + acadoWorkspace.d[24]; +acadoVariables.x[29] += + acadoWorkspace.evGx[100]*acadoWorkspace.x[0] + acadoWorkspace.evGx[101]*acadoWorkspace.x[1] + acadoWorkspace.evGx[102]*acadoWorkspace.x[2] + acadoWorkspace.evGx[103]*acadoWorkspace.x[3] + acadoWorkspace.d[25]; +acadoVariables.x[30] += + acadoWorkspace.evGx[104]*acadoWorkspace.x[0] + acadoWorkspace.evGx[105]*acadoWorkspace.x[1] + acadoWorkspace.evGx[106]*acadoWorkspace.x[2] + acadoWorkspace.evGx[107]*acadoWorkspace.x[3] + acadoWorkspace.d[26]; +acadoVariables.x[31] += + acadoWorkspace.evGx[108]*acadoWorkspace.x[0] + acadoWorkspace.evGx[109]*acadoWorkspace.x[1] + acadoWorkspace.evGx[110]*acadoWorkspace.x[2] + acadoWorkspace.evGx[111]*acadoWorkspace.x[3] + acadoWorkspace.d[27]; +acadoVariables.x[32] += + acadoWorkspace.evGx[112]*acadoWorkspace.x[0] + acadoWorkspace.evGx[113]*acadoWorkspace.x[1] + acadoWorkspace.evGx[114]*acadoWorkspace.x[2] + acadoWorkspace.evGx[115]*acadoWorkspace.x[3] + acadoWorkspace.d[28]; +acadoVariables.x[33] += + acadoWorkspace.evGx[116]*acadoWorkspace.x[0] + acadoWorkspace.evGx[117]*acadoWorkspace.x[1] + acadoWorkspace.evGx[118]*acadoWorkspace.x[2] + acadoWorkspace.evGx[119]*acadoWorkspace.x[3] + acadoWorkspace.d[29]; +acadoVariables.x[34] += + acadoWorkspace.evGx[120]*acadoWorkspace.x[0] + acadoWorkspace.evGx[121]*acadoWorkspace.x[1] + acadoWorkspace.evGx[122]*acadoWorkspace.x[2] + acadoWorkspace.evGx[123]*acadoWorkspace.x[3] + acadoWorkspace.d[30]; +acadoVariables.x[35] += + acadoWorkspace.evGx[124]*acadoWorkspace.x[0] + acadoWorkspace.evGx[125]*acadoWorkspace.x[1] + acadoWorkspace.evGx[126]*acadoWorkspace.x[2] + acadoWorkspace.evGx[127]*acadoWorkspace.x[3] + acadoWorkspace.d[31]; +acadoVariables.x[36] += + acadoWorkspace.evGx[128]*acadoWorkspace.x[0] + acadoWorkspace.evGx[129]*acadoWorkspace.x[1] + acadoWorkspace.evGx[130]*acadoWorkspace.x[2] + acadoWorkspace.evGx[131]*acadoWorkspace.x[3] + acadoWorkspace.d[32]; +acadoVariables.x[37] += + acadoWorkspace.evGx[132]*acadoWorkspace.x[0] + acadoWorkspace.evGx[133]*acadoWorkspace.x[1] + acadoWorkspace.evGx[134]*acadoWorkspace.x[2] + acadoWorkspace.evGx[135]*acadoWorkspace.x[3] + acadoWorkspace.d[33]; +acadoVariables.x[38] += + acadoWorkspace.evGx[136]*acadoWorkspace.x[0] + acadoWorkspace.evGx[137]*acadoWorkspace.x[1] + acadoWorkspace.evGx[138]*acadoWorkspace.x[2] + acadoWorkspace.evGx[139]*acadoWorkspace.x[3] + acadoWorkspace.d[34]; +acadoVariables.x[39] += + acadoWorkspace.evGx[140]*acadoWorkspace.x[0] + acadoWorkspace.evGx[141]*acadoWorkspace.x[1] + acadoWorkspace.evGx[142]*acadoWorkspace.x[2] + acadoWorkspace.evGx[143]*acadoWorkspace.x[3] + acadoWorkspace.d[35]; +acadoVariables.x[40] += + acadoWorkspace.evGx[144]*acadoWorkspace.x[0] + acadoWorkspace.evGx[145]*acadoWorkspace.x[1] + acadoWorkspace.evGx[146]*acadoWorkspace.x[2] + acadoWorkspace.evGx[147]*acadoWorkspace.x[3] + acadoWorkspace.d[36]; +acadoVariables.x[41] += + acadoWorkspace.evGx[148]*acadoWorkspace.x[0] + acadoWorkspace.evGx[149]*acadoWorkspace.x[1] + acadoWorkspace.evGx[150]*acadoWorkspace.x[2] + acadoWorkspace.evGx[151]*acadoWorkspace.x[3] + acadoWorkspace.d[37]; +acadoVariables.x[42] += + acadoWorkspace.evGx[152]*acadoWorkspace.x[0] + acadoWorkspace.evGx[153]*acadoWorkspace.x[1] + acadoWorkspace.evGx[154]*acadoWorkspace.x[2] + acadoWorkspace.evGx[155]*acadoWorkspace.x[3] + acadoWorkspace.d[38]; +acadoVariables.x[43] += + acadoWorkspace.evGx[156]*acadoWorkspace.x[0] + acadoWorkspace.evGx[157]*acadoWorkspace.x[1] + acadoWorkspace.evGx[158]*acadoWorkspace.x[2] + acadoWorkspace.evGx[159]*acadoWorkspace.x[3] + acadoWorkspace.d[39]; +acadoVariables.x[44] += + acadoWorkspace.evGx[160]*acadoWorkspace.x[0] + acadoWorkspace.evGx[161]*acadoWorkspace.x[1] + acadoWorkspace.evGx[162]*acadoWorkspace.x[2] + acadoWorkspace.evGx[163]*acadoWorkspace.x[3] + acadoWorkspace.d[40]; +acadoVariables.x[45] += + acadoWorkspace.evGx[164]*acadoWorkspace.x[0] + acadoWorkspace.evGx[165]*acadoWorkspace.x[1] + acadoWorkspace.evGx[166]*acadoWorkspace.x[2] + acadoWorkspace.evGx[167]*acadoWorkspace.x[3] + acadoWorkspace.d[41]; +acadoVariables.x[46] += + acadoWorkspace.evGx[168]*acadoWorkspace.x[0] + acadoWorkspace.evGx[169]*acadoWorkspace.x[1] + acadoWorkspace.evGx[170]*acadoWorkspace.x[2] + acadoWorkspace.evGx[171]*acadoWorkspace.x[3] + acadoWorkspace.d[42]; +acadoVariables.x[47] += + acadoWorkspace.evGx[172]*acadoWorkspace.x[0] + acadoWorkspace.evGx[173]*acadoWorkspace.x[1] + acadoWorkspace.evGx[174]*acadoWorkspace.x[2] + acadoWorkspace.evGx[175]*acadoWorkspace.x[3] + acadoWorkspace.d[43]; +acadoVariables.x[48] += + acadoWorkspace.evGx[176]*acadoWorkspace.x[0] + acadoWorkspace.evGx[177]*acadoWorkspace.x[1] + acadoWorkspace.evGx[178]*acadoWorkspace.x[2] + acadoWorkspace.evGx[179]*acadoWorkspace.x[3] + acadoWorkspace.d[44]; +acadoVariables.x[49] += + acadoWorkspace.evGx[180]*acadoWorkspace.x[0] + acadoWorkspace.evGx[181]*acadoWorkspace.x[1] + acadoWorkspace.evGx[182]*acadoWorkspace.x[2] + acadoWorkspace.evGx[183]*acadoWorkspace.x[3] + acadoWorkspace.d[45]; +acadoVariables.x[50] += + acadoWorkspace.evGx[184]*acadoWorkspace.x[0] + acadoWorkspace.evGx[185]*acadoWorkspace.x[1] + acadoWorkspace.evGx[186]*acadoWorkspace.x[2] + acadoWorkspace.evGx[187]*acadoWorkspace.x[3] + acadoWorkspace.d[46]; +acadoVariables.x[51] += + acadoWorkspace.evGx[188]*acadoWorkspace.x[0] + acadoWorkspace.evGx[189]*acadoWorkspace.x[1] + acadoWorkspace.evGx[190]*acadoWorkspace.x[2] + acadoWorkspace.evGx[191]*acadoWorkspace.x[3] + acadoWorkspace.d[47]; +acadoVariables.x[52] += + acadoWorkspace.evGx[192]*acadoWorkspace.x[0] + acadoWorkspace.evGx[193]*acadoWorkspace.x[1] + acadoWorkspace.evGx[194]*acadoWorkspace.x[2] + acadoWorkspace.evGx[195]*acadoWorkspace.x[3] + acadoWorkspace.d[48]; +acadoVariables.x[53] += + acadoWorkspace.evGx[196]*acadoWorkspace.x[0] + acadoWorkspace.evGx[197]*acadoWorkspace.x[1] + acadoWorkspace.evGx[198]*acadoWorkspace.x[2] + acadoWorkspace.evGx[199]*acadoWorkspace.x[3] + acadoWorkspace.d[49]; +acadoVariables.x[54] += + acadoWorkspace.evGx[200]*acadoWorkspace.x[0] + acadoWorkspace.evGx[201]*acadoWorkspace.x[1] + acadoWorkspace.evGx[202]*acadoWorkspace.x[2] + acadoWorkspace.evGx[203]*acadoWorkspace.x[3] + acadoWorkspace.d[50]; +acadoVariables.x[55] += + acadoWorkspace.evGx[204]*acadoWorkspace.x[0] + acadoWorkspace.evGx[205]*acadoWorkspace.x[1] + acadoWorkspace.evGx[206]*acadoWorkspace.x[2] + acadoWorkspace.evGx[207]*acadoWorkspace.x[3] + acadoWorkspace.d[51]; +acadoVariables.x[56] += + acadoWorkspace.evGx[208]*acadoWorkspace.x[0] + acadoWorkspace.evGx[209]*acadoWorkspace.x[1] + acadoWorkspace.evGx[210]*acadoWorkspace.x[2] + acadoWorkspace.evGx[211]*acadoWorkspace.x[3] + acadoWorkspace.d[52]; +acadoVariables.x[57] += + acadoWorkspace.evGx[212]*acadoWorkspace.x[0] + acadoWorkspace.evGx[213]*acadoWorkspace.x[1] + acadoWorkspace.evGx[214]*acadoWorkspace.x[2] + acadoWorkspace.evGx[215]*acadoWorkspace.x[3] + acadoWorkspace.d[53]; +acadoVariables.x[58] += + acadoWorkspace.evGx[216]*acadoWorkspace.x[0] + acadoWorkspace.evGx[217]*acadoWorkspace.x[1] + acadoWorkspace.evGx[218]*acadoWorkspace.x[2] + acadoWorkspace.evGx[219]*acadoWorkspace.x[3] + acadoWorkspace.d[54]; +acadoVariables.x[59] += + acadoWorkspace.evGx[220]*acadoWorkspace.x[0] + acadoWorkspace.evGx[221]*acadoWorkspace.x[1] + acadoWorkspace.evGx[222]*acadoWorkspace.x[2] + acadoWorkspace.evGx[223]*acadoWorkspace.x[3] + acadoWorkspace.d[55]; +acadoVariables.x[60] += + acadoWorkspace.evGx[224]*acadoWorkspace.x[0] + acadoWorkspace.evGx[225]*acadoWorkspace.x[1] + acadoWorkspace.evGx[226]*acadoWorkspace.x[2] + acadoWorkspace.evGx[227]*acadoWorkspace.x[3] + acadoWorkspace.d[56]; +acadoVariables.x[61] += + acadoWorkspace.evGx[228]*acadoWorkspace.x[0] + acadoWorkspace.evGx[229]*acadoWorkspace.x[1] + acadoWorkspace.evGx[230]*acadoWorkspace.x[2] + acadoWorkspace.evGx[231]*acadoWorkspace.x[3] + acadoWorkspace.d[57]; +acadoVariables.x[62] += + acadoWorkspace.evGx[232]*acadoWorkspace.x[0] + acadoWorkspace.evGx[233]*acadoWorkspace.x[1] + acadoWorkspace.evGx[234]*acadoWorkspace.x[2] + acadoWorkspace.evGx[235]*acadoWorkspace.x[3] + acadoWorkspace.d[58]; +acadoVariables.x[63] += + acadoWorkspace.evGx[236]*acadoWorkspace.x[0] + acadoWorkspace.evGx[237]*acadoWorkspace.x[1] + acadoWorkspace.evGx[238]*acadoWorkspace.x[2] + acadoWorkspace.evGx[239]*acadoWorkspace.x[3] + acadoWorkspace.d[59]; +acadoVariables.x[64] += + acadoWorkspace.evGx[240]*acadoWorkspace.x[0] + acadoWorkspace.evGx[241]*acadoWorkspace.x[1] + acadoWorkspace.evGx[242]*acadoWorkspace.x[2] + acadoWorkspace.evGx[243]*acadoWorkspace.x[3] + acadoWorkspace.d[60]; +acadoVariables.x[65] += + acadoWorkspace.evGx[244]*acadoWorkspace.x[0] + acadoWorkspace.evGx[245]*acadoWorkspace.x[1] + acadoWorkspace.evGx[246]*acadoWorkspace.x[2] + acadoWorkspace.evGx[247]*acadoWorkspace.x[3] + acadoWorkspace.d[61]; +acadoVariables.x[66] += + acadoWorkspace.evGx[248]*acadoWorkspace.x[0] + acadoWorkspace.evGx[249]*acadoWorkspace.x[1] + acadoWorkspace.evGx[250]*acadoWorkspace.x[2] + acadoWorkspace.evGx[251]*acadoWorkspace.x[3] + acadoWorkspace.d[62]; +acadoVariables.x[67] += + acadoWorkspace.evGx[252]*acadoWorkspace.x[0] + acadoWorkspace.evGx[253]*acadoWorkspace.x[1] + acadoWorkspace.evGx[254]*acadoWorkspace.x[2] + acadoWorkspace.evGx[255]*acadoWorkspace.x[3] + acadoWorkspace.d[63]; +acadoVariables.x[68] += + acadoWorkspace.evGx[256]*acadoWorkspace.x[0] + acadoWorkspace.evGx[257]*acadoWorkspace.x[1] + acadoWorkspace.evGx[258]*acadoWorkspace.x[2] + acadoWorkspace.evGx[259]*acadoWorkspace.x[3] + acadoWorkspace.d[64]; +acadoVariables.x[69] += + acadoWorkspace.evGx[260]*acadoWorkspace.x[0] + acadoWorkspace.evGx[261]*acadoWorkspace.x[1] + acadoWorkspace.evGx[262]*acadoWorkspace.x[2] + acadoWorkspace.evGx[263]*acadoWorkspace.x[3] + acadoWorkspace.d[65]; +acadoVariables.x[70] += + acadoWorkspace.evGx[264]*acadoWorkspace.x[0] + acadoWorkspace.evGx[265]*acadoWorkspace.x[1] + acadoWorkspace.evGx[266]*acadoWorkspace.x[2] + acadoWorkspace.evGx[267]*acadoWorkspace.x[3] + acadoWorkspace.d[66]; +acadoVariables.x[71] += + acadoWorkspace.evGx[268]*acadoWorkspace.x[0] + acadoWorkspace.evGx[269]*acadoWorkspace.x[1] + acadoWorkspace.evGx[270]*acadoWorkspace.x[2] + acadoWorkspace.evGx[271]*acadoWorkspace.x[3] + acadoWorkspace.d[67]; +acadoVariables.x[72] += + acadoWorkspace.evGx[272]*acadoWorkspace.x[0] + acadoWorkspace.evGx[273]*acadoWorkspace.x[1] + acadoWorkspace.evGx[274]*acadoWorkspace.x[2] + acadoWorkspace.evGx[275]*acadoWorkspace.x[3] + acadoWorkspace.d[68]; +acadoVariables.x[73] += + acadoWorkspace.evGx[276]*acadoWorkspace.x[0] + acadoWorkspace.evGx[277]*acadoWorkspace.x[1] + acadoWorkspace.evGx[278]*acadoWorkspace.x[2] + acadoWorkspace.evGx[279]*acadoWorkspace.x[3] + acadoWorkspace.d[69]; +acadoVariables.x[74] += + acadoWorkspace.evGx[280]*acadoWorkspace.x[0] + acadoWorkspace.evGx[281]*acadoWorkspace.x[1] + acadoWorkspace.evGx[282]*acadoWorkspace.x[2] + acadoWorkspace.evGx[283]*acadoWorkspace.x[3] + acadoWorkspace.d[70]; +acadoVariables.x[75] += + acadoWorkspace.evGx[284]*acadoWorkspace.x[0] + acadoWorkspace.evGx[285]*acadoWorkspace.x[1] + acadoWorkspace.evGx[286]*acadoWorkspace.x[2] + acadoWorkspace.evGx[287]*acadoWorkspace.x[3] + acadoWorkspace.d[71]; +acadoVariables.x[76] += + acadoWorkspace.evGx[288]*acadoWorkspace.x[0] + acadoWorkspace.evGx[289]*acadoWorkspace.x[1] + acadoWorkspace.evGx[290]*acadoWorkspace.x[2] + acadoWorkspace.evGx[291]*acadoWorkspace.x[3] + acadoWorkspace.d[72]; +acadoVariables.x[77] += + acadoWorkspace.evGx[292]*acadoWorkspace.x[0] + acadoWorkspace.evGx[293]*acadoWorkspace.x[1] + acadoWorkspace.evGx[294]*acadoWorkspace.x[2] + acadoWorkspace.evGx[295]*acadoWorkspace.x[3] + acadoWorkspace.d[73]; +acadoVariables.x[78] += + acadoWorkspace.evGx[296]*acadoWorkspace.x[0] + acadoWorkspace.evGx[297]*acadoWorkspace.x[1] + acadoWorkspace.evGx[298]*acadoWorkspace.x[2] + acadoWorkspace.evGx[299]*acadoWorkspace.x[3] + acadoWorkspace.d[74]; +acadoVariables.x[79] += + acadoWorkspace.evGx[300]*acadoWorkspace.x[0] + acadoWorkspace.evGx[301]*acadoWorkspace.x[1] + acadoWorkspace.evGx[302]*acadoWorkspace.x[2] + acadoWorkspace.evGx[303]*acadoWorkspace.x[3] + acadoWorkspace.d[75]; +acadoVariables.x[80] += + acadoWorkspace.evGx[304]*acadoWorkspace.x[0] + acadoWorkspace.evGx[305]*acadoWorkspace.x[1] + acadoWorkspace.evGx[306]*acadoWorkspace.x[2] + acadoWorkspace.evGx[307]*acadoWorkspace.x[3] + acadoWorkspace.d[76]; +acadoVariables.x[81] += + acadoWorkspace.evGx[308]*acadoWorkspace.x[0] + acadoWorkspace.evGx[309]*acadoWorkspace.x[1] + acadoWorkspace.evGx[310]*acadoWorkspace.x[2] + acadoWorkspace.evGx[311]*acadoWorkspace.x[3] + acadoWorkspace.d[77]; +acadoVariables.x[82] += + acadoWorkspace.evGx[312]*acadoWorkspace.x[0] + acadoWorkspace.evGx[313]*acadoWorkspace.x[1] + acadoWorkspace.evGx[314]*acadoWorkspace.x[2] + acadoWorkspace.evGx[315]*acadoWorkspace.x[3] + acadoWorkspace.d[78]; +acadoVariables.x[83] += + acadoWorkspace.evGx[316]*acadoWorkspace.x[0] + acadoWorkspace.evGx[317]*acadoWorkspace.x[1] + acadoWorkspace.evGx[318]*acadoWorkspace.x[2] + acadoWorkspace.evGx[319]*acadoWorkspace.x[3] + acadoWorkspace.d[79]; + +acado_multEDu( acadoWorkspace.E, &(acadoWorkspace.x[ 4 ]), &(acadoVariables.x[ 4 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 4 ]), &(acadoWorkspace.x[ 4 ]), &(acadoVariables.x[ 8 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 8 ]), &(acadoWorkspace.x[ 5 ]), &(acadoVariables.x[ 8 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 12 ]), &(acadoWorkspace.x[ 4 ]), &(acadoVariables.x[ 12 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 16 ]), &(acadoWorkspace.x[ 5 ]), &(acadoVariables.x[ 12 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 20 ]), &(acadoWorkspace.x[ 6 ]), &(acadoVariables.x[ 12 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 24 ]), &(acadoWorkspace.x[ 4 ]), &(acadoVariables.x[ 16 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 28 ]), &(acadoWorkspace.x[ 5 ]), &(acadoVariables.x[ 16 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 32 ]), &(acadoWorkspace.x[ 6 ]), &(acadoVariables.x[ 16 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 36 ]), &(acadoWorkspace.x[ 7 ]), &(acadoVariables.x[ 16 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 40 ]), &(acadoWorkspace.x[ 4 ]), &(acadoVariables.x[ 20 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 44 ]), &(acadoWorkspace.x[ 5 ]), &(acadoVariables.x[ 20 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 48 ]), &(acadoWorkspace.x[ 6 ]), &(acadoVariables.x[ 20 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 52 ]), &(acadoWorkspace.x[ 7 ]), &(acadoVariables.x[ 20 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 56 ]), &(acadoWorkspace.x[ 8 ]), &(acadoVariables.x[ 20 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 60 ]), &(acadoWorkspace.x[ 4 ]), &(acadoVariables.x[ 24 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 64 ]), &(acadoWorkspace.x[ 5 ]), &(acadoVariables.x[ 24 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 68 ]), &(acadoWorkspace.x[ 6 ]), &(acadoVariables.x[ 24 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 72 ]), &(acadoWorkspace.x[ 7 ]), &(acadoVariables.x[ 24 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 76 ]), &(acadoWorkspace.x[ 8 ]), &(acadoVariables.x[ 24 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 80 ]), &(acadoWorkspace.x[ 9 ]), &(acadoVariables.x[ 24 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 84 ]), &(acadoWorkspace.x[ 4 ]), &(acadoVariables.x[ 28 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 88 ]), &(acadoWorkspace.x[ 5 ]), &(acadoVariables.x[ 28 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 92 ]), &(acadoWorkspace.x[ 6 ]), &(acadoVariables.x[ 28 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 96 ]), &(acadoWorkspace.x[ 7 ]), &(acadoVariables.x[ 28 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 100 ]), &(acadoWorkspace.x[ 8 ]), &(acadoVariables.x[ 28 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 104 ]), &(acadoWorkspace.x[ 9 ]), &(acadoVariables.x[ 28 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 108 ]), &(acadoWorkspace.x[ 10 ]), &(acadoVariables.x[ 28 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 112 ]), &(acadoWorkspace.x[ 4 ]), &(acadoVariables.x[ 32 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 116 ]), &(acadoWorkspace.x[ 5 ]), &(acadoVariables.x[ 32 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 120 ]), &(acadoWorkspace.x[ 6 ]), &(acadoVariables.x[ 32 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 124 ]), &(acadoWorkspace.x[ 7 ]), &(acadoVariables.x[ 32 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 128 ]), &(acadoWorkspace.x[ 8 ]), &(acadoVariables.x[ 32 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 132 ]), &(acadoWorkspace.x[ 9 ]), &(acadoVariables.x[ 32 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 136 ]), &(acadoWorkspace.x[ 10 ]), &(acadoVariables.x[ 32 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 140 ]), &(acadoWorkspace.x[ 11 ]), &(acadoVariables.x[ 32 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 144 ]), &(acadoWorkspace.x[ 4 ]), &(acadoVariables.x[ 36 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 148 ]), &(acadoWorkspace.x[ 5 ]), &(acadoVariables.x[ 36 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 152 ]), &(acadoWorkspace.x[ 6 ]), &(acadoVariables.x[ 36 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 156 ]), &(acadoWorkspace.x[ 7 ]), &(acadoVariables.x[ 36 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 160 ]), &(acadoWorkspace.x[ 8 ]), &(acadoVariables.x[ 36 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 164 ]), &(acadoWorkspace.x[ 9 ]), &(acadoVariables.x[ 36 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 168 ]), &(acadoWorkspace.x[ 10 ]), &(acadoVariables.x[ 36 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 172 ]), &(acadoWorkspace.x[ 11 ]), &(acadoVariables.x[ 36 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 176 ]), &(acadoWorkspace.x[ 12 ]), &(acadoVariables.x[ 36 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 180 ]), &(acadoWorkspace.x[ 4 ]), &(acadoVariables.x[ 40 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 184 ]), &(acadoWorkspace.x[ 5 ]), &(acadoVariables.x[ 40 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 188 ]), &(acadoWorkspace.x[ 6 ]), &(acadoVariables.x[ 40 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 192 ]), &(acadoWorkspace.x[ 7 ]), &(acadoVariables.x[ 40 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 196 ]), &(acadoWorkspace.x[ 8 ]), &(acadoVariables.x[ 40 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 200 ]), &(acadoWorkspace.x[ 9 ]), &(acadoVariables.x[ 40 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 204 ]), &(acadoWorkspace.x[ 10 ]), &(acadoVariables.x[ 40 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 208 ]), &(acadoWorkspace.x[ 11 ]), &(acadoVariables.x[ 40 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 212 ]), &(acadoWorkspace.x[ 12 ]), &(acadoVariables.x[ 40 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 216 ]), &(acadoWorkspace.x[ 13 ]), &(acadoVariables.x[ 40 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 220 ]), &(acadoWorkspace.x[ 4 ]), &(acadoVariables.x[ 44 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 224 ]), &(acadoWorkspace.x[ 5 ]), &(acadoVariables.x[ 44 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 228 ]), &(acadoWorkspace.x[ 6 ]), &(acadoVariables.x[ 44 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 232 ]), &(acadoWorkspace.x[ 7 ]), &(acadoVariables.x[ 44 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 236 ]), &(acadoWorkspace.x[ 8 ]), &(acadoVariables.x[ 44 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 240 ]), &(acadoWorkspace.x[ 9 ]), &(acadoVariables.x[ 44 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 244 ]), &(acadoWorkspace.x[ 10 ]), &(acadoVariables.x[ 44 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 248 ]), &(acadoWorkspace.x[ 11 ]), &(acadoVariables.x[ 44 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 252 ]), &(acadoWorkspace.x[ 12 ]), &(acadoVariables.x[ 44 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 256 ]), &(acadoWorkspace.x[ 13 ]), &(acadoVariables.x[ 44 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 260 ]), &(acadoWorkspace.x[ 14 ]), &(acadoVariables.x[ 44 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 264 ]), &(acadoWorkspace.x[ 4 ]), &(acadoVariables.x[ 48 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 268 ]), &(acadoWorkspace.x[ 5 ]), &(acadoVariables.x[ 48 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 272 ]), &(acadoWorkspace.x[ 6 ]), &(acadoVariables.x[ 48 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 276 ]), &(acadoWorkspace.x[ 7 ]), &(acadoVariables.x[ 48 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 280 ]), &(acadoWorkspace.x[ 8 ]), &(acadoVariables.x[ 48 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 284 ]), &(acadoWorkspace.x[ 9 ]), &(acadoVariables.x[ 48 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 288 ]), &(acadoWorkspace.x[ 10 ]), &(acadoVariables.x[ 48 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 292 ]), &(acadoWorkspace.x[ 11 ]), &(acadoVariables.x[ 48 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 296 ]), &(acadoWorkspace.x[ 12 ]), &(acadoVariables.x[ 48 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 300 ]), &(acadoWorkspace.x[ 13 ]), &(acadoVariables.x[ 48 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 304 ]), &(acadoWorkspace.x[ 14 ]), &(acadoVariables.x[ 48 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 308 ]), &(acadoWorkspace.x[ 15 ]), &(acadoVariables.x[ 48 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 312 ]), &(acadoWorkspace.x[ 4 ]), &(acadoVariables.x[ 52 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 316 ]), &(acadoWorkspace.x[ 5 ]), &(acadoVariables.x[ 52 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 320 ]), &(acadoWorkspace.x[ 6 ]), &(acadoVariables.x[ 52 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 324 ]), &(acadoWorkspace.x[ 7 ]), &(acadoVariables.x[ 52 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 328 ]), &(acadoWorkspace.x[ 8 ]), &(acadoVariables.x[ 52 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 332 ]), &(acadoWorkspace.x[ 9 ]), &(acadoVariables.x[ 52 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 336 ]), &(acadoWorkspace.x[ 10 ]), &(acadoVariables.x[ 52 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 340 ]), &(acadoWorkspace.x[ 11 ]), &(acadoVariables.x[ 52 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 344 ]), &(acadoWorkspace.x[ 12 ]), &(acadoVariables.x[ 52 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 348 ]), &(acadoWorkspace.x[ 13 ]), &(acadoVariables.x[ 52 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 352 ]), &(acadoWorkspace.x[ 14 ]), &(acadoVariables.x[ 52 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 356 ]), &(acadoWorkspace.x[ 15 ]), &(acadoVariables.x[ 52 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 360 ]), &(acadoWorkspace.x[ 16 ]), &(acadoVariables.x[ 52 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 364 ]), &(acadoWorkspace.x[ 4 ]), &(acadoVariables.x[ 56 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 368 ]), &(acadoWorkspace.x[ 5 ]), &(acadoVariables.x[ 56 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 372 ]), &(acadoWorkspace.x[ 6 ]), &(acadoVariables.x[ 56 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 376 ]), &(acadoWorkspace.x[ 7 ]), &(acadoVariables.x[ 56 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 380 ]), &(acadoWorkspace.x[ 8 ]), &(acadoVariables.x[ 56 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 384 ]), &(acadoWorkspace.x[ 9 ]), &(acadoVariables.x[ 56 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 388 ]), &(acadoWorkspace.x[ 10 ]), &(acadoVariables.x[ 56 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 392 ]), &(acadoWorkspace.x[ 11 ]), &(acadoVariables.x[ 56 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 396 ]), &(acadoWorkspace.x[ 12 ]), &(acadoVariables.x[ 56 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 400 ]), &(acadoWorkspace.x[ 13 ]), &(acadoVariables.x[ 56 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 404 ]), &(acadoWorkspace.x[ 14 ]), &(acadoVariables.x[ 56 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 408 ]), &(acadoWorkspace.x[ 15 ]), &(acadoVariables.x[ 56 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 412 ]), &(acadoWorkspace.x[ 16 ]), &(acadoVariables.x[ 56 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 416 ]), &(acadoWorkspace.x[ 17 ]), &(acadoVariables.x[ 56 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 420 ]), &(acadoWorkspace.x[ 4 ]), &(acadoVariables.x[ 60 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 424 ]), &(acadoWorkspace.x[ 5 ]), &(acadoVariables.x[ 60 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 428 ]), &(acadoWorkspace.x[ 6 ]), &(acadoVariables.x[ 60 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 432 ]), &(acadoWorkspace.x[ 7 ]), &(acadoVariables.x[ 60 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 436 ]), &(acadoWorkspace.x[ 8 ]), &(acadoVariables.x[ 60 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 440 ]), &(acadoWorkspace.x[ 9 ]), &(acadoVariables.x[ 60 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 444 ]), &(acadoWorkspace.x[ 10 ]), &(acadoVariables.x[ 60 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 448 ]), &(acadoWorkspace.x[ 11 ]), &(acadoVariables.x[ 60 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 452 ]), &(acadoWorkspace.x[ 12 ]), &(acadoVariables.x[ 60 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 456 ]), &(acadoWorkspace.x[ 13 ]), &(acadoVariables.x[ 60 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 460 ]), &(acadoWorkspace.x[ 14 ]), &(acadoVariables.x[ 60 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 464 ]), &(acadoWorkspace.x[ 15 ]), &(acadoVariables.x[ 60 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 468 ]), &(acadoWorkspace.x[ 16 ]), &(acadoVariables.x[ 60 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 472 ]), &(acadoWorkspace.x[ 17 ]), &(acadoVariables.x[ 60 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 476 ]), &(acadoWorkspace.x[ 18 ]), &(acadoVariables.x[ 60 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 480 ]), &(acadoWorkspace.x[ 4 ]), &(acadoVariables.x[ 64 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 484 ]), &(acadoWorkspace.x[ 5 ]), &(acadoVariables.x[ 64 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 488 ]), &(acadoWorkspace.x[ 6 ]), &(acadoVariables.x[ 64 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 492 ]), &(acadoWorkspace.x[ 7 ]), &(acadoVariables.x[ 64 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 496 ]), &(acadoWorkspace.x[ 8 ]), &(acadoVariables.x[ 64 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 500 ]), &(acadoWorkspace.x[ 9 ]), &(acadoVariables.x[ 64 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 504 ]), &(acadoWorkspace.x[ 10 ]), &(acadoVariables.x[ 64 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 508 ]), &(acadoWorkspace.x[ 11 ]), &(acadoVariables.x[ 64 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 512 ]), &(acadoWorkspace.x[ 12 ]), &(acadoVariables.x[ 64 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 516 ]), &(acadoWorkspace.x[ 13 ]), &(acadoVariables.x[ 64 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 520 ]), &(acadoWorkspace.x[ 14 ]), &(acadoVariables.x[ 64 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 524 ]), &(acadoWorkspace.x[ 15 ]), &(acadoVariables.x[ 64 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 528 ]), &(acadoWorkspace.x[ 16 ]), &(acadoVariables.x[ 64 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 532 ]), &(acadoWorkspace.x[ 17 ]), &(acadoVariables.x[ 64 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 536 ]), &(acadoWorkspace.x[ 18 ]), &(acadoVariables.x[ 64 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 540 ]), &(acadoWorkspace.x[ 19 ]), &(acadoVariables.x[ 64 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 544 ]), &(acadoWorkspace.x[ 4 ]), &(acadoVariables.x[ 68 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 548 ]), &(acadoWorkspace.x[ 5 ]), &(acadoVariables.x[ 68 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 552 ]), &(acadoWorkspace.x[ 6 ]), &(acadoVariables.x[ 68 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 556 ]), &(acadoWorkspace.x[ 7 ]), &(acadoVariables.x[ 68 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 560 ]), &(acadoWorkspace.x[ 8 ]), &(acadoVariables.x[ 68 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 564 ]), &(acadoWorkspace.x[ 9 ]), &(acadoVariables.x[ 68 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 568 ]), &(acadoWorkspace.x[ 10 ]), &(acadoVariables.x[ 68 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 572 ]), &(acadoWorkspace.x[ 11 ]), &(acadoVariables.x[ 68 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 576 ]), &(acadoWorkspace.x[ 12 ]), &(acadoVariables.x[ 68 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 580 ]), &(acadoWorkspace.x[ 13 ]), &(acadoVariables.x[ 68 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 584 ]), &(acadoWorkspace.x[ 14 ]), &(acadoVariables.x[ 68 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 588 ]), &(acadoWorkspace.x[ 15 ]), &(acadoVariables.x[ 68 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 592 ]), &(acadoWorkspace.x[ 16 ]), &(acadoVariables.x[ 68 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 596 ]), &(acadoWorkspace.x[ 17 ]), &(acadoVariables.x[ 68 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 600 ]), &(acadoWorkspace.x[ 18 ]), &(acadoVariables.x[ 68 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 604 ]), &(acadoWorkspace.x[ 19 ]), &(acadoVariables.x[ 68 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 608 ]), &(acadoWorkspace.x[ 20 ]), &(acadoVariables.x[ 68 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 612 ]), &(acadoWorkspace.x[ 4 ]), &(acadoVariables.x[ 72 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 616 ]), &(acadoWorkspace.x[ 5 ]), &(acadoVariables.x[ 72 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 620 ]), &(acadoWorkspace.x[ 6 ]), &(acadoVariables.x[ 72 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 624 ]), &(acadoWorkspace.x[ 7 ]), &(acadoVariables.x[ 72 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 628 ]), &(acadoWorkspace.x[ 8 ]), &(acadoVariables.x[ 72 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 632 ]), &(acadoWorkspace.x[ 9 ]), &(acadoVariables.x[ 72 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 636 ]), &(acadoWorkspace.x[ 10 ]), &(acadoVariables.x[ 72 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 640 ]), &(acadoWorkspace.x[ 11 ]), &(acadoVariables.x[ 72 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 644 ]), &(acadoWorkspace.x[ 12 ]), &(acadoVariables.x[ 72 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 648 ]), &(acadoWorkspace.x[ 13 ]), &(acadoVariables.x[ 72 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 652 ]), &(acadoWorkspace.x[ 14 ]), &(acadoVariables.x[ 72 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 656 ]), &(acadoWorkspace.x[ 15 ]), &(acadoVariables.x[ 72 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 660 ]), &(acadoWorkspace.x[ 16 ]), &(acadoVariables.x[ 72 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 664 ]), &(acadoWorkspace.x[ 17 ]), &(acadoVariables.x[ 72 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 668 ]), &(acadoWorkspace.x[ 18 ]), &(acadoVariables.x[ 72 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 672 ]), &(acadoWorkspace.x[ 19 ]), &(acadoVariables.x[ 72 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 676 ]), &(acadoWorkspace.x[ 20 ]), &(acadoVariables.x[ 72 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 680 ]), &(acadoWorkspace.x[ 21 ]), &(acadoVariables.x[ 72 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 684 ]), &(acadoWorkspace.x[ 4 ]), &(acadoVariables.x[ 76 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 688 ]), &(acadoWorkspace.x[ 5 ]), &(acadoVariables.x[ 76 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 692 ]), &(acadoWorkspace.x[ 6 ]), &(acadoVariables.x[ 76 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 696 ]), &(acadoWorkspace.x[ 7 ]), &(acadoVariables.x[ 76 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 700 ]), &(acadoWorkspace.x[ 8 ]), &(acadoVariables.x[ 76 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 704 ]), &(acadoWorkspace.x[ 9 ]), &(acadoVariables.x[ 76 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 708 ]), &(acadoWorkspace.x[ 10 ]), &(acadoVariables.x[ 76 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 712 ]), &(acadoWorkspace.x[ 11 ]), &(acadoVariables.x[ 76 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 716 ]), &(acadoWorkspace.x[ 12 ]), &(acadoVariables.x[ 76 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 720 ]), &(acadoWorkspace.x[ 13 ]), &(acadoVariables.x[ 76 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 724 ]), &(acadoWorkspace.x[ 14 ]), &(acadoVariables.x[ 76 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 728 ]), &(acadoWorkspace.x[ 15 ]), &(acadoVariables.x[ 76 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 732 ]), &(acadoWorkspace.x[ 16 ]), &(acadoVariables.x[ 76 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 736 ]), &(acadoWorkspace.x[ 17 ]), &(acadoVariables.x[ 76 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 740 ]), &(acadoWorkspace.x[ 18 ]), &(acadoVariables.x[ 76 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 744 ]), &(acadoWorkspace.x[ 19 ]), &(acadoVariables.x[ 76 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 748 ]), &(acadoWorkspace.x[ 20 ]), &(acadoVariables.x[ 76 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 752 ]), &(acadoWorkspace.x[ 21 ]), &(acadoVariables.x[ 76 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 756 ]), &(acadoWorkspace.x[ 22 ]), &(acadoVariables.x[ 76 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 760 ]), &(acadoWorkspace.x[ 4 ]), &(acadoVariables.x[ 80 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 764 ]), &(acadoWorkspace.x[ 5 ]), &(acadoVariables.x[ 80 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 768 ]), &(acadoWorkspace.x[ 6 ]), &(acadoVariables.x[ 80 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 772 ]), &(acadoWorkspace.x[ 7 ]), &(acadoVariables.x[ 80 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 776 ]), &(acadoWorkspace.x[ 8 ]), &(acadoVariables.x[ 80 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 780 ]), &(acadoWorkspace.x[ 9 ]), &(acadoVariables.x[ 80 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 784 ]), &(acadoWorkspace.x[ 10 ]), &(acadoVariables.x[ 80 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 788 ]), &(acadoWorkspace.x[ 11 ]), &(acadoVariables.x[ 80 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 792 ]), &(acadoWorkspace.x[ 12 ]), &(acadoVariables.x[ 80 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 796 ]), &(acadoWorkspace.x[ 13 ]), &(acadoVariables.x[ 80 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 800 ]), &(acadoWorkspace.x[ 14 ]), &(acadoVariables.x[ 80 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 804 ]), &(acadoWorkspace.x[ 15 ]), &(acadoVariables.x[ 80 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 808 ]), &(acadoWorkspace.x[ 16 ]), &(acadoVariables.x[ 80 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 812 ]), &(acadoWorkspace.x[ 17 ]), &(acadoVariables.x[ 80 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 816 ]), &(acadoWorkspace.x[ 18 ]), &(acadoVariables.x[ 80 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 820 ]), &(acadoWorkspace.x[ 19 ]), &(acadoVariables.x[ 80 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 824 ]), &(acadoWorkspace.x[ 20 ]), &(acadoVariables.x[ 80 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 828 ]), &(acadoWorkspace.x[ 21 ]), &(acadoVariables.x[ 80 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 832 ]), &(acadoWorkspace.x[ 22 ]), &(acadoVariables.x[ 80 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 836 ]), &(acadoWorkspace.x[ 23 ]), &(acadoVariables.x[ 80 ]) ); +} + +int acado_preparationStep( ) +{ +int ret; + +ret = acado_modelSimulation(); +acado_evaluateObjective( ); +acado_condensePrep( ); +return ret; +} + +int acado_feedbackStep( ) +{ +int tmp; + +acado_condenseFdb( ); + +tmp = acado_solve( ); + +acado_expand( ); +return tmp; +} + +int acado_initializeSolver( ) +{ +int ret; + +/* This is a function which must be called once before any other function call! */ + + +ret = 0; + +memset(&acadoWorkspace, 0, sizeof( acadoWorkspace )); +return ret; +} + +void acado_initializeNodesByForwardSimulation( ) +{ +int index; +for (index = 0; index < 20; ++index) +{ +acadoWorkspace.state[0] = acadoVariables.x[index * 4]; +acadoWorkspace.state[1] = acadoVariables.x[index * 4 + 1]; +acadoWorkspace.state[2] = acadoVariables.x[index * 4 + 2]; +acadoWorkspace.state[3] = acadoVariables.x[index * 4 + 3]; +acadoWorkspace.state[24] = acadoVariables.u[index]; +acadoWorkspace.state[25] = acadoVariables.od[index * 18]; +acadoWorkspace.state[26] = acadoVariables.od[index * 18 + 1]; +acadoWorkspace.state[27] = acadoVariables.od[index * 18 + 2]; +acadoWorkspace.state[28] = acadoVariables.od[index * 18 + 3]; +acadoWorkspace.state[29] = acadoVariables.od[index * 18 + 4]; +acadoWorkspace.state[30] = acadoVariables.od[index * 18 + 5]; +acadoWorkspace.state[31] = acadoVariables.od[index * 18 + 6]; +acadoWorkspace.state[32] = acadoVariables.od[index * 18 + 7]; +acadoWorkspace.state[33] = acadoVariables.od[index * 18 + 8]; +acadoWorkspace.state[34] = acadoVariables.od[index * 18 + 9]; +acadoWorkspace.state[35] = acadoVariables.od[index * 18 + 10]; +acadoWorkspace.state[36] = acadoVariables.od[index * 18 + 11]; +acadoWorkspace.state[37] = acadoVariables.od[index * 18 + 12]; +acadoWorkspace.state[38] = acadoVariables.od[index * 18 + 13]; +acadoWorkspace.state[39] = acadoVariables.od[index * 18 + 14]; +acadoWorkspace.state[40] = acadoVariables.od[index * 18 + 15]; +acadoWorkspace.state[41] = acadoVariables.od[index * 18 + 16]; +acadoWorkspace.state[42] = acadoVariables.od[index * 18 + 17]; + +acado_integrate(acadoWorkspace.state, index == 0, index); + +acadoVariables.x[index * 4 + 4] = acadoWorkspace.state[0]; +acadoVariables.x[index * 4 + 5] = acadoWorkspace.state[1]; +acadoVariables.x[index * 4 + 6] = acadoWorkspace.state[2]; +acadoVariables.x[index * 4 + 7] = acadoWorkspace.state[3]; +} +} + +void acado_shiftStates( int strategy, real_t* const xEnd, real_t* const uEnd ) +{ +int index; +for (index = 0; index < 20; ++index) +{ +acadoVariables.x[index * 4] = acadoVariables.x[index * 4 + 4]; +acadoVariables.x[index * 4 + 1] = acadoVariables.x[index * 4 + 5]; +acadoVariables.x[index * 4 + 2] = acadoVariables.x[index * 4 + 6]; +acadoVariables.x[index * 4 + 3] = acadoVariables.x[index * 4 + 7]; +} + +if (strategy == 1 && xEnd != 0) +{ +acadoVariables.x[80] = xEnd[0]; +acadoVariables.x[81] = xEnd[1]; +acadoVariables.x[82] = xEnd[2]; +acadoVariables.x[83] = xEnd[3]; +} +else if (strategy == 2) +{ +acadoWorkspace.state[0] = acadoVariables.x[80]; +acadoWorkspace.state[1] = acadoVariables.x[81]; +acadoWorkspace.state[2] = acadoVariables.x[82]; +acadoWorkspace.state[3] = acadoVariables.x[83]; +if (uEnd != 0) +{ +acadoWorkspace.state[24] = uEnd[0]; +} +else +{ +acadoWorkspace.state[24] = acadoVariables.u[19]; +} +acadoWorkspace.state[25] = acadoVariables.od[360]; +acadoWorkspace.state[26] = acadoVariables.od[361]; +acadoWorkspace.state[27] = acadoVariables.od[362]; +acadoWorkspace.state[28] = acadoVariables.od[363]; +acadoWorkspace.state[29] = acadoVariables.od[364]; +acadoWorkspace.state[30] = acadoVariables.od[365]; +acadoWorkspace.state[31] = acadoVariables.od[366]; +acadoWorkspace.state[32] = acadoVariables.od[367]; +acadoWorkspace.state[33] = acadoVariables.od[368]; +acadoWorkspace.state[34] = acadoVariables.od[369]; +acadoWorkspace.state[35] = acadoVariables.od[370]; +acadoWorkspace.state[36] = acadoVariables.od[371]; +acadoWorkspace.state[37] = acadoVariables.od[372]; +acadoWorkspace.state[38] = acadoVariables.od[373]; +acadoWorkspace.state[39] = acadoVariables.od[374]; +acadoWorkspace.state[40] = acadoVariables.od[375]; +acadoWorkspace.state[41] = acadoVariables.od[376]; +acadoWorkspace.state[42] = acadoVariables.od[377]; + +acado_integrate(acadoWorkspace.state, 1, 19); + +acadoVariables.x[80] = acadoWorkspace.state[0]; +acadoVariables.x[81] = acadoWorkspace.state[1]; +acadoVariables.x[82] = acadoWorkspace.state[2]; +acadoVariables.x[83] = acadoWorkspace.state[3]; +} +} + +void acado_shiftControls( real_t* const uEnd ) +{ +int index; +for (index = 0; index < 19; ++index) +{ +acadoVariables.u[index] = acadoVariables.u[index + 1]; +} + +if (uEnd != 0) +{ +acadoVariables.u[19] = uEnd[0]; +} +} + +real_t acado_getKKT( ) +{ +real_t kkt; + +int index; +real_t prd; + +kkt = + acadoWorkspace.g[0]*acadoWorkspace.x[0] + acadoWorkspace.g[1]*acadoWorkspace.x[1] + acadoWorkspace.g[2]*acadoWorkspace.x[2] + acadoWorkspace.g[3]*acadoWorkspace.x[3] + acadoWorkspace.g[4]*acadoWorkspace.x[4] + acadoWorkspace.g[5]*acadoWorkspace.x[5] + acadoWorkspace.g[6]*acadoWorkspace.x[6] + acadoWorkspace.g[7]*acadoWorkspace.x[7] + acadoWorkspace.g[8]*acadoWorkspace.x[8] + acadoWorkspace.g[9]*acadoWorkspace.x[9] + acadoWorkspace.g[10]*acadoWorkspace.x[10] + acadoWorkspace.g[11]*acadoWorkspace.x[11] + acadoWorkspace.g[12]*acadoWorkspace.x[12] + acadoWorkspace.g[13]*acadoWorkspace.x[13] + acadoWorkspace.g[14]*acadoWorkspace.x[14] + acadoWorkspace.g[15]*acadoWorkspace.x[15] + acadoWorkspace.g[16]*acadoWorkspace.x[16] + acadoWorkspace.g[17]*acadoWorkspace.x[17] + acadoWorkspace.g[18]*acadoWorkspace.x[18] + acadoWorkspace.g[19]*acadoWorkspace.x[19] + acadoWorkspace.g[20]*acadoWorkspace.x[20] + acadoWorkspace.g[21]*acadoWorkspace.x[21] + acadoWorkspace.g[22]*acadoWorkspace.x[22] + acadoWorkspace.g[23]*acadoWorkspace.x[23]; +kkt = fabs( kkt ); +for (index = 0; index < 24; ++index) +{ +prd = acadoWorkspace.y[index]; +if (prd > 1e-12) +kkt += fabs(acadoWorkspace.lb[index] * prd); +else if (prd < -1e-12) +kkt += fabs(acadoWorkspace.ub[index] * prd); +} +for (index = 0; index < 40; ++index) +{ +prd = acadoWorkspace.y[index + 24]; +if (prd > 1e-12) +kkt += fabs(acadoWorkspace.lbA[index] * prd); +else if (prd < -1e-12) +kkt += fabs(acadoWorkspace.ubA[index] * prd); +} +return kkt; +} + +real_t acado_getObjective( ) +{ +real_t objVal; + +int lRun1; +/** Row vector of size: 5 */ +real_t tmpDy[ 5 ]; + +/** Row vector of size: 4 */ +real_t tmpDyN[ 4 ]; + +for (lRun1 = 0; lRun1 < 20; ++lRun1) +{ +acadoWorkspace.objValueIn[0] = acadoVariables.x[lRun1 * 4]; +acadoWorkspace.objValueIn[1] = acadoVariables.x[lRun1 * 4 + 1]; +acadoWorkspace.objValueIn[2] = acadoVariables.x[lRun1 * 4 + 2]; +acadoWorkspace.objValueIn[3] = acadoVariables.x[lRun1 * 4 + 3]; +acadoWorkspace.objValueIn[4] = acadoVariables.u[lRun1]; +acadoWorkspace.objValueIn[5] = acadoVariables.od[lRun1 * 18]; +acadoWorkspace.objValueIn[6] = acadoVariables.od[lRun1 * 18 + 1]; +acadoWorkspace.objValueIn[7] = acadoVariables.od[lRun1 * 18 + 2]; +acadoWorkspace.objValueIn[8] = acadoVariables.od[lRun1 * 18 + 3]; +acadoWorkspace.objValueIn[9] = acadoVariables.od[lRun1 * 18 + 4]; +acadoWorkspace.objValueIn[10] = acadoVariables.od[lRun1 * 18 + 5]; +acadoWorkspace.objValueIn[11] = acadoVariables.od[lRun1 * 18 + 6]; +acadoWorkspace.objValueIn[12] = acadoVariables.od[lRun1 * 18 + 7]; +acadoWorkspace.objValueIn[13] = acadoVariables.od[lRun1 * 18 + 8]; +acadoWorkspace.objValueIn[14] = acadoVariables.od[lRun1 * 18 + 9]; +acadoWorkspace.objValueIn[15] = acadoVariables.od[lRun1 * 18 + 10]; +acadoWorkspace.objValueIn[16] = acadoVariables.od[lRun1 * 18 + 11]; +acadoWorkspace.objValueIn[17] = acadoVariables.od[lRun1 * 18 + 12]; +acadoWorkspace.objValueIn[18] = acadoVariables.od[lRun1 * 18 + 13]; +acadoWorkspace.objValueIn[19] = acadoVariables.od[lRun1 * 18 + 14]; +acadoWorkspace.objValueIn[20] = acadoVariables.od[lRun1 * 18 + 15]; +acadoWorkspace.objValueIn[21] = acadoVariables.od[lRun1 * 18 + 16]; +acadoWorkspace.objValueIn[22] = acadoVariables.od[lRun1 * 18 + 17]; + +acado_evaluateLSQ( acadoWorkspace.objValueIn, acadoWorkspace.objValueOut ); +acadoWorkspace.Dy[lRun1 * 5] = acadoWorkspace.objValueOut[0] - acadoVariables.y[lRun1 * 5]; +acadoWorkspace.Dy[lRun1 * 5 + 1] = acadoWorkspace.objValueOut[1] - acadoVariables.y[lRun1 * 5 + 1]; +acadoWorkspace.Dy[lRun1 * 5 + 2] = acadoWorkspace.objValueOut[2] - acadoVariables.y[lRun1 * 5 + 2]; +acadoWorkspace.Dy[lRun1 * 5 + 3] = acadoWorkspace.objValueOut[3] - acadoVariables.y[lRun1 * 5 + 3]; +acadoWorkspace.Dy[lRun1 * 5 + 4] = acadoWorkspace.objValueOut[4] - acadoVariables.y[lRun1 * 5 + 4]; +} +acadoWorkspace.objValueIn[0] = acadoVariables.x[80]; +acadoWorkspace.objValueIn[1] = acadoVariables.x[81]; +acadoWorkspace.objValueIn[2] = acadoVariables.x[82]; +acadoWorkspace.objValueIn[3] = acadoVariables.x[83]; +acadoWorkspace.objValueIn[4] = acadoVariables.od[360]; +acadoWorkspace.objValueIn[5] = acadoVariables.od[361]; +acadoWorkspace.objValueIn[6] = acadoVariables.od[362]; +acadoWorkspace.objValueIn[7] = acadoVariables.od[363]; +acadoWorkspace.objValueIn[8] = acadoVariables.od[364]; +acadoWorkspace.objValueIn[9] = acadoVariables.od[365]; +acadoWorkspace.objValueIn[10] = acadoVariables.od[366]; +acadoWorkspace.objValueIn[11] = acadoVariables.od[367]; +acadoWorkspace.objValueIn[12] = acadoVariables.od[368]; +acadoWorkspace.objValueIn[13] = acadoVariables.od[369]; +acadoWorkspace.objValueIn[14] = acadoVariables.od[370]; +acadoWorkspace.objValueIn[15] = acadoVariables.od[371]; +acadoWorkspace.objValueIn[16] = acadoVariables.od[372]; +acadoWorkspace.objValueIn[17] = acadoVariables.od[373]; +acadoWorkspace.objValueIn[18] = acadoVariables.od[374]; +acadoWorkspace.objValueIn[19] = acadoVariables.od[375]; +acadoWorkspace.objValueIn[20] = acadoVariables.od[376]; +acadoWorkspace.objValueIn[21] = acadoVariables.od[377]; +acado_evaluateLSQEndTerm( acadoWorkspace.objValueIn, acadoWorkspace.objValueOut ); +acadoWorkspace.DyN[0] = acadoWorkspace.objValueOut[0] - acadoVariables.yN[0]; +acadoWorkspace.DyN[1] = acadoWorkspace.objValueOut[1] - acadoVariables.yN[1]; +acadoWorkspace.DyN[2] = acadoWorkspace.objValueOut[2] - acadoVariables.yN[2]; +acadoWorkspace.DyN[3] = acadoWorkspace.objValueOut[3] - acadoVariables.yN[3]; +objVal = 0.0000000000000000e+00; +for (lRun1 = 0; lRun1 < 20; ++lRun1) +{ +tmpDy[0] = + acadoWorkspace.Dy[lRun1 * 5]*acadoVariables.W[lRun1 * 25] + acadoWorkspace.Dy[lRun1 * 5 + 1]*acadoVariables.W[lRun1 * 25 + 5] + acadoWorkspace.Dy[lRun1 * 5 + 2]*acadoVariables.W[lRun1 * 25 + 10] + acadoWorkspace.Dy[lRun1 * 5 + 3]*acadoVariables.W[lRun1 * 25 + 15] + acadoWorkspace.Dy[lRun1 * 5 + 4]*acadoVariables.W[lRun1 * 25 + 20]; +tmpDy[1] = + acadoWorkspace.Dy[lRun1 * 5]*acadoVariables.W[lRun1 * 25 + 1] + acadoWorkspace.Dy[lRun1 * 5 + 1]*acadoVariables.W[lRun1 * 25 + 6] + acadoWorkspace.Dy[lRun1 * 5 + 2]*acadoVariables.W[lRun1 * 25 + 11] + acadoWorkspace.Dy[lRun1 * 5 + 3]*acadoVariables.W[lRun1 * 25 + 16] + acadoWorkspace.Dy[lRun1 * 5 + 4]*acadoVariables.W[lRun1 * 25 + 21]; +tmpDy[2] = + acadoWorkspace.Dy[lRun1 * 5]*acadoVariables.W[lRun1 * 25 + 2] + acadoWorkspace.Dy[lRun1 * 5 + 1]*acadoVariables.W[lRun1 * 25 + 7] + acadoWorkspace.Dy[lRun1 * 5 + 2]*acadoVariables.W[lRun1 * 25 + 12] + acadoWorkspace.Dy[lRun1 * 5 + 3]*acadoVariables.W[lRun1 * 25 + 17] + acadoWorkspace.Dy[lRun1 * 5 + 4]*acadoVariables.W[lRun1 * 25 + 22]; +tmpDy[3] = + acadoWorkspace.Dy[lRun1 * 5]*acadoVariables.W[lRun1 * 25 + 3] + acadoWorkspace.Dy[lRun1 * 5 + 1]*acadoVariables.W[lRun1 * 25 + 8] + acadoWorkspace.Dy[lRun1 * 5 + 2]*acadoVariables.W[lRun1 * 25 + 13] + acadoWorkspace.Dy[lRun1 * 5 + 3]*acadoVariables.W[lRun1 * 25 + 18] + acadoWorkspace.Dy[lRun1 * 5 + 4]*acadoVariables.W[lRun1 * 25 + 23]; +tmpDy[4] = + acadoWorkspace.Dy[lRun1 * 5]*acadoVariables.W[lRun1 * 25 + 4] + acadoWorkspace.Dy[lRun1 * 5 + 1]*acadoVariables.W[lRun1 * 25 + 9] + acadoWorkspace.Dy[lRun1 * 5 + 2]*acadoVariables.W[lRun1 * 25 + 14] + acadoWorkspace.Dy[lRun1 * 5 + 3]*acadoVariables.W[lRun1 * 25 + 19] + acadoWorkspace.Dy[lRun1 * 5 + 4]*acadoVariables.W[lRun1 * 25 + 24]; +objVal += + acadoWorkspace.Dy[lRun1 * 5]*tmpDy[0] + acadoWorkspace.Dy[lRun1 * 5 + 1]*tmpDy[1] + acadoWorkspace.Dy[lRun1 * 5 + 2]*tmpDy[2] + acadoWorkspace.Dy[lRun1 * 5 + 3]*tmpDy[3] + acadoWorkspace.Dy[lRun1 * 5 + 4]*tmpDy[4]; +} + +tmpDyN[0] = + acadoWorkspace.DyN[0]*acadoVariables.WN[0] + acadoWorkspace.DyN[1]*acadoVariables.WN[4] + acadoWorkspace.DyN[2]*acadoVariables.WN[8] + acadoWorkspace.DyN[3]*acadoVariables.WN[12]; +tmpDyN[1] = + acadoWorkspace.DyN[0]*acadoVariables.WN[1] + acadoWorkspace.DyN[1]*acadoVariables.WN[5] + acadoWorkspace.DyN[2]*acadoVariables.WN[9] + acadoWorkspace.DyN[3]*acadoVariables.WN[13]; +tmpDyN[2] = + acadoWorkspace.DyN[0]*acadoVariables.WN[2] + acadoWorkspace.DyN[1]*acadoVariables.WN[6] + acadoWorkspace.DyN[2]*acadoVariables.WN[10] + acadoWorkspace.DyN[3]*acadoVariables.WN[14]; +tmpDyN[3] = + acadoWorkspace.DyN[0]*acadoVariables.WN[3] + acadoWorkspace.DyN[1]*acadoVariables.WN[7] + acadoWorkspace.DyN[2]*acadoVariables.WN[11] + acadoWorkspace.DyN[3]*acadoVariables.WN[15]; +objVal += + acadoWorkspace.DyN[0]*tmpDyN[0] + acadoWorkspace.DyN[1]*tmpDyN[1] + acadoWorkspace.DyN[2]*tmpDyN[2] + acadoWorkspace.DyN[3]*tmpDyN[3]; + +objVal *= 0.5; +return objVal; +} + diff --git a/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_solver.d b/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_solver.d new file mode 100644 index 00000000000000..2dae4b94389e48 --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_solver.d @@ -0,0 +1,3 @@ +lib_mpc_export/acado_solver.o: lib_mpc_export/acado_solver.c \ + lib_mpc_export/acado_common.h \ + lib_mpc_export/acado_qpoases_interface.hpp diff --git a/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_solver.o b/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_solver.o new file mode 100644 index 00000000000000..f91ea40ab5e655 Binary files /dev/null and b/selfdrive/controls/lib/lateral_mpc/lib_mpc_export/acado_solver.o differ diff --git a/selfdrive/controls/lib/lateral_mpc/lib_qp/Bounds.d b/selfdrive/controls/lib/lateral_mpc/lib_qp/Bounds.d new file mode 100644 index 00000000000000..752ec5e9f3c686 --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc/lib_qp/Bounds.d @@ -0,0 +1,14 @@ +lib_qp/Bounds.o: ../../../../phonelibs/qpoases/SRC/Bounds.cpp \ + ../../../../phonelibs/qpoases/INCLUDE/Bounds.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/SubjectTo.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Indexlist.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Utils.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/MessageHandling.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Types.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Constants.hpp \ + lib_mpc_export/acado_qpoases_interface.hpp \ + ../../../../phonelibs/qpoases/SRC/MessageHandling.ipp \ + ../../../../phonelibs/qpoases/SRC/Utils.ipp \ + ../../../../phonelibs/qpoases/SRC/Indexlist.ipp \ + ../../../../phonelibs/qpoases/SRC/SubjectTo.ipp \ + ../../../../phonelibs/qpoases/SRC/Bounds.ipp diff --git a/selfdrive/controls/lib/lateral_mpc/lib_qp/Bounds.o b/selfdrive/controls/lib/lateral_mpc/lib_qp/Bounds.o new file mode 100644 index 00000000000000..ba30572669f57d Binary files /dev/null and b/selfdrive/controls/lib/lateral_mpc/lib_qp/Bounds.o differ diff --git a/selfdrive/controls/lib/lateral_mpc/lib_qp/Constraints.d b/selfdrive/controls/lib/lateral_mpc/lib_qp/Constraints.d new file mode 100644 index 00000000000000..60295bc07b3dc9 --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc/lib_qp/Constraints.d @@ -0,0 +1,14 @@ +lib_qp/Constraints.o: ../../../../phonelibs/qpoases/SRC/Constraints.cpp \ + ../../../../phonelibs/qpoases/INCLUDE/Constraints.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/SubjectTo.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Indexlist.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Utils.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/MessageHandling.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Types.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Constants.hpp \ + lib_mpc_export/acado_qpoases_interface.hpp \ + ../../../../phonelibs/qpoases/SRC/MessageHandling.ipp \ + ../../../../phonelibs/qpoases/SRC/Utils.ipp \ + ../../../../phonelibs/qpoases/SRC/Indexlist.ipp \ + ../../../../phonelibs/qpoases/SRC/SubjectTo.ipp \ + ../../../../phonelibs/qpoases/SRC/Constraints.ipp diff --git a/selfdrive/controls/lib/lateral_mpc/lib_qp/Constraints.o b/selfdrive/controls/lib/lateral_mpc/lib_qp/Constraints.o new file mode 100644 index 00000000000000..d892c668667029 Binary files /dev/null and b/selfdrive/controls/lib/lateral_mpc/lib_qp/Constraints.o differ diff --git a/selfdrive/controls/lib/lateral_mpc/lib_qp/CyclingManager.d b/selfdrive/controls/lib/lateral_mpc/lib_qp/CyclingManager.d new file mode 100644 index 00000000000000..24145d8ed318e1 --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc/lib_qp/CyclingManager.d @@ -0,0 +1,11 @@ +lib_qp/CyclingManager.o: \ + ../../../../phonelibs/qpoases/SRC/CyclingManager.cpp \ + ../../../../phonelibs/qpoases/INCLUDE/CyclingManager.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Utils.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/MessageHandling.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Types.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Constants.hpp \ + lib_mpc_export/acado_qpoases_interface.hpp \ + ../../../../phonelibs/qpoases/SRC/MessageHandling.ipp \ + ../../../../phonelibs/qpoases/SRC/Utils.ipp \ + ../../../../phonelibs/qpoases/SRC/CyclingManager.ipp diff --git a/selfdrive/controls/lib/lateral_mpc/lib_qp/CyclingManager.o b/selfdrive/controls/lib/lateral_mpc/lib_qp/CyclingManager.o new file mode 100644 index 00000000000000..685e25d56b0c62 Binary files /dev/null and b/selfdrive/controls/lib/lateral_mpc/lib_qp/CyclingManager.o differ diff --git a/selfdrive/controls/lib/lateral_mpc/lib_qp/EXTRAS/SolutionAnalysis.d b/selfdrive/controls/lib/lateral_mpc/lib_qp/EXTRAS/SolutionAnalysis.d new file mode 100644 index 00000000000000..77c09376eef96e --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc/lib_qp/EXTRAS/SolutionAnalysis.d @@ -0,0 +1,24 @@ +lib_qp/EXTRAS/SolutionAnalysis.o: \ + ../../../../phonelibs/qpoases/SRC/EXTRAS/SolutionAnalysis.cpp \ + ../../../../phonelibs/qpoases/INCLUDE/EXTRAS/SolutionAnalysis.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/QProblem.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/QProblemB.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Bounds.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/SubjectTo.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Indexlist.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Utils.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/MessageHandling.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Types.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Constants.hpp \ + lib_mpc_export/acado_qpoases_interface.hpp \ + ../../../../phonelibs/qpoases/SRC/MessageHandling.ipp \ + ../../../../phonelibs/qpoases/SRC/Utils.ipp \ + ../../../../phonelibs/qpoases/SRC/Indexlist.ipp \ + ../../../../phonelibs/qpoases/SRC/SubjectTo.ipp \ + ../../../../phonelibs/qpoases/SRC/Bounds.ipp \ + ../../../../phonelibs/qpoases/SRC/QProblemB.ipp \ + ../../../../phonelibs/qpoases/INCLUDE/Constraints.hpp \ + ../../../../phonelibs/qpoases/SRC/Constraints.ipp \ + ../../../../phonelibs/qpoases/INCLUDE/CyclingManager.hpp \ + ../../../../phonelibs/qpoases/SRC/CyclingManager.ipp \ + ../../../../phonelibs/qpoases/SRC/QProblem.ipp diff --git a/selfdrive/controls/lib/lateral_mpc/lib_qp/EXTRAS/SolutionAnalysis.o b/selfdrive/controls/lib/lateral_mpc/lib_qp/EXTRAS/SolutionAnalysis.o new file mode 100644 index 00000000000000..987f1e56361641 Binary files /dev/null and b/selfdrive/controls/lib/lateral_mpc/lib_qp/EXTRAS/SolutionAnalysis.o differ diff --git a/selfdrive/controls/lib/lateral_mpc/lib_qp/Indexlist.d b/selfdrive/controls/lib/lateral_mpc/lib_qp/Indexlist.d new file mode 100644 index 00000000000000..6ead64cb9d8ee6 --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc/lib_qp/Indexlist.d @@ -0,0 +1,10 @@ +lib_qp/Indexlist.o: ../../../../phonelibs/qpoases/SRC/Indexlist.cpp \ + ../../../../phonelibs/qpoases/INCLUDE/Indexlist.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Utils.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/MessageHandling.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Types.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Constants.hpp \ + lib_mpc_export/acado_qpoases_interface.hpp \ + ../../../../phonelibs/qpoases/SRC/MessageHandling.ipp \ + ../../../../phonelibs/qpoases/SRC/Utils.ipp \ + ../../../../phonelibs/qpoases/SRC/Indexlist.ipp diff --git a/selfdrive/controls/lib/lateral_mpc/lib_qp/Indexlist.o b/selfdrive/controls/lib/lateral_mpc/lib_qp/Indexlist.o new file mode 100644 index 00000000000000..bd77188d453aae Binary files /dev/null and b/selfdrive/controls/lib/lateral_mpc/lib_qp/Indexlist.o differ diff --git a/selfdrive/controls/lib/lateral_mpc/lib_qp/MessageHandling.d b/selfdrive/controls/lib/lateral_mpc/lib_qp/MessageHandling.d new file mode 100644 index 00000000000000..b5c6166aba1f64 --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc/lib_qp/MessageHandling.d @@ -0,0 +1,9 @@ +lib_qp/MessageHandling.o: \ + ../../../../phonelibs/qpoases/SRC/MessageHandling.cpp \ + ../../../../phonelibs/qpoases/INCLUDE/MessageHandling.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Types.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Constants.hpp \ + lib_mpc_export/acado_qpoases_interface.hpp \ + ../../../../phonelibs/qpoases/SRC/MessageHandling.ipp \ + ../../../../phonelibs/qpoases/INCLUDE/Utils.hpp \ + ../../../../phonelibs/qpoases/SRC/Utils.ipp diff --git a/selfdrive/controls/lib/lateral_mpc/lib_qp/MessageHandling.o b/selfdrive/controls/lib/lateral_mpc/lib_qp/MessageHandling.o new file mode 100644 index 00000000000000..87b200d0475adb Binary files /dev/null and b/selfdrive/controls/lib/lateral_mpc/lib_qp/MessageHandling.o differ diff --git a/selfdrive/controls/lib/lateral_mpc/lib_qp/QProblem.d b/selfdrive/controls/lib/lateral_mpc/lib_qp/QProblem.d new file mode 100644 index 00000000000000..1f6e188af55c17 --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc/lib_qp/QProblem.d @@ -0,0 +1,22 @@ +lib_qp/QProblem.o: ../../../../phonelibs/qpoases/SRC/QProblem.cpp \ + ../../../../phonelibs/qpoases/INCLUDE/QProblem.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/QProblemB.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Bounds.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/SubjectTo.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Indexlist.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Utils.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/MessageHandling.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Types.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Constants.hpp \ + lib_mpc_export/acado_qpoases_interface.hpp \ + ../../../../phonelibs/qpoases/SRC/MessageHandling.ipp \ + ../../../../phonelibs/qpoases/SRC/Utils.ipp \ + ../../../../phonelibs/qpoases/SRC/Indexlist.ipp \ + ../../../../phonelibs/qpoases/SRC/SubjectTo.ipp \ + ../../../../phonelibs/qpoases/SRC/Bounds.ipp \ + ../../../../phonelibs/qpoases/SRC/QProblemB.ipp \ + ../../../../phonelibs/qpoases/INCLUDE/Constraints.hpp \ + ../../../../phonelibs/qpoases/SRC/Constraints.ipp \ + ../../../../phonelibs/qpoases/INCLUDE/CyclingManager.hpp \ + ../../../../phonelibs/qpoases/SRC/CyclingManager.ipp \ + ../../../../phonelibs/qpoases/SRC/QProblem.ipp diff --git a/selfdrive/controls/lib/lateral_mpc/lib_qp/QProblem.o b/selfdrive/controls/lib/lateral_mpc/lib_qp/QProblem.o new file mode 100644 index 00000000000000..8c179beae1dc8f Binary files /dev/null and b/selfdrive/controls/lib/lateral_mpc/lib_qp/QProblem.o differ diff --git a/selfdrive/controls/lib/lateral_mpc/lib_qp/QProblemB.d b/selfdrive/controls/lib/lateral_mpc/lib_qp/QProblemB.d new file mode 100644 index 00000000000000..7878a825ce5749 --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc/lib_qp/QProblemB.d @@ -0,0 +1,16 @@ +lib_qp/QProblemB.o: ../../../../phonelibs/qpoases/SRC/QProblemB.cpp \ + ../../../../phonelibs/qpoases/INCLUDE/QProblemB.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Bounds.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/SubjectTo.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Indexlist.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Utils.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/MessageHandling.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Types.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Constants.hpp \ + lib_mpc_export/acado_qpoases_interface.hpp \ + ../../../../phonelibs/qpoases/SRC/MessageHandling.ipp \ + ../../../../phonelibs/qpoases/SRC/Utils.ipp \ + ../../../../phonelibs/qpoases/SRC/Indexlist.ipp \ + ../../../../phonelibs/qpoases/SRC/SubjectTo.ipp \ + ../../../../phonelibs/qpoases/SRC/Bounds.ipp \ + ../../../../phonelibs/qpoases/SRC/QProblemB.ipp diff --git a/selfdrive/controls/lib/lateral_mpc/lib_qp/QProblemB.o b/selfdrive/controls/lib/lateral_mpc/lib_qp/QProblemB.o new file mode 100644 index 00000000000000..9c75cb83225246 Binary files /dev/null and b/selfdrive/controls/lib/lateral_mpc/lib_qp/QProblemB.o differ diff --git a/selfdrive/controls/lib/lateral_mpc/lib_qp/SubjectTo.d b/selfdrive/controls/lib/lateral_mpc/lib_qp/SubjectTo.d new file mode 100644 index 00000000000000..c896d9a9faf58d --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc/lib_qp/SubjectTo.d @@ -0,0 +1,12 @@ +lib_qp/SubjectTo.o: ../../../../phonelibs/qpoases/SRC/SubjectTo.cpp \ + ../../../../phonelibs/qpoases/INCLUDE/SubjectTo.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Indexlist.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Utils.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/MessageHandling.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Types.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Constants.hpp \ + lib_mpc_export/acado_qpoases_interface.hpp \ + ../../../../phonelibs/qpoases/SRC/MessageHandling.ipp \ + ../../../../phonelibs/qpoases/SRC/Utils.ipp \ + ../../../../phonelibs/qpoases/SRC/Indexlist.ipp \ + ../../../../phonelibs/qpoases/SRC/SubjectTo.ipp diff --git a/selfdrive/controls/lib/lateral_mpc/lib_qp/SubjectTo.o b/selfdrive/controls/lib/lateral_mpc/lib_qp/SubjectTo.o new file mode 100644 index 00000000000000..820c930ce31ec4 Binary files /dev/null and b/selfdrive/controls/lib/lateral_mpc/lib_qp/SubjectTo.o differ diff --git a/selfdrive/controls/lib/lateral_mpc/lib_qp/Utils.d b/selfdrive/controls/lib/lateral_mpc/lib_qp/Utils.d new file mode 100644 index 00000000000000..58f35a065397a3 --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc/lib_qp/Utils.d @@ -0,0 +1,8 @@ +lib_qp/Utils.o: ../../../../phonelibs/qpoases/SRC/Utils.cpp \ + ../../../../phonelibs/qpoases/INCLUDE/Utils.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/MessageHandling.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Types.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Constants.hpp \ + lib_mpc_export/acado_qpoases_interface.hpp \ + ../../../../phonelibs/qpoases/SRC/MessageHandling.ipp \ + ../../../../phonelibs/qpoases/SRC/Utils.ipp diff --git a/selfdrive/controls/lib/lateral_mpc/lib_qp/Utils.o b/selfdrive/controls/lib/lateral_mpc/lib_qp/Utils.o new file mode 100644 index 00000000000000..ef645ef188049f Binary files /dev/null and b/selfdrive/controls/lib/lateral_mpc/lib_qp/Utils.o differ diff --git a/selfdrive/controls/lib/lateral_mpc/libmpc.so b/selfdrive/controls/lib/lateral_mpc/libmpc.so new file mode 100755 index 00000000000000..a0c0dc815d3b10 Binary files /dev/null and b/selfdrive/controls/lib/lateral_mpc/libmpc.so differ diff --git a/selfdrive/controls/lib/lateral_mpc/libmpc_py.py b/selfdrive/controls/lib/lateral_mpc/libmpc_py.py new file mode 100644 index 00000000000000..1537d2f6c027dd --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc/libmpc_py.py @@ -0,0 +1,30 @@ +import os +import subprocess + +from cffi import FFI + +mpc_dir = os.path.dirname(os.path.abspath(__file__)) +libmpc_fn = os.path.join(mpc_dir, "libmpc.so") +subprocess.check_call(["make", "-j4"], cwd=mpc_dir) + +ffi = FFI() +ffi.cdef(""" +typedef struct { + double x, y, psi, delta, t; +} state_t; + +typedef struct { + double x[21]; + double y[21]; + double psi[21]; + double delta[21]; + double cost; +} log_t; + +void init(double pathCost, double laneCost, double headingCost, double steerRateCost); +int run_mpc(state_t * x0, log_t * solution, + double l_poly[4], double r_poly[4], double p_poly[4], + double l_prob, double r_prob, double p_prob, double curvature_factor, double v_ref, double lane_width); +""") + +libmpc = ffi.dlopen(libmpc_fn) diff --git a/selfdrive/controls/lib/longcontrol.py b/selfdrive/controls/lib/longcontrol.py new file mode 100644 index 00000000000000..db92430e61dbcf --- /dev/null +++ b/selfdrive/controls/lib/longcontrol.py @@ -0,0 +1,130 @@ +from cereal import log +from common.numpy_fast import clip, interp +from selfdrive.controls.lib.pid import PIController + +LongCtrlState = log.Live100Data.LongControlState + +STOPPING_EGO_SPEED = 0.5 +MIN_CAN_SPEED = 0.3 # TODO: parametrize this in car interface +STOPPING_TARGET_SPEED = MIN_CAN_SPEED + 0.01 +STARTING_TARGET_SPEED = 0.5 +BRAKE_THRESHOLD_TO_PID = 0.2 + +STOPPING_BRAKE_RATE = 0.2 # brake_travel/s while trying to stop +STARTING_BRAKE_RATE = 0.8 # brake_travel/s while releasing on restart +BRAKE_STOPPING_TARGET = 0.25 # apply at least this amount of brake to maintain the vehicle stationary + +_MAX_SPEED_ERROR_BP = [0., 30.] # speed breakpoints +_MAX_SPEED_ERROR_V = [1.5, .8] # max positive v_pid error VS actual speed; this avoids controls windup due to slow pedal resp + +RATE = 100.0 + + +def long_control_state_trans(active, long_control_state, v_ego, v_target, v_pid, + output_gb, brake_pressed, cruise_standstill): + """Update longitudinal control state machine""" + stopping_condition = (v_ego < 2.0 and cruise_standstill) or \ + (v_ego < STOPPING_EGO_SPEED and \ + ((v_pid < STOPPING_TARGET_SPEED and v_target < STOPPING_TARGET_SPEED) or + brake_pressed)) + + starting_condition = v_target > STARTING_TARGET_SPEED and not cruise_standstill + + if not active: + long_control_state = LongCtrlState.off + + else: + if long_control_state == LongCtrlState.off: + if active: + long_control_state = LongCtrlState.pid + + elif long_control_state == LongCtrlState.pid: + if stopping_condition: + long_control_state = LongCtrlState.stopping + + elif long_control_state == LongCtrlState.stopping: + if starting_condition: + long_control_state = LongCtrlState.starting + + elif long_control_state == LongCtrlState.starting: + if stopping_condition: + long_control_state = LongCtrlState.stopping + elif output_gb >= -BRAKE_THRESHOLD_TO_PID: + long_control_state = LongCtrlState.pid + + return long_control_state + + +class LongControl(object): + def __init__(self, CP, compute_gb): + self.long_control_state = LongCtrlState.off # initialized to off + self.pid = PIController((CP.longitudinalKpBP, CP.longitudinalKpV), + (CP.longitudinalKiBP, CP.longitudinalKiV), + rate=RATE, + sat_limit=0.8, + convert=compute_gb) + self.v_pid = 0.0 + self.last_output_gb = 0.0 + + def reset(self, v_pid): + """Reset PID controller and change setpoint""" + self.pid.reset() + self.v_pid = v_pid + + def update(self, active, v_ego, brake_pressed, standstill, cruise_standstill, v_cruise, v_target, v_target_future, a_target, CP, lead_1): + """Update longitudinal control. This updates the state machine and runs a PID loop""" + # Actuation limits + gas_max = interp(v_ego, CP.gasMaxBP, CP.gasMaxV) + brake_max = interp(v_ego, CP.brakeMaxBP, CP.brakeMaxV) + + # Update state machine + output_gb = self.last_output_gb + self.long_control_state = long_control_state_trans(active, self.long_control_state, v_ego, + v_target_future, self.v_pid, output_gb, + brake_pressed, cruise_standstill) + + v_ego_pid = max(v_ego, MIN_CAN_SPEED) # Without this we get jumps, CAN bus reports 0 when speed < 0.3 + + if self.long_control_state == LongCtrlState.off: + self.v_pid = v_ego_pid + self.pid.reset() + output_gb = 0. + + # tracking objects and driving + elif self.long_control_state == LongCtrlState.pid: + self.v_pid = v_target + self.pid.pos_limit = gas_max + self.pid.neg_limit = - brake_max + + # Toyota starts braking more when it thinks you want to stop + # Freeze the integrator so we don't accelerate to compensate, and don't allow positive acceleration + prevent_overshoot = not CP.stoppingControl and v_ego < 1.5 and v_target_future < 0.7 + deadzone = interp(v_ego_pid, CP.longPidDeadzoneBP, CP.longPidDeadzoneV) + + output_gb = self.pid.update(self.v_pid, v_ego_pid, speed=v_ego_pid, deadzone=deadzone, feedforward=a_target, freeze_integrator=prevent_overshoot) + + if prevent_overshoot: + output_gb = min(output_gb, 0.0) + + # Intention is to stop, switch to a different brake control until we stop + elif self.long_control_state == LongCtrlState.stopping: + # Keep applying brakes until the car is stopped + if not standstill or output_gb > -BRAKE_STOPPING_TARGET: + output_gb -= STOPPING_BRAKE_RATE / RATE + output_gb = clip(output_gb, -brake_max, gas_max) + + self.v_pid = v_ego + self.pid.reset() + + # Intention is to move again, release brake fast before handing control to PID + elif self.long_control_state == LongCtrlState.starting: + if output_gb < -0.2: + output_gb += STARTING_BRAKE_RATE / RATE + self.v_pid = v_ego + self.pid.reset() + + self.last_output_gb = output_gb + final_gas = clip(output_gb, 0., gas_max) + final_brake = -clip(output_gb, -brake_max, 0.) + + return final_gas, final_brake diff --git a/selfdrive/controls/lib/longitudinal_mpc/Makefile b/selfdrive/controls/lib/longitudinal_mpc/Makefile new file mode 100644 index 00000000000000..93cb0a880ef403 --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc/Makefile @@ -0,0 +1,89 @@ +CC = clang +CXX = clang++ + +PHONELIBS = ../../../../phonelibs + +UNAME_S := $(shell uname -s) +UNAME_M := $(shell uname -m) + +CFLAGS = -O3 -fPIC -I. +CXXFLAGS = -O3 -fPIC -I. + +QPOASES_FLAGS = -I$(PHONELIBS)/qpoases -I$(PHONELIBS)/qpoases/INCLUDE -I$(PHONELIBS)/qpoases/SRC + +ACADO_FLAGS = -I$(PHONELIBS)/acado/include -I$(PHONELIBS)/acado/include/acado + +ifeq ($(UNAME_S),Darwin) + ACADO_LIBS := -lacado_toolkit_s +else ifeq ($(UNAME_M),aarch64) + ACADO_LIBS := -L $(PHONELIBS)/acado/aarch64/lib -l:libacado_toolkit.a -l:libacado_casadi.a -l:libacado_csparse.a +else + ACADO_LIBS := -L $(PHONELIBS)/acado/x64/lib -l:libacado_toolkit.a -l:libacado_casadi.a -l:libacado_csparse.a +endif + +OBJS = \ + lib_qp/Bounds.o \ + lib_qp/Constraints.o \ + lib_qp/CyclingManager.o \ + lib_qp/Indexlist.o \ + lib_qp/MessageHandling.o \ + lib_qp/QProblem.o \ + lib_qp/QProblemB.o \ + lib_qp/SubjectTo.o \ + lib_qp/Utils.o \ + lib_qp/EXTRAS/SolutionAnalysis.o \ + lib_mpc_export/acado_qpoases_interface.o \ + lib_mpc_export/acado_integrator.o \ + lib_mpc_export/acado_solver.o \ + lib_mpc_export/acado_auxiliary_functions.o \ + longitudinal_mpc.o + +DEPS := $(OBJS:.o=.d) + +.PHONY: all +all: libmpc1.so libmpc2.so + +libmpc1.so: $(OBJS) + $(CXX) -shared -o '$@' $^ -lm + +libmpc2.so: libmpc1.so + cp libmpc1.so libmpc2.so + +lib_qp/%.o: $(PHONELIBS)/qpoases/SRC/%.cpp + @echo "[ CXX ] $@" + mkdir -p lib_qp/EXTRAS + $(CXX) $(CXXFLAGS) -MMD \ + -I lib_mpc_export/ \ + $(QPOASES_FLAGS) \ + -c -o '$@' '$<' + +%.o: %.cpp + @echo "[ CXX ] $@" + $(CXX) $(CXXFLAGS) -MMD \ + -I lib_mpc_export/ \ + $(QPOASES_FLAGS) \ + -c -o '$@' '$<' + +%.o: %.c + @echo "[ CC ] $@" + $(CC) $(CFLAGS) -MMD \ + -I lib_mpc_export/ \ + $(QPOASES_FLAGS) \ + -c -o '$@' '$<' + +generator: generator.cpp + $(CXX) -v -Wall -std=c++11 \ + generator.cpp \ + -o generator \ + $(ACADO_FLAGS) \ + $(ACADO_LIBS) + +.PHONY: generate +generate: generator + ./generator + +.PHONY: clean +clean: + rm -f *.so generator $(OBJS) $(DEPS) + +-include $(DEPS) diff --git a/selfdrive/controls/lib/longitudinal_mpc/__init__.py b/selfdrive/controls/lib/longitudinal_mpc/__init__.py new file mode 100644 index 00000000000000..e69de29bb2d1d6 diff --git a/selfdrive/controls/lib/longitudinal_mpc/generator.cpp b/selfdrive/controls/lib/longitudinal_mpc/generator.cpp new file mode 100644 index 00000000000000..f5c95394d8d3f1 --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc/generator.cpp @@ -0,0 +1,106 @@ +#include + +const int controlHorizon = 50; + +using namespace std; + +#define G 9.81 +#define TR 1.8 + +#define RW(v_ego, v_l) (v_ego * TR - (v_l - v_ego) * TR + v_ego*v_ego/(2*G) - v_l*v_l / (2*G)) +#define NORM_RW_ERROR(v_ego, v_l, p) ((RW(v_ego, v_l) + 4.0 - p)/(sqrt(v_ego + 0.5) + 0.1)) + +int main( ) +{ + USING_NAMESPACE_ACADO + + + DifferentialEquation f; + + DifferentialState x_ego, v_ego, a_ego; + DifferentialState x_l, v_l, t; + + OnlineData lambda, a_l_0; + + Control j_ego; + + auto desired = 4.0 + RW(v_ego, v_l); + auto d_l = x_l - x_ego; + + // Directly calculate a_l to prevent instabilites due to discretization + auto a_l = a_l_0 * exp(-lambda * t * t / 2); + + // Equations of motion + f << dot(x_ego) == v_ego; + f << dot(v_ego) == a_ego; + f << dot(a_ego) == j_ego; + + f << dot(x_l) == v_l; + f << dot(v_l) == a_l; + f << dot(t) == 1; + + // Running cost + Function h; + h << exp(0.3 * NORM_RW_ERROR(v_ego, v_l, d_l)) - exp(0.3 * NORM_RW_ERROR(v_ego, v_l, desired)); + h << (d_l - desired) / (0.05 * v_ego + 0.5); + h << a_ego * (0.1 * v_ego + 1.0); + h << j_ego * (0.1 * v_ego + 1.0); + + // Weights are defined in mpc. + BMatrix Q(4,4); Q.setAll(true); + + // Terminal cost + Function hN; + hN << exp(0.3 * NORM_RW_ERROR(v_ego, v_l, d_l)) - exp(0.3 * NORM_RW_ERROR(v_ego, v_l, desired)); + hN << (d_l - desired) / (0.05 * v_ego + 0.5); + hN << a_ego * (0.1 * v_ego + 1.0); + + // Weights are defined in mpc. + BMatrix QN(3,3); QN.setAll(true); + + // Non uniform time grid + // First 5 timesteps are 0.2, after that it's 0.6 + DMatrix numSteps(20, 1); + for (int i = 0; i < 5; i++){ + numSteps(i) = 1; + } + for (int i = 5; i < 20; i++){ + numSteps(i) = 3; + } + + // Setup Optimal Control Problem + const double tStart = 0.0; + const double tEnd = 10.0; + + OCP ocp( tStart, tEnd, numSteps); + ocp.subjectTo(f); + + ocp.minimizeLSQ(Q, h); + ocp.minimizeLSQEndTerm(QN, hN); + + ocp.subjectTo( 0.0 <= v_ego); + ocp.setNOD(2); + + OCPexport mpc(ocp); + mpc.set( HESSIAN_APPROXIMATION, GAUSS_NEWTON ); + mpc.set( DISCRETIZATION_TYPE, MULTIPLE_SHOOTING ); + mpc.set( INTEGRATOR_TYPE, INT_RK4 ); + mpc.set( NUM_INTEGRATOR_STEPS, controlHorizon); + mpc.set( MAX_NUM_QP_ITERATIONS, 500); + mpc.set( CG_USE_VARIABLE_WEIGHTING_MATRIX, YES); + + mpc.set( SPARSE_QP_SOLUTION, CONDENSING ); + mpc.set( QP_SOLVER, QP_QPOASES ); + mpc.set( HOTSTART_QP, YES ); + mpc.set( GENERATE_TEST_FILE, NO); + mpc.set( GENERATE_MAKE_FILE, NO ); + mpc.set( GENERATE_MATLAB_INTERFACE, NO ); + mpc.set( GENERATE_SIMULINK_INTERFACE, NO ); + + if (mpc.exportCode( "lib_mpc_export" ) != SUCCESSFUL_RETURN) + exit( EXIT_FAILURE ); + + mpc.printDimensionsQP( ); + + return EXIT_SUCCESS; +} diff --git a/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_auxiliary_functions.c b/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_auxiliary_functions.c new file mode 100644 index 00000000000000..6f0bb705c8a897 --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_auxiliary_functions.c @@ -0,0 +1,212 @@ +/* + * This file was auto-generated using the ACADO Toolkit. + * + * While ACADO Toolkit is free software released under the terms of + * the GNU Lesser General Public License (LGPL), the generated code + * as such remains the property of the user who used ACADO Toolkit + * to generate this code. In particular, user dependent data of the code + * do not inherit the GNU LGPL license. On the other hand, parts of the + * generated code that are a direct copy of source code from the + * ACADO Toolkit or the software tools it is based on, remain, as derived + * work, automatically covered by the LGPL license. + * + * ACADO Toolkit 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. + * + */ + + +#include "acado_auxiliary_functions.h" + +#include + +real_t* acado_getVariablesX( ) +{ + return acadoVariables.x; +} + +real_t* acado_getVariablesU( ) +{ + return acadoVariables.u; +} + +#if ACADO_NY > 0 +real_t* acado_getVariablesY( ) +{ + return acadoVariables.y; +} +#endif + +#if ACADO_NYN > 0 +real_t* acado_getVariablesYN( ) +{ + return acadoVariables.yN; +} +#endif + +real_t* acado_getVariablesX0( ) +{ +#if ACADO_INITIAL_VALUE_FIXED + return acadoVariables.x0; +#else + return 0; +#endif +} + +/** Print differential variables. */ +void acado_printDifferentialVariables( ) +{ + int i, j; + printf("\nDifferential variables:\n[\n"); + for (i = 0; i < ACADO_N + 1; ++i) + { + for (j = 0; j < ACADO_NX; ++j) + printf("\t%e", acadoVariables.x[i * ACADO_NX + j]); + printf("\n"); + } + printf("]\n\n"); +} + +/** Print control variables. */ +void acado_printControlVariables( ) +{ + int i, j; + printf("\nControl variables:\n[\n"); + for (i = 0; i < ACADO_N; ++i) + { + for (j = 0; j < ACADO_NU; ++j) + printf("\t%e", acadoVariables.u[i * ACADO_NU + j]); + printf("\n"); + } + printf("]\n\n"); +} + +/** Print ACADO code generation notice. */ +void acado_printHeader( ) +{ + printf( + "\nACADO Toolkit -- A Toolkit for Automatic Control and Dynamic Optimization.\n" + "Copyright (C) 2008-2015 by Boris Houska, Hans Joachim Ferreau,\n" + "Milan Vukov and Rien Quirynen, KU Leuven.\n" + ); + + printf( + "Developed within the Optimization in Engineering Center (OPTEC) under\n" + "supervision of Moritz Diehl. All rights reserved.\n\n" + "ACADO Toolkit is distributed under the terms of the GNU Lesser\n" + "General Public License 3 in the hope that it will be useful,\n" + "but WITHOUT ANY WARRANTY; without even the implied warranty of\n" + "MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the\n" + "GNU Lesser General Public License for more details.\n\n" + ); +} + +#if !(defined _DSPACE) +#if (defined _WIN32 || defined _WIN64) && !(defined __MINGW32__ || defined __MINGW64__) + +void acado_tic( acado_timer* t ) +{ + QueryPerformanceFrequency(&t->freq); + QueryPerformanceCounter(&t->tic); +} + +real_t acado_toc( acado_timer* t ) +{ + QueryPerformanceCounter(&t->toc); + return ((t->toc.QuadPart - t->tic.QuadPart) / (real_t)t->freq.QuadPart); +} + + +#elif (defined __APPLE__) + +void acado_tic( acado_timer* t ) +{ + /* read current clock cycles */ + t->tic = mach_absolute_time(); +} + +real_t acado_toc( acado_timer* t ) +{ + + uint64_t duration; /* elapsed time in clock cycles*/ + + t->toc = mach_absolute_time(); + duration = t->toc - t->tic; + + /*conversion from clock cycles to nanoseconds*/ + mach_timebase_info(&(t->tinfo)); + duration *= t->tinfo.numer; + duration /= t->tinfo.denom; + + return (real_t)duration / 1e9; +} + +#else + +#if __STDC_VERSION__ >= 199901L +/* C99 mode */ + +/* read current time */ +void acado_tic( acado_timer* t ) +{ + gettimeofday(&t->tic, 0); +} + +/* return time passed since last call to tic on this timer */ +real_t acado_toc( acado_timer* t ) +{ + struct timeval temp; + + gettimeofday(&t->toc, 0); + + if ((t->toc.tv_usec - t->tic.tv_usec) < 0) + { + temp.tv_sec = t->toc.tv_sec - t->tic.tv_sec - 1; + temp.tv_usec = 1000000 + t->toc.tv_usec - t->tic.tv_usec; + } + else + { + temp.tv_sec = t->toc.tv_sec - t->tic.tv_sec; + temp.tv_usec = t->toc.tv_usec - t->tic.tv_usec; + } + + return (real_t)temp.tv_sec + (real_t)temp.tv_usec / 1e6; +} + +#else +/* ANSI */ + +/* read current time */ +void acado_tic( acado_timer* t ) +{ + clock_gettime(CLOCK_MONOTONIC, &t->tic); +} + + +/* return time passed since last call to tic on this timer */ +real_t acado_toc( acado_timer* t ) +{ + struct timespec temp; + + clock_gettime(CLOCK_MONOTONIC, &t->toc); + + if ((t->toc.tv_nsec - t->tic.tv_nsec) < 0) + { + temp.tv_sec = t->toc.tv_sec - t->tic.tv_sec - 1; + temp.tv_nsec = 1000000000+t->toc.tv_nsec - t->tic.tv_nsec; + } + else + { + temp.tv_sec = t->toc.tv_sec - t->tic.tv_sec; + temp.tv_nsec = t->toc.tv_nsec - t->tic.tv_nsec; + } + + return (real_t)temp.tv_sec + (real_t)temp.tv_nsec / 1e9; +} + +#endif /* __STDC_VERSION__ >= 199901L */ + +#endif /* (defined _WIN32 || _WIN64) */ + +#endif diff --git a/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_auxiliary_functions.d b/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_auxiliary_functions.d new file mode 100644 index 00000000000000..50c6a60d1fb846 --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_auxiliary_functions.d @@ -0,0 +1,5 @@ +lib_mpc_export/acado_auxiliary_functions.o: \ + lib_mpc_export/acado_auxiliary_functions.c \ + lib_mpc_export/acado_auxiliary_functions.h \ + lib_mpc_export/acado_common.h \ + lib_mpc_export/acado_qpoases_interface.hpp diff --git a/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_auxiliary_functions.h b/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_auxiliary_functions.h new file mode 100644 index 00000000000000..b1be0a661c0125 --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_auxiliary_functions.h @@ -0,0 +1,138 @@ +/* + * This file was auto-generated using the ACADO Toolkit. + * + * While ACADO Toolkit is free software released under the terms of + * the GNU Lesser General Public License (LGPL), the generated code + * as such remains the property of the user who used ACADO Toolkit + * to generate this code. In particular, user dependent data of the code + * do not inherit the GNU LGPL license. On the other hand, parts of the + * generated code that are a direct copy of source code from the + * ACADO Toolkit or the software tools it is based on, remain, as derived + * work, automatically covered by the LGPL license. + * + * ACADO Toolkit 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. + * + */ + + +#ifndef ACADO_AUXILIARY_FUNCTIONS_H +#define ACADO_AUXILIARY_FUNCTIONS_H + +#include "acado_common.h" + +#ifndef __MATLAB__ +#ifdef __cplusplus +extern "C" +{ +#endif /* __cplusplus */ +#endif /* __MATLAB__ */ + +/** Get pointer to the matrix with differential variables. */ +real_t* acado_getVariablesX( ); + +/** Get pointer to the matrix with control variables. */ +real_t* acado_getVariablesU( ); + +#if ACADO_NY > 0 +/** Get pointer to the matrix with references/measurements. */ +real_t* acado_getVariablesY( ); +#endif + +#if ACADO_NYN > 0 +/** Get pointer to the vector with references/measurement on the last node. */ +real_t* acado_getVariablesYN( ); +#endif + +/** Get pointer to the current state feedback vector. Only applicable for NMPC. */ +real_t* acado_getVariablesX0( ); + +/** Print differential variables. */ +void acado_printDifferentialVariables( ); + +/** Print control variables. */ +void acado_printControlVariables( ); + +/** Print ACADO code generation notice. */ +void acado_printHeader( ); + +/* + * A huge thanks goes to Alexander Domahidi from ETHZ, Switzerland, for + * providing us with the following timing routines. + */ + +#if !(defined _DSPACE) +#if (defined _WIN32 || defined _WIN64) && !(defined __MINGW32__ || defined __MINGW64__) + +/* Use Windows QueryPerformanceCounter for timing. */ +#include + +/** A structure for keeping internal timer data. */ +typedef struct acado_timer_ +{ + LARGE_INTEGER tic; + LARGE_INTEGER toc; + LARGE_INTEGER freq; +} acado_timer; + + +#elif (defined __APPLE__) + +#include "unistd.h" +#include + +/** A structure for keeping internal timer data. */ +typedef struct acado_timer_ +{ + uint64_t tic; + uint64_t toc; + mach_timebase_info_data_t tinfo; +} acado_timer; + +#else + +/* Use POSIX clock_gettime() for timing on non-Windows machines. */ +#include + +#if __STDC_VERSION__ >= 199901L +/* C99 mode of operation. */ + +#include +#include + +typedef struct acado_timer_ +{ + struct timeval tic; + struct timeval toc; +} acado_timer; + +#else +/* ANSI C */ + +/** A structure for keeping internal timer data. */ +typedef struct acado_timer_ +{ + struct timespec tic; + struct timespec toc; +} acado_timer; + +#endif /* __STDC_VERSION__ >= 199901L */ + +#endif /* (defined _WIN32 || defined _WIN64) */ + +/** A function for measurement of the current time. */ +void acado_tic( acado_timer* t ); + +/** A function which returns the elapsed time. */ +real_t acado_toc( acado_timer* t ); + +#endif + +#ifndef __MATLAB__ +#ifdef __cplusplus +} /* extern "C" */ +#endif /* __cplusplus */ +#endif /* __MATLAB__ */ + +#endif /* ACADO_AUXILIARY_FUNCTIONS_H */ diff --git a/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_auxiliary_functions.o b/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_auxiliary_functions.o new file mode 100644 index 00000000000000..65182c5bb1ee55 Binary files /dev/null and b/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_auxiliary_functions.o differ diff --git a/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_common.h b/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_common.h new file mode 100644 index 00000000000000..cecba6e7408cba --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_common.h @@ -0,0 +1,357 @@ +/* + * This file was auto-generated using the ACADO Toolkit. + * + * While ACADO Toolkit is free software released under the terms of + * the GNU Lesser General Public License (LGPL), the generated code + * as such remains the property of the user who used ACADO Toolkit + * to generate this code. In particular, user dependent data of the code + * do not inherit the GNU LGPL license. On the other hand, parts of the + * generated code that are a direct copy of source code from the + * ACADO Toolkit or the software tools it is based on, remain, as derived + * work, automatically covered by the LGPL license. + * + * ACADO Toolkit 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. + * + */ + + +#ifndef ACADO_COMMON_H +#define ACADO_COMMON_H + +#include +#include + +#ifndef __MATLAB__ +#ifdef __cplusplus +extern "C" +{ +#endif /* __cplusplus */ +#endif /* __MATLAB__ */ + +/** \defgroup ACADO ACADO CGT generated module. */ +/** @{ */ + +/** qpOASES QP solver indicator. */ +#define ACADO_QPOASES 0 +#define ACADO_QPOASES3 1 +/** FORCES QP solver indicator.*/ +#define ACADO_FORCES 2 +/** qpDUNES QP solver indicator.*/ +#define ACADO_QPDUNES 3 +/** HPMPC QP solver indicator. */ +#define ACADO_HPMPC 4 +#define ACADO_GENERIC 5 + +/** Indicator for determining the QP solver used by the ACADO solver code. */ +#define ACADO_QP_SOLVER ACADO_QPOASES + +#include "acado_qpoases_interface.hpp" + + +/* + * Common definitions + */ +/** User defined block based condensing. */ +#define ACADO_BLOCK_CONDENSING 0 +/** Compute covariance matrix of the last state estimate. */ +#define ACADO_COMPUTE_COVARIANCE_MATRIX 0 +/** Flag indicating whether constraint values are hard-coded or not. */ +#define ACADO_HARDCODED_CONSTRAINT_VALUES 1 +/** Indicator for fixed initial state. */ +#define ACADO_INITIAL_STATE_FIXED 1 +/** Number of control/estimation intervals. */ +#define ACADO_N 20 +/** Number of online data values. */ +#define ACADO_NOD 2 +/** Number of path constraints. */ +#define ACADO_NPAC 0 +/** Number of control variables. */ +#define ACADO_NU 1 +/** Number of differential variables. */ +#define ACADO_NX 6 +/** Number of algebraic variables. */ +#define ACADO_NXA 0 +/** Number of differential derivative variables. */ +#define ACADO_NXD 0 +/** Number of references/measurements per node on the first N nodes. */ +#define ACADO_NY 4 +/** Number of references/measurements on the last (N + 1)st node. */ +#define ACADO_NYN 3 +/** Total number of QP optimization variables. */ +#define ACADO_QP_NV 26 +/** Number of Runge-Kutta stages per integration step. */ +#define ACADO_RK_NSTAGES 4 +/** Providing interface for arrival cost. */ +#define ACADO_USE_ARRIVAL_COST 0 +/** Indicator for usage of non-hard-coded linear terms in the objective. */ +#define ACADO_USE_LINEAR_TERMS 0 +/** Indicator for type of fixed weighting matrices. */ +#define ACADO_WEIGHTING_MATRICES_TYPE 2 + + +/* + * Globally used structure definitions + */ + +/** The structure containing the user data. + * + * Via this structure the user "communicates" with the solver code. + */ +typedef struct ACADOvariables_ +{ +int dummy; +/** Matrix of size: 21 x 6 (row major format) + * + * Matrix containing 21 differential variable vectors. + */ +real_t x[ 126 ]; + +/** Column vector of size: 20 + * + * Matrix containing 20 control variable vectors. + */ +real_t u[ 20 ]; + +/** Matrix of size: 21 x 2 (row major format) + * + * Matrix containing 21 online data vectors. + */ +real_t od[ 42 ]; + +/** Column vector of size: 80 + * + * Matrix containing 20 reference/measurement vectors of size 4 for first 20 nodes. + */ +real_t y[ 80 ]; + +/** Column vector of size: 3 + * + * Reference/measurement vector for the 21. node. + */ +real_t yN[ 3 ]; + +/** Matrix of size: 80 x 4 (row major format) */ +real_t W[ 320 ]; + +/** Matrix of size: 3 x 3 (row major format) */ +real_t WN[ 9 ]; + +/** Column vector of size: 6 + * + * Current state feedback vector. + */ +real_t x0[ 6 ]; + + +} ACADOvariables; + +/** Private workspace used by the auto-generated code. + * + * Data members of this structure are private to the solver. + * In other words, the user code should not modify values of this + * structure. + */ +typedef struct ACADOworkspace_ +{ +/** Column vector of size: 10 */ +real_t rhs_aux[ 10 ]; + +real_t rk_ttt; + +/** Row vector of size: 51 */ +real_t rk_xxx[ 51 ]; + +/** Matrix of size: 4 x 48 (row major format) */ +real_t rk_kkk[ 192 ]; + +/** Row vector of size: 51 */ +real_t state[ 51 ]; + +/** Column vector of size: 120 */ +real_t d[ 120 ]; + +/** Column vector of size: 80 */ +real_t Dy[ 80 ]; + +/** Column vector of size: 3 */ +real_t DyN[ 3 ]; + +/** Matrix of size: 120 x 6 (row major format) */ +real_t evGx[ 720 ]; + +/** Column vector of size: 120 */ +real_t evGu[ 120 ]; + +/** Column vector of size: 30 */ +real_t objAuxVar[ 30 ]; + +/** Row vector of size: 9 */ +real_t objValueIn[ 9 ]; + +/** Row vector of size: 32 */ +real_t objValueOut[ 32 ]; + +/** Matrix of size: 120 x 6 (row major format) */ +real_t Q1[ 720 ]; + +/** Matrix of size: 120 x 4 (row major format) */ +real_t Q2[ 480 ]; + +/** Column vector of size: 20 */ +real_t R1[ 20 ]; + +/** Matrix of size: 20 x 4 (row major format) */ +real_t R2[ 80 ]; + +/** Column vector of size: 120 */ +real_t S1[ 120 ]; + +/** Matrix of size: 6 x 6 (row major format) */ +real_t QN1[ 36 ]; + +/** Matrix of size: 6 x 3 (row major format) */ +real_t QN2[ 18 ]; + +/** Column vector of size: 6 */ +real_t Dx0[ 6 ]; + +/** Matrix of size: 6 x 6 (row major format) */ +real_t T[ 36 ]; + +/** Column vector of size: 1260 */ +real_t E[ 1260 ]; + +/** Column vector of size: 1260 */ +real_t QE[ 1260 ]; + +/** Matrix of size: 120 x 6 (row major format) */ +real_t QGx[ 720 ]; + +/** Column vector of size: 120 */ +real_t Qd[ 120 ]; + +/** Column vector of size: 126 */ +real_t QDy[ 126 ]; + +/** Matrix of size: 20 x 6 (row major format) */ +real_t H10[ 120 ]; + +/** Matrix of size: 26 x 26 (row major format) */ +real_t H[ 676 ]; + +/** Matrix of size: 20 x 26 (row major format) */ +real_t A[ 520 ]; + +/** Column vector of size: 26 */ +real_t g[ 26 ]; + +/** Column vector of size: 26 */ +real_t lb[ 26 ]; + +/** Column vector of size: 26 */ +real_t ub[ 26 ]; + +/** Column vector of size: 20 */ +real_t lbA[ 20 ]; + +/** Column vector of size: 20 */ +real_t ubA[ 20 ]; + +/** Column vector of size: 26 */ +real_t x[ 26 ]; + +/** Column vector of size: 46 */ +real_t y[ 46 ]; + + +} ACADOworkspace; + +/* + * Forward function declarations. + */ + + +/** Performs the integration and sensitivity propagation for one shooting interval. + * + * \param rk_eta Working array to pass the input values and return the results. + * \param resetIntegrator The internal memory of the integrator can be reset. + * \param rk_index Number of the shooting interval. + * + * \return Status code of the integrator. + */ +int acado_integrate( real_t* const rk_eta, int resetIntegrator, int rk_index ); + +/** Export of an ACADO symbolic function. + * + * \param in Input to the exported function. + * \param out Output of the exported function. + */ +void acado_rhs_forw(const real_t* in, real_t* out); + +/** Preparation step of the RTI scheme. + * + * \return Status of the integration module. =0: OK, otherwise the error code. + */ +int acado_preparationStep( ); + +/** Feedback/estimation step of the RTI scheme. + * + * \return Status code of the qpOASES QP solver. + */ +int acado_feedbackStep( ); + +/** Solver initialization. Must be called once before any other function call. + * + * \return =0: OK, otherwise an error code of a QP solver. + */ +int acado_initializeSolver( ); + +/** Initialize shooting nodes by a forward simulation starting from the first node. + */ +void acado_initializeNodesByForwardSimulation( ); + +/** Shift differential variables vector by one interval. + * + * \param strategy Shifting strategy: 1. Initialize node 21 with xEnd. 2. Initialize node 21 by forward simulation. + * \param xEnd Value for the x vector on the last node. If =0 the old value is used. + * \param uEnd Value for the u vector on the second to last node. If =0 the old value is used. + */ +void acado_shiftStates( int strategy, real_t* const xEnd, real_t* const uEnd ); + +/** Shift controls vector by one interval. + * + * \param uEnd Value for the u vector on the second to last node. If =0 the old value is used. + */ +void acado_shiftControls( real_t* const uEnd ); + +/** Get the KKT tolerance of the current iterate. + * + * \return The KKT tolerance value. + */ +real_t acado_getKKT( ); + +/** Calculate the objective value. + * + * \return Value of the objective function. + */ +real_t acado_getObjective( ); + + +/* + * Extern declarations. + */ + +extern ACADOworkspace acadoWorkspace; +extern ACADOvariables acadoVariables; + +/** @} */ + +#ifndef __MATLAB__ +#ifdef __cplusplus +} /* extern "C" */ +#endif /* __cplusplus */ +#endif /* __MATLAB__ */ + +#endif /* ACADO_COMMON_H */ diff --git a/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_integrator.c b/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_integrator.c new file mode 100644 index 00000000000000..2e77d54147dbee --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_integrator.c @@ -0,0 +1,402 @@ +/* + * This file was auto-generated using the ACADO Toolkit. + * + * While ACADO Toolkit is free software released under the terms of + * the GNU Lesser General Public License (LGPL), the generated code + * as such remains the property of the user who used ACADO Toolkit + * to generate this code. In particular, user dependent data of the code + * do not inherit the GNU LGPL license. On the other hand, parts of the + * generated code that are a direct copy of source code from the + * ACADO Toolkit or the software tools it is based on, remain, as derived + * work, automatically covered by the LGPL license. + * + * ACADO Toolkit 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. + * + */ + + +#include "acado_common.h" + + +void acado_rhs_forw(const real_t* in, real_t* out) +{ +const real_t* xd = in; +const real_t* u = in + 48; +const real_t* od = in + 49; +/* Vector of auxiliary variables; number of elements: 10. */ +real_t* a = acadoWorkspace.rhs_aux; + +/* Compute intermediate quantities: */ +a[0] = (exp((((((real_t)(0.0000000000000000e+00)-od[0])*xd[5])*xd[5])/(real_t)(2.0000000000000000e+00)))); +a[1] = ((real_t)(1.0000000000000000e+00)/(real_t)(2.0000000000000000e+00)); +a[2] = (exp((((((real_t)(0.0000000000000000e+00)-od[0])*xd[5])*xd[5])/(real_t)(2.0000000000000000e+00)))); +a[3] = (((((((real_t)(0.0000000000000000e+00)-od[0])*xd[36])*xd[5])+((((real_t)(0.0000000000000000e+00)-od[0])*xd[5])*xd[36]))*a[1])*a[2]); +a[4] = (((((((real_t)(0.0000000000000000e+00)-od[0])*xd[37])*xd[5])+((((real_t)(0.0000000000000000e+00)-od[0])*xd[5])*xd[37]))*a[1])*a[2]); +a[5] = (((((((real_t)(0.0000000000000000e+00)-od[0])*xd[38])*xd[5])+((((real_t)(0.0000000000000000e+00)-od[0])*xd[5])*xd[38]))*a[1])*a[2]); +a[6] = (((((((real_t)(0.0000000000000000e+00)-od[0])*xd[39])*xd[5])+((((real_t)(0.0000000000000000e+00)-od[0])*xd[5])*xd[39]))*a[1])*a[2]); +a[7] = (((((((real_t)(0.0000000000000000e+00)-od[0])*xd[40])*xd[5])+((((real_t)(0.0000000000000000e+00)-od[0])*xd[5])*xd[40]))*a[1])*a[2]); +a[8] = (((((((real_t)(0.0000000000000000e+00)-od[0])*xd[41])*xd[5])+((((real_t)(0.0000000000000000e+00)-od[0])*xd[5])*xd[41]))*a[1])*a[2]); +a[9] = (((((((real_t)(0.0000000000000000e+00)-od[0])*xd[47])*xd[5])+((((real_t)(0.0000000000000000e+00)-od[0])*xd[5])*xd[47]))*a[1])*a[2]); + +/* Compute outputs: */ +out[0] = xd[1]; +out[1] = xd[2]; +out[2] = u[0]; +out[3] = xd[4]; +out[4] = (od[1]*a[0]); +out[5] = (real_t)(1.0000000000000000e+00); +out[6] = xd[12]; +out[7] = xd[13]; +out[8] = xd[14]; +out[9] = xd[15]; +out[10] = xd[16]; +out[11] = xd[17]; +out[12] = xd[18]; +out[13] = xd[19]; +out[14] = xd[20]; +out[15] = xd[21]; +out[16] = xd[22]; +out[17] = xd[23]; +out[18] = (real_t)(0.0000000000000000e+00); +out[19] = (real_t)(0.0000000000000000e+00); +out[20] = (real_t)(0.0000000000000000e+00); +out[21] = (real_t)(0.0000000000000000e+00); +out[22] = (real_t)(0.0000000000000000e+00); +out[23] = (real_t)(0.0000000000000000e+00); +out[24] = xd[30]; +out[25] = xd[31]; +out[26] = xd[32]; +out[27] = xd[33]; +out[28] = xd[34]; +out[29] = xd[35]; +out[30] = (od[1]*a[3]); +out[31] = (od[1]*a[4]); +out[32] = (od[1]*a[5]); +out[33] = (od[1]*a[6]); +out[34] = (od[1]*a[7]); +out[35] = (od[1]*a[8]); +out[36] = (real_t)(0.0000000000000000e+00); +out[37] = (real_t)(0.0000000000000000e+00); +out[38] = (real_t)(0.0000000000000000e+00); +out[39] = (real_t)(0.0000000000000000e+00); +out[40] = (real_t)(0.0000000000000000e+00); +out[41] = (real_t)(0.0000000000000000e+00); +out[42] = xd[43]; +out[43] = xd[44]; +out[44] = (real_t)(1.0000000000000000e+00); +out[45] = xd[46]; +out[46] = (od[1]*a[9]); +out[47] = (real_t)(0.0000000000000000e+00); +} + +/* Fixed step size:0.2 */ +int acado_integrate( real_t* const rk_eta, int resetIntegrator, int rk_index ) +{ +int error; + +int run1; +int numSteps[20] = {1, 1, 1, 1, 1, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3}; +int numInts = numSteps[rk_index]; +acadoWorkspace.rk_ttt = 0.0000000000000000e+00; +rk_eta[6] = 1.0000000000000000e+00; +rk_eta[7] = 0.0000000000000000e+00; +rk_eta[8] = 0.0000000000000000e+00; +rk_eta[9] = 0.0000000000000000e+00; +rk_eta[10] = 0.0000000000000000e+00; +rk_eta[11] = 0.0000000000000000e+00; +rk_eta[12] = 0.0000000000000000e+00; +rk_eta[13] = 1.0000000000000000e+00; +rk_eta[14] = 0.0000000000000000e+00; +rk_eta[15] = 0.0000000000000000e+00; +rk_eta[16] = 0.0000000000000000e+00; +rk_eta[17] = 0.0000000000000000e+00; +rk_eta[18] = 0.0000000000000000e+00; +rk_eta[19] = 0.0000000000000000e+00; +rk_eta[20] = 1.0000000000000000e+00; +rk_eta[21] = 0.0000000000000000e+00; +rk_eta[22] = 0.0000000000000000e+00; +rk_eta[23] = 0.0000000000000000e+00; +rk_eta[24] = 0.0000000000000000e+00; +rk_eta[25] = 0.0000000000000000e+00; +rk_eta[26] = 0.0000000000000000e+00; +rk_eta[27] = 1.0000000000000000e+00; +rk_eta[28] = 0.0000000000000000e+00; +rk_eta[29] = 0.0000000000000000e+00; +rk_eta[30] = 0.0000000000000000e+00; +rk_eta[31] = 0.0000000000000000e+00; +rk_eta[32] = 0.0000000000000000e+00; +rk_eta[33] = 0.0000000000000000e+00; +rk_eta[34] = 1.0000000000000000e+00; +rk_eta[35] = 0.0000000000000000e+00; +rk_eta[36] = 0.0000000000000000e+00; +rk_eta[37] = 0.0000000000000000e+00; +rk_eta[38] = 0.0000000000000000e+00; +rk_eta[39] = 0.0000000000000000e+00; +rk_eta[40] = 0.0000000000000000e+00; +rk_eta[41] = 1.0000000000000000e+00; +rk_eta[42] = 0.0000000000000000e+00; +rk_eta[43] = 0.0000000000000000e+00; +rk_eta[44] = 0.0000000000000000e+00; +rk_eta[45] = 0.0000000000000000e+00; +rk_eta[46] = 0.0000000000000000e+00; +rk_eta[47] = 0.0000000000000000e+00; +acadoWorkspace.rk_xxx[48] = rk_eta[48]; +acadoWorkspace.rk_xxx[49] = rk_eta[49]; +acadoWorkspace.rk_xxx[50] = rk_eta[50]; + +for (run1 = 0; run1 < 1; ++run1) +{ +for(run1 = 0; run1 < numInts; run1++ ) { +acadoWorkspace.rk_xxx[0] = + rk_eta[0]; +acadoWorkspace.rk_xxx[1] = + rk_eta[1]; +acadoWorkspace.rk_xxx[2] = + rk_eta[2]; +acadoWorkspace.rk_xxx[3] = + rk_eta[3]; +acadoWorkspace.rk_xxx[4] = + rk_eta[4]; +acadoWorkspace.rk_xxx[5] = + rk_eta[5]; +acadoWorkspace.rk_xxx[6] = + rk_eta[6]; +acadoWorkspace.rk_xxx[7] = + rk_eta[7]; +acadoWorkspace.rk_xxx[8] = + rk_eta[8]; +acadoWorkspace.rk_xxx[9] = + rk_eta[9]; +acadoWorkspace.rk_xxx[10] = + rk_eta[10]; +acadoWorkspace.rk_xxx[11] = + rk_eta[11]; +acadoWorkspace.rk_xxx[12] = + rk_eta[12]; +acadoWorkspace.rk_xxx[13] = + rk_eta[13]; +acadoWorkspace.rk_xxx[14] = + rk_eta[14]; +acadoWorkspace.rk_xxx[15] = + rk_eta[15]; +acadoWorkspace.rk_xxx[16] = + rk_eta[16]; +acadoWorkspace.rk_xxx[17] = + rk_eta[17]; +acadoWorkspace.rk_xxx[18] = + rk_eta[18]; +acadoWorkspace.rk_xxx[19] = + rk_eta[19]; +acadoWorkspace.rk_xxx[20] = + rk_eta[20]; +acadoWorkspace.rk_xxx[21] = + rk_eta[21]; +acadoWorkspace.rk_xxx[22] = + rk_eta[22]; +acadoWorkspace.rk_xxx[23] = + rk_eta[23]; +acadoWorkspace.rk_xxx[24] = + rk_eta[24]; +acadoWorkspace.rk_xxx[25] = + rk_eta[25]; +acadoWorkspace.rk_xxx[26] = + rk_eta[26]; +acadoWorkspace.rk_xxx[27] = + rk_eta[27]; +acadoWorkspace.rk_xxx[28] = + rk_eta[28]; +acadoWorkspace.rk_xxx[29] = + rk_eta[29]; +acadoWorkspace.rk_xxx[30] = + rk_eta[30]; +acadoWorkspace.rk_xxx[31] = + rk_eta[31]; +acadoWorkspace.rk_xxx[32] = + rk_eta[32]; +acadoWorkspace.rk_xxx[33] = + rk_eta[33]; +acadoWorkspace.rk_xxx[34] = + rk_eta[34]; +acadoWorkspace.rk_xxx[35] = + rk_eta[35]; +acadoWorkspace.rk_xxx[36] = + rk_eta[36]; +acadoWorkspace.rk_xxx[37] = + rk_eta[37]; +acadoWorkspace.rk_xxx[38] = + rk_eta[38]; +acadoWorkspace.rk_xxx[39] = + rk_eta[39]; +acadoWorkspace.rk_xxx[40] = + rk_eta[40]; +acadoWorkspace.rk_xxx[41] = + rk_eta[41]; +acadoWorkspace.rk_xxx[42] = + rk_eta[42]; +acadoWorkspace.rk_xxx[43] = + rk_eta[43]; +acadoWorkspace.rk_xxx[44] = + rk_eta[44]; +acadoWorkspace.rk_xxx[45] = + rk_eta[45]; +acadoWorkspace.rk_xxx[46] = + rk_eta[46]; +acadoWorkspace.rk_xxx[47] = + rk_eta[47]; +acado_rhs_forw( acadoWorkspace.rk_xxx, acadoWorkspace.rk_kkk ); +acadoWorkspace.rk_xxx[0] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[0] + rk_eta[0]; +acadoWorkspace.rk_xxx[1] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[1] + rk_eta[1]; +acadoWorkspace.rk_xxx[2] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[2] + rk_eta[2]; +acadoWorkspace.rk_xxx[3] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[3] + rk_eta[3]; +acadoWorkspace.rk_xxx[4] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[4] + rk_eta[4]; +acadoWorkspace.rk_xxx[5] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[5] + rk_eta[5]; +acadoWorkspace.rk_xxx[6] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[6] + rk_eta[6]; +acadoWorkspace.rk_xxx[7] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[7] + rk_eta[7]; +acadoWorkspace.rk_xxx[8] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[8] + rk_eta[8]; +acadoWorkspace.rk_xxx[9] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[9] + rk_eta[9]; +acadoWorkspace.rk_xxx[10] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[10] + rk_eta[10]; +acadoWorkspace.rk_xxx[11] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[11] + rk_eta[11]; +acadoWorkspace.rk_xxx[12] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[12] + rk_eta[12]; +acadoWorkspace.rk_xxx[13] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[13] + rk_eta[13]; +acadoWorkspace.rk_xxx[14] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[14] + rk_eta[14]; +acadoWorkspace.rk_xxx[15] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[15] + rk_eta[15]; +acadoWorkspace.rk_xxx[16] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[16] + rk_eta[16]; +acadoWorkspace.rk_xxx[17] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[17] + rk_eta[17]; +acadoWorkspace.rk_xxx[18] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[18] + rk_eta[18]; +acadoWorkspace.rk_xxx[19] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[19] + rk_eta[19]; +acadoWorkspace.rk_xxx[20] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[20] + rk_eta[20]; +acadoWorkspace.rk_xxx[21] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[21] + rk_eta[21]; +acadoWorkspace.rk_xxx[22] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[22] + rk_eta[22]; +acadoWorkspace.rk_xxx[23] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[23] + rk_eta[23]; +acadoWorkspace.rk_xxx[24] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[24] + rk_eta[24]; +acadoWorkspace.rk_xxx[25] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[25] + rk_eta[25]; +acadoWorkspace.rk_xxx[26] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[26] + rk_eta[26]; +acadoWorkspace.rk_xxx[27] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[27] + rk_eta[27]; +acadoWorkspace.rk_xxx[28] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[28] + rk_eta[28]; +acadoWorkspace.rk_xxx[29] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[29] + rk_eta[29]; +acadoWorkspace.rk_xxx[30] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[30] + rk_eta[30]; +acadoWorkspace.rk_xxx[31] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[31] + rk_eta[31]; +acadoWorkspace.rk_xxx[32] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[32] + rk_eta[32]; +acadoWorkspace.rk_xxx[33] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[33] + rk_eta[33]; +acadoWorkspace.rk_xxx[34] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[34] + rk_eta[34]; +acadoWorkspace.rk_xxx[35] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[35] + rk_eta[35]; +acadoWorkspace.rk_xxx[36] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[36] + rk_eta[36]; +acadoWorkspace.rk_xxx[37] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[37] + rk_eta[37]; +acadoWorkspace.rk_xxx[38] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[38] + rk_eta[38]; +acadoWorkspace.rk_xxx[39] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[39] + rk_eta[39]; +acadoWorkspace.rk_xxx[40] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[40] + rk_eta[40]; +acadoWorkspace.rk_xxx[41] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[41] + rk_eta[41]; +acadoWorkspace.rk_xxx[42] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[42] + rk_eta[42]; +acadoWorkspace.rk_xxx[43] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[43] + rk_eta[43]; +acadoWorkspace.rk_xxx[44] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[44] + rk_eta[44]; +acadoWorkspace.rk_xxx[45] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[45] + rk_eta[45]; +acadoWorkspace.rk_xxx[46] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[46] + rk_eta[46]; +acadoWorkspace.rk_xxx[47] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[47] + rk_eta[47]; +acado_rhs_forw( acadoWorkspace.rk_xxx, &(acadoWorkspace.rk_kkk[ 48 ]) ); +acadoWorkspace.rk_xxx[0] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[48] + rk_eta[0]; +acadoWorkspace.rk_xxx[1] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[49] + rk_eta[1]; +acadoWorkspace.rk_xxx[2] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[50] + rk_eta[2]; +acadoWorkspace.rk_xxx[3] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[51] + rk_eta[3]; +acadoWorkspace.rk_xxx[4] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[52] + rk_eta[4]; +acadoWorkspace.rk_xxx[5] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[53] + rk_eta[5]; +acadoWorkspace.rk_xxx[6] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[54] + rk_eta[6]; +acadoWorkspace.rk_xxx[7] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[55] + rk_eta[7]; +acadoWorkspace.rk_xxx[8] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[56] + rk_eta[8]; +acadoWorkspace.rk_xxx[9] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[57] + rk_eta[9]; +acadoWorkspace.rk_xxx[10] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[58] + rk_eta[10]; +acadoWorkspace.rk_xxx[11] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[59] + rk_eta[11]; +acadoWorkspace.rk_xxx[12] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[60] + rk_eta[12]; +acadoWorkspace.rk_xxx[13] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[61] + rk_eta[13]; +acadoWorkspace.rk_xxx[14] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[62] + rk_eta[14]; +acadoWorkspace.rk_xxx[15] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[63] + rk_eta[15]; +acadoWorkspace.rk_xxx[16] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[64] + rk_eta[16]; +acadoWorkspace.rk_xxx[17] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[65] + rk_eta[17]; +acadoWorkspace.rk_xxx[18] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[66] + rk_eta[18]; +acadoWorkspace.rk_xxx[19] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[67] + rk_eta[19]; +acadoWorkspace.rk_xxx[20] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[68] + rk_eta[20]; +acadoWorkspace.rk_xxx[21] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[69] + rk_eta[21]; +acadoWorkspace.rk_xxx[22] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[70] + rk_eta[22]; +acadoWorkspace.rk_xxx[23] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[71] + rk_eta[23]; +acadoWorkspace.rk_xxx[24] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[72] + rk_eta[24]; +acadoWorkspace.rk_xxx[25] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[73] + rk_eta[25]; +acadoWorkspace.rk_xxx[26] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[74] + rk_eta[26]; +acadoWorkspace.rk_xxx[27] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[75] + rk_eta[27]; +acadoWorkspace.rk_xxx[28] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[76] + rk_eta[28]; +acadoWorkspace.rk_xxx[29] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[77] + rk_eta[29]; +acadoWorkspace.rk_xxx[30] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[78] + rk_eta[30]; +acadoWorkspace.rk_xxx[31] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[79] + rk_eta[31]; +acadoWorkspace.rk_xxx[32] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[80] + rk_eta[32]; +acadoWorkspace.rk_xxx[33] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[81] + rk_eta[33]; +acadoWorkspace.rk_xxx[34] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[82] + rk_eta[34]; +acadoWorkspace.rk_xxx[35] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[83] + rk_eta[35]; +acadoWorkspace.rk_xxx[36] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[84] + rk_eta[36]; +acadoWorkspace.rk_xxx[37] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[85] + rk_eta[37]; +acadoWorkspace.rk_xxx[38] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[86] + rk_eta[38]; +acadoWorkspace.rk_xxx[39] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[87] + rk_eta[39]; +acadoWorkspace.rk_xxx[40] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[88] + rk_eta[40]; +acadoWorkspace.rk_xxx[41] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[89] + rk_eta[41]; +acadoWorkspace.rk_xxx[42] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[90] + rk_eta[42]; +acadoWorkspace.rk_xxx[43] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[91] + rk_eta[43]; +acadoWorkspace.rk_xxx[44] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[92] + rk_eta[44]; +acadoWorkspace.rk_xxx[45] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[93] + rk_eta[45]; +acadoWorkspace.rk_xxx[46] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[94] + rk_eta[46]; +acadoWorkspace.rk_xxx[47] = + (real_t)9.9999999999999964e-02*acadoWorkspace.rk_kkk[95] + rk_eta[47]; +acado_rhs_forw( acadoWorkspace.rk_xxx, &(acadoWorkspace.rk_kkk[ 96 ]) ); +acadoWorkspace.rk_xxx[0] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[96] + rk_eta[0]; +acadoWorkspace.rk_xxx[1] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[97] + rk_eta[1]; +acadoWorkspace.rk_xxx[2] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[98] + rk_eta[2]; +acadoWorkspace.rk_xxx[3] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[99] + rk_eta[3]; +acadoWorkspace.rk_xxx[4] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[100] + rk_eta[4]; +acadoWorkspace.rk_xxx[5] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[101] + rk_eta[5]; +acadoWorkspace.rk_xxx[6] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[102] + rk_eta[6]; +acadoWorkspace.rk_xxx[7] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[103] + rk_eta[7]; +acadoWorkspace.rk_xxx[8] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[104] + rk_eta[8]; +acadoWorkspace.rk_xxx[9] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[105] + rk_eta[9]; +acadoWorkspace.rk_xxx[10] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[106] + rk_eta[10]; +acadoWorkspace.rk_xxx[11] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[107] + rk_eta[11]; +acadoWorkspace.rk_xxx[12] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[108] + rk_eta[12]; +acadoWorkspace.rk_xxx[13] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[109] + rk_eta[13]; +acadoWorkspace.rk_xxx[14] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[110] + rk_eta[14]; +acadoWorkspace.rk_xxx[15] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[111] + rk_eta[15]; +acadoWorkspace.rk_xxx[16] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[112] + rk_eta[16]; +acadoWorkspace.rk_xxx[17] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[113] + rk_eta[17]; +acadoWorkspace.rk_xxx[18] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[114] + rk_eta[18]; +acadoWorkspace.rk_xxx[19] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[115] + rk_eta[19]; +acadoWorkspace.rk_xxx[20] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[116] + rk_eta[20]; +acadoWorkspace.rk_xxx[21] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[117] + rk_eta[21]; +acadoWorkspace.rk_xxx[22] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[118] + rk_eta[22]; +acadoWorkspace.rk_xxx[23] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[119] + rk_eta[23]; +acadoWorkspace.rk_xxx[24] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[120] + rk_eta[24]; +acadoWorkspace.rk_xxx[25] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[121] + rk_eta[25]; +acadoWorkspace.rk_xxx[26] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[122] + rk_eta[26]; +acadoWorkspace.rk_xxx[27] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[123] + rk_eta[27]; +acadoWorkspace.rk_xxx[28] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[124] + rk_eta[28]; +acadoWorkspace.rk_xxx[29] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[125] + rk_eta[29]; +acadoWorkspace.rk_xxx[30] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[126] + rk_eta[30]; +acadoWorkspace.rk_xxx[31] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[127] + rk_eta[31]; +acadoWorkspace.rk_xxx[32] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[128] + rk_eta[32]; +acadoWorkspace.rk_xxx[33] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[129] + rk_eta[33]; +acadoWorkspace.rk_xxx[34] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[130] + rk_eta[34]; +acadoWorkspace.rk_xxx[35] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[131] + rk_eta[35]; +acadoWorkspace.rk_xxx[36] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[132] + rk_eta[36]; +acadoWorkspace.rk_xxx[37] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[133] + rk_eta[37]; +acadoWorkspace.rk_xxx[38] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[134] + rk_eta[38]; +acadoWorkspace.rk_xxx[39] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[135] + rk_eta[39]; +acadoWorkspace.rk_xxx[40] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[136] + rk_eta[40]; +acadoWorkspace.rk_xxx[41] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[137] + rk_eta[41]; +acadoWorkspace.rk_xxx[42] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[138] + rk_eta[42]; +acadoWorkspace.rk_xxx[43] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[139] + rk_eta[43]; +acadoWorkspace.rk_xxx[44] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[140] + rk_eta[44]; +acadoWorkspace.rk_xxx[45] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[141] + rk_eta[45]; +acadoWorkspace.rk_xxx[46] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[142] + rk_eta[46]; +acadoWorkspace.rk_xxx[47] = + (real_t)1.9999999999999993e-01*acadoWorkspace.rk_kkk[143] + rk_eta[47]; +acado_rhs_forw( acadoWorkspace.rk_xxx, &(acadoWorkspace.rk_kkk[ 144 ]) ); +rk_eta[0] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[0] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[48] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[96] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[144]; +rk_eta[1] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[1] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[49] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[97] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[145]; +rk_eta[2] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[2] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[50] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[98] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[146]; +rk_eta[3] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[3] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[51] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[99] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[147]; +rk_eta[4] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[4] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[52] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[100] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[148]; +rk_eta[5] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[5] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[53] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[101] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[149]; +rk_eta[6] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[6] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[54] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[102] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[150]; +rk_eta[7] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[7] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[55] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[103] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[151]; +rk_eta[8] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[8] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[56] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[104] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[152]; +rk_eta[9] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[9] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[57] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[105] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[153]; +rk_eta[10] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[10] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[58] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[106] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[154]; +rk_eta[11] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[11] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[59] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[107] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[155]; +rk_eta[12] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[12] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[60] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[108] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[156]; +rk_eta[13] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[13] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[61] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[109] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[157]; +rk_eta[14] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[14] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[62] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[110] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[158]; +rk_eta[15] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[15] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[63] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[111] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[159]; +rk_eta[16] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[16] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[64] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[112] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[160]; +rk_eta[17] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[17] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[65] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[113] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[161]; +rk_eta[18] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[18] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[66] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[114] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[162]; +rk_eta[19] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[19] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[67] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[115] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[163]; +rk_eta[20] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[20] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[68] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[116] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[164]; +rk_eta[21] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[21] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[69] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[117] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[165]; +rk_eta[22] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[22] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[70] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[118] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[166]; +rk_eta[23] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[23] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[71] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[119] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[167]; +rk_eta[24] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[24] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[72] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[120] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[168]; +rk_eta[25] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[25] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[73] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[121] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[169]; +rk_eta[26] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[26] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[74] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[122] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[170]; +rk_eta[27] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[27] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[75] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[123] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[171]; +rk_eta[28] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[28] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[76] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[124] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[172]; +rk_eta[29] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[29] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[77] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[125] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[173]; +rk_eta[30] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[30] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[78] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[126] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[174]; +rk_eta[31] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[31] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[79] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[127] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[175]; +rk_eta[32] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[32] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[80] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[128] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[176]; +rk_eta[33] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[33] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[81] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[129] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[177]; +rk_eta[34] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[34] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[82] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[130] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[178]; +rk_eta[35] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[35] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[83] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[131] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[179]; +rk_eta[36] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[36] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[84] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[132] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[180]; +rk_eta[37] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[37] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[85] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[133] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[181]; +rk_eta[38] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[38] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[86] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[134] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[182]; +rk_eta[39] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[39] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[87] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[135] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[183]; +rk_eta[40] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[40] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[88] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[136] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[184]; +rk_eta[41] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[41] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[89] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[137] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[185]; +rk_eta[42] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[42] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[90] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[138] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[186]; +rk_eta[43] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[43] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[91] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[139] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[187]; +rk_eta[44] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[44] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[92] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[140] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[188]; +rk_eta[45] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[45] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[93] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[141] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[189]; +rk_eta[46] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[46] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[94] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[142] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[190]; +rk_eta[47] += + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[47] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[95] + (real_t)6.6666666666666638e-02*acadoWorkspace.rk_kkk[143] + (real_t)3.3333333333333319e-02*acadoWorkspace.rk_kkk[191]; +acadoWorkspace.rk_ttt += 1.0000000000000000e+00; +} +} +error = 0; +return error; +} + diff --git a/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_integrator.d b/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_integrator.d new file mode 100644 index 00000000000000..7c057e5ec0f3a9 --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_integrator.d @@ -0,0 +1,3 @@ +lib_mpc_export/acado_integrator.o: lib_mpc_export/acado_integrator.c \ + lib_mpc_export/acado_common.h \ + lib_mpc_export/acado_qpoases_interface.hpp diff --git a/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_integrator.o b/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_integrator.o new file mode 100644 index 00000000000000..0008b139779a03 Binary files /dev/null and b/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_integrator.o differ diff --git a/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_qpoases_interface.cpp b/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_qpoases_interface.cpp new file mode 100644 index 00000000000000..a4d9f8cde2777f --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_qpoases_interface.cpp @@ -0,0 +1,70 @@ +/* + * This file was auto-generated using the ACADO Toolkit. + * + * While ACADO Toolkit is free software released under the terms of + * the GNU Lesser General Public License (LGPL), the generated code + * as such remains the property of the user who used ACADO Toolkit + * to generate this code. In particular, user dependent data of the code + * do not inherit the GNU LGPL license. On the other hand, parts of the + * generated code that are a direct copy of source code from the + * ACADO Toolkit or the software tools it is based on, remain, as derived + * work, automatically covered by the LGPL license. + * + * ACADO Toolkit 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. + * + */ + + +extern "C" +{ +#include "acado_common.h" +} + +#include "INCLUDE/QProblem.hpp" + +#if ACADO_COMPUTE_COVARIANCE_MATRIX == 1 +#include "INCLUDE/EXTRAS/SolutionAnalysis.hpp" +#endif /* ACADO_COMPUTE_COVARIANCE_MATRIX */ + +static int acado_nWSR; + + + +#if ACADO_COMPUTE_COVARIANCE_MATRIX == 1 +static SolutionAnalysis acado_sa; +#endif /* ACADO_COMPUTE_COVARIANCE_MATRIX */ + +int acado_solve( void ) +{ + acado_nWSR = QPOASES_NWSRMAX; + + QProblem qp(26, 20); + + returnValue retVal = qp.init(acadoWorkspace.H, acadoWorkspace.g, acadoWorkspace.A, acadoWorkspace.lb, acadoWorkspace.ub, acadoWorkspace.lbA, acadoWorkspace.ubA, acado_nWSR, acadoWorkspace.y); + + qp.getPrimalSolution( acadoWorkspace.x ); + qp.getDualSolution( acadoWorkspace.y ); + +#if ACADO_COMPUTE_COVARIANCE_MATRIX == 1 + + if (retVal != SUCCESSFUL_RETURN) + return (int)retVal; + + retVal = acado_sa.getHessianInverse( &qp,var ); + +#endif /* ACADO_COMPUTE_COVARIANCE_MATRIX */ + + return (int)retVal; +} + +int acado_getNWSR( void ) +{ + return acado_nWSR; +} + +const char* acado_getErrorString( int error ) +{ + return MessageHandling::getErrorString( error ); +} diff --git a/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_qpoases_interface.d b/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_qpoases_interface.d new file mode 100644 index 00000000000000..ba3c6ef1c831b7 --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_qpoases_interface.d @@ -0,0 +1,24 @@ +lib_mpc_export/acado_qpoases_interface.o: \ + lib_mpc_export/acado_qpoases_interface.cpp \ + lib_mpc_export/acado_common.h \ + lib_mpc_export/acado_qpoases_interface.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/QProblem.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/QProblemB.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Bounds.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/SubjectTo.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Indexlist.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Utils.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/MessageHandling.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Types.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Constants.hpp \ + ../../../../phonelibs/qpoases/SRC/MessageHandling.ipp \ + ../../../../phonelibs/qpoases/SRC/Utils.ipp \ + ../../../../phonelibs/qpoases/SRC/Indexlist.ipp \ + ../../../../phonelibs/qpoases/SRC/SubjectTo.ipp \ + ../../../../phonelibs/qpoases/SRC/Bounds.ipp \ + ../../../../phonelibs/qpoases/SRC/QProblemB.ipp \ + ../../../../phonelibs/qpoases/INCLUDE/Constraints.hpp \ + ../../../../phonelibs/qpoases/SRC/Constraints.ipp \ + ../../../../phonelibs/qpoases/INCLUDE/CyclingManager.hpp \ + ../../../../phonelibs/qpoases/SRC/CyclingManager.ipp \ + ../../../../phonelibs/qpoases/SRC/QProblem.ipp diff --git a/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_qpoases_interface.hpp b/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_qpoases_interface.hpp new file mode 100644 index 00000000000000..3b3c75aa111c72 --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_qpoases_interface.hpp @@ -0,0 +1,65 @@ +/* + * This file was auto-generated using the ACADO Toolkit. + * + * While ACADO Toolkit is free software released under the terms of + * the GNU Lesser General Public License (LGPL), the generated code + * as such remains the property of the user who used ACADO Toolkit + * to generate this code. In particular, user dependent data of the code + * do not inherit the GNU LGPL license. On the other hand, parts of the + * generated code that are a direct copy of source code from the + * ACADO Toolkit or the software tools it is based on, remain, as derived + * work, automatically covered by the LGPL license. + * + * ACADO Toolkit 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. + * + */ + + +#ifndef QPOASES_HEADER +#define QPOASES_HEADER + +#ifdef PC_DEBUG +#include +#endif /* PC_DEBUG */ + +#include + +#ifdef __cplusplus +#define EXTERNC extern "C" +#else +#define EXTERNC +#endif + +/* + * A set of options for qpOASES + */ + +/** Maximum number of optimization variables. */ +#define QPOASES_NVMAX 26 +/** Maximum number of constraints. */ +#define QPOASES_NCMAX 20 +/** Maximum number of working set recalculations. */ +#define QPOASES_NWSRMAX 500 +/** Print level for qpOASES. */ +#define QPOASES_PRINTLEVEL PL_NONE +/** The value of EPS */ +#define QPOASES_EPS 2.221e-16 +/** Internally used floating point type */ +typedef double real_t; + +/* + * Forward function declarations + */ + +/** A function that calls the QP solver */ +EXTERNC int acado_solve( void ); + +/** Get the number of active set changes */ +EXTERNC int acado_getNWSR( void ); + +/** Get the error string. */ +const char* acado_getErrorString( int error ); + +#endif /* QPOASES_HEADER */ diff --git a/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_qpoases_interface.o b/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_qpoases_interface.o new file mode 100644 index 00000000000000..ce919eb77f5fa8 Binary files /dev/null and b/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_qpoases_interface.o differ diff --git a/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_solver.c b/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_solver.c new file mode 100644 index 00000000000000..8bd1970888e5ab --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_solver.c @@ -0,0 +1,5375 @@ +/* + * This file was auto-generated using the ACADO Toolkit. + * + * While ACADO Toolkit is free software released under the terms of + * the GNU Lesser General Public License (LGPL), the generated code + * as such remains the property of the user who used ACADO Toolkit + * to generate this code. In particular, user dependent data of the code + * do not inherit the GNU LGPL license. On the other hand, parts of the + * generated code that are a direct copy of source code from the + * ACADO Toolkit or the software tools it is based on, remain, as derived + * work, automatically covered by the LGPL license. + * + * ACADO Toolkit 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. + * + */ + + +#include "acado_common.h" + + + + +/******************************************************************************/ +/* */ +/* ACADO code generation */ +/* */ +/******************************************************************************/ + + +int acado_modelSimulation( ) +{ +int ret; + +int lRun1; +ret = 0; +for (lRun1 = 0; lRun1 < 20; ++lRun1) +{ +acadoWorkspace.state[0] = acadoVariables.x[lRun1 * 6]; +acadoWorkspace.state[1] = acadoVariables.x[lRun1 * 6 + 1]; +acadoWorkspace.state[2] = acadoVariables.x[lRun1 * 6 + 2]; +acadoWorkspace.state[3] = acadoVariables.x[lRun1 * 6 + 3]; +acadoWorkspace.state[4] = acadoVariables.x[lRun1 * 6 + 4]; +acadoWorkspace.state[5] = acadoVariables.x[lRun1 * 6 + 5]; + +acadoWorkspace.state[48] = acadoVariables.u[lRun1]; +acadoWorkspace.state[49] = acadoVariables.od[lRun1 * 2]; +acadoWorkspace.state[50] = acadoVariables.od[lRun1 * 2 + 1]; + +ret = acado_integrate(acadoWorkspace.state, 1, lRun1); + +acadoWorkspace.d[lRun1 * 6] = acadoWorkspace.state[0] - acadoVariables.x[lRun1 * 6 + 6]; +acadoWorkspace.d[lRun1 * 6 + 1] = acadoWorkspace.state[1] - acadoVariables.x[lRun1 * 6 + 7]; +acadoWorkspace.d[lRun1 * 6 + 2] = acadoWorkspace.state[2] - acadoVariables.x[lRun1 * 6 + 8]; +acadoWorkspace.d[lRun1 * 6 + 3] = acadoWorkspace.state[3] - acadoVariables.x[lRun1 * 6 + 9]; +acadoWorkspace.d[lRun1 * 6 + 4] = acadoWorkspace.state[4] - acadoVariables.x[lRun1 * 6 + 10]; +acadoWorkspace.d[lRun1 * 6 + 5] = acadoWorkspace.state[5] - acadoVariables.x[lRun1 * 6 + 11]; + +acadoWorkspace.evGx[lRun1 * 36] = acadoWorkspace.state[6]; +acadoWorkspace.evGx[lRun1 * 36 + 1] = acadoWorkspace.state[7]; +acadoWorkspace.evGx[lRun1 * 36 + 2] = acadoWorkspace.state[8]; +acadoWorkspace.evGx[lRun1 * 36 + 3] = acadoWorkspace.state[9]; +acadoWorkspace.evGx[lRun1 * 36 + 4] = acadoWorkspace.state[10]; +acadoWorkspace.evGx[lRun1 * 36 + 5] = acadoWorkspace.state[11]; +acadoWorkspace.evGx[lRun1 * 36 + 6] = acadoWorkspace.state[12]; +acadoWorkspace.evGx[lRun1 * 36 + 7] = acadoWorkspace.state[13]; +acadoWorkspace.evGx[lRun1 * 36 + 8] = acadoWorkspace.state[14]; +acadoWorkspace.evGx[lRun1 * 36 + 9] = acadoWorkspace.state[15]; +acadoWorkspace.evGx[lRun1 * 36 + 10] = acadoWorkspace.state[16]; +acadoWorkspace.evGx[lRun1 * 36 + 11] = acadoWorkspace.state[17]; +acadoWorkspace.evGx[lRun1 * 36 + 12] = acadoWorkspace.state[18]; +acadoWorkspace.evGx[lRun1 * 36 + 13] = acadoWorkspace.state[19]; +acadoWorkspace.evGx[lRun1 * 36 + 14] = acadoWorkspace.state[20]; +acadoWorkspace.evGx[lRun1 * 36 + 15] = acadoWorkspace.state[21]; +acadoWorkspace.evGx[lRun1 * 36 + 16] = acadoWorkspace.state[22]; +acadoWorkspace.evGx[lRun1 * 36 + 17] = acadoWorkspace.state[23]; +acadoWorkspace.evGx[lRun1 * 36 + 18] = acadoWorkspace.state[24]; +acadoWorkspace.evGx[lRun1 * 36 + 19] = acadoWorkspace.state[25]; +acadoWorkspace.evGx[lRun1 * 36 + 20] = acadoWorkspace.state[26]; +acadoWorkspace.evGx[lRun1 * 36 + 21] = acadoWorkspace.state[27]; +acadoWorkspace.evGx[lRun1 * 36 + 22] = acadoWorkspace.state[28]; +acadoWorkspace.evGx[lRun1 * 36 + 23] = acadoWorkspace.state[29]; +acadoWorkspace.evGx[lRun1 * 36 + 24] = acadoWorkspace.state[30]; +acadoWorkspace.evGx[lRun1 * 36 + 25] = acadoWorkspace.state[31]; +acadoWorkspace.evGx[lRun1 * 36 + 26] = acadoWorkspace.state[32]; +acadoWorkspace.evGx[lRun1 * 36 + 27] = acadoWorkspace.state[33]; +acadoWorkspace.evGx[lRun1 * 36 + 28] = acadoWorkspace.state[34]; +acadoWorkspace.evGx[lRun1 * 36 + 29] = acadoWorkspace.state[35]; +acadoWorkspace.evGx[lRun1 * 36 + 30] = acadoWorkspace.state[36]; +acadoWorkspace.evGx[lRun1 * 36 + 31] = acadoWorkspace.state[37]; +acadoWorkspace.evGx[lRun1 * 36 + 32] = acadoWorkspace.state[38]; +acadoWorkspace.evGx[lRun1 * 36 + 33] = acadoWorkspace.state[39]; +acadoWorkspace.evGx[lRun1 * 36 + 34] = acadoWorkspace.state[40]; +acadoWorkspace.evGx[lRun1 * 36 + 35] = acadoWorkspace.state[41]; + +acadoWorkspace.evGu[lRun1 * 6] = acadoWorkspace.state[42]; +acadoWorkspace.evGu[lRun1 * 6 + 1] = acadoWorkspace.state[43]; +acadoWorkspace.evGu[lRun1 * 6 + 2] = acadoWorkspace.state[44]; +acadoWorkspace.evGu[lRun1 * 6 + 3] = acadoWorkspace.state[45]; +acadoWorkspace.evGu[lRun1 * 6 + 4] = acadoWorkspace.state[46]; +acadoWorkspace.evGu[lRun1 * 6 + 5] = acadoWorkspace.state[47]; +} +return ret; +} + +void acado_evaluateLSQ(const real_t* in, real_t* out, double TR) +{ +const real_t* xd = in; +const real_t* u = in + 6; +/* Vector of auxiliary variables; number of elements: 30. */ +real_t* a = acadoWorkspace.objAuxVar; + +/* Compute intermediate quantities: */ +a[0] = (sqrt((xd[1]+(real_t)(5.0000000000000000e-01)))); +a[1] = (exp(((real_t)(2.9999999999999999e-01)*(((((((xd[1]*(real_t)(TR))-((xd[4]-xd[1])*(real_t)(TR)))+((xd[1]*xd[1])/(real_t)(1.9620000000000001e+01)))-((xd[4]*xd[4])/(real_t)(1.9620000000000001e+01)))+(real_t)(4.0000000000000000e+00))-(xd[3]-xd[0]))/(a[0]+(real_t)(1.0000000000000001e-01)))))); +a[2] = (sqrt((xd[1]+(real_t)(5.0000000000000000e-01)))); +a[3] = (exp(((real_t)(2.9999999999999999e-01)*(((((((xd[1]*(real_t)(TR))-((xd[4]-xd[1])*(real_t)(TR)))+((xd[1]*xd[1])/(real_t)(1.9620000000000001e+01)))-((xd[4]*xd[4])/(real_t)(1.9620000000000001e+01)))+(real_t)(4.0000000000000000e+00))-((real_t)(4.0000000000000000e+00)+((((xd[1]*(real_t)(TR))-((xd[4]-xd[1])*(real_t)(TR)))+((xd[1]*xd[1])/(real_t)(1.9620000000000001e+01)))-((xd[4]*xd[4])/(real_t)(1.9620000000000001e+01)))))/(a[2]+(real_t)(1.0000000000000001e-01)))))); +a[4] = ((real_t)(1.0000000000000000e+00)/(a[0]+(real_t)(1.0000000000000001e-01))); +a[5] = (exp(((real_t)(2.9999999999999999e-01)*(((((((xd[1]*(real_t)(TR))-((xd[4]-xd[1])*(real_t)(TR)))+((xd[1]*xd[1])/(real_t)(1.9620000000000001e+01)))-((xd[4]*xd[4])/(real_t)(1.9620000000000001e+01)))+(real_t)(4.0000000000000000e+00))-(xd[3]-xd[0]))/(a[0]+(real_t)(1.0000000000000001e-01)))))); +a[6] = (((real_t)(2.9999999999999999e-01)*(((real_t)(0.0000000000000000e+00)-((real_t)(0.0000000000000000e+00)-(real_t)(1.0000000000000000e+00)))*a[4]))*a[5]); +a[7] = ((real_t)(1.0000000000000000e+00)/(real_t)(1.9620000000000001e+01)); +a[8] = (1.0/sqrt((xd[1]+(real_t)(5.0000000000000000e-01)))); +a[9] = (a[8]*(real_t)(5.0000000000000000e-01)); +a[10] = (a[4]*a[4]); +a[11] = (((real_t)(2.9999999999999999e-01)*(((((real_t)(TR)-((real_t)(-TR)))+((xd[1]+xd[1])*a[7]))*a[4])-((((((((xd[1]*(real_t)(TR))-((xd[4]-xd[1])*(real_t)(TR)))+((xd[1]*xd[1])/(real_t)(1.9620000000000001e+01)))-((xd[4]*xd[4])/(real_t)(1.9620000000000001e+01)))+(real_t)(4.0000000000000000e+00))-(xd[3]-xd[0]))*a[9])*a[10])))*a[5]); +a[12] = ((real_t)(1.0000000000000000e+00)/(real_t)(1.9620000000000001e+01)); +a[13] = ((real_t)(1.0000000000000000e+00)/(real_t)(1.9620000000000001e+01)); +a[14] = ((real_t)(1.0000000000000000e+00)/(a[2]+(real_t)(1.0000000000000001e-01))); +a[15] = (1.0/sqrt((xd[1]+(real_t)(5.0000000000000000e-01)))); +a[16] = (a[15]*(real_t)(5.0000000000000000e-01)); +a[17] = (a[14]*a[14]); +a[18] = (exp(((real_t)(2.9999999999999999e-01)*(((((((xd[1]*(real_t)(TR))-((xd[4]-xd[1])*(real_t)(TR)))+((xd[1]*xd[1])/(real_t)(1.9620000000000001e+01)))-((xd[4]*xd[4])/(real_t)(1.9620000000000001e+01)))+(real_t)(4.0000000000000000e+00))-((real_t)(4.0000000000000000e+00)+((((xd[1]*(real_t)(TR))-((xd[4]-xd[1])*(real_t)(TR)))+((xd[1]*xd[1])/(real_t)(1.9620000000000001e+01)))-((xd[4]*xd[4])/(real_t)(1.9620000000000001e+01)))))/(a[2]+(real_t)(1.0000000000000001e-01)))))); +a[19] = (((real_t)(2.9999999999999999e-01)*((((((real_t)(TR)-((real_t)(-TR)))+((xd[1]+xd[1])*a[12]))-(((real_t)(TR)-((real_t)(-TR)))+((xd[1]+xd[1])*a[13])))*a[14])-((((((((xd[1]*(real_t)(TR))-((xd[4]-xd[1])*(real_t)(TR)))+((xd[1]*xd[1])/(real_t)(1.9620000000000001e+01)))-((xd[4]*xd[4])/(real_t)(1.9620000000000001e+01)))+(real_t)(4.0000000000000000e+00))-((real_t)(4.0000000000000000e+00)+((((xd[1]*(real_t)(TR))-((xd[4]-xd[1])*(real_t)(TR)))+((xd[1]*xd[1])/(real_t)(1.9620000000000001e+01)))-((xd[4]*xd[4])/(real_t)(1.9620000000000001e+01)))))*a[16])*a[17])))*a[18]); +a[20] = (((real_t)(2.9999999999999999e-01)*(((real_t)(0.0000000000000000e+00)-(real_t)(1.0000000000000000e+00))*a[4]))*a[5]); +a[21] = ((real_t)(1.0000000000000000e+00)/(real_t)(1.9620000000000001e+01)); +a[22] = (((real_t)(2.9999999999999999e-01)*((((real_t)(0.0000000000000000e+00)-(real_t)(TR))-((xd[4]+xd[4])*a[21]))*a[4]))*a[5]); +a[23] = ((real_t)(1.0000000000000000e+00)/(real_t)(1.9620000000000001e+01)); +a[24] = ((real_t)(1.0000000000000000e+00)/(real_t)(1.9620000000000001e+01)); +a[25] = (((real_t)(2.9999999999999999e-01)*(((((real_t)(0.0000000000000000e+00)-(real_t)(TR))-((xd[4]+xd[4])*a[23]))-(((real_t)(0.0000000000000000e+00)-(real_t)(TR))-((xd[4]+xd[4])*a[24])))*a[14]))*a[18]); +a[26] = ((real_t)(1.0000000000000000e+00)/(((real_t)(5.0000000000000003e-02)*xd[1])+(real_t)(5.0000000000000000e-01))); +a[27] = ((real_t)(1.0000000000000000e+00)/(real_t)(1.9620000000000001e+01)); +a[28] = (a[26]*a[26]); +a[29] = ((real_t)(1.0000000000000000e+00)/(real_t)(1.9620000000000001e+01)); + +/* Compute outputs: */ +out[0] = (a[1]-a[3]); +out[1] = (((xd[3]-xd[0])-((real_t)(4.0000000000000000e+00)+((((xd[1]*(real_t)(TR))-((xd[4]-xd[1])*(real_t)(TR)))+((xd[1]*xd[1])/(real_t)(1.9620000000000001e+01)))-((xd[4]*xd[4])/(real_t)(1.9620000000000001e+01)))))/(((real_t)(5.0000000000000003e-02)*xd[1])+(real_t)(5.0000000000000000e-01))); +out[2] = (xd[2]*(((real_t)(1.0000000000000001e-01)*xd[1])+(real_t)(1.0000000000000000e+00))); +out[3] = (u[0]*(((real_t)(1.0000000000000001e-01)*xd[1])+(real_t)(1.0000000000000000e+00))); +out[4] = a[6]; +out[5] = (a[11]-a[19]); +out[6] = (real_t)(0.0000000000000000e+00); +out[7] = a[20]; +out[8] = (a[22]-a[25]); +out[9] = (real_t)(0.0000000000000000e+00); +out[10] = (((real_t)(0.0000000000000000e+00)-(real_t)(1.0000000000000000e+00))*a[26]); +out[11] = ((((real_t)(0.0000000000000000e+00)-(((real_t)(TR)-((real_t)(-TR)))+((xd[1]+xd[1])*a[27])))*a[26])-((((xd[3]-xd[0])-((real_t)(4.0000000000000000e+00)+((((xd[1]*(real_t)(TR))-((xd[4]-xd[1])*(real_t)(TR)))+((xd[1]*xd[1])/(real_t)(1.9620000000000001e+01)))-((xd[4]*xd[4])/(real_t)(1.9620000000000001e+01)))))*(real_t)(5.0000000000000003e-02))*a[28])); +out[12] = (real_t)(0.0000000000000000e+00); +out[13] = a[26]; +out[14] = (((real_t)(0.0000000000000000e+00)-(((real_t)(0.0000000000000000e+00)-(real_t)(TR))-((xd[4]+xd[4])*a[29])))*a[26]); +out[15] = (real_t)(0.0000000000000000e+00); +out[16] = (real_t)(0.0000000000000000e+00); +out[17] = (xd[2]*(real_t)(1.0000000000000001e-01)); +out[18] = (((real_t)(1.0000000000000001e-01)*xd[1])+(real_t)(1.0000000000000000e+00)); +out[19] = (real_t)(0.0000000000000000e+00); +out[20] = (real_t)(0.0000000000000000e+00); +out[21] = (real_t)(0.0000000000000000e+00); +out[22] = (real_t)(0.0000000000000000e+00); +out[23] = (u[0]*(real_t)(1.0000000000000001e-01)); +out[24] = (real_t)(0.0000000000000000e+00); +out[25] = (real_t)(0.0000000000000000e+00); +out[26] = (real_t)(0.0000000000000000e+00); +out[27] = (real_t)(0.0000000000000000e+00); +out[28] = (real_t)(0.0000000000000000e+00); +out[29] = (real_t)(0.0000000000000000e+00); +out[30] = (real_t)(0.0000000000000000e+00); +out[31] = (((real_t)(1.0000000000000001e-01)*xd[1])+(real_t)(1.0000000000000000e+00)); +} + +void acado_evaluateLSQEndTerm(const real_t* in, real_t* out, double TR) +{ +const real_t* xd = in; +/* Vector of auxiliary variables; number of elements: 30. */ +real_t* a = acadoWorkspace.objAuxVar; + +/* Compute intermediate quantities: */ +a[0] = (sqrt((xd[1]+(real_t)(5.0000000000000000e-01)))); +a[1] = (exp(((real_t)(2.9999999999999999e-01)*(((((((xd[1]*(real_t)(TR))-((xd[4]-xd[1])*(real_t)(TR)))+((xd[1]*xd[1])/(real_t)(1.9620000000000001e+01)))-((xd[4]*xd[4])/(real_t)(1.9620000000000001e+01)))+(real_t)(4.0000000000000000e+00))-(xd[3]-xd[0]))/(a[0]+(real_t)(1.0000000000000001e-01)))))); +a[2] = (sqrt((xd[1]+(real_t)(5.0000000000000000e-01)))); +a[3] = (exp(((real_t)(2.9999999999999999e-01)*(((((((xd[1]*(real_t)(TR))-((xd[4]-xd[1])*(real_t)(TR)))+((xd[1]*xd[1])/(real_t)(1.9620000000000001e+01)))-((xd[4]*xd[4])/(real_t)(1.9620000000000001e+01)))+(real_t)(4.0000000000000000e+00))-((real_t)(4.0000000000000000e+00)+((((xd[1]*(real_t)(TR))-((xd[4]-xd[1])*(real_t)(TR)))+((xd[1]*xd[1])/(real_t)(1.9620000000000001e+01)))-((xd[4]*xd[4])/(real_t)(1.9620000000000001e+01)))))/(a[2]+(real_t)(1.0000000000000001e-01)))))); +a[4] = ((real_t)(1.0000000000000000e+00)/(a[0]+(real_t)(1.0000000000000001e-01))); +a[5] = (exp(((real_t)(2.9999999999999999e-01)*(((((((xd[1]*(real_t)(TR))-((xd[4]-xd[1])*(real_t)(TR)))+((xd[1]*xd[1])/(real_t)(1.9620000000000001e+01)))-((xd[4]*xd[4])/(real_t)(1.9620000000000001e+01)))+(real_t)(4.0000000000000000e+00))-(xd[3]-xd[0]))/(a[0]+(real_t)(1.0000000000000001e-01)))))); +a[6] = (((real_t)(2.9999999999999999e-01)*(((real_t)(0.0000000000000000e+00)-((real_t)(0.0000000000000000e+00)-(real_t)(1.0000000000000000e+00)))*a[4]))*a[5]); +a[7] = ((real_t)(1.0000000000000000e+00)/(real_t)(1.9620000000000001e+01)); +a[8] = (1.0/sqrt((xd[1]+(real_t)(5.0000000000000000e-01)))); +a[9] = (a[8]*(real_t)(5.0000000000000000e-01)); +a[10] = (a[4]*a[4]); +a[11] = (((real_t)(2.9999999999999999e-01)*(((((real_t)(TR)-((real_t)(-TR)))+((xd[1]+xd[1])*a[7]))*a[4])-((((((((xd[1]*(real_t)(TR))-((xd[4]-xd[1])*(real_t)(TR)))+((xd[1]*xd[1])/(real_t)(1.9620000000000001e+01)))-((xd[4]*xd[4])/(real_t)(1.9620000000000001e+01)))+(real_t)(4.0000000000000000e+00))-(xd[3]-xd[0]))*a[9])*a[10])))*a[5]); +a[12] = ((real_t)(1.0000000000000000e+00)/(real_t)(1.9620000000000001e+01)); +a[13] = ((real_t)(1.0000000000000000e+00)/(real_t)(1.9620000000000001e+01)); +a[14] = ((real_t)(1.0000000000000000e+00)/(a[2]+(real_t)(1.0000000000000001e-01))); +a[15] = (1.0/sqrt((xd[1]+(real_t)(5.0000000000000000e-01)))); +a[16] = (a[15]*(real_t)(5.0000000000000000e-01)); +a[17] = (a[14]*a[14]); +a[18] = (exp(((real_t)(2.9999999999999999e-01)*(((((((xd[1]*(real_t)(TR))-((xd[4]-xd[1])*(real_t)(TR)))+((xd[1]*xd[1])/(real_t)(1.9620000000000001e+01)))-((xd[4]*xd[4])/(real_t)(1.9620000000000001e+01)))+(real_t)(4.0000000000000000e+00))-((real_t)(4.0000000000000000e+00)+((((xd[1]*(real_t)(TR))-((xd[4]-xd[1])*(real_t)(TR)))+((xd[1]*xd[1])/(real_t)(1.9620000000000001e+01)))-((xd[4]*xd[4])/(real_t)(1.9620000000000001e+01)))))/(a[2]+(real_t)(1.0000000000000001e-01)))))); +a[19] = (((real_t)(2.9999999999999999e-01)*((((((real_t)(TR)-((real_t)(-TR)))+((xd[1]+xd[1])*a[12]))-(((real_t)(TR)-((real_t)(-TR)))+((xd[1]+xd[1])*a[13])))*a[14])-((((((((xd[1]*(real_t)(TR))-((xd[4]-xd[1])*(real_t)(TR)))+((xd[1]*xd[1])/(real_t)(1.9620000000000001e+01)))-((xd[4]*xd[4])/(real_t)(1.9620000000000001e+01)))+(real_t)(4.0000000000000000e+00))-((real_t)(4.0000000000000000e+00)+((((xd[1]*(real_t)(TR))-((xd[4]-xd[1])*(real_t)(TR)))+((xd[1]*xd[1])/(real_t)(1.9620000000000001e+01)))-((xd[4]*xd[4])/(real_t)(1.9620000000000001e+01)))))*a[16])*a[17])))*a[18]); +a[20] = (((real_t)(2.9999999999999999e-01)*(((real_t)(0.0000000000000000e+00)-(real_t)(1.0000000000000000e+00))*a[4]))*a[5]); +a[21] = ((real_t)(1.0000000000000000e+00)/(real_t)(1.9620000000000001e+01)); +a[22] = (((real_t)(2.9999999999999999e-01)*((((real_t)(0.0000000000000000e+00)-(real_t)(TR))-((xd[4]+xd[4])*a[21]))*a[4]))*a[5]); +a[23] = ((real_t)(1.0000000000000000e+00)/(real_t)(1.9620000000000001e+01)); +a[24] = ((real_t)(1.0000000000000000e+00)/(real_t)(1.9620000000000001e+01)); +a[25] = (((real_t)(2.9999999999999999e-01)*(((((real_t)(0.0000000000000000e+00)-(real_t)(TR))-((xd[4]+xd[4])*a[23]))-(((real_t)(0.0000000000000000e+00)-(real_t)(TR))-((xd[4]+xd[4])*a[24])))*a[14]))*a[18]); +a[26] = ((real_t)(1.0000000000000000e+00)/(((real_t)(5.0000000000000003e-02)*xd[1])+(real_t)(5.0000000000000000e-01))); +a[27] = ((real_t)(1.0000000000000000e+00)/(real_t)(1.9620000000000001e+01)); +a[28] = (a[26]*a[26]); +a[29] = ((real_t)(1.0000000000000000e+00)/(real_t)(1.9620000000000001e+01)); + +/* Compute outputs: */ +out[0] = (a[1]-a[3]); +out[1] = (((xd[3]-xd[0])-((real_t)(4.0000000000000000e+00)+((((xd[1]*(real_t)(TR))-((xd[4]-xd[1])*(real_t)(TR)))+((xd[1]*xd[1])/(real_t)(1.9620000000000001e+01)))-((xd[4]*xd[4])/(real_t)(1.9620000000000001e+01)))))/(((real_t)(5.0000000000000003e-02)*xd[1])+(real_t)(5.0000000000000000e-01))); +out[2] = (xd[2]*(((real_t)(1.0000000000000001e-01)*xd[1])+(real_t)(1.0000000000000000e+00))); +out[3] = a[6]; +out[4] = (a[11]-a[19]); +out[5] = (real_t)(0.0000000000000000e+00); +out[6] = a[20]; +out[7] = (a[22]-a[25]); +out[8] = (real_t)(0.0000000000000000e+00); +out[9] = (((real_t)(0.0000000000000000e+00)-(real_t)(1.0000000000000000e+00))*a[26]); +out[10] = ((((real_t)(0.0000000000000000e+00)-(((real_t)(TR)-((real_t)(-TR)))+((xd[1]+xd[1])*a[27])))*a[26])-((((xd[3]-xd[0])-((real_t)(4.0000000000000000e+00)+((((xd[1]*(real_t)(TR))-((xd[4]-xd[1])*(real_t)(TR)))+((xd[1]*xd[1])/(real_t)(1.9620000000000001e+01)))-((xd[4]*xd[4])/(real_t)(1.9620000000000001e+01)))))*(real_t)(5.0000000000000003e-02))*a[28])); +out[11] = (real_t)(0.0000000000000000e+00); +out[12] = a[26]; +out[13] = (((real_t)(0.0000000000000000e+00)-(((real_t)(0.0000000000000000e+00)-(real_t)(TR))-((xd[4]+xd[4])*a[29])))*a[26]); +out[14] = (real_t)(0.0000000000000000e+00); +out[15] = (real_t)(0.0000000000000000e+00); +out[16] = (xd[2]*(real_t)(1.0000000000000001e-01)); +out[17] = (((real_t)(1.0000000000000001e-01)*xd[1])+(real_t)(1.0000000000000000e+00)); +out[18] = (real_t)(0.0000000000000000e+00); +out[19] = (real_t)(0.0000000000000000e+00); +out[20] = (real_t)(0.0000000000000000e+00); +} + +void acado_setObjQ1Q2( real_t* const tmpFx, real_t* const tmpObjS, real_t* const tmpQ1, real_t* const tmpQ2 ) +{ +tmpQ2[0] = + tmpFx[0]*tmpObjS[0] + tmpFx[6]*tmpObjS[4] + tmpFx[12]*tmpObjS[8] + tmpFx[18]*tmpObjS[12]; +tmpQ2[1] = + tmpFx[0]*tmpObjS[1] + tmpFx[6]*tmpObjS[5] + tmpFx[12]*tmpObjS[9] + tmpFx[18]*tmpObjS[13]; +tmpQ2[2] = + tmpFx[0]*tmpObjS[2] + tmpFx[6]*tmpObjS[6] + tmpFx[12]*tmpObjS[10] + tmpFx[18]*tmpObjS[14]; +tmpQ2[3] = + tmpFx[0]*tmpObjS[3] + tmpFx[6]*tmpObjS[7] + tmpFx[12]*tmpObjS[11] + tmpFx[18]*tmpObjS[15]; +tmpQ2[4] = + tmpFx[1]*tmpObjS[0] + tmpFx[7]*tmpObjS[4] + tmpFx[13]*tmpObjS[8] + tmpFx[19]*tmpObjS[12]; +tmpQ2[5] = + tmpFx[1]*tmpObjS[1] + tmpFx[7]*tmpObjS[5] + tmpFx[13]*tmpObjS[9] + tmpFx[19]*tmpObjS[13]; +tmpQ2[6] = + tmpFx[1]*tmpObjS[2] + tmpFx[7]*tmpObjS[6] + tmpFx[13]*tmpObjS[10] + tmpFx[19]*tmpObjS[14]; +tmpQ2[7] = + tmpFx[1]*tmpObjS[3] + tmpFx[7]*tmpObjS[7] + tmpFx[13]*tmpObjS[11] + tmpFx[19]*tmpObjS[15]; +tmpQ2[8] = + tmpFx[2]*tmpObjS[0] + tmpFx[8]*tmpObjS[4] + tmpFx[14]*tmpObjS[8] + tmpFx[20]*tmpObjS[12]; +tmpQ2[9] = + tmpFx[2]*tmpObjS[1] + tmpFx[8]*tmpObjS[5] + tmpFx[14]*tmpObjS[9] + tmpFx[20]*tmpObjS[13]; +tmpQ2[10] = + tmpFx[2]*tmpObjS[2] + tmpFx[8]*tmpObjS[6] + tmpFx[14]*tmpObjS[10] + tmpFx[20]*tmpObjS[14]; +tmpQ2[11] = + tmpFx[2]*tmpObjS[3] + tmpFx[8]*tmpObjS[7] + tmpFx[14]*tmpObjS[11] + tmpFx[20]*tmpObjS[15]; +tmpQ2[12] = + tmpFx[3]*tmpObjS[0] + tmpFx[9]*tmpObjS[4] + tmpFx[15]*tmpObjS[8] + tmpFx[21]*tmpObjS[12]; +tmpQ2[13] = + tmpFx[3]*tmpObjS[1] + tmpFx[9]*tmpObjS[5] + tmpFx[15]*tmpObjS[9] + tmpFx[21]*tmpObjS[13]; +tmpQ2[14] = + tmpFx[3]*tmpObjS[2] + tmpFx[9]*tmpObjS[6] + tmpFx[15]*tmpObjS[10] + tmpFx[21]*tmpObjS[14]; +tmpQ2[15] = + tmpFx[3]*tmpObjS[3] + tmpFx[9]*tmpObjS[7] + tmpFx[15]*tmpObjS[11] + tmpFx[21]*tmpObjS[15]; +tmpQ2[16] = + tmpFx[4]*tmpObjS[0] + tmpFx[10]*tmpObjS[4] + tmpFx[16]*tmpObjS[8] + tmpFx[22]*tmpObjS[12]; +tmpQ2[17] = + tmpFx[4]*tmpObjS[1] + tmpFx[10]*tmpObjS[5] + tmpFx[16]*tmpObjS[9] + tmpFx[22]*tmpObjS[13]; +tmpQ2[18] = + tmpFx[4]*tmpObjS[2] + tmpFx[10]*tmpObjS[6] + tmpFx[16]*tmpObjS[10] + tmpFx[22]*tmpObjS[14]; +tmpQ2[19] = + tmpFx[4]*tmpObjS[3] + tmpFx[10]*tmpObjS[7] + tmpFx[16]*tmpObjS[11] + tmpFx[22]*tmpObjS[15]; +tmpQ2[20] = + tmpFx[5]*tmpObjS[0] + tmpFx[11]*tmpObjS[4] + tmpFx[17]*tmpObjS[8] + tmpFx[23]*tmpObjS[12]; +tmpQ2[21] = + tmpFx[5]*tmpObjS[1] + tmpFx[11]*tmpObjS[5] + tmpFx[17]*tmpObjS[9] + tmpFx[23]*tmpObjS[13]; +tmpQ2[22] = + tmpFx[5]*tmpObjS[2] + tmpFx[11]*tmpObjS[6] + tmpFx[17]*tmpObjS[10] + tmpFx[23]*tmpObjS[14]; +tmpQ2[23] = + tmpFx[5]*tmpObjS[3] + tmpFx[11]*tmpObjS[7] + tmpFx[17]*tmpObjS[11] + tmpFx[23]*tmpObjS[15]; +tmpQ1[0] = + tmpQ2[0]*tmpFx[0] + tmpQ2[1]*tmpFx[6] + tmpQ2[2]*tmpFx[12] + tmpQ2[3]*tmpFx[18]; +tmpQ1[1] = + tmpQ2[0]*tmpFx[1] + tmpQ2[1]*tmpFx[7] + tmpQ2[2]*tmpFx[13] + tmpQ2[3]*tmpFx[19]; +tmpQ1[2] = + tmpQ2[0]*tmpFx[2] + tmpQ2[1]*tmpFx[8] + tmpQ2[2]*tmpFx[14] + tmpQ2[3]*tmpFx[20]; +tmpQ1[3] = + tmpQ2[0]*tmpFx[3] + tmpQ2[1]*tmpFx[9] + tmpQ2[2]*tmpFx[15] + tmpQ2[3]*tmpFx[21]; +tmpQ1[4] = + tmpQ2[0]*tmpFx[4] + tmpQ2[1]*tmpFx[10] + tmpQ2[2]*tmpFx[16] + tmpQ2[3]*tmpFx[22]; +tmpQ1[5] = + tmpQ2[0]*tmpFx[5] + tmpQ2[1]*tmpFx[11] + tmpQ2[2]*tmpFx[17] + tmpQ2[3]*tmpFx[23]; +tmpQ1[6] = + tmpQ2[4]*tmpFx[0] + tmpQ2[5]*tmpFx[6] + tmpQ2[6]*tmpFx[12] + tmpQ2[7]*tmpFx[18]; +tmpQ1[7] = + tmpQ2[4]*tmpFx[1] + tmpQ2[5]*tmpFx[7] + tmpQ2[6]*tmpFx[13] + tmpQ2[7]*tmpFx[19]; +tmpQ1[8] = + tmpQ2[4]*tmpFx[2] + tmpQ2[5]*tmpFx[8] + tmpQ2[6]*tmpFx[14] + tmpQ2[7]*tmpFx[20]; +tmpQ1[9] = + tmpQ2[4]*tmpFx[3] + tmpQ2[5]*tmpFx[9] + tmpQ2[6]*tmpFx[15] + tmpQ2[7]*tmpFx[21]; +tmpQ1[10] = + tmpQ2[4]*tmpFx[4] + tmpQ2[5]*tmpFx[10] + tmpQ2[6]*tmpFx[16] + tmpQ2[7]*tmpFx[22]; +tmpQ1[11] = + tmpQ2[4]*tmpFx[5] + tmpQ2[5]*tmpFx[11] + tmpQ2[6]*tmpFx[17] + tmpQ2[7]*tmpFx[23]; +tmpQ1[12] = + tmpQ2[8]*tmpFx[0] + tmpQ2[9]*tmpFx[6] + tmpQ2[10]*tmpFx[12] + tmpQ2[11]*tmpFx[18]; +tmpQ1[13] = + tmpQ2[8]*tmpFx[1] + tmpQ2[9]*tmpFx[7] + tmpQ2[10]*tmpFx[13] + tmpQ2[11]*tmpFx[19]; +tmpQ1[14] = + tmpQ2[8]*tmpFx[2] + tmpQ2[9]*tmpFx[8] + tmpQ2[10]*tmpFx[14] + tmpQ2[11]*tmpFx[20]; +tmpQ1[15] = + tmpQ2[8]*tmpFx[3] + tmpQ2[9]*tmpFx[9] + tmpQ2[10]*tmpFx[15] + tmpQ2[11]*tmpFx[21]; +tmpQ1[16] = + tmpQ2[8]*tmpFx[4] + tmpQ2[9]*tmpFx[10] + tmpQ2[10]*tmpFx[16] + tmpQ2[11]*tmpFx[22]; +tmpQ1[17] = + tmpQ2[8]*tmpFx[5] + tmpQ2[9]*tmpFx[11] + tmpQ2[10]*tmpFx[17] + tmpQ2[11]*tmpFx[23]; +tmpQ1[18] = + tmpQ2[12]*tmpFx[0] + tmpQ2[13]*tmpFx[6] + tmpQ2[14]*tmpFx[12] + tmpQ2[15]*tmpFx[18]; +tmpQ1[19] = + tmpQ2[12]*tmpFx[1] + tmpQ2[13]*tmpFx[7] + tmpQ2[14]*tmpFx[13] + tmpQ2[15]*tmpFx[19]; +tmpQ1[20] = + tmpQ2[12]*tmpFx[2] + tmpQ2[13]*tmpFx[8] + tmpQ2[14]*tmpFx[14] + tmpQ2[15]*tmpFx[20]; +tmpQ1[21] = + tmpQ2[12]*tmpFx[3] + tmpQ2[13]*tmpFx[9] + tmpQ2[14]*tmpFx[15] + tmpQ2[15]*tmpFx[21]; +tmpQ1[22] = + tmpQ2[12]*tmpFx[4] + tmpQ2[13]*tmpFx[10] + tmpQ2[14]*tmpFx[16] + tmpQ2[15]*tmpFx[22]; +tmpQ1[23] = + tmpQ2[12]*tmpFx[5] + tmpQ2[13]*tmpFx[11] + tmpQ2[14]*tmpFx[17] + tmpQ2[15]*tmpFx[23]; +tmpQ1[24] = + tmpQ2[16]*tmpFx[0] + tmpQ2[17]*tmpFx[6] + tmpQ2[18]*tmpFx[12] + tmpQ2[19]*tmpFx[18]; +tmpQ1[25] = + tmpQ2[16]*tmpFx[1] + tmpQ2[17]*tmpFx[7] + tmpQ2[18]*tmpFx[13] + tmpQ2[19]*tmpFx[19]; +tmpQ1[26] = + tmpQ2[16]*tmpFx[2] + tmpQ2[17]*tmpFx[8] + tmpQ2[18]*tmpFx[14] + tmpQ2[19]*tmpFx[20]; +tmpQ1[27] = + tmpQ2[16]*tmpFx[3] + tmpQ2[17]*tmpFx[9] + tmpQ2[18]*tmpFx[15] + tmpQ2[19]*tmpFx[21]; +tmpQ1[28] = + tmpQ2[16]*tmpFx[4] + tmpQ2[17]*tmpFx[10] + tmpQ2[18]*tmpFx[16] + tmpQ2[19]*tmpFx[22]; +tmpQ1[29] = + tmpQ2[16]*tmpFx[5] + tmpQ2[17]*tmpFx[11] + tmpQ2[18]*tmpFx[17] + tmpQ2[19]*tmpFx[23]; +tmpQ1[30] = + tmpQ2[20]*tmpFx[0] + tmpQ2[21]*tmpFx[6] + tmpQ2[22]*tmpFx[12] + tmpQ2[23]*tmpFx[18]; +tmpQ1[31] = + tmpQ2[20]*tmpFx[1] + tmpQ2[21]*tmpFx[7] + tmpQ2[22]*tmpFx[13] + tmpQ2[23]*tmpFx[19]; +tmpQ1[32] = + tmpQ2[20]*tmpFx[2] + tmpQ2[21]*tmpFx[8] + tmpQ2[22]*tmpFx[14] + tmpQ2[23]*tmpFx[20]; +tmpQ1[33] = + tmpQ2[20]*tmpFx[3] + tmpQ2[21]*tmpFx[9] + tmpQ2[22]*tmpFx[15] + tmpQ2[23]*tmpFx[21]; +tmpQ1[34] = + tmpQ2[20]*tmpFx[4] + tmpQ2[21]*tmpFx[10] + tmpQ2[22]*tmpFx[16] + tmpQ2[23]*tmpFx[22]; +tmpQ1[35] = + tmpQ2[20]*tmpFx[5] + tmpQ2[21]*tmpFx[11] + tmpQ2[22]*tmpFx[17] + tmpQ2[23]*tmpFx[23]; +} + +void acado_setObjR1R2( real_t* const tmpFu, real_t* const tmpObjS, real_t* const tmpR1, real_t* const tmpR2 ) +{ +tmpR2[0] = + tmpFu[0]*tmpObjS[0] + tmpFu[1]*tmpObjS[4] + tmpFu[2]*tmpObjS[8] + tmpFu[3]*tmpObjS[12]; +tmpR2[1] = + tmpFu[0]*tmpObjS[1] + tmpFu[1]*tmpObjS[5] + tmpFu[2]*tmpObjS[9] + tmpFu[3]*tmpObjS[13]; +tmpR2[2] = + tmpFu[0]*tmpObjS[2] + tmpFu[1]*tmpObjS[6] + tmpFu[2]*tmpObjS[10] + tmpFu[3]*tmpObjS[14]; +tmpR2[3] = + tmpFu[0]*tmpObjS[3] + tmpFu[1]*tmpObjS[7] + tmpFu[2]*tmpObjS[11] + tmpFu[3]*tmpObjS[15]; +tmpR1[0] = + tmpR2[0]*tmpFu[0] + tmpR2[1]*tmpFu[1] + tmpR2[2]*tmpFu[2] + tmpR2[3]*tmpFu[3]; +} + +void acado_setObjQN1QN2( real_t* const tmpFx, real_t* const tmpObjSEndTerm, real_t* const tmpQN1, real_t* const tmpQN2 ) +{ +tmpQN2[0] = + tmpFx[0]*tmpObjSEndTerm[0] + tmpFx[6]*tmpObjSEndTerm[3] + tmpFx[12]*tmpObjSEndTerm[6]; +tmpQN2[1] = + tmpFx[0]*tmpObjSEndTerm[1] + tmpFx[6]*tmpObjSEndTerm[4] + tmpFx[12]*tmpObjSEndTerm[7]; +tmpQN2[2] = + tmpFx[0]*tmpObjSEndTerm[2] + tmpFx[6]*tmpObjSEndTerm[5] + tmpFx[12]*tmpObjSEndTerm[8]; +tmpQN2[3] = + tmpFx[1]*tmpObjSEndTerm[0] + tmpFx[7]*tmpObjSEndTerm[3] + tmpFx[13]*tmpObjSEndTerm[6]; +tmpQN2[4] = + tmpFx[1]*tmpObjSEndTerm[1] + tmpFx[7]*tmpObjSEndTerm[4] + tmpFx[13]*tmpObjSEndTerm[7]; +tmpQN2[5] = + tmpFx[1]*tmpObjSEndTerm[2] + tmpFx[7]*tmpObjSEndTerm[5] + tmpFx[13]*tmpObjSEndTerm[8]; +tmpQN2[6] = + tmpFx[2]*tmpObjSEndTerm[0] + tmpFx[8]*tmpObjSEndTerm[3] + tmpFx[14]*tmpObjSEndTerm[6]; +tmpQN2[7] = + tmpFx[2]*tmpObjSEndTerm[1] + tmpFx[8]*tmpObjSEndTerm[4] + tmpFx[14]*tmpObjSEndTerm[7]; +tmpQN2[8] = + tmpFx[2]*tmpObjSEndTerm[2] + tmpFx[8]*tmpObjSEndTerm[5] + tmpFx[14]*tmpObjSEndTerm[8]; +tmpQN2[9] = + tmpFx[3]*tmpObjSEndTerm[0] + tmpFx[9]*tmpObjSEndTerm[3] + tmpFx[15]*tmpObjSEndTerm[6]; +tmpQN2[10] = + tmpFx[3]*tmpObjSEndTerm[1] + tmpFx[9]*tmpObjSEndTerm[4] + tmpFx[15]*tmpObjSEndTerm[7]; +tmpQN2[11] = + tmpFx[3]*tmpObjSEndTerm[2] + tmpFx[9]*tmpObjSEndTerm[5] + tmpFx[15]*tmpObjSEndTerm[8]; +tmpQN2[12] = + tmpFx[4]*tmpObjSEndTerm[0] + tmpFx[10]*tmpObjSEndTerm[3] + tmpFx[16]*tmpObjSEndTerm[6]; +tmpQN2[13] = + tmpFx[4]*tmpObjSEndTerm[1] + tmpFx[10]*tmpObjSEndTerm[4] + tmpFx[16]*tmpObjSEndTerm[7]; +tmpQN2[14] = + tmpFx[4]*tmpObjSEndTerm[2] + tmpFx[10]*tmpObjSEndTerm[5] + tmpFx[16]*tmpObjSEndTerm[8]; +tmpQN2[15] = + tmpFx[5]*tmpObjSEndTerm[0] + tmpFx[11]*tmpObjSEndTerm[3] + tmpFx[17]*tmpObjSEndTerm[6]; +tmpQN2[16] = + tmpFx[5]*tmpObjSEndTerm[1] + tmpFx[11]*tmpObjSEndTerm[4] + tmpFx[17]*tmpObjSEndTerm[7]; +tmpQN2[17] = + tmpFx[5]*tmpObjSEndTerm[2] + tmpFx[11]*tmpObjSEndTerm[5] + tmpFx[17]*tmpObjSEndTerm[8]; +tmpQN1[0] = + tmpQN2[0]*tmpFx[0] + tmpQN2[1]*tmpFx[6] + tmpQN2[2]*tmpFx[12]; +tmpQN1[1] = + tmpQN2[0]*tmpFx[1] + tmpQN2[1]*tmpFx[7] + tmpQN2[2]*tmpFx[13]; +tmpQN1[2] = + tmpQN2[0]*tmpFx[2] + tmpQN2[1]*tmpFx[8] + tmpQN2[2]*tmpFx[14]; +tmpQN1[3] = + tmpQN2[0]*tmpFx[3] + tmpQN2[1]*tmpFx[9] + tmpQN2[2]*tmpFx[15]; +tmpQN1[4] = + tmpQN2[0]*tmpFx[4] + tmpQN2[1]*tmpFx[10] + tmpQN2[2]*tmpFx[16]; +tmpQN1[5] = + tmpQN2[0]*tmpFx[5] + tmpQN2[1]*tmpFx[11] + tmpQN2[2]*tmpFx[17]; +tmpQN1[6] = + tmpQN2[3]*tmpFx[0] + tmpQN2[4]*tmpFx[6] + tmpQN2[5]*tmpFx[12]; +tmpQN1[7] = + tmpQN2[3]*tmpFx[1] + tmpQN2[4]*tmpFx[7] + tmpQN2[5]*tmpFx[13]; +tmpQN1[8] = + tmpQN2[3]*tmpFx[2] + tmpQN2[4]*tmpFx[8] + tmpQN2[5]*tmpFx[14]; +tmpQN1[9] = + tmpQN2[3]*tmpFx[3] + tmpQN2[4]*tmpFx[9] + tmpQN2[5]*tmpFx[15]; +tmpQN1[10] = + tmpQN2[3]*tmpFx[4] + tmpQN2[4]*tmpFx[10] + tmpQN2[5]*tmpFx[16]; +tmpQN1[11] = + tmpQN2[3]*tmpFx[5] + tmpQN2[4]*tmpFx[11] + tmpQN2[5]*tmpFx[17]; +tmpQN1[12] = + tmpQN2[6]*tmpFx[0] + tmpQN2[7]*tmpFx[6] + tmpQN2[8]*tmpFx[12]; +tmpQN1[13] = + tmpQN2[6]*tmpFx[1] + tmpQN2[7]*tmpFx[7] + tmpQN2[8]*tmpFx[13]; +tmpQN1[14] = + tmpQN2[6]*tmpFx[2] + tmpQN2[7]*tmpFx[8] + tmpQN2[8]*tmpFx[14]; +tmpQN1[15] = + tmpQN2[6]*tmpFx[3] + tmpQN2[7]*tmpFx[9] + tmpQN2[8]*tmpFx[15]; +tmpQN1[16] = + tmpQN2[6]*tmpFx[4] + tmpQN2[7]*tmpFx[10] + tmpQN2[8]*tmpFx[16]; +tmpQN1[17] = + tmpQN2[6]*tmpFx[5] + tmpQN2[7]*tmpFx[11] + tmpQN2[8]*tmpFx[17]; +tmpQN1[18] = + tmpQN2[9]*tmpFx[0] + tmpQN2[10]*tmpFx[6] + tmpQN2[11]*tmpFx[12]; +tmpQN1[19] = + tmpQN2[9]*tmpFx[1] + tmpQN2[10]*tmpFx[7] + tmpQN2[11]*tmpFx[13]; +tmpQN1[20] = + tmpQN2[9]*tmpFx[2] + tmpQN2[10]*tmpFx[8] + tmpQN2[11]*tmpFx[14]; +tmpQN1[21] = + tmpQN2[9]*tmpFx[3] + tmpQN2[10]*tmpFx[9] + tmpQN2[11]*tmpFx[15]; +tmpQN1[22] = + tmpQN2[9]*tmpFx[4] + tmpQN2[10]*tmpFx[10] + tmpQN2[11]*tmpFx[16]; +tmpQN1[23] = + tmpQN2[9]*tmpFx[5] + tmpQN2[10]*tmpFx[11] + tmpQN2[11]*tmpFx[17]; +tmpQN1[24] = + tmpQN2[12]*tmpFx[0] + tmpQN2[13]*tmpFx[6] + tmpQN2[14]*tmpFx[12]; +tmpQN1[25] = + tmpQN2[12]*tmpFx[1] + tmpQN2[13]*tmpFx[7] + tmpQN2[14]*tmpFx[13]; +tmpQN1[26] = + tmpQN2[12]*tmpFx[2] + tmpQN2[13]*tmpFx[8] + tmpQN2[14]*tmpFx[14]; +tmpQN1[27] = + tmpQN2[12]*tmpFx[3] + tmpQN2[13]*tmpFx[9] + tmpQN2[14]*tmpFx[15]; +tmpQN1[28] = + tmpQN2[12]*tmpFx[4] + tmpQN2[13]*tmpFx[10] + tmpQN2[14]*tmpFx[16]; +tmpQN1[29] = + tmpQN2[12]*tmpFx[5] + tmpQN2[13]*tmpFx[11] + tmpQN2[14]*tmpFx[17]; +tmpQN1[30] = + tmpQN2[15]*tmpFx[0] + tmpQN2[16]*tmpFx[6] + tmpQN2[17]*tmpFx[12]; +tmpQN1[31] = + tmpQN2[15]*tmpFx[1] + tmpQN2[16]*tmpFx[7] + tmpQN2[17]*tmpFx[13]; +tmpQN1[32] = + tmpQN2[15]*tmpFx[2] + tmpQN2[16]*tmpFx[8] + tmpQN2[17]*tmpFx[14]; +tmpQN1[33] = + tmpQN2[15]*tmpFx[3] + tmpQN2[16]*tmpFx[9] + tmpQN2[17]*tmpFx[15]; +tmpQN1[34] = + tmpQN2[15]*tmpFx[4] + tmpQN2[16]*tmpFx[10] + tmpQN2[17]*tmpFx[16]; +tmpQN1[35] = + tmpQN2[15]*tmpFx[5] + tmpQN2[16]*tmpFx[11] + tmpQN2[17]*tmpFx[17]; +} + +void acado_evaluateObjective(double TR) +{ +int runObj; +for (runObj = 0; runObj < 20; ++runObj) +{ +acadoWorkspace.objValueIn[0] = acadoVariables.x[runObj * 6]; +acadoWorkspace.objValueIn[1] = acadoVariables.x[runObj * 6 + 1]; +acadoWorkspace.objValueIn[2] = acadoVariables.x[runObj * 6 + 2]; +acadoWorkspace.objValueIn[3] = acadoVariables.x[runObj * 6 + 3]; +acadoWorkspace.objValueIn[4] = acadoVariables.x[runObj * 6 + 4]; +acadoWorkspace.objValueIn[5] = acadoVariables.x[runObj * 6 + 5]; +acadoWorkspace.objValueIn[6] = acadoVariables.u[runObj]; +acadoWorkspace.objValueIn[7] = acadoVariables.od[runObj * 2]; +acadoWorkspace.objValueIn[8] = acadoVariables.od[runObj * 2 + 1]; + +acado_evaluateLSQ( acadoWorkspace.objValueIn, acadoWorkspace.objValueOut, TR); +acadoWorkspace.Dy[runObj * 4] = acadoWorkspace.objValueOut[0]; +acadoWorkspace.Dy[runObj * 4 + 1] = acadoWorkspace.objValueOut[1]; +acadoWorkspace.Dy[runObj * 4 + 2] = acadoWorkspace.objValueOut[2]; +acadoWorkspace.Dy[runObj * 4 + 3] = acadoWorkspace.objValueOut[3]; + +acado_setObjQ1Q2( &(acadoWorkspace.objValueOut[ 4 ]), &(acadoVariables.W[ runObj * 16 ]), &(acadoWorkspace.Q1[ runObj * 36 ]), &(acadoWorkspace.Q2[ runObj * 24 ]) ); + +acado_setObjR1R2( &(acadoWorkspace.objValueOut[ 28 ]), &(acadoVariables.W[ runObj * 16 ]), &(acadoWorkspace.R1[ runObj ]), &(acadoWorkspace.R2[ runObj * 4 ]) ); + +} +acadoWorkspace.objValueIn[0] = acadoVariables.x[120]; +acadoWorkspace.objValueIn[1] = acadoVariables.x[121]; +acadoWorkspace.objValueIn[2] = acadoVariables.x[122]; +acadoWorkspace.objValueIn[3] = acadoVariables.x[123]; +acadoWorkspace.objValueIn[4] = acadoVariables.x[124]; +acadoWorkspace.objValueIn[5] = acadoVariables.x[125]; +acadoWorkspace.objValueIn[6] = acadoVariables.od[40]; +acadoWorkspace.objValueIn[7] = acadoVariables.od[41]; +acado_evaluateLSQEndTerm( acadoWorkspace.objValueIn, acadoWorkspace.objValueOut, TR ); + +acadoWorkspace.DyN[0] = acadoWorkspace.objValueOut[0]; +acadoWorkspace.DyN[1] = acadoWorkspace.objValueOut[1]; +acadoWorkspace.DyN[2] = acadoWorkspace.objValueOut[2]; + +acado_setObjQN1QN2( &(acadoWorkspace.objValueOut[ 3 ]), acadoVariables.WN, acadoWorkspace.QN1, acadoWorkspace.QN2 ); + +} + +void acado_multGxd( real_t* const dOld, real_t* const Gx1, real_t* const dNew ) +{ +dNew[0] += + Gx1[0]*dOld[0] + Gx1[1]*dOld[1] + Gx1[2]*dOld[2] + Gx1[3]*dOld[3] + Gx1[4]*dOld[4] + Gx1[5]*dOld[5]; +dNew[1] += + Gx1[6]*dOld[0] + Gx1[7]*dOld[1] + Gx1[8]*dOld[2] + Gx1[9]*dOld[3] + Gx1[10]*dOld[4] + Gx1[11]*dOld[5]; +dNew[2] += + Gx1[12]*dOld[0] + Gx1[13]*dOld[1] + Gx1[14]*dOld[2] + Gx1[15]*dOld[3] + Gx1[16]*dOld[4] + Gx1[17]*dOld[5]; +dNew[3] += + Gx1[18]*dOld[0] + Gx1[19]*dOld[1] + Gx1[20]*dOld[2] + Gx1[21]*dOld[3] + Gx1[22]*dOld[4] + Gx1[23]*dOld[5]; +dNew[4] += + Gx1[24]*dOld[0] + Gx1[25]*dOld[1] + Gx1[26]*dOld[2] + Gx1[27]*dOld[3] + Gx1[28]*dOld[4] + Gx1[29]*dOld[5]; +dNew[5] += + Gx1[30]*dOld[0] + Gx1[31]*dOld[1] + Gx1[32]*dOld[2] + Gx1[33]*dOld[3] + Gx1[34]*dOld[4] + Gx1[35]*dOld[5]; +} + +void acado_moveGxT( real_t* const Gx1, real_t* const Gx2 ) +{ +Gx2[0] = Gx1[0]; +Gx2[1] = Gx1[1]; +Gx2[2] = Gx1[2]; +Gx2[3] = Gx1[3]; +Gx2[4] = Gx1[4]; +Gx2[5] = Gx1[5]; +Gx2[6] = Gx1[6]; +Gx2[7] = Gx1[7]; +Gx2[8] = Gx1[8]; +Gx2[9] = Gx1[9]; +Gx2[10] = Gx1[10]; +Gx2[11] = Gx1[11]; +Gx2[12] = Gx1[12]; +Gx2[13] = Gx1[13]; +Gx2[14] = Gx1[14]; +Gx2[15] = Gx1[15]; +Gx2[16] = Gx1[16]; +Gx2[17] = Gx1[17]; +Gx2[18] = Gx1[18]; +Gx2[19] = Gx1[19]; +Gx2[20] = Gx1[20]; +Gx2[21] = Gx1[21]; +Gx2[22] = Gx1[22]; +Gx2[23] = Gx1[23]; +Gx2[24] = Gx1[24]; +Gx2[25] = Gx1[25]; +Gx2[26] = Gx1[26]; +Gx2[27] = Gx1[27]; +Gx2[28] = Gx1[28]; +Gx2[29] = Gx1[29]; +Gx2[30] = Gx1[30]; +Gx2[31] = Gx1[31]; +Gx2[32] = Gx1[32]; +Gx2[33] = Gx1[33]; +Gx2[34] = Gx1[34]; +Gx2[35] = Gx1[35]; +} + +void acado_multGxGx( real_t* const Gx1, real_t* const Gx2, real_t* const Gx3 ) +{ +Gx3[0] = + Gx1[0]*Gx2[0] + Gx1[1]*Gx2[6] + Gx1[2]*Gx2[12] + Gx1[3]*Gx2[18] + Gx1[4]*Gx2[24] + Gx1[5]*Gx2[30]; +Gx3[1] = + Gx1[0]*Gx2[1] + Gx1[1]*Gx2[7] + Gx1[2]*Gx2[13] + Gx1[3]*Gx2[19] + Gx1[4]*Gx2[25] + Gx1[5]*Gx2[31]; +Gx3[2] = + Gx1[0]*Gx2[2] + Gx1[1]*Gx2[8] + Gx1[2]*Gx2[14] + Gx1[3]*Gx2[20] + Gx1[4]*Gx2[26] + Gx1[5]*Gx2[32]; +Gx3[3] = + Gx1[0]*Gx2[3] + Gx1[1]*Gx2[9] + Gx1[2]*Gx2[15] + Gx1[3]*Gx2[21] + Gx1[4]*Gx2[27] + Gx1[5]*Gx2[33]; +Gx3[4] = + Gx1[0]*Gx2[4] + Gx1[1]*Gx2[10] + Gx1[2]*Gx2[16] + Gx1[3]*Gx2[22] + Gx1[4]*Gx2[28] + Gx1[5]*Gx2[34]; +Gx3[5] = + Gx1[0]*Gx2[5] + Gx1[1]*Gx2[11] + Gx1[2]*Gx2[17] + Gx1[3]*Gx2[23] + Gx1[4]*Gx2[29] + Gx1[5]*Gx2[35]; +Gx3[6] = + Gx1[6]*Gx2[0] + Gx1[7]*Gx2[6] + Gx1[8]*Gx2[12] + Gx1[9]*Gx2[18] + Gx1[10]*Gx2[24] + Gx1[11]*Gx2[30]; +Gx3[7] = + Gx1[6]*Gx2[1] + Gx1[7]*Gx2[7] + Gx1[8]*Gx2[13] + Gx1[9]*Gx2[19] + Gx1[10]*Gx2[25] + Gx1[11]*Gx2[31]; +Gx3[8] = + Gx1[6]*Gx2[2] + Gx1[7]*Gx2[8] + Gx1[8]*Gx2[14] + Gx1[9]*Gx2[20] + Gx1[10]*Gx2[26] + Gx1[11]*Gx2[32]; +Gx3[9] = + Gx1[6]*Gx2[3] + Gx1[7]*Gx2[9] + Gx1[8]*Gx2[15] + Gx1[9]*Gx2[21] + Gx1[10]*Gx2[27] + Gx1[11]*Gx2[33]; +Gx3[10] = + Gx1[6]*Gx2[4] + Gx1[7]*Gx2[10] + Gx1[8]*Gx2[16] + Gx1[9]*Gx2[22] + Gx1[10]*Gx2[28] + Gx1[11]*Gx2[34]; +Gx3[11] = + Gx1[6]*Gx2[5] + Gx1[7]*Gx2[11] + Gx1[8]*Gx2[17] + Gx1[9]*Gx2[23] + Gx1[10]*Gx2[29] + Gx1[11]*Gx2[35]; +Gx3[12] = + Gx1[12]*Gx2[0] + Gx1[13]*Gx2[6] + Gx1[14]*Gx2[12] + Gx1[15]*Gx2[18] + Gx1[16]*Gx2[24] + Gx1[17]*Gx2[30]; +Gx3[13] = + Gx1[12]*Gx2[1] + Gx1[13]*Gx2[7] + Gx1[14]*Gx2[13] + Gx1[15]*Gx2[19] + Gx1[16]*Gx2[25] + Gx1[17]*Gx2[31]; +Gx3[14] = + Gx1[12]*Gx2[2] + Gx1[13]*Gx2[8] + Gx1[14]*Gx2[14] + Gx1[15]*Gx2[20] + Gx1[16]*Gx2[26] + Gx1[17]*Gx2[32]; +Gx3[15] = + Gx1[12]*Gx2[3] + Gx1[13]*Gx2[9] + Gx1[14]*Gx2[15] + Gx1[15]*Gx2[21] + Gx1[16]*Gx2[27] + Gx1[17]*Gx2[33]; +Gx3[16] = + Gx1[12]*Gx2[4] + Gx1[13]*Gx2[10] + Gx1[14]*Gx2[16] + Gx1[15]*Gx2[22] + Gx1[16]*Gx2[28] + Gx1[17]*Gx2[34]; +Gx3[17] = + Gx1[12]*Gx2[5] + Gx1[13]*Gx2[11] + Gx1[14]*Gx2[17] + Gx1[15]*Gx2[23] + Gx1[16]*Gx2[29] + Gx1[17]*Gx2[35]; +Gx3[18] = + Gx1[18]*Gx2[0] + Gx1[19]*Gx2[6] + Gx1[20]*Gx2[12] + Gx1[21]*Gx2[18] + Gx1[22]*Gx2[24] + Gx1[23]*Gx2[30]; +Gx3[19] = + Gx1[18]*Gx2[1] + Gx1[19]*Gx2[7] + Gx1[20]*Gx2[13] + Gx1[21]*Gx2[19] + Gx1[22]*Gx2[25] + Gx1[23]*Gx2[31]; +Gx3[20] = + Gx1[18]*Gx2[2] + Gx1[19]*Gx2[8] + Gx1[20]*Gx2[14] + Gx1[21]*Gx2[20] + Gx1[22]*Gx2[26] + Gx1[23]*Gx2[32]; +Gx3[21] = + Gx1[18]*Gx2[3] + Gx1[19]*Gx2[9] + Gx1[20]*Gx2[15] + Gx1[21]*Gx2[21] + Gx1[22]*Gx2[27] + Gx1[23]*Gx2[33]; +Gx3[22] = + Gx1[18]*Gx2[4] + Gx1[19]*Gx2[10] + Gx1[20]*Gx2[16] + Gx1[21]*Gx2[22] + Gx1[22]*Gx2[28] + Gx1[23]*Gx2[34]; +Gx3[23] = + Gx1[18]*Gx2[5] + Gx1[19]*Gx2[11] + Gx1[20]*Gx2[17] + Gx1[21]*Gx2[23] + Gx1[22]*Gx2[29] + Gx1[23]*Gx2[35]; +Gx3[24] = + Gx1[24]*Gx2[0] + Gx1[25]*Gx2[6] + Gx1[26]*Gx2[12] + Gx1[27]*Gx2[18] + Gx1[28]*Gx2[24] + Gx1[29]*Gx2[30]; +Gx3[25] = + Gx1[24]*Gx2[1] + Gx1[25]*Gx2[7] + Gx1[26]*Gx2[13] + Gx1[27]*Gx2[19] + Gx1[28]*Gx2[25] + Gx1[29]*Gx2[31]; +Gx3[26] = + Gx1[24]*Gx2[2] + Gx1[25]*Gx2[8] + Gx1[26]*Gx2[14] + Gx1[27]*Gx2[20] + Gx1[28]*Gx2[26] + Gx1[29]*Gx2[32]; +Gx3[27] = + Gx1[24]*Gx2[3] + Gx1[25]*Gx2[9] + Gx1[26]*Gx2[15] + Gx1[27]*Gx2[21] + Gx1[28]*Gx2[27] + Gx1[29]*Gx2[33]; +Gx3[28] = + Gx1[24]*Gx2[4] + Gx1[25]*Gx2[10] + Gx1[26]*Gx2[16] + Gx1[27]*Gx2[22] + Gx1[28]*Gx2[28] + Gx1[29]*Gx2[34]; +Gx3[29] = + Gx1[24]*Gx2[5] + Gx1[25]*Gx2[11] + Gx1[26]*Gx2[17] + Gx1[27]*Gx2[23] + Gx1[28]*Gx2[29] + Gx1[29]*Gx2[35]; +Gx3[30] = + Gx1[30]*Gx2[0] + Gx1[31]*Gx2[6] + Gx1[32]*Gx2[12] + Gx1[33]*Gx2[18] + Gx1[34]*Gx2[24] + Gx1[35]*Gx2[30]; +Gx3[31] = + Gx1[30]*Gx2[1] + Gx1[31]*Gx2[7] + Gx1[32]*Gx2[13] + Gx1[33]*Gx2[19] + Gx1[34]*Gx2[25] + Gx1[35]*Gx2[31]; +Gx3[32] = + Gx1[30]*Gx2[2] + Gx1[31]*Gx2[8] + Gx1[32]*Gx2[14] + Gx1[33]*Gx2[20] + Gx1[34]*Gx2[26] + Gx1[35]*Gx2[32]; +Gx3[33] = + Gx1[30]*Gx2[3] + Gx1[31]*Gx2[9] + Gx1[32]*Gx2[15] + Gx1[33]*Gx2[21] + Gx1[34]*Gx2[27] + Gx1[35]*Gx2[33]; +Gx3[34] = + Gx1[30]*Gx2[4] + Gx1[31]*Gx2[10] + Gx1[32]*Gx2[16] + Gx1[33]*Gx2[22] + Gx1[34]*Gx2[28] + Gx1[35]*Gx2[34]; +Gx3[35] = + Gx1[30]*Gx2[5] + Gx1[31]*Gx2[11] + Gx1[32]*Gx2[17] + Gx1[33]*Gx2[23] + Gx1[34]*Gx2[29] + Gx1[35]*Gx2[35]; +} + +void acado_multGxGu( real_t* const Gx1, real_t* const Gu1, real_t* const Gu2 ) +{ +Gu2[0] = + Gx1[0]*Gu1[0] + Gx1[1]*Gu1[1] + Gx1[2]*Gu1[2] + Gx1[3]*Gu1[3] + Gx1[4]*Gu1[4] + Gx1[5]*Gu1[5]; +Gu2[1] = + Gx1[6]*Gu1[0] + Gx1[7]*Gu1[1] + Gx1[8]*Gu1[2] + Gx1[9]*Gu1[3] + Gx1[10]*Gu1[4] + Gx1[11]*Gu1[5]; +Gu2[2] = + Gx1[12]*Gu1[0] + Gx1[13]*Gu1[1] + Gx1[14]*Gu1[2] + Gx1[15]*Gu1[3] + Gx1[16]*Gu1[4] + Gx1[17]*Gu1[5]; +Gu2[3] = + Gx1[18]*Gu1[0] + Gx1[19]*Gu1[1] + Gx1[20]*Gu1[2] + Gx1[21]*Gu1[3] + Gx1[22]*Gu1[4] + Gx1[23]*Gu1[5]; +Gu2[4] = + Gx1[24]*Gu1[0] + Gx1[25]*Gu1[1] + Gx1[26]*Gu1[2] + Gx1[27]*Gu1[3] + Gx1[28]*Gu1[4] + Gx1[29]*Gu1[5]; +Gu2[5] = + Gx1[30]*Gu1[0] + Gx1[31]*Gu1[1] + Gx1[32]*Gu1[2] + Gx1[33]*Gu1[3] + Gx1[34]*Gu1[4] + Gx1[35]*Gu1[5]; +} + +void acado_moveGuE( real_t* const Gu1, real_t* const Gu2 ) +{ +Gu2[0] = Gu1[0]; +Gu2[1] = Gu1[1]; +Gu2[2] = Gu1[2]; +Gu2[3] = Gu1[3]; +Gu2[4] = Gu1[4]; +Gu2[5] = Gu1[5]; +} + +void acado_setBlockH11( int iRow, int iCol, real_t* const Gu1, real_t* const Gu2 ) +{ +acadoWorkspace.H[(iRow * 26 + 156) + (iCol + 6)] += + Gu1[0]*Gu2[0] + Gu1[1]*Gu2[1] + Gu1[2]*Gu2[2] + Gu1[3]*Gu2[3] + Gu1[4]*Gu2[4] + Gu1[5]*Gu2[5]; +} + +void acado_setBlockH11_R1( int iRow, int iCol, real_t* const R11 ) +{ +acadoWorkspace.H[(iRow * 26 + 156) + (iCol + 6)] = R11[0]; +} + +void acado_zeroBlockH11( int iRow, int iCol ) +{ +acadoWorkspace.H[(iRow * 26 + 156) + (iCol + 6)] = 0.0000000000000000e+00; +} + +void acado_copyHTH( int iRow, int iCol ) +{ +acadoWorkspace.H[(iRow * 26 + 156) + (iCol + 6)] = acadoWorkspace.H[(iCol * 26 + 156) + (iRow + 6)]; +} + +void acado_multQ1d( real_t* const Gx1, real_t* const dOld, real_t* const dNew ) +{ +dNew[0] = + Gx1[0]*dOld[0] + Gx1[1]*dOld[1] + Gx1[2]*dOld[2] + Gx1[3]*dOld[3] + Gx1[4]*dOld[4] + Gx1[5]*dOld[5]; +dNew[1] = + Gx1[6]*dOld[0] + Gx1[7]*dOld[1] + Gx1[8]*dOld[2] + Gx1[9]*dOld[3] + Gx1[10]*dOld[4] + Gx1[11]*dOld[5]; +dNew[2] = + Gx1[12]*dOld[0] + Gx1[13]*dOld[1] + Gx1[14]*dOld[2] + Gx1[15]*dOld[3] + Gx1[16]*dOld[4] + Gx1[17]*dOld[5]; +dNew[3] = + Gx1[18]*dOld[0] + Gx1[19]*dOld[1] + Gx1[20]*dOld[2] + Gx1[21]*dOld[3] + Gx1[22]*dOld[4] + Gx1[23]*dOld[5]; +dNew[4] = + Gx1[24]*dOld[0] + Gx1[25]*dOld[1] + Gx1[26]*dOld[2] + Gx1[27]*dOld[3] + Gx1[28]*dOld[4] + Gx1[29]*dOld[5]; +dNew[5] = + Gx1[30]*dOld[0] + Gx1[31]*dOld[1] + Gx1[32]*dOld[2] + Gx1[33]*dOld[3] + Gx1[34]*dOld[4] + Gx1[35]*dOld[5]; +} + +void acado_multQN1d( real_t* const QN1, real_t* const dOld, real_t* const dNew ) +{ +dNew[0] = + acadoWorkspace.QN1[0]*dOld[0] + acadoWorkspace.QN1[1]*dOld[1] + acadoWorkspace.QN1[2]*dOld[2] + acadoWorkspace.QN1[3]*dOld[3] + acadoWorkspace.QN1[4]*dOld[4] + acadoWorkspace.QN1[5]*dOld[5]; +dNew[1] = + acadoWorkspace.QN1[6]*dOld[0] + acadoWorkspace.QN1[7]*dOld[1] + acadoWorkspace.QN1[8]*dOld[2] + acadoWorkspace.QN1[9]*dOld[3] + acadoWorkspace.QN1[10]*dOld[4] + acadoWorkspace.QN1[11]*dOld[5]; +dNew[2] = + acadoWorkspace.QN1[12]*dOld[0] + acadoWorkspace.QN1[13]*dOld[1] + acadoWorkspace.QN1[14]*dOld[2] + acadoWorkspace.QN1[15]*dOld[3] + acadoWorkspace.QN1[16]*dOld[4] + acadoWorkspace.QN1[17]*dOld[5]; +dNew[3] = + acadoWorkspace.QN1[18]*dOld[0] + acadoWorkspace.QN1[19]*dOld[1] + acadoWorkspace.QN1[20]*dOld[2] + acadoWorkspace.QN1[21]*dOld[3] + acadoWorkspace.QN1[22]*dOld[4] + acadoWorkspace.QN1[23]*dOld[5]; +dNew[4] = + acadoWorkspace.QN1[24]*dOld[0] + acadoWorkspace.QN1[25]*dOld[1] + acadoWorkspace.QN1[26]*dOld[2] + acadoWorkspace.QN1[27]*dOld[3] + acadoWorkspace.QN1[28]*dOld[4] + acadoWorkspace.QN1[29]*dOld[5]; +dNew[5] = + acadoWorkspace.QN1[30]*dOld[0] + acadoWorkspace.QN1[31]*dOld[1] + acadoWorkspace.QN1[32]*dOld[2] + acadoWorkspace.QN1[33]*dOld[3] + acadoWorkspace.QN1[34]*dOld[4] + acadoWorkspace.QN1[35]*dOld[5]; +} + +void acado_multRDy( real_t* const R2, real_t* const Dy1, real_t* const RDy1 ) +{ +RDy1[0] = + R2[0]*Dy1[0] + R2[1]*Dy1[1] + R2[2]*Dy1[2] + R2[3]*Dy1[3]; +} + +void acado_multQDy( real_t* const Q2, real_t* const Dy1, real_t* const QDy1 ) +{ +QDy1[0] = + Q2[0]*Dy1[0] + Q2[1]*Dy1[1] + Q2[2]*Dy1[2] + Q2[3]*Dy1[3]; +QDy1[1] = + Q2[4]*Dy1[0] + Q2[5]*Dy1[1] + Q2[6]*Dy1[2] + Q2[7]*Dy1[3]; +QDy1[2] = + Q2[8]*Dy1[0] + Q2[9]*Dy1[1] + Q2[10]*Dy1[2] + Q2[11]*Dy1[3]; +QDy1[3] = + Q2[12]*Dy1[0] + Q2[13]*Dy1[1] + Q2[14]*Dy1[2] + Q2[15]*Dy1[3]; +QDy1[4] = + Q2[16]*Dy1[0] + Q2[17]*Dy1[1] + Q2[18]*Dy1[2] + Q2[19]*Dy1[3]; +QDy1[5] = + Q2[20]*Dy1[0] + Q2[21]*Dy1[1] + Q2[22]*Dy1[2] + Q2[23]*Dy1[3]; +} + +void acado_multEQDy( real_t* const E1, real_t* const QDy1, real_t* const U1 ) +{ +U1[0] += + E1[0]*QDy1[0] + E1[1]*QDy1[1] + E1[2]*QDy1[2] + E1[3]*QDy1[3] + E1[4]*QDy1[4] + E1[5]*QDy1[5]; +} + +void acado_multQETGx( real_t* const E1, real_t* const Gx1, real_t* const H101 ) +{ +H101[0] += + E1[0]*Gx1[0] + E1[1]*Gx1[6] + E1[2]*Gx1[12] + E1[3]*Gx1[18] + E1[4]*Gx1[24] + E1[5]*Gx1[30]; +H101[1] += + E1[0]*Gx1[1] + E1[1]*Gx1[7] + E1[2]*Gx1[13] + E1[3]*Gx1[19] + E1[4]*Gx1[25] + E1[5]*Gx1[31]; +H101[2] += + E1[0]*Gx1[2] + E1[1]*Gx1[8] + E1[2]*Gx1[14] + E1[3]*Gx1[20] + E1[4]*Gx1[26] + E1[5]*Gx1[32]; +H101[3] += + E1[0]*Gx1[3] + E1[1]*Gx1[9] + E1[2]*Gx1[15] + E1[3]*Gx1[21] + E1[4]*Gx1[27] + E1[5]*Gx1[33]; +H101[4] += + E1[0]*Gx1[4] + E1[1]*Gx1[10] + E1[2]*Gx1[16] + E1[3]*Gx1[22] + E1[4]*Gx1[28] + E1[5]*Gx1[34]; +H101[5] += + E1[0]*Gx1[5] + E1[1]*Gx1[11] + E1[2]*Gx1[17] + E1[3]*Gx1[23] + E1[4]*Gx1[29] + E1[5]*Gx1[35]; +} + +void acado_zeroBlockH10( real_t* const H101 ) +{ +{ int lCopy; for (lCopy = 0; lCopy < 6; lCopy++) H101[ lCopy ] = 0; } +} + +void acado_multEDu( real_t* const E1, real_t* const U1, real_t* const dNew ) +{ +dNew[0] += + E1[0]*U1[0]; +dNew[1] += + E1[1]*U1[0]; +dNew[2] += + E1[2]*U1[0]; +dNew[3] += + E1[3]*U1[0]; +dNew[4] += + E1[4]*U1[0]; +dNew[5] += + E1[5]*U1[0]; +} + +void acado_zeroBlockH00( ) +{ +acadoWorkspace.H[0] = 0.0000000000000000e+00; +acadoWorkspace.H[1] = 0.0000000000000000e+00; +acadoWorkspace.H[2] = 0.0000000000000000e+00; +acadoWorkspace.H[3] = 0.0000000000000000e+00; +acadoWorkspace.H[4] = 0.0000000000000000e+00; +acadoWorkspace.H[5] = 0.0000000000000000e+00; +acadoWorkspace.H[26] = 0.0000000000000000e+00; +acadoWorkspace.H[27] = 0.0000000000000000e+00; +acadoWorkspace.H[28] = 0.0000000000000000e+00; +acadoWorkspace.H[29] = 0.0000000000000000e+00; +acadoWorkspace.H[30] = 0.0000000000000000e+00; +acadoWorkspace.H[31] = 0.0000000000000000e+00; +acadoWorkspace.H[52] = 0.0000000000000000e+00; +acadoWorkspace.H[53] = 0.0000000000000000e+00; +acadoWorkspace.H[54] = 0.0000000000000000e+00; +acadoWorkspace.H[55] = 0.0000000000000000e+00; +acadoWorkspace.H[56] = 0.0000000000000000e+00; +acadoWorkspace.H[57] = 0.0000000000000000e+00; +acadoWorkspace.H[78] = 0.0000000000000000e+00; +acadoWorkspace.H[79] = 0.0000000000000000e+00; +acadoWorkspace.H[80] = 0.0000000000000000e+00; +acadoWorkspace.H[81] = 0.0000000000000000e+00; +acadoWorkspace.H[82] = 0.0000000000000000e+00; +acadoWorkspace.H[83] = 0.0000000000000000e+00; +acadoWorkspace.H[104] = 0.0000000000000000e+00; +acadoWorkspace.H[105] = 0.0000000000000000e+00; +acadoWorkspace.H[106] = 0.0000000000000000e+00; +acadoWorkspace.H[107] = 0.0000000000000000e+00; +acadoWorkspace.H[108] = 0.0000000000000000e+00; +acadoWorkspace.H[109] = 0.0000000000000000e+00; +acadoWorkspace.H[130] = 0.0000000000000000e+00; +acadoWorkspace.H[131] = 0.0000000000000000e+00; +acadoWorkspace.H[132] = 0.0000000000000000e+00; +acadoWorkspace.H[133] = 0.0000000000000000e+00; +acadoWorkspace.H[134] = 0.0000000000000000e+00; +acadoWorkspace.H[135] = 0.0000000000000000e+00; +} + +void acado_multCTQC( real_t* const Gx1, real_t* const Gx2 ) +{ +acadoWorkspace.H[0] += + Gx1[0]*Gx2[0] + Gx1[6]*Gx2[6] + Gx1[12]*Gx2[12] + Gx1[18]*Gx2[18] + Gx1[24]*Gx2[24] + Gx1[30]*Gx2[30]; +acadoWorkspace.H[1] += + Gx1[0]*Gx2[1] + Gx1[6]*Gx2[7] + Gx1[12]*Gx2[13] + Gx1[18]*Gx2[19] + Gx1[24]*Gx2[25] + Gx1[30]*Gx2[31]; +acadoWorkspace.H[2] += + Gx1[0]*Gx2[2] + Gx1[6]*Gx2[8] + Gx1[12]*Gx2[14] + Gx1[18]*Gx2[20] + Gx1[24]*Gx2[26] + Gx1[30]*Gx2[32]; +acadoWorkspace.H[3] += + Gx1[0]*Gx2[3] + Gx1[6]*Gx2[9] + Gx1[12]*Gx2[15] + Gx1[18]*Gx2[21] + Gx1[24]*Gx2[27] + Gx1[30]*Gx2[33]; +acadoWorkspace.H[4] += + Gx1[0]*Gx2[4] + Gx1[6]*Gx2[10] + Gx1[12]*Gx2[16] + Gx1[18]*Gx2[22] + Gx1[24]*Gx2[28] + Gx1[30]*Gx2[34]; +acadoWorkspace.H[5] += + Gx1[0]*Gx2[5] + Gx1[6]*Gx2[11] + Gx1[12]*Gx2[17] + Gx1[18]*Gx2[23] + Gx1[24]*Gx2[29] + Gx1[30]*Gx2[35]; +acadoWorkspace.H[26] += + Gx1[1]*Gx2[0] + Gx1[7]*Gx2[6] + Gx1[13]*Gx2[12] + Gx1[19]*Gx2[18] + Gx1[25]*Gx2[24] + Gx1[31]*Gx2[30]; +acadoWorkspace.H[27] += + Gx1[1]*Gx2[1] + Gx1[7]*Gx2[7] + Gx1[13]*Gx2[13] + Gx1[19]*Gx2[19] + Gx1[25]*Gx2[25] + Gx1[31]*Gx2[31]; +acadoWorkspace.H[28] += + Gx1[1]*Gx2[2] + Gx1[7]*Gx2[8] + Gx1[13]*Gx2[14] + Gx1[19]*Gx2[20] + Gx1[25]*Gx2[26] + Gx1[31]*Gx2[32]; +acadoWorkspace.H[29] += + Gx1[1]*Gx2[3] + Gx1[7]*Gx2[9] + Gx1[13]*Gx2[15] + Gx1[19]*Gx2[21] + Gx1[25]*Gx2[27] + Gx1[31]*Gx2[33]; +acadoWorkspace.H[30] += + Gx1[1]*Gx2[4] + Gx1[7]*Gx2[10] + Gx1[13]*Gx2[16] + Gx1[19]*Gx2[22] + Gx1[25]*Gx2[28] + Gx1[31]*Gx2[34]; +acadoWorkspace.H[31] += + Gx1[1]*Gx2[5] + Gx1[7]*Gx2[11] + Gx1[13]*Gx2[17] + Gx1[19]*Gx2[23] + Gx1[25]*Gx2[29] + Gx1[31]*Gx2[35]; +acadoWorkspace.H[52] += + Gx1[2]*Gx2[0] + Gx1[8]*Gx2[6] + Gx1[14]*Gx2[12] + Gx1[20]*Gx2[18] + Gx1[26]*Gx2[24] + Gx1[32]*Gx2[30]; +acadoWorkspace.H[53] += + Gx1[2]*Gx2[1] + Gx1[8]*Gx2[7] + Gx1[14]*Gx2[13] + Gx1[20]*Gx2[19] + Gx1[26]*Gx2[25] + Gx1[32]*Gx2[31]; +acadoWorkspace.H[54] += + Gx1[2]*Gx2[2] + Gx1[8]*Gx2[8] + Gx1[14]*Gx2[14] + Gx1[20]*Gx2[20] + Gx1[26]*Gx2[26] + Gx1[32]*Gx2[32]; +acadoWorkspace.H[55] += + Gx1[2]*Gx2[3] + Gx1[8]*Gx2[9] + Gx1[14]*Gx2[15] + Gx1[20]*Gx2[21] + Gx1[26]*Gx2[27] + Gx1[32]*Gx2[33]; +acadoWorkspace.H[56] += + Gx1[2]*Gx2[4] + Gx1[8]*Gx2[10] + Gx1[14]*Gx2[16] + Gx1[20]*Gx2[22] + Gx1[26]*Gx2[28] + Gx1[32]*Gx2[34]; +acadoWorkspace.H[57] += + Gx1[2]*Gx2[5] + Gx1[8]*Gx2[11] + Gx1[14]*Gx2[17] + Gx1[20]*Gx2[23] + Gx1[26]*Gx2[29] + Gx1[32]*Gx2[35]; +acadoWorkspace.H[78] += + Gx1[3]*Gx2[0] + Gx1[9]*Gx2[6] + Gx1[15]*Gx2[12] + Gx1[21]*Gx2[18] + Gx1[27]*Gx2[24] + Gx1[33]*Gx2[30]; +acadoWorkspace.H[79] += + Gx1[3]*Gx2[1] + Gx1[9]*Gx2[7] + Gx1[15]*Gx2[13] + Gx1[21]*Gx2[19] + Gx1[27]*Gx2[25] + Gx1[33]*Gx2[31]; +acadoWorkspace.H[80] += + Gx1[3]*Gx2[2] + Gx1[9]*Gx2[8] + Gx1[15]*Gx2[14] + Gx1[21]*Gx2[20] + Gx1[27]*Gx2[26] + Gx1[33]*Gx2[32]; +acadoWorkspace.H[81] += + Gx1[3]*Gx2[3] + Gx1[9]*Gx2[9] + Gx1[15]*Gx2[15] + Gx1[21]*Gx2[21] + Gx1[27]*Gx2[27] + Gx1[33]*Gx2[33]; +acadoWorkspace.H[82] += + Gx1[3]*Gx2[4] + Gx1[9]*Gx2[10] + Gx1[15]*Gx2[16] + Gx1[21]*Gx2[22] + Gx1[27]*Gx2[28] + Gx1[33]*Gx2[34]; +acadoWorkspace.H[83] += + Gx1[3]*Gx2[5] + Gx1[9]*Gx2[11] + Gx1[15]*Gx2[17] + Gx1[21]*Gx2[23] + Gx1[27]*Gx2[29] + Gx1[33]*Gx2[35]; +acadoWorkspace.H[104] += + Gx1[4]*Gx2[0] + Gx1[10]*Gx2[6] + Gx1[16]*Gx2[12] + Gx1[22]*Gx2[18] + Gx1[28]*Gx2[24] + Gx1[34]*Gx2[30]; +acadoWorkspace.H[105] += + Gx1[4]*Gx2[1] + Gx1[10]*Gx2[7] + Gx1[16]*Gx2[13] + Gx1[22]*Gx2[19] + Gx1[28]*Gx2[25] + Gx1[34]*Gx2[31]; +acadoWorkspace.H[106] += + Gx1[4]*Gx2[2] + Gx1[10]*Gx2[8] + Gx1[16]*Gx2[14] + Gx1[22]*Gx2[20] + Gx1[28]*Gx2[26] + Gx1[34]*Gx2[32]; +acadoWorkspace.H[107] += + Gx1[4]*Gx2[3] + Gx1[10]*Gx2[9] + Gx1[16]*Gx2[15] + Gx1[22]*Gx2[21] + Gx1[28]*Gx2[27] + Gx1[34]*Gx2[33]; +acadoWorkspace.H[108] += + Gx1[4]*Gx2[4] + Gx1[10]*Gx2[10] + Gx1[16]*Gx2[16] + Gx1[22]*Gx2[22] + Gx1[28]*Gx2[28] + Gx1[34]*Gx2[34]; +acadoWorkspace.H[109] += + Gx1[4]*Gx2[5] + Gx1[10]*Gx2[11] + Gx1[16]*Gx2[17] + Gx1[22]*Gx2[23] + Gx1[28]*Gx2[29] + Gx1[34]*Gx2[35]; +acadoWorkspace.H[130] += + Gx1[5]*Gx2[0] + Gx1[11]*Gx2[6] + Gx1[17]*Gx2[12] + Gx1[23]*Gx2[18] + Gx1[29]*Gx2[24] + Gx1[35]*Gx2[30]; +acadoWorkspace.H[131] += + Gx1[5]*Gx2[1] + Gx1[11]*Gx2[7] + Gx1[17]*Gx2[13] + Gx1[23]*Gx2[19] + Gx1[29]*Gx2[25] + Gx1[35]*Gx2[31]; +acadoWorkspace.H[132] += + Gx1[5]*Gx2[2] + Gx1[11]*Gx2[8] + Gx1[17]*Gx2[14] + Gx1[23]*Gx2[20] + Gx1[29]*Gx2[26] + Gx1[35]*Gx2[32]; +acadoWorkspace.H[133] += + Gx1[5]*Gx2[3] + Gx1[11]*Gx2[9] + Gx1[17]*Gx2[15] + Gx1[23]*Gx2[21] + Gx1[29]*Gx2[27] + Gx1[35]*Gx2[33]; +acadoWorkspace.H[134] += + Gx1[5]*Gx2[4] + Gx1[11]*Gx2[10] + Gx1[17]*Gx2[16] + Gx1[23]*Gx2[22] + Gx1[29]*Gx2[28] + Gx1[35]*Gx2[34]; +acadoWorkspace.H[135] += + Gx1[5]*Gx2[5] + Gx1[11]*Gx2[11] + Gx1[17]*Gx2[17] + Gx1[23]*Gx2[23] + Gx1[29]*Gx2[29] + Gx1[35]*Gx2[35]; +} + +void acado_macCTSlx( real_t* const C0, real_t* const g0 ) +{ +g0[0] += 0.0; +; +g0[1] += 0.0; +; +g0[2] += 0.0; +; +g0[3] += 0.0; +; +g0[4] += 0.0; +; +g0[5] += 0.0; +; +} + +void acado_macETSlu( real_t* const E0, real_t* const g1 ) +{ +g1[0] += 0.0; +; +} + +void acado_condensePrep( ) +{ +int lRun1; +int lRun2; +int lRun3; +int lRun4; +int lRun5; +/** Row vector of size: 20 */ +static const int xBoundIndices[ 20 ] = +{ 7, 13, 19, 25, 31, 37, 43, 49, 55, 61, 67, 73, 79, 85, 91, 97, 103, 109, 115, 121 }; +acado_moveGuE( acadoWorkspace.evGu, acadoWorkspace.E ); +acado_moveGxT( &(acadoWorkspace.evGx[ 36 ]), acadoWorkspace.T ); +acado_multGxd( acadoWorkspace.d, &(acadoWorkspace.evGx[ 36 ]), &(acadoWorkspace.d[ 6 ]) ); +acado_multGxGx( acadoWorkspace.T, acadoWorkspace.evGx, &(acadoWorkspace.evGx[ 36 ]) ); + +acado_multGxGu( acadoWorkspace.T, acadoWorkspace.E, &(acadoWorkspace.E[ 6 ]) ); + +acado_moveGuE( &(acadoWorkspace.evGu[ 6 ]), &(acadoWorkspace.E[ 12 ]) ); + +acado_moveGxT( &(acadoWorkspace.evGx[ 72 ]), acadoWorkspace.T ); +acado_multGxd( &(acadoWorkspace.d[ 6 ]), &(acadoWorkspace.evGx[ 72 ]), &(acadoWorkspace.d[ 12 ]) ); +acado_multGxGx( acadoWorkspace.T, &(acadoWorkspace.evGx[ 36 ]), &(acadoWorkspace.evGx[ 72 ]) ); + +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 6 ]), &(acadoWorkspace.E[ 18 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 12 ]), &(acadoWorkspace.E[ 24 ]) ); + +acado_moveGuE( &(acadoWorkspace.evGu[ 12 ]), &(acadoWorkspace.E[ 30 ]) ); + +acado_moveGxT( &(acadoWorkspace.evGx[ 108 ]), acadoWorkspace.T ); +acado_multGxd( &(acadoWorkspace.d[ 12 ]), &(acadoWorkspace.evGx[ 108 ]), &(acadoWorkspace.d[ 18 ]) ); +acado_multGxGx( acadoWorkspace.T, &(acadoWorkspace.evGx[ 72 ]), &(acadoWorkspace.evGx[ 108 ]) ); + +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 18 ]), &(acadoWorkspace.E[ 36 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 24 ]), &(acadoWorkspace.E[ 42 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 30 ]), &(acadoWorkspace.E[ 48 ]) ); + +acado_moveGuE( &(acadoWorkspace.evGu[ 18 ]), &(acadoWorkspace.E[ 54 ]) ); + +acado_moveGxT( &(acadoWorkspace.evGx[ 144 ]), acadoWorkspace.T ); +acado_multGxd( &(acadoWorkspace.d[ 18 ]), &(acadoWorkspace.evGx[ 144 ]), &(acadoWorkspace.d[ 24 ]) ); +acado_multGxGx( acadoWorkspace.T, &(acadoWorkspace.evGx[ 108 ]), &(acadoWorkspace.evGx[ 144 ]) ); + +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 36 ]), &(acadoWorkspace.E[ 60 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 42 ]), &(acadoWorkspace.E[ 66 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 48 ]), &(acadoWorkspace.E[ 72 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 54 ]), &(acadoWorkspace.E[ 78 ]) ); + +acado_moveGuE( &(acadoWorkspace.evGu[ 24 ]), &(acadoWorkspace.E[ 84 ]) ); + +acado_moveGxT( &(acadoWorkspace.evGx[ 180 ]), acadoWorkspace.T ); +acado_multGxd( &(acadoWorkspace.d[ 24 ]), &(acadoWorkspace.evGx[ 180 ]), &(acadoWorkspace.d[ 30 ]) ); +acado_multGxGx( acadoWorkspace.T, &(acadoWorkspace.evGx[ 144 ]), &(acadoWorkspace.evGx[ 180 ]) ); + +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 60 ]), &(acadoWorkspace.E[ 90 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 66 ]), &(acadoWorkspace.E[ 96 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 72 ]), &(acadoWorkspace.E[ 102 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 78 ]), &(acadoWorkspace.E[ 108 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 84 ]), &(acadoWorkspace.E[ 114 ]) ); + +acado_moveGuE( &(acadoWorkspace.evGu[ 30 ]), &(acadoWorkspace.E[ 120 ]) ); + +acado_moveGxT( &(acadoWorkspace.evGx[ 216 ]), acadoWorkspace.T ); +acado_multGxd( &(acadoWorkspace.d[ 30 ]), &(acadoWorkspace.evGx[ 216 ]), &(acadoWorkspace.d[ 36 ]) ); +acado_multGxGx( acadoWorkspace.T, &(acadoWorkspace.evGx[ 180 ]), &(acadoWorkspace.evGx[ 216 ]) ); + +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 90 ]), &(acadoWorkspace.E[ 126 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 96 ]), &(acadoWorkspace.E[ 132 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 102 ]), &(acadoWorkspace.E[ 138 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 108 ]), &(acadoWorkspace.E[ 144 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 114 ]), &(acadoWorkspace.E[ 150 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 120 ]), &(acadoWorkspace.E[ 156 ]) ); + +acado_moveGuE( &(acadoWorkspace.evGu[ 36 ]), &(acadoWorkspace.E[ 162 ]) ); + +acado_moveGxT( &(acadoWorkspace.evGx[ 252 ]), acadoWorkspace.T ); +acado_multGxd( &(acadoWorkspace.d[ 36 ]), &(acadoWorkspace.evGx[ 252 ]), &(acadoWorkspace.d[ 42 ]) ); +acado_multGxGx( acadoWorkspace.T, &(acadoWorkspace.evGx[ 216 ]), &(acadoWorkspace.evGx[ 252 ]) ); + +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 126 ]), &(acadoWorkspace.E[ 168 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 132 ]), &(acadoWorkspace.E[ 174 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 138 ]), &(acadoWorkspace.E[ 180 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 144 ]), &(acadoWorkspace.E[ 186 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 150 ]), &(acadoWorkspace.E[ 192 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 156 ]), &(acadoWorkspace.E[ 198 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 162 ]), &(acadoWorkspace.E[ 204 ]) ); + +acado_moveGuE( &(acadoWorkspace.evGu[ 42 ]), &(acadoWorkspace.E[ 210 ]) ); + +acado_moveGxT( &(acadoWorkspace.evGx[ 288 ]), acadoWorkspace.T ); +acado_multGxd( &(acadoWorkspace.d[ 42 ]), &(acadoWorkspace.evGx[ 288 ]), &(acadoWorkspace.d[ 48 ]) ); +acado_multGxGx( acadoWorkspace.T, &(acadoWorkspace.evGx[ 252 ]), &(acadoWorkspace.evGx[ 288 ]) ); + +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 168 ]), &(acadoWorkspace.E[ 216 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 174 ]), &(acadoWorkspace.E[ 222 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 180 ]), &(acadoWorkspace.E[ 228 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 186 ]), &(acadoWorkspace.E[ 234 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 192 ]), &(acadoWorkspace.E[ 240 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 198 ]), &(acadoWorkspace.E[ 246 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 204 ]), &(acadoWorkspace.E[ 252 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 210 ]), &(acadoWorkspace.E[ 258 ]) ); + +acado_moveGuE( &(acadoWorkspace.evGu[ 48 ]), &(acadoWorkspace.E[ 264 ]) ); + +acado_moveGxT( &(acadoWorkspace.evGx[ 324 ]), acadoWorkspace.T ); +acado_multGxd( &(acadoWorkspace.d[ 48 ]), &(acadoWorkspace.evGx[ 324 ]), &(acadoWorkspace.d[ 54 ]) ); +acado_multGxGx( acadoWorkspace.T, &(acadoWorkspace.evGx[ 288 ]), &(acadoWorkspace.evGx[ 324 ]) ); + +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 216 ]), &(acadoWorkspace.E[ 270 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 222 ]), &(acadoWorkspace.E[ 276 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 228 ]), &(acadoWorkspace.E[ 282 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 234 ]), &(acadoWorkspace.E[ 288 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 240 ]), &(acadoWorkspace.E[ 294 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 246 ]), &(acadoWorkspace.E[ 300 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 252 ]), &(acadoWorkspace.E[ 306 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 258 ]), &(acadoWorkspace.E[ 312 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 264 ]), &(acadoWorkspace.E[ 318 ]) ); + +acado_moveGuE( &(acadoWorkspace.evGu[ 54 ]), &(acadoWorkspace.E[ 324 ]) ); + +acado_moveGxT( &(acadoWorkspace.evGx[ 360 ]), acadoWorkspace.T ); +acado_multGxd( &(acadoWorkspace.d[ 54 ]), &(acadoWorkspace.evGx[ 360 ]), &(acadoWorkspace.d[ 60 ]) ); +acado_multGxGx( acadoWorkspace.T, &(acadoWorkspace.evGx[ 324 ]), &(acadoWorkspace.evGx[ 360 ]) ); + +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 270 ]), &(acadoWorkspace.E[ 330 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 276 ]), &(acadoWorkspace.E[ 336 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 282 ]), &(acadoWorkspace.E[ 342 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 288 ]), &(acadoWorkspace.E[ 348 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 294 ]), &(acadoWorkspace.E[ 354 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 300 ]), &(acadoWorkspace.E[ 360 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 306 ]), &(acadoWorkspace.E[ 366 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 312 ]), &(acadoWorkspace.E[ 372 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 318 ]), &(acadoWorkspace.E[ 378 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 324 ]), &(acadoWorkspace.E[ 384 ]) ); + +acado_moveGuE( &(acadoWorkspace.evGu[ 60 ]), &(acadoWorkspace.E[ 390 ]) ); + +acado_moveGxT( &(acadoWorkspace.evGx[ 396 ]), acadoWorkspace.T ); +acado_multGxd( &(acadoWorkspace.d[ 60 ]), &(acadoWorkspace.evGx[ 396 ]), &(acadoWorkspace.d[ 66 ]) ); +acado_multGxGx( acadoWorkspace.T, &(acadoWorkspace.evGx[ 360 ]), &(acadoWorkspace.evGx[ 396 ]) ); + +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 330 ]), &(acadoWorkspace.E[ 396 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 336 ]), &(acadoWorkspace.E[ 402 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 342 ]), &(acadoWorkspace.E[ 408 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 348 ]), &(acadoWorkspace.E[ 414 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 354 ]), &(acadoWorkspace.E[ 420 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 360 ]), &(acadoWorkspace.E[ 426 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 366 ]), &(acadoWorkspace.E[ 432 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 372 ]), &(acadoWorkspace.E[ 438 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 378 ]), &(acadoWorkspace.E[ 444 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 384 ]), &(acadoWorkspace.E[ 450 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 390 ]), &(acadoWorkspace.E[ 456 ]) ); + +acado_moveGuE( &(acadoWorkspace.evGu[ 66 ]), &(acadoWorkspace.E[ 462 ]) ); + +acado_moveGxT( &(acadoWorkspace.evGx[ 432 ]), acadoWorkspace.T ); +acado_multGxd( &(acadoWorkspace.d[ 66 ]), &(acadoWorkspace.evGx[ 432 ]), &(acadoWorkspace.d[ 72 ]) ); +acado_multGxGx( acadoWorkspace.T, &(acadoWorkspace.evGx[ 396 ]), &(acadoWorkspace.evGx[ 432 ]) ); + +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 396 ]), &(acadoWorkspace.E[ 468 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 402 ]), &(acadoWorkspace.E[ 474 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 408 ]), &(acadoWorkspace.E[ 480 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 414 ]), &(acadoWorkspace.E[ 486 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 420 ]), &(acadoWorkspace.E[ 492 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 426 ]), &(acadoWorkspace.E[ 498 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 432 ]), &(acadoWorkspace.E[ 504 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 438 ]), &(acadoWorkspace.E[ 510 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 444 ]), &(acadoWorkspace.E[ 516 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 450 ]), &(acadoWorkspace.E[ 522 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 456 ]), &(acadoWorkspace.E[ 528 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 462 ]), &(acadoWorkspace.E[ 534 ]) ); + +acado_moveGuE( &(acadoWorkspace.evGu[ 72 ]), &(acadoWorkspace.E[ 540 ]) ); + +acado_moveGxT( &(acadoWorkspace.evGx[ 468 ]), acadoWorkspace.T ); +acado_multGxd( &(acadoWorkspace.d[ 72 ]), &(acadoWorkspace.evGx[ 468 ]), &(acadoWorkspace.d[ 78 ]) ); +acado_multGxGx( acadoWorkspace.T, &(acadoWorkspace.evGx[ 432 ]), &(acadoWorkspace.evGx[ 468 ]) ); + +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 468 ]), &(acadoWorkspace.E[ 546 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 474 ]), &(acadoWorkspace.E[ 552 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 480 ]), &(acadoWorkspace.E[ 558 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 486 ]), &(acadoWorkspace.E[ 564 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 492 ]), &(acadoWorkspace.E[ 570 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 498 ]), &(acadoWorkspace.E[ 576 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 504 ]), &(acadoWorkspace.E[ 582 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 510 ]), &(acadoWorkspace.E[ 588 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 516 ]), &(acadoWorkspace.E[ 594 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 522 ]), &(acadoWorkspace.E[ 600 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 528 ]), &(acadoWorkspace.E[ 606 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 534 ]), &(acadoWorkspace.E[ 612 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 540 ]), &(acadoWorkspace.E[ 618 ]) ); + +acado_moveGuE( &(acadoWorkspace.evGu[ 78 ]), &(acadoWorkspace.E[ 624 ]) ); + +acado_moveGxT( &(acadoWorkspace.evGx[ 504 ]), acadoWorkspace.T ); +acado_multGxd( &(acadoWorkspace.d[ 78 ]), &(acadoWorkspace.evGx[ 504 ]), &(acadoWorkspace.d[ 84 ]) ); +acado_multGxGx( acadoWorkspace.T, &(acadoWorkspace.evGx[ 468 ]), &(acadoWorkspace.evGx[ 504 ]) ); + +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 546 ]), &(acadoWorkspace.E[ 630 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 552 ]), &(acadoWorkspace.E[ 636 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 558 ]), &(acadoWorkspace.E[ 642 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 564 ]), &(acadoWorkspace.E[ 648 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 570 ]), &(acadoWorkspace.E[ 654 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 576 ]), &(acadoWorkspace.E[ 660 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 582 ]), &(acadoWorkspace.E[ 666 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 588 ]), &(acadoWorkspace.E[ 672 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 594 ]), &(acadoWorkspace.E[ 678 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 600 ]), &(acadoWorkspace.E[ 684 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 606 ]), &(acadoWorkspace.E[ 690 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 612 ]), &(acadoWorkspace.E[ 696 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 618 ]), &(acadoWorkspace.E[ 702 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 624 ]), &(acadoWorkspace.E[ 708 ]) ); + +acado_moveGuE( &(acadoWorkspace.evGu[ 84 ]), &(acadoWorkspace.E[ 714 ]) ); + +acado_moveGxT( &(acadoWorkspace.evGx[ 540 ]), acadoWorkspace.T ); +acado_multGxd( &(acadoWorkspace.d[ 84 ]), &(acadoWorkspace.evGx[ 540 ]), &(acadoWorkspace.d[ 90 ]) ); +acado_multGxGx( acadoWorkspace.T, &(acadoWorkspace.evGx[ 504 ]), &(acadoWorkspace.evGx[ 540 ]) ); + +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 630 ]), &(acadoWorkspace.E[ 720 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 636 ]), &(acadoWorkspace.E[ 726 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 642 ]), &(acadoWorkspace.E[ 732 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 648 ]), &(acadoWorkspace.E[ 738 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 654 ]), &(acadoWorkspace.E[ 744 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 660 ]), &(acadoWorkspace.E[ 750 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 666 ]), &(acadoWorkspace.E[ 756 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 672 ]), &(acadoWorkspace.E[ 762 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 678 ]), &(acadoWorkspace.E[ 768 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 684 ]), &(acadoWorkspace.E[ 774 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 690 ]), &(acadoWorkspace.E[ 780 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 696 ]), &(acadoWorkspace.E[ 786 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 702 ]), &(acadoWorkspace.E[ 792 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 708 ]), &(acadoWorkspace.E[ 798 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 714 ]), &(acadoWorkspace.E[ 804 ]) ); + +acado_moveGuE( &(acadoWorkspace.evGu[ 90 ]), &(acadoWorkspace.E[ 810 ]) ); + +acado_moveGxT( &(acadoWorkspace.evGx[ 576 ]), acadoWorkspace.T ); +acado_multGxd( &(acadoWorkspace.d[ 90 ]), &(acadoWorkspace.evGx[ 576 ]), &(acadoWorkspace.d[ 96 ]) ); +acado_multGxGx( acadoWorkspace.T, &(acadoWorkspace.evGx[ 540 ]), &(acadoWorkspace.evGx[ 576 ]) ); + +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 720 ]), &(acadoWorkspace.E[ 816 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 726 ]), &(acadoWorkspace.E[ 822 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 732 ]), &(acadoWorkspace.E[ 828 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 738 ]), &(acadoWorkspace.E[ 834 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 744 ]), &(acadoWorkspace.E[ 840 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 750 ]), &(acadoWorkspace.E[ 846 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 756 ]), &(acadoWorkspace.E[ 852 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 762 ]), &(acadoWorkspace.E[ 858 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 768 ]), &(acadoWorkspace.E[ 864 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 774 ]), &(acadoWorkspace.E[ 870 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 780 ]), &(acadoWorkspace.E[ 876 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 786 ]), &(acadoWorkspace.E[ 882 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 792 ]), &(acadoWorkspace.E[ 888 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 798 ]), &(acadoWorkspace.E[ 894 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 804 ]), &(acadoWorkspace.E[ 900 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 810 ]), &(acadoWorkspace.E[ 906 ]) ); + +acado_moveGuE( &(acadoWorkspace.evGu[ 96 ]), &(acadoWorkspace.E[ 912 ]) ); + +acado_moveGxT( &(acadoWorkspace.evGx[ 612 ]), acadoWorkspace.T ); +acado_multGxd( &(acadoWorkspace.d[ 96 ]), &(acadoWorkspace.evGx[ 612 ]), &(acadoWorkspace.d[ 102 ]) ); +acado_multGxGx( acadoWorkspace.T, &(acadoWorkspace.evGx[ 576 ]), &(acadoWorkspace.evGx[ 612 ]) ); + +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 816 ]), &(acadoWorkspace.E[ 918 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 822 ]), &(acadoWorkspace.E[ 924 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 828 ]), &(acadoWorkspace.E[ 930 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 834 ]), &(acadoWorkspace.E[ 936 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 840 ]), &(acadoWorkspace.E[ 942 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 846 ]), &(acadoWorkspace.E[ 948 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 852 ]), &(acadoWorkspace.E[ 954 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 858 ]), &(acadoWorkspace.E[ 960 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 864 ]), &(acadoWorkspace.E[ 966 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 870 ]), &(acadoWorkspace.E[ 972 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 876 ]), &(acadoWorkspace.E[ 978 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 882 ]), &(acadoWorkspace.E[ 984 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 888 ]), &(acadoWorkspace.E[ 990 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 894 ]), &(acadoWorkspace.E[ 996 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 900 ]), &(acadoWorkspace.E[ 1002 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 906 ]), &(acadoWorkspace.E[ 1008 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 912 ]), &(acadoWorkspace.E[ 1014 ]) ); + +acado_moveGuE( &(acadoWorkspace.evGu[ 102 ]), &(acadoWorkspace.E[ 1020 ]) ); + +acado_moveGxT( &(acadoWorkspace.evGx[ 648 ]), acadoWorkspace.T ); +acado_multGxd( &(acadoWorkspace.d[ 102 ]), &(acadoWorkspace.evGx[ 648 ]), &(acadoWorkspace.d[ 108 ]) ); +acado_multGxGx( acadoWorkspace.T, &(acadoWorkspace.evGx[ 612 ]), &(acadoWorkspace.evGx[ 648 ]) ); + +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 918 ]), &(acadoWorkspace.E[ 1026 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 924 ]), &(acadoWorkspace.E[ 1032 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 930 ]), &(acadoWorkspace.E[ 1038 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 936 ]), &(acadoWorkspace.E[ 1044 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 942 ]), &(acadoWorkspace.E[ 1050 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 948 ]), &(acadoWorkspace.E[ 1056 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 954 ]), &(acadoWorkspace.E[ 1062 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 960 ]), &(acadoWorkspace.E[ 1068 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 966 ]), &(acadoWorkspace.E[ 1074 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 972 ]), &(acadoWorkspace.E[ 1080 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 978 ]), &(acadoWorkspace.E[ 1086 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 984 ]), &(acadoWorkspace.E[ 1092 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 990 ]), &(acadoWorkspace.E[ 1098 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 996 ]), &(acadoWorkspace.E[ 1104 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 1002 ]), &(acadoWorkspace.E[ 1110 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 1008 ]), &(acadoWorkspace.E[ 1116 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 1014 ]), &(acadoWorkspace.E[ 1122 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 1020 ]), &(acadoWorkspace.E[ 1128 ]) ); + +acado_moveGuE( &(acadoWorkspace.evGu[ 108 ]), &(acadoWorkspace.E[ 1134 ]) ); + +acado_moveGxT( &(acadoWorkspace.evGx[ 684 ]), acadoWorkspace.T ); +acado_multGxd( &(acadoWorkspace.d[ 108 ]), &(acadoWorkspace.evGx[ 684 ]), &(acadoWorkspace.d[ 114 ]) ); +acado_multGxGx( acadoWorkspace.T, &(acadoWorkspace.evGx[ 648 ]), &(acadoWorkspace.evGx[ 684 ]) ); + +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 1026 ]), &(acadoWorkspace.E[ 1140 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 1032 ]), &(acadoWorkspace.E[ 1146 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 1038 ]), &(acadoWorkspace.E[ 1152 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 1044 ]), &(acadoWorkspace.E[ 1158 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 1050 ]), &(acadoWorkspace.E[ 1164 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 1056 ]), &(acadoWorkspace.E[ 1170 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 1062 ]), &(acadoWorkspace.E[ 1176 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 1068 ]), &(acadoWorkspace.E[ 1182 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 1074 ]), &(acadoWorkspace.E[ 1188 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 1080 ]), &(acadoWorkspace.E[ 1194 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 1086 ]), &(acadoWorkspace.E[ 1200 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 1092 ]), &(acadoWorkspace.E[ 1206 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 1098 ]), &(acadoWorkspace.E[ 1212 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 1104 ]), &(acadoWorkspace.E[ 1218 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 1110 ]), &(acadoWorkspace.E[ 1224 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 1116 ]), &(acadoWorkspace.E[ 1230 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 1122 ]), &(acadoWorkspace.E[ 1236 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 1128 ]), &(acadoWorkspace.E[ 1242 ]) ); +acado_multGxGu( acadoWorkspace.T, &(acadoWorkspace.E[ 1134 ]), &(acadoWorkspace.E[ 1248 ]) ); + +acado_moveGuE( &(acadoWorkspace.evGu[ 114 ]), &(acadoWorkspace.E[ 1254 ]) ); + +acado_multGxGx( &(acadoWorkspace.Q1[ 36 ]), acadoWorkspace.evGx, acadoWorkspace.QGx ); +acado_multGxGx( &(acadoWorkspace.Q1[ 72 ]), &(acadoWorkspace.evGx[ 36 ]), &(acadoWorkspace.QGx[ 36 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 108 ]), &(acadoWorkspace.evGx[ 72 ]), &(acadoWorkspace.QGx[ 72 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 144 ]), &(acadoWorkspace.evGx[ 108 ]), &(acadoWorkspace.QGx[ 108 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 180 ]), &(acadoWorkspace.evGx[ 144 ]), &(acadoWorkspace.QGx[ 144 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 216 ]), &(acadoWorkspace.evGx[ 180 ]), &(acadoWorkspace.QGx[ 180 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 252 ]), &(acadoWorkspace.evGx[ 216 ]), &(acadoWorkspace.QGx[ 216 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 288 ]), &(acadoWorkspace.evGx[ 252 ]), &(acadoWorkspace.QGx[ 252 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 324 ]), &(acadoWorkspace.evGx[ 288 ]), &(acadoWorkspace.QGx[ 288 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 360 ]), &(acadoWorkspace.evGx[ 324 ]), &(acadoWorkspace.QGx[ 324 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 396 ]), &(acadoWorkspace.evGx[ 360 ]), &(acadoWorkspace.QGx[ 360 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 432 ]), &(acadoWorkspace.evGx[ 396 ]), &(acadoWorkspace.QGx[ 396 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 468 ]), &(acadoWorkspace.evGx[ 432 ]), &(acadoWorkspace.QGx[ 432 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 504 ]), &(acadoWorkspace.evGx[ 468 ]), &(acadoWorkspace.QGx[ 468 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 540 ]), &(acadoWorkspace.evGx[ 504 ]), &(acadoWorkspace.QGx[ 504 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 576 ]), &(acadoWorkspace.evGx[ 540 ]), &(acadoWorkspace.QGx[ 540 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 612 ]), &(acadoWorkspace.evGx[ 576 ]), &(acadoWorkspace.QGx[ 576 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 648 ]), &(acadoWorkspace.evGx[ 612 ]), &(acadoWorkspace.QGx[ 612 ]) ); +acado_multGxGx( &(acadoWorkspace.Q1[ 684 ]), &(acadoWorkspace.evGx[ 648 ]), &(acadoWorkspace.QGx[ 648 ]) ); +acado_multGxGx( acadoWorkspace.QN1, &(acadoWorkspace.evGx[ 684 ]), &(acadoWorkspace.QGx[ 684 ]) ); + +acado_multGxGu( &(acadoWorkspace.Q1[ 36 ]), acadoWorkspace.E, acadoWorkspace.QE ); +acado_multGxGu( &(acadoWorkspace.Q1[ 72 ]), &(acadoWorkspace.E[ 6 ]), &(acadoWorkspace.QE[ 6 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 72 ]), &(acadoWorkspace.E[ 12 ]), &(acadoWorkspace.QE[ 12 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 108 ]), &(acadoWorkspace.E[ 18 ]), &(acadoWorkspace.QE[ 18 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 108 ]), &(acadoWorkspace.E[ 24 ]), &(acadoWorkspace.QE[ 24 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 108 ]), &(acadoWorkspace.E[ 30 ]), &(acadoWorkspace.QE[ 30 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 144 ]), &(acadoWorkspace.E[ 36 ]), &(acadoWorkspace.QE[ 36 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 144 ]), &(acadoWorkspace.E[ 42 ]), &(acadoWorkspace.QE[ 42 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 144 ]), &(acadoWorkspace.E[ 48 ]), &(acadoWorkspace.QE[ 48 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 144 ]), &(acadoWorkspace.E[ 54 ]), &(acadoWorkspace.QE[ 54 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 180 ]), &(acadoWorkspace.E[ 60 ]), &(acadoWorkspace.QE[ 60 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 180 ]), &(acadoWorkspace.E[ 66 ]), &(acadoWorkspace.QE[ 66 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 180 ]), &(acadoWorkspace.E[ 72 ]), &(acadoWorkspace.QE[ 72 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 180 ]), &(acadoWorkspace.E[ 78 ]), &(acadoWorkspace.QE[ 78 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 180 ]), &(acadoWorkspace.E[ 84 ]), &(acadoWorkspace.QE[ 84 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 216 ]), &(acadoWorkspace.E[ 90 ]), &(acadoWorkspace.QE[ 90 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 216 ]), &(acadoWorkspace.E[ 96 ]), &(acadoWorkspace.QE[ 96 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 216 ]), &(acadoWorkspace.E[ 102 ]), &(acadoWorkspace.QE[ 102 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 216 ]), &(acadoWorkspace.E[ 108 ]), &(acadoWorkspace.QE[ 108 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 216 ]), &(acadoWorkspace.E[ 114 ]), &(acadoWorkspace.QE[ 114 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 216 ]), &(acadoWorkspace.E[ 120 ]), &(acadoWorkspace.QE[ 120 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 252 ]), &(acadoWorkspace.E[ 126 ]), &(acadoWorkspace.QE[ 126 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 252 ]), &(acadoWorkspace.E[ 132 ]), &(acadoWorkspace.QE[ 132 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 252 ]), &(acadoWorkspace.E[ 138 ]), &(acadoWorkspace.QE[ 138 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 252 ]), &(acadoWorkspace.E[ 144 ]), &(acadoWorkspace.QE[ 144 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 252 ]), &(acadoWorkspace.E[ 150 ]), &(acadoWorkspace.QE[ 150 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 252 ]), &(acadoWorkspace.E[ 156 ]), &(acadoWorkspace.QE[ 156 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 252 ]), &(acadoWorkspace.E[ 162 ]), &(acadoWorkspace.QE[ 162 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 288 ]), &(acadoWorkspace.E[ 168 ]), &(acadoWorkspace.QE[ 168 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 288 ]), &(acadoWorkspace.E[ 174 ]), &(acadoWorkspace.QE[ 174 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 288 ]), &(acadoWorkspace.E[ 180 ]), &(acadoWorkspace.QE[ 180 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 288 ]), &(acadoWorkspace.E[ 186 ]), &(acadoWorkspace.QE[ 186 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 288 ]), &(acadoWorkspace.E[ 192 ]), &(acadoWorkspace.QE[ 192 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 288 ]), &(acadoWorkspace.E[ 198 ]), &(acadoWorkspace.QE[ 198 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 288 ]), &(acadoWorkspace.E[ 204 ]), &(acadoWorkspace.QE[ 204 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 288 ]), &(acadoWorkspace.E[ 210 ]), &(acadoWorkspace.QE[ 210 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 324 ]), &(acadoWorkspace.E[ 216 ]), &(acadoWorkspace.QE[ 216 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 324 ]), &(acadoWorkspace.E[ 222 ]), &(acadoWorkspace.QE[ 222 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 324 ]), &(acadoWorkspace.E[ 228 ]), &(acadoWorkspace.QE[ 228 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 324 ]), &(acadoWorkspace.E[ 234 ]), &(acadoWorkspace.QE[ 234 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 324 ]), &(acadoWorkspace.E[ 240 ]), &(acadoWorkspace.QE[ 240 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 324 ]), &(acadoWorkspace.E[ 246 ]), &(acadoWorkspace.QE[ 246 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 324 ]), &(acadoWorkspace.E[ 252 ]), &(acadoWorkspace.QE[ 252 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 324 ]), &(acadoWorkspace.E[ 258 ]), &(acadoWorkspace.QE[ 258 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 324 ]), &(acadoWorkspace.E[ 264 ]), &(acadoWorkspace.QE[ 264 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 360 ]), &(acadoWorkspace.E[ 270 ]), &(acadoWorkspace.QE[ 270 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 360 ]), &(acadoWorkspace.E[ 276 ]), &(acadoWorkspace.QE[ 276 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 360 ]), &(acadoWorkspace.E[ 282 ]), &(acadoWorkspace.QE[ 282 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 360 ]), &(acadoWorkspace.E[ 288 ]), &(acadoWorkspace.QE[ 288 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 360 ]), &(acadoWorkspace.E[ 294 ]), &(acadoWorkspace.QE[ 294 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 360 ]), &(acadoWorkspace.E[ 300 ]), &(acadoWorkspace.QE[ 300 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 360 ]), &(acadoWorkspace.E[ 306 ]), &(acadoWorkspace.QE[ 306 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 360 ]), &(acadoWorkspace.E[ 312 ]), &(acadoWorkspace.QE[ 312 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 360 ]), &(acadoWorkspace.E[ 318 ]), &(acadoWorkspace.QE[ 318 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 360 ]), &(acadoWorkspace.E[ 324 ]), &(acadoWorkspace.QE[ 324 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 396 ]), &(acadoWorkspace.E[ 330 ]), &(acadoWorkspace.QE[ 330 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 396 ]), &(acadoWorkspace.E[ 336 ]), &(acadoWorkspace.QE[ 336 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 396 ]), &(acadoWorkspace.E[ 342 ]), &(acadoWorkspace.QE[ 342 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 396 ]), &(acadoWorkspace.E[ 348 ]), &(acadoWorkspace.QE[ 348 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 396 ]), &(acadoWorkspace.E[ 354 ]), &(acadoWorkspace.QE[ 354 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 396 ]), &(acadoWorkspace.E[ 360 ]), &(acadoWorkspace.QE[ 360 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 396 ]), &(acadoWorkspace.E[ 366 ]), &(acadoWorkspace.QE[ 366 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 396 ]), &(acadoWorkspace.E[ 372 ]), &(acadoWorkspace.QE[ 372 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 396 ]), &(acadoWorkspace.E[ 378 ]), &(acadoWorkspace.QE[ 378 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 396 ]), &(acadoWorkspace.E[ 384 ]), &(acadoWorkspace.QE[ 384 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 396 ]), &(acadoWorkspace.E[ 390 ]), &(acadoWorkspace.QE[ 390 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 432 ]), &(acadoWorkspace.E[ 396 ]), &(acadoWorkspace.QE[ 396 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 432 ]), &(acadoWorkspace.E[ 402 ]), &(acadoWorkspace.QE[ 402 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 432 ]), &(acadoWorkspace.E[ 408 ]), &(acadoWorkspace.QE[ 408 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 432 ]), &(acadoWorkspace.E[ 414 ]), &(acadoWorkspace.QE[ 414 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 432 ]), &(acadoWorkspace.E[ 420 ]), &(acadoWorkspace.QE[ 420 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 432 ]), &(acadoWorkspace.E[ 426 ]), &(acadoWorkspace.QE[ 426 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 432 ]), &(acadoWorkspace.E[ 432 ]), &(acadoWorkspace.QE[ 432 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 432 ]), &(acadoWorkspace.E[ 438 ]), &(acadoWorkspace.QE[ 438 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 432 ]), &(acadoWorkspace.E[ 444 ]), &(acadoWorkspace.QE[ 444 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 432 ]), &(acadoWorkspace.E[ 450 ]), &(acadoWorkspace.QE[ 450 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 432 ]), &(acadoWorkspace.E[ 456 ]), &(acadoWorkspace.QE[ 456 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 432 ]), &(acadoWorkspace.E[ 462 ]), &(acadoWorkspace.QE[ 462 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 468 ]), &(acadoWorkspace.E[ 468 ]), &(acadoWorkspace.QE[ 468 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 468 ]), &(acadoWorkspace.E[ 474 ]), &(acadoWorkspace.QE[ 474 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 468 ]), &(acadoWorkspace.E[ 480 ]), &(acadoWorkspace.QE[ 480 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 468 ]), &(acadoWorkspace.E[ 486 ]), &(acadoWorkspace.QE[ 486 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 468 ]), &(acadoWorkspace.E[ 492 ]), &(acadoWorkspace.QE[ 492 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 468 ]), &(acadoWorkspace.E[ 498 ]), &(acadoWorkspace.QE[ 498 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 468 ]), &(acadoWorkspace.E[ 504 ]), &(acadoWorkspace.QE[ 504 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 468 ]), &(acadoWorkspace.E[ 510 ]), &(acadoWorkspace.QE[ 510 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 468 ]), &(acadoWorkspace.E[ 516 ]), &(acadoWorkspace.QE[ 516 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 468 ]), &(acadoWorkspace.E[ 522 ]), &(acadoWorkspace.QE[ 522 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 468 ]), &(acadoWorkspace.E[ 528 ]), &(acadoWorkspace.QE[ 528 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 468 ]), &(acadoWorkspace.E[ 534 ]), &(acadoWorkspace.QE[ 534 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 468 ]), &(acadoWorkspace.E[ 540 ]), &(acadoWorkspace.QE[ 540 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 504 ]), &(acadoWorkspace.E[ 546 ]), &(acadoWorkspace.QE[ 546 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 504 ]), &(acadoWorkspace.E[ 552 ]), &(acadoWorkspace.QE[ 552 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 504 ]), &(acadoWorkspace.E[ 558 ]), &(acadoWorkspace.QE[ 558 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 504 ]), &(acadoWorkspace.E[ 564 ]), &(acadoWorkspace.QE[ 564 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 504 ]), &(acadoWorkspace.E[ 570 ]), &(acadoWorkspace.QE[ 570 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 504 ]), &(acadoWorkspace.E[ 576 ]), &(acadoWorkspace.QE[ 576 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 504 ]), &(acadoWorkspace.E[ 582 ]), &(acadoWorkspace.QE[ 582 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 504 ]), &(acadoWorkspace.E[ 588 ]), &(acadoWorkspace.QE[ 588 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 504 ]), &(acadoWorkspace.E[ 594 ]), &(acadoWorkspace.QE[ 594 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 504 ]), &(acadoWorkspace.E[ 600 ]), &(acadoWorkspace.QE[ 600 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 504 ]), &(acadoWorkspace.E[ 606 ]), &(acadoWorkspace.QE[ 606 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 504 ]), &(acadoWorkspace.E[ 612 ]), &(acadoWorkspace.QE[ 612 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 504 ]), &(acadoWorkspace.E[ 618 ]), &(acadoWorkspace.QE[ 618 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 504 ]), &(acadoWorkspace.E[ 624 ]), &(acadoWorkspace.QE[ 624 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 540 ]), &(acadoWorkspace.E[ 630 ]), &(acadoWorkspace.QE[ 630 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 540 ]), &(acadoWorkspace.E[ 636 ]), &(acadoWorkspace.QE[ 636 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 540 ]), &(acadoWorkspace.E[ 642 ]), &(acadoWorkspace.QE[ 642 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 540 ]), &(acadoWorkspace.E[ 648 ]), &(acadoWorkspace.QE[ 648 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 540 ]), &(acadoWorkspace.E[ 654 ]), &(acadoWorkspace.QE[ 654 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 540 ]), &(acadoWorkspace.E[ 660 ]), &(acadoWorkspace.QE[ 660 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 540 ]), &(acadoWorkspace.E[ 666 ]), &(acadoWorkspace.QE[ 666 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 540 ]), &(acadoWorkspace.E[ 672 ]), &(acadoWorkspace.QE[ 672 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 540 ]), &(acadoWorkspace.E[ 678 ]), &(acadoWorkspace.QE[ 678 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 540 ]), &(acadoWorkspace.E[ 684 ]), &(acadoWorkspace.QE[ 684 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 540 ]), &(acadoWorkspace.E[ 690 ]), &(acadoWorkspace.QE[ 690 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 540 ]), &(acadoWorkspace.E[ 696 ]), &(acadoWorkspace.QE[ 696 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 540 ]), &(acadoWorkspace.E[ 702 ]), &(acadoWorkspace.QE[ 702 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 540 ]), &(acadoWorkspace.E[ 708 ]), &(acadoWorkspace.QE[ 708 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 540 ]), &(acadoWorkspace.E[ 714 ]), &(acadoWorkspace.QE[ 714 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 576 ]), &(acadoWorkspace.E[ 720 ]), &(acadoWorkspace.QE[ 720 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 576 ]), &(acadoWorkspace.E[ 726 ]), &(acadoWorkspace.QE[ 726 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 576 ]), &(acadoWorkspace.E[ 732 ]), &(acadoWorkspace.QE[ 732 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 576 ]), &(acadoWorkspace.E[ 738 ]), &(acadoWorkspace.QE[ 738 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 576 ]), &(acadoWorkspace.E[ 744 ]), &(acadoWorkspace.QE[ 744 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 576 ]), &(acadoWorkspace.E[ 750 ]), &(acadoWorkspace.QE[ 750 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 576 ]), &(acadoWorkspace.E[ 756 ]), &(acadoWorkspace.QE[ 756 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 576 ]), &(acadoWorkspace.E[ 762 ]), &(acadoWorkspace.QE[ 762 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 576 ]), &(acadoWorkspace.E[ 768 ]), &(acadoWorkspace.QE[ 768 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 576 ]), &(acadoWorkspace.E[ 774 ]), &(acadoWorkspace.QE[ 774 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 576 ]), &(acadoWorkspace.E[ 780 ]), &(acadoWorkspace.QE[ 780 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 576 ]), &(acadoWorkspace.E[ 786 ]), &(acadoWorkspace.QE[ 786 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 576 ]), &(acadoWorkspace.E[ 792 ]), &(acadoWorkspace.QE[ 792 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 576 ]), &(acadoWorkspace.E[ 798 ]), &(acadoWorkspace.QE[ 798 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 576 ]), &(acadoWorkspace.E[ 804 ]), &(acadoWorkspace.QE[ 804 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 576 ]), &(acadoWorkspace.E[ 810 ]), &(acadoWorkspace.QE[ 810 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 612 ]), &(acadoWorkspace.E[ 816 ]), &(acadoWorkspace.QE[ 816 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 612 ]), &(acadoWorkspace.E[ 822 ]), &(acadoWorkspace.QE[ 822 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 612 ]), &(acadoWorkspace.E[ 828 ]), &(acadoWorkspace.QE[ 828 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 612 ]), &(acadoWorkspace.E[ 834 ]), &(acadoWorkspace.QE[ 834 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 612 ]), &(acadoWorkspace.E[ 840 ]), &(acadoWorkspace.QE[ 840 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 612 ]), &(acadoWorkspace.E[ 846 ]), &(acadoWorkspace.QE[ 846 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 612 ]), &(acadoWorkspace.E[ 852 ]), &(acadoWorkspace.QE[ 852 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 612 ]), &(acadoWorkspace.E[ 858 ]), &(acadoWorkspace.QE[ 858 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 612 ]), &(acadoWorkspace.E[ 864 ]), &(acadoWorkspace.QE[ 864 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 612 ]), &(acadoWorkspace.E[ 870 ]), &(acadoWorkspace.QE[ 870 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 612 ]), &(acadoWorkspace.E[ 876 ]), &(acadoWorkspace.QE[ 876 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 612 ]), &(acadoWorkspace.E[ 882 ]), &(acadoWorkspace.QE[ 882 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 612 ]), &(acadoWorkspace.E[ 888 ]), &(acadoWorkspace.QE[ 888 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 612 ]), &(acadoWorkspace.E[ 894 ]), &(acadoWorkspace.QE[ 894 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 612 ]), &(acadoWorkspace.E[ 900 ]), &(acadoWorkspace.QE[ 900 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 612 ]), &(acadoWorkspace.E[ 906 ]), &(acadoWorkspace.QE[ 906 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 612 ]), &(acadoWorkspace.E[ 912 ]), &(acadoWorkspace.QE[ 912 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 648 ]), &(acadoWorkspace.E[ 918 ]), &(acadoWorkspace.QE[ 918 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 648 ]), &(acadoWorkspace.E[ 924 ]), &(acadoWorkspace.QE[ 924 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 648 ]), &(acadoWorkspace.E[ 930 ]), &(acadoWorkspace.QE[ 930 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 648 ]), &(acadoWorkspace.E[ 936 ]), &(acadoWorkspace.QE[ 936 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 648 ]), &(acadoWorkspace.E[ 942 ]), &(acadoWorkspace.QE[ 942 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 648 ]), &(acadoWorkspace.E[ 948 ]), &(acadoWorkspace.QE[ 948 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 648 ]), &(acadoWorkspace.E[ 954 ]), &(acadoWorkspace.QE[ 954 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 648 ]), &(acadoWorkspace.E[ 960 ]), &(acadoWorkspace.QE[ 960 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 648 ]), &(acadoWorkspace.E[ 966 ]), &(acadoWorkspace.QE[ 966 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 648 ]), &(acadoWorkspace.E[ 972 ]), &(acadoWorkspace.QE[ 972 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 648 ]), &(acadoWorkspace.E[ 978 ]), &(acadoWorkspace.QE[ 978 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 648 ]), &(acadoWorkspace.E[ 984 ]), &(acadoWorkspace.QE[ 984 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 648 ]), &(acadoWorkspace.E[ 990 ]), &(acadoWorkspace.QE[ 990 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 648 ]), &(acadoWorkspace.E[ 996 ]), &(acadoWorkspace.QE[ 996 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 648 ]), &(acadoWorkspace.E[ 1002 ]), &(acadoWorkspace.QE[ 1002 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 648 ]), &(acadoWorkspace.E[ 1008 ]), &(acadoWorkspace.QE[ 1008 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 648 ]), &(acadoWorkspace.E[ 1014 ]), &(acadoWorkspace.QE[ 1014 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 648 ]), &(acadoWorkspace.E[ 1020 ]), &(acadoWorkspace.QE[ 1020 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 684 ]), &(acadoWorkspace.E[ 1026 ]), &(acadoWorkspace.QE[ 1026 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 684 ]), &(acadoWorkspace.E[ 1032 ]), &(acadoWorkspace.QE[ 1032 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 684 ]), &(acadoWorkspace.E[ 1038 ]), &(acadoWorkspace.QE[ 1038 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 684 ]), &(acadoWorkspace.E[ 1044 ]), &(acadoWorkspace.QE[ 1044 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 684 ]), &(acadoWorkspace.E[ 1050 ]), &(acadoWorkspace.QE[ 1050 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 684 ]), &(acadoWorkspace.E[ 1056 ]), &(acadoWorkspace.QE[ 1056 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 684 ]), &(acadoWorkspace.E[ 1062 ]), &(acadoWorkspace.QE[ 1062 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 684 ]), &(acadoWorkspace.E[ 1068 ]), &(acadoWorkspace.QE[ 1068 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 684 ]), &(acadoWorkspace.E[ 1074 ]), &(acadoWorkspace.QE[ 1074 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 684 ]), &(acadoWorkspace.E[ 1080 ]), &(acadoWorkspace.QE[ 1080 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 684 ]), &(acadoWorkspace.E[ 1086 ]), &(acadoWorkspace.QE[ 1086 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 684 ]), &(acadoWorkspace.E[ 1092 ]), &(acadoWorkspace.QE[ 1092 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 684 ]), &(acadoWorkspace.E[ 1098 ]), &(acadoWorkspace.QE[ 1098 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 684 ]), &(acadoWorkspace.E[ 1104 ]), &(acadoWorkspace.QE[ 1104 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 684 ]), &(acadoWorkspace.E[ 1110 ]), &(acadoWorkspace.QE[ 1110 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 684 ]), &(acadoWorkspace.E[ 1116 ]), &(acadoWorkspace.QE[ 1116 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 684 ]), &(acadoWorkspace.E[ 1122 ]), &(acadoWorkspace.QE[ 1122 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 684 ]), &(acadoWorkspace.E[ 1128 ]), &(acadoWorkspace.QE[ 1128 ]) ); +acado_multGxGu( &(acadoWorkspace.Q1[ 684 ]), &(acadoWorkspace.E[ 1134 ]), &(acadoWorkspace.QE[ 1134 ]) ); +acado_multGxGu( acadoWorkspace.QN1, &(acadoWorkspace.E[ 1140 ]), &(acadoWorkspace.QE[ 1140 ]) ); +acado_multGxGu( acadoWorkspace.QN1, &(acadoWorkspace.E[ 1146 ]), &(acadoWorkspace.QE[ 1146 ]) ); +acado_multGxGu( acadoWorkspace.QN1, &(acadoWorkspace.E[ 1152 ]), &(acadoWorkspace.QE[ 1152 ]) ); +acado_multGxGu( acadoWorkspace.QN1, &(acadoWorkspace.E[ 1158 ]), &(acadoWorkspace.QE[ 1158 ]) ); +acado_multGxGu( acadoWorkspace.QN1, &(acadoWorkspace.E[ 1164 ]), &(acadoWorkspace.QE[ 1164 ]) ); +acado_multGxGu( acadoWorkspace.QN1, &(acadoWorkspace.E[ 1170 ]), &(acadoWorkspace.QE[ 1170 ]) ); +acado_multGxGu( acadoWorkspace.QN1, &(acadoWorkspace.E[ 1176 ]), &(acadoWorkspace.QE[ 1176 ]) ); +acado_multGxGu( acadoWorkspace.QN1, &(acadoWorkspace.E[ 1182 ]), &(acadoWorkspace.QE[ 1182 ]) ); +acado_multGxGu( acadoWorkspace.QN1, &(acadoWorkspace.E[ 1188 ]), &(acadoWorkspace.QE[ 1188 ]) ); +acado_multGxGu( acadoWorkspace.QN1, &(acadoWorkspace.E[ 1194 ]), &(acadoWorkspace.QE[ 1194 ]) ); +acado_multGxGu( acadoWorkspace.QN1, &(acadoWorkspace.E[ 1200 ]), &(acadoWorkspace.QE[ 1200 ]) ); +acado_multGxGu( acadoWorkspace.QN1, &(acadoWorkspace.E[ 1206 ]), &(acadoWorkspace.QE[ 1206 ]) ); +acado_multGxGu( acadoWorkspace.QN1, &(acadoWorkspace.E[ 1212 ]), &(acadoWorkspace.QE[ 1212 ]) ); +acado_multGxGu( acadoWorkspace.QN1, &(acadoWorkspace.E[ 1218 ]), &(acadoWorkspace.QE[ 1218 ]) ); +acado_multGxGu( acadoWorkspace.QN1, &(acadoWorkspace.E[ 1224 ]), &(acadoWorkspace.QE[ 1224 ]) ); +acado_multGxGu( acadoWorkspace.QN1, &(acadoWorkspace.E[ 1230 ]), &(acadoWorkspace.QE[ 1230 ]) ); +acado_multGxGu( acadoWorkspace.QN1, &(acadoWorkspace.E[ 1236 ]), &(acadoWorkspace.QE[ 1236 ]) ); +acado_multGxGu( acadoWorkspace.QN1, &(acadoWorkspace.E[ 1242 ]), &(acadoWorkspace.QE[ 1242 ]) ); +acado_multGxGu( acadoWorkspace.QN1, &(acadoWorkspace.E[ 1248 ]), &(acadoWorkspace.QE[ 1248 ]) ); +acado_multGxGu( acadoWorkspace.QN1, &(acadoWorkspace.E[ 1254 ]), &(acadoWorkspace.QE[ 1254 ]) ); + +acado_zeroBlockH00( ); +acado_multCTQC( acadoWorkspace.evGx, acadoWorkspace.QGx ); +acado_multCTQC( &(acadoWorkspace.evGx[ 36 ]), &(acadoWorkspace.QGx[ 36 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 72 ]), &(acadoWorkspace.QGx[ 72 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 108 ]), &(acadoWorkspace.QGx[ 108 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 144 ]), &(acadoWorkspace.QGx[ 144 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 180 ]), &(acadoWorkspace.QGx[ 180 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 216 ]), &(acadoWorkspace.QGx[ 216 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 252 ]), &(acadoWorkspace.QGx[ 252 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 288 ]), &(acadoWorkspace.QGx[ 288 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 324 ]), &(acadoWorkspace.QGx[ 324 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 360 ]), &(acadoWorkspace.QGx[ 360 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 396 ]), &(acadoWorkspace.QGx[ 396 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 432 ]), &(acadoWorkspace.QGx[ 432 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 468 ]), &(acadoWorkspace.QGx[ 468 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 504 ]), &(acadoWorkspace.QGx[ 504 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 540 ]), &(acadoWorkspace.QGx[ 540 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 576 ]), &(acadoWorkspace.QGx[ 576 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 612 ]), &(acadoWorkspace.QGx[ 612 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 648 ]), &(acadoWorkspace.QGx[ 648 ]) ); +acado_multCTQC( &(acadoWorkspace.evGx[ 684 ]), &(acadoWorkspace.QGx[ 684 ]) ); + +acado_zeroBlockH10( acadoWorkspace.H10 ); +acado_multQETGx( acadoWorkspace.QE, acadoWorkspace.evGx, acadoWorkspace.H10 ); +acado_multQETGx( &(acadoWorkspace.QE[ 6 ]), &(acadoWorkspace.evGx[ 36 ]), acadoWorkspace.H10 ); +acado_multQETGx( &(acadoWorkspace.QE[ 18 ]), &(acadoWorkspace.evGx[ 72 ]), acadoWorkspace.H10 ); +acado_multQETGx( &(acadoWorkspace.QE[ 36 ]), &(acadoWorkspace.evGx[ 108 ]), acadoWorkspace.H10 ); +acado_multQETGx( &(acadoWorkspace.QE[ 60 ]), &(acadoWorkspace.evGx[ 144 ]), acadoWorkspace.H10 ); +acado_multQETGx( &(acadoWorkspace.QE[ 90 ]), &(acadoWorkspace.evGx[ 180 ]), acadoWorkspace.H10 ); +acado_multQETGx( &(acadoWorkspace.QE[ 126 ]), &(acadoWorkspace.evGx[ 216 ]), acadoWorkspace.H10 ); +acado_multQETGx( &(acadoWorkspace.QE[ 168 ]), &(acadoWorkspace.evGx[ 252 ]), acadoWorkspace.H10 ); +acado_multQETGx( &(acadoWorkspace.QE[ 216 ]), &(acadoWorkspace.evGx[ 288 ]), acadoWorkspace.H10 ); +acado_multQETGx( &(acadoWorkspace.QE[ 270 ]), &(acadoWorkspace.evGx[ 324 ]), acadoWorkspace.H10 ); +acado_multQETGx( &(acadoWorkspace.QE[ 330 ]), &(acadoWorkspace.evGx[ 360 ]), acadoWorkspace.H10 ); +acado_multQETGx( &(acadoWorkspace.QE[ 396 ]), &(acadoWorkspace.evGx[ 396 ]), acadoWorkspace.H10 ); +acado_multQETGx( &(acadoWorkspace.QE[ 468 ]), &(acadoWorkspace.evGx[ 432 ]), acadoWorkspace.H10 ); +acado_multQETGx( &(acadoWorkspace.QE[ 546 ]), &(acadoWorkspace.evGx[ 468 ]), acadoWorkspace.H10 ); +acado_multQETGx( &(acadoWorkspace.QE[ 630 ]), &(acadoWorkspace.evGx[ 504 ]), acadoWorkspace.H10 ); +acado_multQETGx( &(acadoWorkspace.QE[ 720 ]), &(acadoWorkspace.evGx[ 540 ]), acadoWorkspace.H10 ); +acado_multQETGx( &(acadoWorkspace.QE[ 816 ]), &(acadoWorkspace.evGx[ 576 ]), acadoWorkspace.H10 ); +acado_multQETGx( &(acadoWorkspace.QE[ 918 ]), &(acadoWorkspace.evGx[ 612 ]), acadoWorkspace.H10 ); +acado_multQETGx( &(acadoWorkspace.QE[ 1026 ]), &(acadoWorkspace.evGx[ 648 ]), acadoWorkspace.H10 ); +acado_multQETGx( &(acadoWorkspace.QE[ 1140 ]), &(acadoWorkspace.evGx[ 684 ]), acadoWorkspace.H10 ); +acado_zeroBlockH10( &(acadoWorkspace.H10[ 6 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 12 ]), &(acadoWorkspace.evGx[ 36 ]), &(acadoWorkspace.H10[ 6 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 24 ]), &(acadoWorkspace.evGx[ 72 ]), &(acadoWorkspace.H10[ 6 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 42 ]), &(acadoWorkspace.evGx[ 108 ]), &(acadoWorkspace.H10[ 6 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 66 ]), &(acadoWorkspace.evGx[ 144 ]), &(acadoWorkspace.H10[ 6 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 96 ]), &(acadoWorkspace.evGx[ 180 ]), &(acadoWorkspace.H10[ 6 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 132 ]), &(acadoWorkspace.evGx[ 216 ]), &(acadoWorkspace.H10[ 6 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 174 ]), &(acadoWorkspace.evGx[ 252 ]), &(acadoWorkspace.H10[ 6 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 222 ]), &(acadoWorkspace.evGx[ 288 ]), &(acadoWorkspace.H10[ 6 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 276 ]), &(acadoWorkspace.evGx[ 324 ]), &(acadoWorkspace.H10[ 6 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 336 ]), &(acadoWorkspace.evGx[ 360 ]), &(acadoWorkspace.H10[ 6 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 402 ]), &(acadoWorkspace.evGx[ 396 ]), &(acadoWorkspace.H10[ 6 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 474 ]), &(acadoWorkspace.evGx[ 432 ]), &(acadoWorkspace.H10[ 6 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 552 ]), &(acadoWorkspace.evGx[ 468 ]), &(acadoWorkspace.H10[ 6 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 636 ]), &(acadoWorkspace.evGx[ 504 ]), &(acadoWorkspace.H10[ 6 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 726 ]), &(acadoWorkspace.evGx[ 540 ]), &(acadoWorkspace.H10[ 6 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 822 ]), &(acadoWorkspace.evGx[ 576 ]), &(acadoWorkspace.H10[ 6 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 924 ]), &(acadoWorkspace.evGx[ 612 ]), &(acadoWorkspace.H10[ 6 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 1032 ]), &(acadoWorkspace.evGx[ 648 ]), &(acadoWorkspace.H10[ 6 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 1146 ]), &(acadoWorkspace.evGx[ 684 ]), &(acadoWorkspace.H10[ 6 ]) ); +acado_zeroBlockH10( &(acadoWorkspace.H10[ 12 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 30 ]), &(acadoWorkspace.evGx[ 72 ]), &(acadoWorkspace.H10[ 12 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 48 ]), &(acadoWorkspace.evGx[ 108 ]), &(acadoWorkspace.H10[ 12 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 72 ]), &(acadoWorkspace.evGx[ 144 ]), &(acadoWorkspace.H10[ 12 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 102 ]), &(acadoWorkspace.evGx[ 180 ]), &(acadoWorkspace.H10[ 12 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 138 ]), &(acadoWorkspace.evGx[ 216 ]), &(acadoWorkspace.H10[ 12 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 180 ]), &(acadoWorkspace.evGx[ 252 ]), &(acadoWorkspace.H10[ 12 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 228 ]), &(acadoWorkspace.evGx[ 288 ]), &(acadoWorkspace.H10[ 12 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 282 ]), &(acadoWorkspace.evGx[ 324 ]), &(acadoWorkspace.H10[ 12 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 342 ]), &(acadoWorkspace.evGx[ 360 ]), &(acadoWorkspace.H10[ 12 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 408 ]), &(acadoWorkspace.evGx[ 396 ]), &(acadoWorkspace.H10[ 12 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 480 ]), &(acadoWorkspace.evGx[ 432 ]), &(acadoWorkspace.H10[ 12 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 558 ]), &(acadoWorkspace.evGx[ 468 ]), &(acadoWorkspace.H10[ 12 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 642 ]), &(acadoWorkspace.evGx[ 504 ]), &(acadoWorkspace.H10[ 12 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 732 ]), &(acadoWorkspace.evGx[ 540 ]), &(acadoWorkspace.H10[ 12 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 828 ]), &(acadoWorkspace.evGx[ 576 ]), &(acadoWorkspace.H10[ 12 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 930 ]), &(acadoWorkspace.evGx[ 612 ]), &(acadoWorkspace.H10[ 12 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 1038 ]), &(acadoWorkspace.evGx[ 648 ]), &(acadoWorkspace.H10[ 12 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 1152 ]), &(acadoWorkspace.evGx[ 684 ]), &(acadoWorkspace.H10[ 12 ]) ); +acado_zeroBlockH10( &(acadoWorkspace.H10[ 18 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 54 ]), &(acadoWorkspace.evGx[ 108 ]), &(acadoWorkspace.H10[ 18 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 78 ]), &(acadoWorkspace.evGx[ 144 ]), &(acadoWorkspace.H10[ 18 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 108 ]), &(acadoWorkspace.evGx[ 180 ]), &(acadoWorkspace.H10[ 18 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 144 ]), &(acadoWorkspace.evGx[ 216 ]), &(acadoWorkspace.H10[ 18 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 186 ]), &(acadoWorkspace.evGx[ 252 ]), &(acadoWorkspace.H10[ 18 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 234 ]), &(acadoWorkspace.evGx[ 288 ]), &(acadoWorkspace.H10[ 18 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 288 ]), &(acadoWorkspace.evGx[ 324 ]), &(acadoWorkspace.H10[ 18 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 348 ]), &(acadoWorkspace.evGx[ 360 ]), &(acadoWorkspace.H10[ 18 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 414 ]), &(acadoWorkspace.evGx[ 396 ]), &(acadoWorkspace.H10[ 18 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 486 ]), &(acadoWorkspace.evGx[ 432 ]), &(acadoWorkspace.H10[ 18 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 564 ]), &(acadoWorkspace.evGx[ 468 ]), &(acadoWorkspace.H10[ 18 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 648 ]), &(acadoWorkspace.evGx[ 504 ]), &(acadoWorkspace.H10[ 18 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 738 ]), &(acadoWorkspace.evGx[ 540 ]), &(acadoWorkspace.H10[ 18 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 834 ]), &(acadoWorkspace.evGx[ 576 ]), &(acadoWorkspace.H10[ 18 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 936 ]), &(acadoWorkspace.evGx[ 612 ]), &(acadoWorkspace.H10[ 18 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 1044 ]), &(acadoWorkspace.evGx[ 648 ]), &(acadoWorkspace.H10[ 18 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 1158 ]), &(acadoWorkspace.evGx[ 684 ]), &(acadoWorkspace.H10[ 18 ]) ); +acado_zeroBlockH10( &(acadoWorkspace.H10[ 24 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 84 ]), &(acadoWorkspace.evGx[ 144 ]), &(acadoWorkspace.H10[ 24 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 114 ]), &(acadoWorkspace.evGx[ 180 ]), &(acadoWorkspace.H10[ 24 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 150 ]), &(acadoWorkspace.evGx[ 216 ]), &(acadoWorkspace.H10[ 24 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 192 ]), &(acadoWorkspace.evGx[ 252 ]), &(acadoWorkspace.H10[ 24 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 240 ]), &(acadoWorkspace.evGx[ 288 ]), &(acadoWorkspace.H10[ 24 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 294 ]), &(acadoWorkspace.evGx[ 324 ]), &(acadoWorkspace.H10[ 24 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 354 ]), &(acadoWorkspace.evGx[ 360 ]), &(acadoWorkspace.H10[ 24 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 420 ]), &(acadoWorkspace.evGx[ 396 ]), &(acadoWorkspace.H10[ 24 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 492 ]), &(acadoWorkspace.evGx[ 432 ]), &(acadoWorkspace.H10[ 24 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 570 ]), &(acadoWorkspace.evGx[ 468 ]), &(acadoWorkspace.H10[ 24 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 654 ]), &(acadoWorkspace.evGx[ 504 ]), &(acadoWorkspace.H10[ 24 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 744 ]), &(acadoWorkspace.evGx[ 540 ]), &(acadoWorkspace.H10[ 24 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 840 ]), &(acadoWorkspace.evGx[ 576 ]), &(acadoWorkspace.H10[ 24 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 942 ]), &(acadoWorkspace.evGx[ 612 ]), &(acadoWorkspace.H10[ 24 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 1050 ]), &(acadoWorkspace.evGx[ 648 ]), &(acadoWorkspace.H10[ 24 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 1164 ]), &(acadoWorkspace.evGx[ 684 ]), &(acadoWorkspace.H10[ 24 ]) ); +acado_zeroBlockH10( &(acadoWorkspace.H10[ 30 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 120 ]), &(acadoWorkspace.evGx[ 180 ]), &(acadoWorkspace.H10[ 30 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 156 ]), &(acadoWorkspace.evGx[ 216 ]), &(acadoWorkspace.H10[ 30 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 198 ]), &(acadoWorkspace.evGx[ 252 ]), &(acadoWorkspace.H10[ 30 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 246 ]), &(acadoWorkspace.evGx[ 288 ]), &(acadoWorkspace.H10[ 30 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 300 ]), &(acadoWorkspace.evGx[ 324 ]), &(acadoWorkspace.H10[ 30 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 360 ]), &(acadoWorkspace.evGx[ 360 ]), &(acadoWorkspace.H10[ 30 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 426 ]), &(acadoWorkspace.evGx[ 396 ]), &(acadoWorkspace.H10[ 30 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 498 ]), &(acadoWorkspace.evGx[ 432 ]), &(acadoWorkspace.H10[ 30 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 576 ]), &(acadoWorkspace.evGx[ 468 ]), &(acadoWorkspace.H10[ 30 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 660 ]), &(acadoWorkspace.evGx[ 504 ]), &(acadoWorkspace.H10[ 30 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 750 ]), &(acadoWorkspace.evGx[ 540 ]), &(acadoWorkspace.H10[ 30 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 846 ]), &(acadoWorkspace.evGx[ 576 ]), &(acadoWorkspace.H10[ 30 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 948 ]), &(acadoWorkspace.evGx[ 612 ]), &(acadoWorkspace.H10[ 30 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 1056 ]), &(acadoWorkspace.evGx[ 648 ]), &(acadoWorkspace.H10[ 30 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 1170 ]), &(acadoWorkspace.evGx[ 684 ]), &(acadoWorkspace.H10[ 30 ]) ); +acado_zeroBlockH10( &(acadoWorkspace.H10[ 36 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 162 ]), &(acadoWorkspace.evGx[ 216 ]), &(acadoWorkspace.H10[ 36 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 204 ]), &(acadoWorkspace.evGx[ 252 ]), &(acadoWorkspace.H10[ 36 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 252 ]), &(acadoWorkspace.evGx[ 288 ]), &(acadoWorkspace.H10[ 36 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 306 ]), &(acadoWorkspace.evGx[ 324 ]), &(acadoWorkspace.H10[ 36 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 366 ]), &(acadoWorkspace.evGx[ 360 ]), &(acadoWorkspace.H10[ 36 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 432 ]), &(acadoWorkspace.evGx[ 396 ]), &(acadoWorkspace.H10[ 36 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 504 ]), &(acadoWorkspace.evGx[ 432 ]), &(acadoWorkspace.H10[ 36 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 582 ]), &(acadoWorkspace.evGx[ 468 ]), &(acadoWorkspace.H10[ 36 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 666 ]), &(acadoWorkspace.evGx[ 504 ]), &(acadoWorkspace.H10[ 36 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 756 ]), &(acadoWorkspace.evGx[ 540 ]), &(acadoWorkspace.H10[ 36 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 852 ]), &(acadoWorkspace.evGx[ 576 ]), &(acadoWorkspace.H10[ 36 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 954 ]), &(acadoWorkspace.evGx[ 612 ]), &(acadoWorkspace.H10[ 36 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 1062 ]), &(acadoWorkspace.evGx[ 648 ]), &(acadoWorkspace.H10[ 36 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 1176 ]), &(acadoWorkspace.evGx[ 684 ]), &(acadoWorkspace.H10[ 36 ]) ); +acado_zeroBlockH10( &(acadoWorkspace.H10[ 42 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 210 ]), &(acadoWorkspace.evGx[ 252 ]), &(acadoWorkspace.H10[ 42 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 258 ]), &(acadoWorkspace.evGx[ 288 ]), &(acadoWorkspace.H10[ 42 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 312 ]), &(acadoWorkspace.evGx[ 324 ]), &(acadoWorkspace.H10[ 42 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 372 ]), &(acadoWorkspace.evGx[ 360 ]), &(acadoWorkspace.H10[ 42 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 438 ]), &(acadoWorkspace.evGx[ 396 ]), &(acadoWorkspace.H10[ 42 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 510 ]), &(acadoWorkspace.evGx[ 432 ]), &(acadoWorkspace.H10[ 42 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 588 ]), &(acadoWorkspace.evGx[ 468 ]), &(acadoWorkspace.H10[ 42 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 672 ]), &(acadoWorkspace.evGx[ 504 ]), &(acadoWorkspace.H10[ 42 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 762 ]), &(acadoWorkspace.evGx[ 540 ]), &(acadoWorkspace.H10[ 42 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 858 ]), &(acadoWorkspace.evGx[ 576 ]), &(acadoWorkspace.H10[ 42 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 960 ]), &(acadoWorkspace.evGx[ 612 ]), &(acadoWorkspace.H10[ 42 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 1068 ]), &(acadoWorkspace.evGx[ 648 ]), &(acadoWorkspace.H10[ 42 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 1182 ]), &(acadoWorkspace.evGx[ 684 ]), &(acadoWorkspace.H10[ 42 ]) ); +acado_zeroBlockH10( &(acadoWorkspace.H10[ 48 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 264 ]), &(acadoWorkspace.evGx[ 288 ]), &(acadoWorkspace.H10[ 48 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 318 ]), &(acadoWorkspace.evGx[ 324 ]), &(acadoWorkspace.H10[ 48 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 378 ]), &(acadoWorkspace.evGx[ 360 ]), &(acadoWorkspace.H10[ 48 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 444 ]), &(acadoWorkspace.evGx[ 396 ]), &(acadoWorkspace.H10[ 48 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 516 ]), &(acadoWorkspace.evGx[ 432 ]), &(acadoWorkspace.H10[ 48 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 594 ]), &(acadoWorkspace.evGx[ 468 ]), &(acadoWorkspace.H10[ 48 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 678 ]), &(acadoWorkspace.evGx[ 504 ]), &(acadoWorkspace.H10[ 48 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 768 ]), &(acadoWorkspace.evGx[ 540 ]), &(acadoWorkspace.H10[ 48 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 864 ]), &(acadoWorkspace.evGx[ 576 ]), &(acadoWorkspace.H10[ 48 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 966 ]), &(acadoWorkspace.evGx[ 612 ]), &(acadoWorkspace.H10[ 48 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 1074 ]), &(acadoWorkspace.evGx[ 648 ]), &(acadoWorkspace.H10[ 48 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 1188 ]), &(acadoWorkspace.evGx[ 684 ]), &(acadoWorkspace.H10[ 48 ]) ); +acado_zeroBlockH10( &(acadoWorkspace.H10[ 54 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 324 ]), &(acadoWorkspace.evGx[ 324 ]), &(acadoWorkspace.H10[ 54 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 384 ]), &(acadoWorkspace.evGx[ 360 ]), &(acadoWorkspace.H10[ 54 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 450 ]), &(acadoWorkspace.evGx[ 396 ]), &(acadoWorkspace.H10[ 54 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 522 ]), &(acadoWorkspace.evGx[ 432 ]), &(acadoWorkspace.H10[ 54 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 600 ]), &(acadoWorkspace.evGx[ 468 ]), &(acadoWorkspace.H10[ 54 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 684 ]), &(acadoWorkspace.evGx[ 504 ]), &(acadoWorkspace.H10[ 54 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 774 ]), &(acadoWorkspace.evGx[ 540 ]), &(acadoWorkspace.H10[ 54 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 870 ]), &(acadoWorkspace.evGx[ 576 ]), &(acadoWorkspace.H10[ 54 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 972 ]), &(acadoWorkspace.evGx[ 612 ]), &(acadoWorkspace.H10[ 54 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 1080 ]), &(acadoWorkspace.evGx[ 648 ]), &(acadoWorkspace.H10[ 54 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 1194 ]), &(acadoWorkspace.evGx[ 684 ]), &(acadoWorkspace.H10[ 54 ]) ); +acado_zeroBlockH10( &(acadoWorkspace.H10[ 60 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 390 ]), &(acadoWorkspace.evGx[ 360 ]), &(acadoWorkspace.H10[ 60 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 456 ]), &(acadoWorkspace.evGx[ 396 ]), &(acadoWorkspace.H10[ 60 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 528 ]), &(acadoWorkspace.evGx[ 432 ]), &(acadoWorkspace.H10[ 60 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 606 ]), &(acadoWorkspace.evGx[ 468 ]), &(acadoWorkspace.H10[ 60 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 690 ]), &(acadoWorkspace.evGx[ 504 ]), &(acadoWorkspace.H10[ 60 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 780 ]), &(acadoWorkspace.evGx[ 540 ]), &(acadoWorkspace.H10[ 60 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 876 ]), &(acadoWorkspace.evGx[ 576 ]), &(acadoWorkspace.H10[ 60 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 978 ]), &(acadoWorkspace.evGx[ 612 ]), &(acadoWorkspace.H10[ 60 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 1086 ]), &(acadoWorkspace.evGx[ 648 ]), &(acadoWorkspace.H10[ 60 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 1200 ]), &(acadoWorkspace.evGx[ 684 ]), &(acadoWorkspace.H10[ 60 ]) ); +acado_zeroBlockH10( &(acadoWorkspace.H10[ 66 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 462 ]), &(acadoWorkspace.evGx[ 396 ]), &(acadoWorkspace.H10[ 66 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 534 ]), &(acadoWorkspace.evGx[ 432 ]), &(acadoWorkspace.H10[ 66 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 612 ]), &(acadoWorkspace.evGx[ 468 ]), &(acadoWorkspace.H10[ 66 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 696 ]), &(acadoWorkspace.evGx[ 504 ]), &(acadoWorkspace.H10[ 66 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 786 ]), &(acadoWorkspace.evGx[ 540 ]), &(acadoWorkspace.H10[ 66 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 882 ]), &(acadoWorkspace.evGx[ 576 ]), &(acadoWorkspace.H10[ 66 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 984 ]), &(acadoWorkspace.evGx[ 612 ]), &(acadoWorkspace.H10[ 66 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 1092 ]), &(acadoWorkspace.evGx[ 648 ]), &(acadoWorkspace.H10[ 66 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 1206 ]), &(acadoWorkspace.evGx[ 684 ]), &(acadoWorkspace.H10[ 66 ]) ); +acado_zeroBlockH10( &(acadoWorkspace.H10[ 72 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 540 ]), &(acadoWorkspace.evGx[ 432 ]), &(acadoWorkspace.H10[ 72 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 618 ]), &(acadoWorkspace.evGx[ 468 ]), &(acadoWorkspace.H10[ 72 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 702 ]), &(acadoWorkspace.evGx[ 504 ]), &(acadoWorkspace.H10[ 72 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 792 ]), &(acadoWorkspace.evGx[ 540 ]), &(acadoWorkspace.H10[ 72 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 888 ]), &(acadoWorkspace.evGx[ 576 ]), &(acadoWorkspace.H10[ 72 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 990 ]), &(acadoWorkspace.evGx[ 612 ]), &(acadoWorkspace.H10[ 72 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 1098 ]), &(acadoWorkspace.evGx[ 648 ]), &(acadoWorkspace.H10[ 72 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 1212 ]), &(acadoWorkspace.evGx[ 684 ]), &(acadoWorkspace.H10[ 72 ]) ); +acado_zeroBlockH10( &(acadoWorkspace.H10[ 78 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 624 ]), &(acadoWorkspace.evGx[ 468 ]), &(acadoWorkspace.H10[ 78 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 708 ]), &(acadoWorkspace.evGx[ 504 ]), &(acadoWorkspace.H10[ 78 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 798 ]), &(acadoWorkspace.evGx[ 540 ]), &(acadoWorkspace.H10[ 78 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 894 ]), &(acadoWorkspace.evGx[ 576 ]), &(acadoWorkspace.H10[ 78 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 996 ]), &(acadoWorkspace.evGx[ 612 ]), &(acadoWorkspace.H10[ 78 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 1104 ]), &(acadoWorkspace.evGx[ 648 ]), &(acadoWorkspace.H10[ 78 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 1218 ]), &(acadoWorkspace.evGx[ 684 ]), &(acadoWorkspace.H10[ 78 ]) ); +acado_zeroBlockH10( &(acadoWorkspace.H10[ 84 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 714 ]), &(acadoWorkspace.evGx[ 504 ]), &(acadoWorkspace.H10[ 84 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 804 ]), &(acadoWorkspace.evGx[ 540 ]), &(acadoWorkspace.H10[ 84 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 900 ]), &(acadoWorkspace.evGx[ 576 ]), &(acadoWorkspace.H10[ 84 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 1002 ]), &(acadoWorkspace.evGx[ 612 ]), &(acadoWorkspace.H10[ 84 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 1110 ]), &(acadoWorkspace.evGx[ 648 ]), &(acadoWorkspace.H10[ 84 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 1224 ]), &(acadoWorkspace.evGx[ 684 ]), &(acadoWorkspace.H10[ 84 ]) ); +acado_zeroBlockH10( &(acadoWorkspace.H10[ 90 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 810 ]), &(acadoWorkspace.evGx[ 540 ]), &(acadoWorkspace.H10[ 90 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 906 ]), &(acadoWorkspace.evGx[ 576 ]), &(acadoWorkspace.H10[ 90 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 1008 ]), &(acadoWorkspace.evGx[ 612 ]), &(acadoWorkspace.H10[ 90 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 1116 ]), &(acadoWorkspace.evGx[ 648 ]), &(acadoWorkspace.H10[ 90 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 1230 ]), &(acadoWorkspace.evGx[ 684 ]), &(acadoWorkspace.H10[ 90 ]) ); +acado_zeroBlockH10( &(acadoWorkspace.H10[ 96 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 912 ]), &(acadoWorkspace.evGx[ 576 ]), &(acadoWorkspace.H10[ 96 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 1014 ]), &(acadoWorkspace.evGx[ 612 ]), &(acadoWorkspace.H10[ 96 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 1122 ]), &(acadoWorkspace.evGx[ 648 ]), &(acadoWorkspace.H10[ 96 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 1236 ]), &(acadoWorkspace.evGx[ 684 ]), &(acadoWorkspace.H10[ 96 ]) ); +acado_zeroBlockH10( &(acadoWorkspace.H10[ 102 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 1020 ]), &(acadoWorkspace.evGx[ 612 ]), &(acadoWorkspace.H10[ 102 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 1128 ]), &(acadoWorkspace.evGx[ 648 ]), &(acadoWorkspace.H10[ 102 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 1242 ]), &(acadoWorkspace.evGx[ 684 ]), &(acadoWorkspace.H10[ 102 ]) ); +acado_zeroBlockH10( &(acadoWorkspace.H10[ 108 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 1134 ]), &(acadoWorkspace.evGx[ 648 ]), &(acadoWorkspace.H10[ 108 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 1248 ]), &(acadoWorkspace.evGx[ 684 ]), &(acadoWorkspace.H10[ 108 ]) ); +acado_zeroBlockH10( &(acadoWorkspace.H10[ 114 ]) ); +acado_multQETGx( &(acadoWorkspace.QE[ 1254 ]), &(acadoWorkspace.evGx[ 684 ]), &(acadoWorkspace.H10[ 114 ]) ); + +acadoWorkspace.H[6] = acadoWorkspace.H10[0]; +acadoWorkspace.H[7] = acadoWorkspace.H10[6]; +acadoWorkspace.H[8] = acadoWorkspace.H10[12]; +acadoWorkspace.H[9] = acadoWorkspace.H10[18]; +acadoWorkspace.H[10] = acadoWorkspace.H10[24]; +acadoWorkspace.H[11] = acadoWorkspace.H10[30]; +acadoWorkspace.H[12] = acadoWorkspace.H10[36]; +acadoWorkspace.H[13] = acadoWorkspace.H10[42]; +acadoWorkspace.H[14] = acadoWorkspace.H10[48]; +acadoWorkspace.H[15] = acadoWorkspace.H10[54]; +acadoWorkspace.H[16] = acadoWorkspace.H10[60]; +acadoWorkspace.H[17] = acadoWorkspace.H10[66]; +acadoWorkspace.H[18] = acadoWorkspace.H10[72]; +acadoWorkspace.H[19] = acadoWorkspace.H10[78]; +acadoWorkspace.H[20] = acadoWorkspace.H10[84]; +acadoWorkspace.H[21] = acadoWorkspace.H10[90]; +acadoWorkspace.H[22] = acadoWorkspace.H10[96]; +acadoWorkspace.H[23] = acadoWorkspace.H10[102]; +acadoWorkspace.H[24] = acadoWorkspace.H10[108]; +acadoWorkspace.H[25] = acadoWorkspace.H10[114]; +acadoWorkspace.H[32] = acadoWorkspace.H10[1]; +acadoWorkspace.H[33] = acadoWorkspace.H10[7]; +acadoWorkspace.H[34] = acadoWorkspace.H10[13]; +acadoWorkspace.H[35] = acadoWorkspace.H10[19]; +acadoWorkspace.H[36] = acadoWorkspace.H10[25]; +acadoWorkspace.H[37] = acadoWorkspace.H10[31]; +acadoWorkspace.H[38] = acadoWorkspace.H10[37]; +acadoWorkspace.H[39] = acadoWorkspace.H10[43]; +acadoWorkspace.H[40] = acadoWorkspace.H10[49]; +acadoWorkspace.H[41] = acadoWorkspace.H10[55]; +acadoWorkspace.H[42] = acadoWorkspace.H10[61]; +acadoWorkspace.H[43] = acadoWorkspace.H10[67]; +acadoWorkspace.H[44] = acadoWorkspace.H10[73]; +acadoWorkspace.H[45] = acadoWorkspace.H10[79]; +acadoWorkspace.H[46] = acadoWorkspace.H10[85]; +acadoWorkspace.H[47] = acadoWorkspace.H10[91]; +acadoWorkspace.H[48] = acadoWorkspace.H10[97]; +acadoWorkspace.H[49] = acadoWorkspace.H10[103]; +acadoWorkspace.H[50] = acadoWorkspace.H10[109]; +acadoWorkspace.H[51] = acadoWorkspace.H10[115]; +acadoWorkspace.H[58] = acadoWorkspace.H10[2]; +acadoWorkspace.H[59] = acadoWorkspace.H10[8]; +acadoWorkspace.H[60] = acadoWorkspace.H10[14]; +acadoWorkspace.H[61] = acadoWorkspace.H10[20]; +acadoWorkspace.H[62] = acadoWorkspace.H10[26]; +acadoWorkspace.H[63] = acadoWorkspace.H10[32]; +acadoWorkspace.H[64] = acadoWorkspace.H10[38]; +acadoWorkspace.H[65] = acadoWorkspace.H10[44]; +acadoWorkspace.H[66] = acadoWorkspace.H10[50]; +acadoWorkspace.H[67] = acadoWorkspace.H10[56]; +acadoWorkspace.H[68] = acadoWorkspace.H10[62]; +acadoWorkspace.H[69] = acadoWorkspace.H10[68]; +acadoWorkspace.H[70] = acadoWorkspace.H10[74]; +acadoWorkspace.H[71] = acadoWorkspace.H10[80]; +acadoWorkspace.H[72] = acadoWorkspace.H10[86]; +acadoWorkspace.H[73] = acadoWorkspace.H10[92]; +acadoWorkspace.H[74] = acadoWorkspace.H10[98]; +acadoWorkspace.H[75] = acadoWorkspace.H10[104]; +acadoWorkspace.H[76] = acadoWorkspace.H10[110]; +acadoWorkspace.H[77] = acadoWorkspace.H10[116]; +acadoWorkspace.H[84] = acadoWorkspace.H10[3]; +acadoWorkspace.H[85] = acadoWorkspace.H10[9]; +acadoWorkspace.H[86] = acadoWorkspace.H10[15]; +acadoWorkspace.H[87] = acadoWorkspace.H10[21]; +acadoWorkspace.H[88] = acadoWorkspace.H10[27]; +acadoWorkspace.H[89] = acadoWorkspace.H10[33]; +acadoWorkspace.H[90] = acadoWorkspace.H10[39]; +acadoWorkspace.H[91] = acadoWorkspace.H10[45]; +acadoWorkspace.H[92] = acadoWorkspace.H10[51]; +acadoWorkspace.H[93] = acadoWorkspace.H10[57]; +acadoWorkspace.H[94] = acadoWorkspace.H10[63]; +acadoWorkspace.H[95] = acadoWorkspace.H10[69]; +acadoWorkspace.H[96] = acadoWorkspace.H10[75]; +acadoWorkspace.H[97] = acadoWorkspace.H10[81]; +acadoWorkspace.H[98] = acadoWorkspace.H10[87]; +acadoWorkspace.H[99] = acadoWorkspace.H10[93]; +acadoWorkspace.H[100] = acadoWorkspace.H10[99]; +acadoWorkspace.H[101] = acadoWorkspace.H10[105]; +acadoWorkspace.H[102] = acadoWorkspace.H10[111]; +acadoWorkspace.H[103] = acadoWorkspace.H10[117]; +acadoWorkspace.H[110] = acadoWorkspace.H10[4]; +acadoWorkspace.H[111] = acadoWorkspace.H10[10]; +acadoWorkspace.H[112] = acadoWorkspace.H10[16]; +acadoWorkspace.H[113] = acadoWorkspace.H10[22]; +acadoWorkspace.H[114] = acadoWorkspace.H10[28]; +acadoWorkspace.H[115] = acadoWorkspace.H10[34]; +acadoWorkspace.H[116] = acadoWorkspace.H10[40]; +acadoWorkspace.H[117] = acadoWorkspace.H10[46]; +acadoWorkspace.H[118] = acadoWorkspace.H10[52]; +acadoWorkspace.H[119] = acadoWorkspace.H10[58]; +acadoWorkspace.H[120] = acadoWorkspace.H10[64]; +acadoWorkspace.H[121] = acadoWorkspace.H10[70]; +acadoWorkspace.H[122] = acadoWorkspace.H10[76]; +acadoWorkspace.H[123] = acadoWorkspace.H10[82]; +acadoWorkspace.H[124] = acadoWorkspace.H10[88]; +acadoWorkspace.H[125] = acadoWorkspace.H10[94]; +acadoWorkspace.H[126] = acadoWorkspace.H10[100]; +acadoWorkspace.H[127] = acadoWorkspace.H10[106]; +acadoWorkspace.H[128] = acadoWorkspace.H10[112]; +acadoWorkspace.H[129] = acadoWorkspace.H10[118]; +acadoWorkspace.H[136] = acadoWorkspace.H10[5]; +acadoWorkspace.H[137] = acadoWorkspace.H10[11]; +acadoWorkspace.H[138] = acadoWorkspace.H10[17]; +acadoWorkspace.H[139] = acadoWorkspace.H10[23]; +acadoWorkspace.H[140] = acadoWorkspace.H10[29]; +acadoWorkspace.H[141] = acadoWorkspace.H10[35]; +acadoWorkspace.H[142] = acadoWorkspace.H10[41]; +acadoWorkspace.H[143] = acadoWorkspace.H10[47]; +acadoWorkspace.H[144] = acadoWorkspace.H10[53]; +acadoWorkspace.H[145] = acadoWorkspace.H10[59]; +acadoWorkspace.H[146] = acadoWorkspace.H10[65]; +acadoWorkspace.H[147] = acadoWorkspace.H10[71]; +acadoWorkspace.H[148] = acadoWorkspace.H10[77]; +acadoWorkspace.H[149] = acadoWorkspace.H10[83]; +acadoWorkspace.H[150] = acadoWorkspace.H10[89]; +acadoWorkspace.H[151] = acadoWorkspace.H10[95]; +acadoWorkspace.H[152] = acadoWorkspace.H10[101]; +acadoWorkspace.H[153] = acadoWorkspace.H10[107]; +acadoWorkspace.H[154] = acadoWorkspace.H10[113]; +acadoWorkspace.H[155] = acadoWorkspace.H10[119]; + +acado_setBlockH11_R1( 0, 0, acadoWorkspace.R1 ); +acado_setBlockH11( 0, 0, acadoWorkspace.E, acadoWorkspace.QE ); +acado_setBlockH11( 0, 0, &(acadoWorkspace.E[ 6 ]), &(acadoWorkspace.QE[ 6 ]) ); +acado_setBlockH11( 0, 0, &(acadoWorkspace.E[ 18 ]), &(acadoWorkspace.QE[ 18 ]) ); +acado_setBlockH11( 0, 0, &(acadoWorkspace.E[ 36 ]), &(acadoWorkspace.QE[ 36 ]) ); +acado_setBlockH11( 0, 0, &(acadoWorkspace.E[ 60 ]), &(acadoWorkspace.QE[ 60 ]) ); +acado_setBlockH11( 0, 0, &(acadoWorkspace.E[ 90 ]), &(acadoWorkspace.QE[ 90 ]) ); +acado_setBlockH11( 0, 0, &(acadoWorkspace.E[ 126 ]), &(acadoWorkspace.QE[ 126 ]) ); +acado_setBlockH11( 0, 0, &(acadoWorkspace.E[ 168 ]), &(acadoWorkspace.QE[ 168 ]) ); +acado_setBlockH11( 0, 0, &(acadoWorkspace.E[ 216 ]), &(acadoWorkspace.QE[ 216 ]) ); +acado_setBlockH11( 0, 0, &(acadoWorkspace.E[ 270 ]), &(acadoWorkspace.QE[ 270 ]) ); +acado_setBlockH11( 0, 0, &(acadoWorkspace.E[ 330 ]), &(acadoWorkspace.QE[ 330 ]) ); +acado_setBlockH11( 0, 0, &(acadoWorkspace.E[ 396 ]), &(acadoWorkspace.QE[ 396 ]) ); +acado_setBlockH11( 0, 0, &(acadoWorkspace.E[ 468 ]), &(acadoWorkspace.QE[ 468 ]) ); +acado_setBlockH11( 0, 0, &(acadoWorkspace.E[ 546 ]), &(acadoWorkspace.QE[ 546 ]) ); +acado_setBlockH11( 0, 0, &(acadoWorkspace.E[ 630 ]), &(acadoWorkspace.QE[ 630 ]) ); +acado_setBlockH11( 0, 0, &(acadoWorkspace.E[ 720 ]), &(acadoWorkspace.QE[ 720 ]) ); +acado_setBlockH11( 0, 0, &(acadoWorkspace.E[ 816 ]), &(acadoWorkspace.QE[ 816 ]) ); +acado_setBlockH11( 0, 0, &(acadoWorkspace.E[ 918 ]), &(acadoWorkspace.QE[ 918 ]) ); +acado_setBlockH11( 0, 0, &(acadoWorkspace.E[ 1026 ]), &(acadoWorkspace.QE[ 1026 ]) ); +acado_setBlockH11( 0, 0, &(acadoWorkspace.E[ 1140 ]), &(acadoWorkspace.QE[ 1140 ]) ); + +acado_zeroBlockH11( 0, 1 ); +acado_setBlockH11( 0, 1, &(acadoWorkspace.E[ 6 ]), &(acadoWorkspace.QE[ 12 ]) ); +acado_setBlockH11( 0, 1, &(acadoWorkspace.E[ 18 ]), &(acadoWorkspace.QE[ 24 ]) ); +acado_setBlockH11( 0, 1, &(acadoWorkspace.E[ 36 ]), &(acadoWorkspace.QE[ 42 ]) ); +acado_setBlockH11( 0, 1, &(acadoWorkspace.E[ 60 ]), &(acadoWorkspace.QE[ 66 ]) ); +acado_setBlockH11( 0, 1, &(acadoWorkspace.E[ 90 ]), &(acadoWorkspace.QE[ 96 ]) ); +acado_setBlockH11( 0, 1, &(acadoWorkspace.E[ 126 ]), &(acadoWorkspace.QE[ 132 ]) ); +acado_setBlockH11( 0, 1, &(acadoWorkspace.E[ 168 ]), &(acadoWorkspace.QE[ 174 ]) ); +acado_setBlockH11( 0, 1, &(acadoWorkspace.E[ 216 ]), &(acadoWorkspace.QE[ 222 ]) ); +acado_setBlockH11( 0, 1, &(acadoWorkspace.E[ 270 ]), &(acadoWorkspace.QE[ 276 ]) ); +acado_setBlockH11( 0, 1, &(acadoWorkspace.E[ 330 ]), &(acadoWorkspace.QE[ 336 ]) ); +acado_setBlockH11( 0, 1, &(acadoWorkspace.E[ 396 ]), &(acadoWorkspace.QE[ 402 ]) ); +acado_setBlockH11( 0, 1, &(acadoWorkspace.E[ 468 ]), &(acadoWorkspace.QE[ 474 ]) ); +acado_setBlockH11( 0, 1, &(acadoWorkspace.E[ 546 ]), &(acadoWorkspace.QE[ 552 ]) ); +acado_setBlockH11( 0, 1, &(acadoWorkspace.E[ 630 ]), &(acadoWorkspace.QE[ 636 ]) ); +acado_setBlockH11( 0, 1, &(acadoWorkspace.E[ 720 ]), &(acadoWorkspace.QE[ 726 ]) ); +acado_setBlockH11( 0, 1, &(acadoWorkspace.E[ 816 ]), &(acadoWorkspace.QE[ 822 ]) ); +acado_setBlockH11( 0, 1, &(acadoWorkspace.E[ 918 ]), &(acadoWorkspace.QE[ 924 ]) ); +acado_setBlockH11( 0, 1, &(acadoWorkspace.E[ 1026 ]), &(acadoWorkspace.QE[ 1032 ]) ); +acado_setBlockH11( 0, 1, &(acadoWorkspace.E[ 1140 ]), &(acadoWorkspace.QE[ 1146 ]) ); + +acado_zeroBlockH11( 0, 2 ); +acado_setBlockH11( 0, 2, &(acadoWorkspace.E[ 18 ]), &(acadoWorkspace.QE[ 30 ]) ); +acado_setBlockH11( 0, 2, &(acadoWorkspace.E[ 36 ]), &(acadoWorkspace.QE[ 48 ]) ); +acado_setBlockH11( 0, 2, &(acadoWorkspace.E[ 60 ]), &(acadoWorkspace.QE[ 72 ]) ); +acado_setBlockH11( 0, 2, &(acadoWorkspace.E[ 90 ]), &(acadoWorkspace.QE[ 102 ]) ); +acado_setBlockH11( 0, 2, &(acadoWorkspace.E[ 126 ]), &(acadoWorkspace.QE[ 138 ]) ); +acado_setBlockH11( 0, 2, &(acadoWorkspace.E[ 168 ]), &(acadoWorkspace.QE[ 180 ]) ); +acado_setBlockH11( 0, 2, &(acadoWorkspace.E[ 216 ]), &(acadoWorkspace.QE[ 228 ]) ); +acado_setBlockH11( 0, 2, &(acadoWorkspace.E[ 270 ]), &(acadoWorkspace.QE[ 282 ]) ); +acado_setBlockH11( 0, 2, &(acadoWorkspace.E[ 330 ]), &(acadoWorkspace.QE[ 342 ]) ); +acado_setBlockH11( 0, 2, &(acadoWorkspace.E[ 396 ]), &(acadoWorkspace.QE[ 408 ]) ); +acado_setBlockH11( 0, 2, &(acadoWorkspace.E[ 468 ]), &(acadoWorkspace.QE[ 480 ]) ); +acado_setBlockH11( 0, 2, &(acadoWorkspace.E[ 546 ]), &(acadoWorkspace.QE[ 558 ]) ); +acado_setBlockH11( 0, 2, &(acadoWorkspace.E[ 630 ]), &(acadoWorkspace.QE[ 642 ]) ); +acado_setBlockH11( 0, 2, &(acadoWorkspace.E[ 720 ]), &(acadoWorkspace.QE[ 732 ]) ); +acado_setBlockH11( 0, 2, &(acadoWorkspace.E[ 816 ]), &(acadoWorkspace.QE[ 828 ]) ); +acado_setBlockH11( 0, 2, &(acadoWorkspace.E[ 918 ]), &(acadoWorkspace.QE[ 930 ]) ); +acado_setBlockH11( 0, 2, &(acadoWorkspace.E[ 1026 ]), &(acadoWorkspace.QE[ 1038 ]) ); +acado_setBlockH11( 0, 2, &(acadoWorkspace.E[ 1140 ]), &(acadoWorkspace.QE[ 1152 ]) ); + +acado_zeroBlockH11( 0, 3 ); +acado_setBlockH11( 0, 3, &(acadoWorkspace.E[ 36 ]), &(acadoWorkspace.QE[ 54 ]) ); +acado_setBlockH11( 0, 3, &(acadoWorkspace.E[ 60 ]), &(acadoWorkspace.QE[ 78 ]) ); +acado_setBlockH11( 0, 3, &(acadoWorkspace.E[ 90 ]), &(acadoWorkspace.QE[ 108 ]) ); +acado_setBlockH11( 0, 3, &(acadoWorkspace.E[ 126 ]), &(acadoWorkspace.QE[ 144 ]) ); +acado_setBlockH11( 0, 3, &(acadoWorkspace.E[ 168 ]), &(acadoWorkspace.QE[ 186 ]) ); +acado_setBlockH11( 0, 3, &(acadoWorkspace.E[ 216 ]), &(acadoWorkspace.QE[ 234 ]) ); +acado_setBlockH11( 0, 3, &(acadoWorkspace.E[ 270 ]), &(acadoWorkspace.QE[ 288 ]) ); +acado_setBlockH11( 0, 3, &(acadoWorkspace.E[ 330 ]), &(acadoWorkspace.QE[ 348 ]) ); +acado_setBlockH11( 0, 3, &(acadoWorkspace.E[ 396 ]), &(acadoWorkspace.QE[ 414 ]) ); +acado_setBlockH11( 0, 3, &(acadoWorkspace.E[ 468 ]), &(acadoWorkspace.QE[ 486 ]) ); +acado_setBlockH11( 0, 3, &(acadoWorkspace.E[ 546 ]), &(acadoWorkspace.QE[ 564 ]) ); +acado_setBlockH11( 0, 3, &(acadoWorkspace.E[ 630 ]), &(acadoWorkspace.QE[ 648 ]) ); +acado_setBlockH11( 0, 3, &(acadoWorkspace.E[ 720 ]), &(acadoWorkspace.QE[ 738 ]) ); +acado_setBlockH11( 0, 3, &(acadoWorkspace.E[ 816 ]), &(acadoWorkspace.QE[ 834 ]) ); +acado_setBlockH11( 0, 3, &(acadoWorkspace.E[ 918 ]), &(acadoWorkspace.QE[ 936 ]) ); +acado_setBlockH11( 0, 3, &(acadoWorkspace.E[ 1026 ]), &(acadoWorkspace.QE[ 1044 ]) ); +acado_setBlockH11( 0, 3, &(acadoWorkspace.E[ 1140 ]), &(acadoWorkspace.QE[ 1158 ]) ); + +acado_zeroBlockH11( 0, 4 ); +acado_setBlockH11( 0, 4, &(acadoWorkspace.E[ 60 ]), &(acadoWorkspace.QE[ 84 ]) ); +acado_setBlockH11( 0, 4, &(acadoWorkspace.E[ 90 ]), &(acadoWorkspace.QE[ 114 ]) ); +acado_setBlockH11( 0, 4, &(acadoWorkspace.E[ 126 ]), &(acadoWorkspace.QE[ 150 ]) ); +acado_setBlockH11( 0, 4, &(acadoWorkspace.E[ 168 ]), &(acadoWorkspace.QE[ 192 ]) ); +acado_setBlockH11( 0, 4, &(acadoWorkspace.E[ 216 ]), &(acadoWorkspace.QE[ 240 ]) ); +acado_setBlockH11( 0, 4, &(acadoWorkspace.E[ 270 ]), &(acadoWorkspace.QE[ 294 ]) ); +acado_setBlockH11( 0, 4, &(acadoWorkspace.E[ 330 ]), &(acadoWorkspace.QE[ 354 ]) ); +acado_setBlockH11( 0, 4, &(acadoWorkspace.E[ 396 ]), &(acadoWorkspace.QE[ 420 ]) ); +acado_setBlockH11( 0, 4, &(acadoWorkspace.E[ 468 ]), &(acadoWorkspace.QE[ 492 ]) ); +acado_setBlockH11( 0, 4, &(acadoWorkspace.E[ 546 ]), &(acadoWorkspace.QE[ 570 ]) ); +acado_setBlockH11( 0, 4, &(acadoWorkspace.E[ 630 ]), &(acadoWorkspace.QE[ 654 ]) ); +acado_setBlockH11( 0, 4, &(acadoWorkspace.E[ 720 ]), &(acadoWorkspace.QE[ 744 ]) ); +acado_setBlockH11( 0, 4, &(acadoWorkspace.E[ 816 ]), &(acadoWorkspace.QE[ 840 ]) ); +acado_setBlockH11( 0, 4, &(acadoWorkspace.E[ 918 ]), &(acadoWorkspace.QE[ 942 ]) ); +acado_setBlockH11( 0, 4, &(acadoWorkspace.E[ 1026 ]), &(acadoWorkspace.QE[ 1050 ]) ); +acado_setBlockH11( 0, 4, &(acadoWorkspace.E[ 1140 ]), &(acadoWorkspace.QE[ 1164 ]) ); + +acado_zeroBlockH11( 0, 5 ); +acado_setBlockH11( 0, 5, &(acadoWorkspace.E[ 90 ]), &(acadoWorkspace.QE[ 120 ]) ); +acado_setBlockH11( 0, 5, &(acadoWorkspace.E[ 126 ]), &(acadoWorkspace.QE[ 156 ]) ); +acado_setBlockH11( 0, 5, &(acadoWorkspace.E[ 168 ]), &(acadoWorkspace.QE[ 198 ]) ); +acado_setBlockH11( 0, 5, &(acadoWorkspace.E[ 216 ]), &(acadoWorkspace.QE[ 246 ]) ); +acado_setBlockH11( 0, 5, &(acadoWorkspace.E[ 270 ]), &(acadoWorkspace.QE[ 300 ]) ); +acado_setBlockH11( 0, 5, &(acadoWorkspace.E[ 330 ]), &(acadoWorkspace.QE[ 360 ]) ); +acado_setBlockH11( 0, 5, &(acadoWorkspace.E[ 396 ]), &(acadoWorkspace.QE[ 426 ]) ); +acado_setBlockH11( 0, 5, &(acadoWorkspace.E[ 468 ]), &(acadoWorkspace.QE[ 498 ]) ); +acado_setBlockH11( 0, 5, &(acadoWorkspace.E[ 546 ]), &(acadoWorkspace.QE[ 576 ]) ); +acado_setBlockH11( 0, 5, &(acadoWorkspace.E[ 630 ]), &(acadoWorkspace.QE[ 660 ]) ); +acado_setBlockH11( 0, 5, &(acadoWorkspace.E[ 720 ]), &(acadoWorkspace.QE[ 750 ]) ); +acado_setBlockH11( 0, 5, &(acadoWorkspace.E[ 816 ]), &(acadoWorkspace.QE[ 846 ]) ); +acado_setBlockH11( 0, 5, &(acadoWorkspace.E[ 918 ]), &(acadoWorkspace.QE[ 948 ]) ); +acado_setBlockH11( 0, 5, &(acadoWorkspace.E[ 1026 ]), &(acadoWorkspace.QE[ 1056 ]) ); +acado_setBlockH11( 0, 5, &(acadoWorkspace.E[ 1140 ]), &(acadoWorkspace.QE[ 1170 ]) ); + +acado_zeroBlockH11( 0, 6 ); +acado_setBlockH11( 0, 6, &(acadoWorkspace.E[ 126 ]), &(acadoWorkspace.QE[ 162 ]) ); +acado_setBlockH11( 0, 6, &(acadoWorkspace.E[ 168 ]), &(acadoWorkspace.QE[ 204 ]) ); +acado_setBlockH11( 0, 6, &(acadoWorkspace.E[ 216 ]), &(acadoWorkspace.QE[ 252 ]) ); +acado_setBlockH11( 0, 6, &(acadoWorkspace.E[ 270 ]), &(acadoWorkspace.QE[ 306 ]) ); +acado_setBlockH11( 0, 6, &(acadoWorkspace.E[ 330 ]), &(acadoWorkspace.QE[ 366 ]) ); +acado_setBlockH11( 0, 6, &(acadoWorkspace.E[ 396 ]), &(acadoWorkspace.QE[ 432 ]) ); +acado_setBlockH11( 0, 6, &(acadoWorkspace.E[ 468 ]), &(acadoWorkspace.QE[ 504 ]) ); +acado_setBlockH11( 0, 6, &(acadoWorkspace.E[ 546 ]), &(acadoWorkspace.QE[ 582 ]) ); +acado_setBlockH11( 0, 6, &(acadoWorkspace.E[ 630 ]), &(acadoWorkspace.QE[ 666 ]) ); +acado_setBlockH11( 0, 6, &(acadoWorkspace.E[ 720 ]), &(acadoWorkspace.QE[ 756 ]) ); +acado_setBlockH11( 0, 6, &(acadoWorkspace.E[ 816 ]), &(acadoWorkspace.QE[ 852 ]) ); +acado_setBlockH11( 0, 6, &(acadoWorkspace.E[ 918 ]), &(acadoWorkspace.QE[ 954 ]) ); +acado_setBlockH11( 0, 6, &(acadoWorkspace.E[ 1026 ]), &(acadoWorkspace.QE[ 1062 ]) ); +acado_setBlockH11( 0, 6, &(acadoWorkspace.E[ 1140 ]), &(acadoWorkspace.QE[ 1176 ]) ); + +acado_zeroBlockH11( 0, 7 ); +acado_setBlockH11( 0, 7, &(acadoWorkspace.E[ 168 ]), &(acadoWorkspace.QE[ 210 ]) ); +acado_setBlockH11( 0, 7, &(acadoWorkspace.E[ 216 ]), &(acadoWorkspace.QE[ 258 ]) ); +acado_setBlockH11( 0, 7, &(acadoWorkspace.E[ 270 ]), &(acadoWorkspace.QE[ 312 ]) ); +acado_setBlockH11( 0, 7, &(acadoWorkspace.E[ 330 ]), &(acadoWorkspace.QE[ 372 ]) ); +acado_setBlockH11( 0, 7, &(acadoWorkspace.E[ 396 ]), &(acadoWorkspace.QE[ 438 ]) ); +acado_setBlockH11( 0, 7, &(acadoWorkspace.E[ 468 ]), &(acadoWorkspace.QE[ 510 ]) ); +acado_setBlockH11( 0, 7, &(acadoWorkspace.E[ 546 ]), &(acadoWorkspace.QE[ 588 ]) ); +acado_setBlockH11( 0, 7, &(acadoWorkspace.E[ 630 ]), &(acadoWorkspace.QE[ 672 ]) ); +acado_setBlockH11( 0, 7, &(acadoWorkspace.E[ 720 ]), &(acadoWorkspace.QE[ 762 ]) ); +acado_setBlockH11( 0, 7, &(acadoWorkspace.E[ 816 ]), &(acadoWorkspace.QE[ 858 ]) ); +acado_setBlockH11( 0, 7, &(acadoWorkspace.E[ 918 ]), &(acadoWorkspace.QE[ 960 ]) ); +acado_setBlockH11( 0, 7, &(acadoWorkspace.E[ 1026 ]), &(acadoWorkspace.QE[ 1068 ]) ); +acado_setBlockH11( 0, 7, &(acadoWorkspace.E[ 1140 ]), &(acadoWorkspace.QE[ 1182 ]) ); + +acado_zeroBlockH11( 0, 8 ); +acado_setBlockH11( 0, 8, &(acadoWorkspace.E[ 216 ]), &(acadoWorkspace.QE[ 264 ]) ); +acado_setBlockH11( 0, 8, &(acadoWorkspace.E[ 270 ]), &(acadoWorkspace.QE[ 318 ]) ); +acado_setBlockH11( 0, 8, &(acadoWorkspace.E[ 330 ]), &(acadoWorkspace.QE[ 378 ]) ); +acado_setBlockH11( 0, 8, &(acadoWorkspace.E[ 396 ]), &(acadoWorkspace.QE[ 444 ]) ); +acado_setBlockH11( 0, 8, &(acadoWorkspace.E[ 468 ]), &(acadoWorkspace.QE[ 516 ]) ); +acado_setBlockH11( 0, 8, &(acadoWorkspace.E[ 546 ]), &(acadoWorkspace.QE[ 594 ]) ); +acado_setBlockH11( 0, 8, &(acadoWorkspace.E[ 630 ]), &(acadoWorkspace.QE[ 678 ]) ); +acado_setBlockH11( 0, 8, &(acadoWorkspace.E[ 720 ]), &(acadoWorkspace.QE[ 768 ]) ); +acado_setBlockH11( 0, 8, &(acadoWorkspace.E[ 816 ]), &(acadoWorkspace.QE[ 864 ]) ); +acado_setBlockH11( 0, 8, &(acadoWorkspace.E[ 918 ]), &(acadoWorkspace.QE[ 966 ]) ); +acado_setBlockH11( 0, 8, &(acadoWorkspace.E[ 1026 ]), &(acadoWorkspace.QE[ 1074 ]) ); +acado_setBlockH11( 0, 8, &(acadoWorkspace.E[ 1140 ]), &(acadoWorkspace.QE[ 1188 ]) ); + +acado_zeroBlockH11( 0, 9 ); +acado_setBlockH11( 0, 9, &(acadoWorkspace.E[ 270 ]), &(acadoWorkspace.QE[ 324 ]) ); +acado_setBlockH11( 0, 9, &(acadoWorkspace.E[ 330 ]), &(acadoWorkspace.QE[ 384 ]) ); +acado_setBlockH11( 0, 9, &(acadoWorkspace.E[ 396 ]), &(acadoWorkspace.QE[ 450 ]) ); +acado_setBlockH11( 0, 9, &(acadoWorkspace.E[ 468 ]), &(acadoWorkspace.QE[ 522 ]) ); +acado_setBlockH11( 0, 9, &(acadoWorkspace.E[ 546 ]), &(acadoWorkspace.QE[ 600 ]) ); +acado_setBlockH11( 0, 9, &(acadoWorkspace.E[ 630 ]), &(acadoWorkspace.QE[ 684 ]) ); +acado_setBlockH11( 0, 9, &(acadoWorkspace.E[ 720 ]), &(acadoWorkspace.QE[ 774 ]) ); +acado_setBlockH11( 0, 9, &(acadoWorkspace.E[ 816 ]), &(acadoWorkspace.QE[ 870 ]) ); +acado_setBlockH11( 0, 9, &(acadoWorkspace.E[ 918 ]), &(acadoWorkspace.QE[ 972 ]) ); +acado_setBlockH11( 0, 9, &(acadoWorkspace.E[ 1026 ]), &(acadoWorkspace.QE[ 1080 ]) ); +acado_setBlockH11( 0, 9, &(acadoWorkspace.E[ 1140 ]), &(acadoWorkspace.QE[ 1194 ]) ); + +acado_zeroBlockH11( 0, 10 ); +acado_setBlockH11( 0, 10, &(acadoWorkspace.E[ 330 ]), &(acadoWorkspace.QE[ 390 ]) ); +acado_setBlockH11( 0, 10, &(acadoWorkspace.E[ 396 ]), &(acadoWorkspace.QE[ 456 ]) ); +acado_setBlockH11( 0, 10, &(acadoWorkspace.E[ 468 ]), &(acadoWorkspace.QE[ 528 ]) ); +acado_setBlockH11( 0, 10, &(acadoWorkspace.E[ 546 ]), &(acadoWorkspace.QE[ 606 ]) ); +acado_setBlockH11( 0, 10, &(acadoWorkspace.E[ 630 ]), &(acadoWorkspace.QE[ 690 ]) ); +acado_setBlockH11( 0, 10, &(acadoWorkspace.E[ 720 ]), &(acadoWorkspace.QE[ 780 ]) ); +acado_setBlockH11( 0, 10, &(acadoWorkspace.E[ 816 ]), &(acadoWorkspace.QE[ 876 ]) ); +acado_setBlockH11( 0, 10, &(acadoWorkspace.E[ 918 ]), &(acadoWorkspace.QE[ 978 ]) ); +acado_setBlockH11( 0, 10, &(acadoWorkspace.E[ 1026 ]), &(acadoWorkspace.QE[ 1086 ]) ); +acado_setBlockH11( 0, 10, &(acadoWorkspace.E[ 1140 ]), &(acadoWorkspace.QE[ 1200 ]) ); + +acado_zeroBlockH11( 0, 11 ); +acado_setBlockH11( 0, 11, &(acadoWorkspace.E[ 396 ]), &(acadoWorkspace.QE[ 462 ]) ); +acado_setBlockH11( 0, 11, &(acadoWorkspace.E[ 468 ]), &(acadoWorkspace.QE[ 534 ]) ); +acado_setBlockH11( 0, 11, &(acadoWorkspace.E[ 546 ]), &(acadoWorkspace.QE[ 612 ]) ); +acado_setBlockH11( 0, 11, &(acadoWorkspace.E[ 630 ]), &(acadoWorkspace.QE[ 696 ]) ); +acado_setBlockH11( 0, 11, &(acadoWorkspace.E[ 720 ]), &(acadoWorkspace.QE[ 786 ]) ); +acado_setBlockH11( 0, 11, &(acadoWorkspace.E[ 816 ]), &(acadoWorkspace.QE[ 882 ]) ); +acado_setBlockH11( 0, 11, &(acadoWorkspace.E[ 918 ]), &(acadoWorkspace.QE[ 984 ]) ); +acado_setBlockH11( 0, 11, &(acadoWorkspace.E[ 1026 ]), &(acadoWorkspace.QE[ 1092 ]) ); +acado_setBlockH11( 0, 11, &(acadoWorkspace.E[ 1140 ]), &(acadoWorkspace.QE[ 1206 ]) ); + +acado_zeroBlockH11( 0, 12 ); +acado_setBlockH11( 0, 12, &(acadoWorkspace.E[ 468 ]), &(acadoWorkspace.QE[ 540 ]) ); +acado_setBlockH11( 0, 12, &(acadoWorkspace.E[ 546 ]), &(acadoWorkspace.QE[ 618 ]) ); +acado_setBlockH11( 0, 12, &(acadoWorkspace.E[ 630 ]), &(acadoWorkspace.QE[ 702 ]) ); +acado_setBlockH11( 0, 12, &(acadoWorkspace.E[ 720 ]), &(acadoWorkspace.QE[ 792 ]) ); +acado_setBlockH11( 0, 12, &(acadoWorkspace.E[ 816 ]), &(acadoWorkspace.QE[ 888 ]) ); +acado_setBlockH11( 0, 12, &(acadoWorkspace.E[ 918 ]), &(acadoWorkspace.QE[ 990 ]) ); +acado_setBlockH11( 0, 12, &(acadoWorkspace.E[ 1026 ]), &(acadoWorkspace.QE[ 1098 ]) ); +acado_setBlockH11( 0, 12, &(acadoWorkspace.E[ 1140 ]), &(acadoWorkspace.QE[ 1212 ]) ); + +acado_zeroBlockH11( 0, 13 ); +acado_setBlockH11( 0, 13, &(acadoWorkspace.E[ 546 ]), &(acadoWorkspace.QE[ 624 ]) ); +acado_setBlockH11( 0, 13, &(acadoWorkspace.E[ 630 ]), &(acadoWorkspace.QE[ 708 ]) ); +acado_setBlockH11( 0, 13, &(acadoWorkspace.E[ 720 ]), &(acadoWorkspace.QE[ 798 ]) ); +acado_setBlockH11( 0, 13, &(acadoWorkspace.E[ 816 ]), &(acadoWorkspace.QE[ 894 ]) ); +acado_setBlockH11( 0, 13, &(acadoWorkspace.E[ 918 ]), &(acadoWorkspace.QE[ 996 ]) ); +acado_setBlockH11( 0, 13, &(acadoWorkspace.E[ 1026 ]), &(acadoWorkspace.QE[ 1104 ]) ); +acado_setBlockH11( 0, 13, &(acadoWorkspace.E[ 1140 ]), &(acadoWorkspace.QE[ 1218 ]) ); + +acado_zeroBlockH11( 0, 14 ); +acado_setBlockH11( 0, 14, &(acadoWorkspace.E[ 630 ]), &(acadoWorkspace.QE[ 714 ]) ); +acado_setBlockH11( 0, 14, &(acadoWorkspace.E[ 720 ]), &(acadoWorkspace.QE[ 804 ]) ); +acado_setBlockH11( 0, 14, &(acadoWorkspace.E[ 816 ]), &(acadoWorkspace.QE[ 900 ]) ); +acado_setBlockH11( 0, 14, &(acadoWorkspace.E[ 918 ]), &(acadoWorkspace.QE[ 1002 ]) ); +acado_setBlockH11( 0, 14, &(acadoWorkspace.E[ 1026 ]), &(acadoWorkspace.QE[ 1110 ]) ); +acado_setBlockH11( 0, 14, &(acadoWorkspace.E[ 1140 ]), &(acadoWorkspace.QE[ 1224 ]) ); + +acado_zeroBlockH11( 0, 15 ); +acado_setBlockH11( 0, 15, &(acadoWorkspace.E[ 720 ]), &(acadoWorkspace.QE[ 810 ]) ); +acado_setBlockH11( 0, 15, &(acadoWorkspace.E[ 816 ]), &(acadoWorkspace.QE[ 906 ]) ); +acado_setBlockH11( 0, 15, &(acadoWorkspace.E[ 918 ]), &(acadoWorkspace.QE[ 1008 ]) ); +acado_setBlockH11( 0, 15, &(acadoWorkspace.E[ 1026 ]), &(acadoWorkspace.QE[ 1116 ]) ); +acado_setBlockH11( 0, 15, &(acadoWorkspace.E[ 1140 ]), &(acadoWorkspace.QE[ 1230 ]) ); + +acado_zeroBlockH11( 0, 16 ); +acado_setBlockH11( 0, 16, &(acadoWorkspace.E[ 816 ]), &(acadoWorkspace.QE[ 912 ]) ); +acado_setBlockH11( 0, 16, &(acadoWorkspace.E[ 918 ]), &(acadoWorkspace.QE[ 1014 ]) ); +acado_setBlockH11( 0, 16, &(acadoWorkspace.E[ 1026 ]), &(acadoWorkspace.QE[ 1122 ]) ); +acado_setBlockH11( 0, 16, &(acadoWorkspace.E[ 1140 ]), &(acadoWorkspace.QE[ 1236 ]) ); + +acado_zeroBlockH11( 0, 17 ); +acado_setBlockH11( 0, 17, &(acadoWorkspace.E[ 918 ]), &(acadoWorkspace.QE[ 1020 ]) ); +acado_setBlockH11( 0, 17, &(acadoWorkspace.E[ 1026 ]), &(acadoWorkspace.QE[ 1128 ]) ); +acado_setBlockH11( 0, 17, &(acadoWorkspace.E[ 1140 ]), &(acadoWorkspace.QE[ 1242 ]) ); + +acado_zeroBlockH11( 0, 18 ); +acado_setBlockH11( 0, 18, &(acadoWorkspace.E[ 1026 ]), &(acadoWorkspace.QE[ 1134 ]) ); +acado_setBlockH11( 0, 18, &(acadoWorkspace.E[ 1140 ]), &(acadoWorkspace.QE[ 1248 ]) ); + +acado_zeroBlockH11( 0, 19 ); +acado_setBlockH11( 0, 19, &(acadoWorkspace.E[ 1140 ]), &(acadoWorkspace.QE[ 1254 ]) ); + +acado_setBlockH11_R1( 1, 1, &(acadoWorkspace.R1[ 1 ]) ); +acado_setBlockH11( 1, 1, &(acadoWorkspace.E[ 12 ]), &(acadoWorkspace.QE[ 12 ]) ); +acado_setBlockH11( 1, 1, &(acadoWorkspace.E[ 24 ]), &(acadoWorkspace.QE[ 24 ]) ); +acado_setBlockH11( 1, 1, &(acadoWorkspace.E[ 42 ]), &(acadoWorkspace.QE[ 42 ]) ); +acado_setBlockH11( 1, 1, &(acadoWorkspace.E[ 66 ]), &(acadoWorkspace.QE[ 66 ]) ); +acado_setBlockH11( 1, 1, &(acadoWorkspace.E[ 96 ]), &(acadoWorkspace.QE[ 96 ]) ); +acado_setBlockH11( 1, 1, &(acadoWorkspace.E[ 132 ]), &(acadoWorkspace.QE[ 132 ]) ); +acado_setBlockH11( 1, 1, &(acadoWorkspace.E[ 174 ]), &(acadoWorkspace.QE[ 174 ]) ); +acado_setBlockH11( 1, 1, &(acadoWorkspace.E[ 222 ]), &(acadoWorkspace.QE[ 222 ]) ); +acado_setBlockH11( 1, 1, &(acadoWorkspace.E[ 276 ]), &(acadoWorkspace.QE[ 276 ]) ); +acado_setBlockH11( 1, 1, &(acadoWorkspace.E[ 336 ]), &(acadoWorkspace.QE[ 336 ]) ); +acado_setBlockH11( 1, 1, &(acadoWorkspace.E[ 402 ]), &(acadoWorkspace.QE[ 402 ]) ); +acado_setBlockH11( 1, 1, &(acadoWorkspace.E[ 474 ]), &(acadoWorkspace.QE[ 474 ]) ); +acado_setBlockH11( 1, 1, &(acadoWorkspace.E[ 552 ]), &(acadoWorkspace.QE[ 552 ]) ); +acado_setBlockH11( 1, 1, &(acadoWorkspace.E[ 636 ]), &(acadoWorkspace.QE[ 636 ]) ); +acado_setBlockH11( 1, 1, &(acadoWorkspace.E[ 726 ]), &(acadoWorkspace.QE[ 726 ]) ); +acado_setBlockH11( 1, 1, &(acadoWorkspace.E[ 822 ]), &(acadoWorkspace.QE[ 822 ]) ); +acado_setBlockH11( 1, 1, &(acadoWorkspace.E[ 924 ]), &(acadoWorkspace.QE[ 924 ]) ); +acado_setBlockH11( 1, 1, &(acadoWorkspace.E[ 1032 ]), &(acadoWorkspace.QE[ 1032 ]) ); +acado_setBlockH11( 1, 1, &(acadoWorkspace.E[ 1146 ]), &(acadoWorkspace.QE[ 1146 ]) ); + +acado_zeroBlockH11( 1, 2 ); +acado_setBlockH11( 1, 2, &(acadoWorkspace.E[ 24 ]), &(acadoWorkspace.QE[ 30 ]) ); +acado_setBlockH11( 1, 2, &(acadoWorkspace.E[ 42 ]), &(acadoWorkspace.QE[ 48 ]) ); +acado_setBlockH11( 1, 2, &(acadoWorkspace.E[ 66 ]), &(acadoWorkspace.QE[ 72 ]) ); +acado_setBlockH11( 1, 2, &(acadoWorkspace.E[ 96 ]), &(acadoWorkspace.QE[ 102 ]) ); +acado_setBlockH11( 1, 2, &(acadoWorkspace.E[ 132 ]), &(acadoWorkspace.QE[ 138 ]) ); +acado_setBlockH11( 1, 2, &(acadoWorkspace.E[ 174 ]), &(acadoWorkspace.QE[ 180 ]) ); +acado_setBlockH11( 1, 2, &(acadoWorkspace.E[ 222 ]), &(acadoWorkspace.QE[ 228 ]) ); +acado_setBlockH11( 1, 2, &(acadoWorkspace.E[ 276 ]), &(acadoWorkspace.QE[ 282 ]) ); +acado_setBlockH11( 1, 2, &(acadoWorkspace.E[ 336 ]), &(acadoWorkspace.QE[ 342 ]) ); +acado_setBlockH11( 1, 2, &(acadoWorkspace.E[ 402 ]), &(acadoWorkspace.QE[ 408 ]) ); +acado_setBlockH11( 1, 2, &(acadoWorkspace.E[ 474 ]), &(acadoWorkspace.QE[ 480 ]) ); +acado_setBlockH11( 1, 2, &(acadoWorkspace.E[ 552 ]), &(acadoWorkspace.QE[ 558 ]) ); +acado_setBlockH11( 1, 2, &(acadoWorkspace.E[ 636 ]), &(acadoWorkspace.QE[ 642 ]) ); +acado_setBlockH11( 1, 2, &(acadoWorkspace.E[ 726 ]), &(acadoWorkspace.QE[ 732 ]) ); +acado_setBlockH11( 1, 2, &(acadoWorkspace.E[ 822 ]), &(acadoWorkspace.QE[ 828 ]) ); +acado_setBlockH11( 1, 2, &(acadoWorkspace.E[ 924 ]), &(acadoWorkspace.QE[ 930 ]) ); +acado_setBlockH11( 1, 2, &(acadoWorkspace.E[ 1032 ]), &(acadoWorkspace.QE[ 1038 ]) ); +acado_setBlockH11( 1, 2, &(acadoWorkspace.E[ 1146 ]), &(acadoWorkspace.QE[ 1152 ]) ); + +acado_zeroBlockH11( 1, 3 ); +acado_setBlockH11( 1, 3, &(acadoWorkspace.E[ 42 ]), &(acadoWorkspace.QE[ 54 ]) ); +acado_setBlockH11( 1, 3, &(acadoWorkspace.E[ 66 ]), &(acadoWorkspace.QE[ 78 ]) ); +acado_setBlockH11( 1, 3, &(acadoWorkspace.E[ 96 ]), &(acadoWorkspace.QE[ 108 ]) ); +acado_setBlockH11( 1, 3, &(acadoWorkspace.E[ 132 ]), &(acadoWorkspace.QE[ 144 ]) ); +acado_setBlockH11( 1, 3, &(acadoWorkspace.E[ 174 ]), &(acadoWorkspace.QE[ 186 ]) ); +acado_setBlockH11( 1, 3, &(acadoWorkspace.E[ 222 ]), &(acadoWorkspace.QE[ 234 ]) ); +acado_setBlockH11( 1, 3, &(acadoWorkspace.E[ 276 ]), &(acadoWorkspace.QE[ 288 ]) ); +acado_setBlockH11( 1, 3, &(acadoWorkspace.E[ 336 ]), &(acadoWorkspace.QE[ 348 ]) ); +acado_setBlockH11( 1, 3, &(acadoWorkspace.E[ 402 ]), &(acadoWorkspace.QE[ 414 ]) ); +acado_setBlockH11( 1, 3, &(acadoWorkspace.E[ 474 ]), &(acadoWorkspace.QE[ 486 ]) ); +acado_setBlockH11( 1, 3, &(acadoWorkspace.E[ 552 ]), &(acadoWorkspace.QE[ 564 ]) ); +acado_setBlockH11( 1, 3, &(acadoWorkspace.E[ 636 ]), &(acadoWorkspace.QE[ 648 ]) ); +acado_setBlockH11( 1, 3, &(acadoWorkspace.E[ 726 ]), &(acadoWorkspace.QE[ 738 ]) ); +acado_setBlockH11( 1, 3, &(acadoWorkspace.E[ 822 ]), &(acadoWorkspace.QE[ 834 ]) ); +acado_setBlockH11( 1, 3, &(acadoWorkspace.E[ 924 ]), &(acadoWorkspace.QE[ 936 ]) ); +acado_setBlockH11( 1, 3, &(acadoWorkspace.E[ 1032 ]), &(acadoWorkspace.QE[ 1044 ]) ); +acado_setBlockH11( 1, 3, &(acadoWorkspace.E[ 1146 ]), &(acadoWorkspace.QE[ 1158 ]) ); + +acado_zeroBlockH11( 1, 4 ); +acado_setBlockH11( 1, 4, &(acadoWorkspace.E[ 66 ]), &(acadoWorkspace.QE[ 84 ]) ); +acado_setBlockH11( 1, 4, &(acadoWorkspace.E[ 96 ]), &(acadoWorkspace.QE[ 114 ]) ); +acado_setBlockH11( 1, 4, &(acadoWorkspace.E[ 132 ]), &(acadoWorkspace.QE[ 150 ]) ); +acado_setBlockH11( 1, 4, &(acadoWorkspace.E[ 174 ]), &(acadoWorkspace.QE[ 192 ]) ); +acado_setBlockH11( 1, 4, &(acadoWorkspace.E[ 222 ]), &(acadoWorkspace.QE[ 240 ]) ); +acado_setBlockH11( 1, 4, &(acadoWorkspace.E[ 276 ]), &(acadoWorkspace.QE[ 294 ]) ); +acado_setBlockH11( 1, 4, &(acadoWorkspace.E[ 336 ]), &(acadoWorkspace.QE[ 354 ]) ); +acado_setBlockH11( 1, 4, &(acadoWorkspace.E[ 402 ]), &(acadoWorkspace.QE[ 420 ]) ); +acado_setBlockH11( 1, 4, &(acadoWorkspace.E[ 474 ]), &(acadoWorkspace.QE[ 492 ]) ); +acado_setBlockH11( 1, 4, &(acadoWorkspace.E[ 552 ]), &(acadoWorkspace.QE[ 570 ]) ); +acado_setBlockH11( 1, 4, &(acadoWorkspace.E[ 636 ]), &(acadoWorkspace.QE[ 654 ]) ); +acado_setBlockH11( 1, 4, &(acadoWorkspace.E[ 726 ]), &(acadoWorkspace.QE[ 744 ]) ); +acado_setBlockH11( 1, 4, &(acadoWorkspace.E[ 822 ]), &(acadoWorkspace.QE[ 840 ]) ); +acado_setBlockH11( 1, 4, &(acadoWorkspace.E[ 924 ]), &(acadoWorkspace.QE[ 942 ]) ); +acado_setBlockH11( 1, 4, &(acadoWorkspace.E[ 1032 ]), &(acadoWorkspace.QE[ 1050 ]) ); +acado_setBlockH11( 1, 4, &(acadoWorkspace.E[ 1146 ]), &(acadoWorkspace.QE[ 1164 ]) ); + +acado_zeroBlockH11( 1, 5 ); +acado_setBlockH11( 1, 5, &(acadoWorkspace.E[ 96 ]), &(acadoWorkspace.QE[ 120 ]) ); +acado_setBlockH11( 1, 5, &(acadoWorkspace.E[ 132 ]), &(acadoWorkspace.QE[ 156 ]) ); +acado_setBlockH11( 1, 5, &(acadoWorkspace.E[ 174 ]), &(acadoWorkspace.QE[ 198 ]) ); +acado_setBlockH11( 1, 5, &(acadoWorkspace.E[ 222 ]), &(acadoWorkspace.QE[ 246 ]) ); +acado_setBlockH11( 1, 5, &(acadoWorkspace.E[ 276 ]), &(acadoWorkspace.QE[ 300 ]) ); +acado_setBlockH11( 1, 5, &(acadoWorkspace.E[ 336 ]), &(acadoWorkspace.QE[ 360 ]) ); +acado_setBlockH11( 1, 5, &(acadoWorkspace.E[ 402 ]), &(acadoWorkspace.QE[ 426 ]) ); +acado_setBlockH11( 1, 5, &(acadoWorkspace.E[ 474 ]), &(acadoWorkspace.QE[ 498 ]) ); +acado_setBlockH11( 1, 5, &(acadoWorkspace.E[ 552 ]), &(acadoWorkspace.QE[ 576 ]) ); +acado_setBlockH11( 1, 5, &(acadoWorkspace.E[ 636 ]), &(acadoWorkspace.QE[ 660 ]) ); +acado_setBlockH11( 1, 5, &(acadoWorkspace.E[ 726 ]), &(acadoWorkspace.QE[ 750 ]) ); +acado_setBlockH11( 1, 5, &(acadoWorkspace.E[ 822 ]), &(acadoWorkspace.QE[ 846 ]) ); +acado_setBlockH11( 1, 5, &(acadoWorkspace.E[ 924 ]), &(acadoWorkspace.QE[ 948 ]) ); +acado_setBlockH11( 1, 5, &(acadoWorkspace.E[ 1032 ]), &(acadoWorkspace.QE[ 1056 ]) ); +acado_setBlockH11( 1, 5, &(acadoWorkspace.E[ 1146 ]), &(acadoWorkspace.QE[ 1170 ]) ); + +acado_zeroBlockH11( 1, 6 ); +acado_setBlockH11( 1, 6, &(acadoWorkspace.E[ 132 ]), &(acadoWorkspace.QE[ 162 ]) ); +acado_setBlockH11( 1, 6, &(acadoWorkspace.E[ 174 ]), &(acadoWorkspace.QE[ 204 ]) ); +acado_setBlockH11( 1, 6, &(acadoWorkspace.E[ 222 ]), &(acadoWorkspace.QE[ 252 ]) ); +acado_setBlockH11( 1, 6, &(acadoWorkspace.E[ 276 ]), &(acadoWorkspace.QE[ 306 ]) ); +acado_setBlockH11( 1, 6, &(acadoWorkspace.E[ 336 ]), &(acadoWorkspace.QE[ 366 ]) ); +acado_setBlockH11( 1, 6, &(acadoWorkspace.E[ 402 ]), &(acadoWorkspace.QE[ 432 ]) ); +acado_setBlockH11( 1, 6, &(acadoWorkspace.E[ 474 ]), &(acadoWorkspace.QE[ 504 ]) ); +acado_setBlockH11( 1, 6, &(acadoWorkspace.E[ 552 ]), &(acadoWorkspace.QE[ 582 ]) ); +acado_setBlockH11( 1, 6, &(acadoWorkspace.E[ 636 ]), &(acadoWorkspace.QE[ 666 ]) ); +acado_setBlockH11( 1, 6, &(acadoWorkspace.E[ 726 ]), &(acadoWorkspace.QE[ 756 ]) ); +acado_setBlockH11( 1, 6, &(acadoWorkspace.E[ 822 ]), &(acadoWorkspace.QE[ 852 ]) ); +acado_setBlockH11( 1, 6, &(acadoWorkspace.E[ 924 ]), &(acadoWorkspace.QE[ 954 ]) ); +acado_setBlockH11( 1, 6, &(acadoWorkspace.E[ 1032 ]), &(acadoWorkspace.QE[ 1062 ]) ); +acado_setBlockH11( 1, 6, &(acadoWorkspace.E[ 1146 ]), &(acadoWorkspace.QE[ 1176 ]) ); + +acado_zeroBlockH11( 1, 7 ); +acado_setBlockH11( 1, 7, &(acadoWorkspace.E[ 174 ]), &(acadoWorkspace.QE[ 210 ]) ); +acado_setBlockH11( 1, 7, &(acadoWorkspace.E[ 222 ]), &(acadoWorkspace.QE[ 258 ]) ); +acado_setBlockH11( 1, 7, &(acadoWorkspace.E[ 276 ]), &(acadoWorkspace.QE[ 312 ]) ); +acado_setBlockH11( 1, 7, &(acadoWorkspace.E[ 336 ]), &(acadoWorkspace.QE[ 372 ]) ); +acado_setBlockH11( 1, 7, &(acadoWorkspace.E[ 402 ]), &(acadoWorkspace.QE[ 438 ]) ); +acado_setBlockH11( 1, 7, &(acadoWorkspace.E[ 474 ]), &(acadoWorkspace.QE[ 510 ]) ); +acado_setBlockH11( 1, 7, &(acadoWorkspace.E[ 552 ]), &(acadoWorkspace.QE[ 588 ]) ); +acado_setBlockH11( 1, 7, &(acadoWorkspace.E[ 636 ]), &(acadoWorkspace.QE[ 672 ]) ); +acado_setBlockH11( 1, 7, &(acadoWorkspace.E[ 726 ]), &(acadoWorkspace.QE[ 762 ]) ); +acado_setBlockH11( 1, 7, &(acadoWorkspace.E[ 822 ]), &(acadoWorkspace.QE[ 858 ]) ); +acado_setBlockH11( 1, 7, &(acadoWorkspace.E[ 924 ]), &(acadoWorkspace.QE[ 960 ]) ); +acado_setBlockH11( 1, 7, &(acadoWorkspace.E[ 1032 ]), &(acadoWorkspace.QE[ 1068 ]) ); +acado_setBlockH11( 1, 7, &(acadoWorkspace.E[ 1146 ]), &(acadoWorkspace.QE[ 1182 ]) ); + +acado_zeroBlockH11( 1, 8 ); +acado_setBlockH11( 1, 8, &(acadoWorkspace.E[ 222 ]), &(acadoWorkspace.QE[ 264 ]) ); +acado_setBlockH11( 1, 8, &(acadoWorkspace.E[ 276 ]), &(acadoWorkspace.QE[ 318 ]) ); +acado_setBlockH11( 1, 8, &(acadoWorkspace.E[ 336 ]), &(acadoWorkspace.QE[ 378 ]) ); +acado_setBlockH11( 1, 8, &(acadoWorkspace.E[ 402 ]), &(acadoWorkspace.QE[ 444 ]) ); +acado_setBlockH11( 1, 8, &(acadoWorkspace.E[ 474 ]), &(acadoWorkspace.QE[ 516 ]) ); +acado_setBlockH11( 1, 8, &(acadoWorkspace.E[ 552 ]), &(acadoWorkspace.QE[ 594 ]) ); +acado_setBlockH11( 1, 8, &(acadoWorkspace.E[ 636 ]), &(acadoWorkspace.QE[ 678 ]) ); +acado_setBlockH11( 1, 8, &(acadoWorkspace.E[ 726 ]), &(acadoWorkspace.QE[ 768 ]) ); +acado_setBlockH11( 1, 8, &(acadoWorkspace.E[ 822 ]), &(acadoWorkspace.QE[ 864 ]) ); +acado_setBlockH11( 1, 8, &(acadoWorkspace.E[ 924 ]), &(acadoWorkspace.QE[ 966 ]) ); +acado_setBlockH11( 1, 8, &(acadoWorkspace.E[ 1032 ]), &(acadoWorkspace.QE[ 1074 ]) ); +acado_setBlockH11( 1, 8, &(acadoWorkspace.E[ 1146 ]), &(acadoWorkspace.QE[ 1188 ]) ); + +acado_zeroBlockH11( 1, 9 ); +acado_setBlockH11( 1, 9, &(acadoWorkspace.E[ 276 ]), &(acadoWorkspace.QE[ 324 ]) ); +acado_setBlockH11( 1, 9, &(acadoWorkspace.E[ 336 ]), &(acadoWorkspace.QE[ 384 ]) ); +acado_setBlockH11( 1, 9, &(acadoWorkspace.E[ 402 ]), &(acadoWorkspace.QE[ 450 ]) ); +acado_setBlockH11( 1, 9, &(acadoWorkspace.E[ 474 ]), &(acadoWorkspace.QE[ 522 ]) ); +acado_setBlockH11( 1, 9, &(acadoWorkspace.E[ 552 ]), &(acadoWorkspace.QE[ 600 ]) ); +acado_setBlockH11( 1, 9, &(acadoWorkspace.E[ 636 ]), &(acadoWorkspace.QE[ 684 ]) ); +acado_setBlockH11( 1, 9, &(acadoWorkspace.E[ 726 ]), &(acadoWorkspace.QE[ 774 ]) ); +acado_setBlockH11( 1, 9, &(acadoWorkspace.E[ 822 ]), &(acadoWorkspace.QE[ 870 ]) ); +acado_setBlockH11( 1, 9, &(acadoWorkspace.E[ 924 ]), &(acadoWorkspace.QE[ 972 ]) ); +acado_setBlockH11( 1, 9, &(acadoWorkspace.E[ 1032 ]), &(acadoWorkspace.QE[ 1080 ]) ); +acado_setBlockH11( 1, 9, &(acadoWorkspace.E[ 1146 ]), &(acadoWorkspace.QE[ 1194 ]) ); + +acado_zeroBlockH11( 1, 10 ); +acado_setBlockH11( 1, 10, &(acadoWorkspace.E[ 336 ]), &(acadoWorkspace.QE[ 390 ]) ); +acado_setBlockH11( 1, 10, &(acadoWorkspace.E[ 402 ]), &(acadoWorkspace.QE[ 456 ]) ); +acado_setBlockH11( 1, 10, &(acadoWorkspace.E[ 474 ]), &(acadoWorkspace.QE[ 528 ]) ); +acado_setBlockH11( 1, 10, &(acadoWorkspace.E[ 552 ]), &(acadoWorkspace.QE[ 606 ]) ); +acado_setBlockH11( 1, 10, &(acadoWorkspace.E[ 636 ]), &(acadoWorkspace.QE[ 690 ]) ); +acado_setBlockH11( 1, 10, &(acadoWorkspace.E[ 726 ]), &(acadoWorkspace.QE[ 780 ]) ); +acado_setBlockH11( 1, 10, &(acadoWorkspace.E[ 822 ]), &(acadoWorkspace.QE[ 876 ]) ); +acado_setBlockH11( 1, 10, &(acadoWorkspace.E[ 924 ]), &(acadoWorkspace.QE[ 978 ]) ); +acado_setBlockH11( 1, 10, &(acadoWorkspace.E[ 1032 ]), &(acadoWorkspace.QE[ 1086 ]) ); +acado_setBlockH11( 1, 10, &(acadoWorkspace.E[ 1146 ]), &(acadoWorkspace.QE[ 1200 ]) ); + +acado_zeroBlockH11( 1, 11 ); +acado_setBlockH11( 1, 11, &(acadoWorkspace.E[ 402 ]), &(acadoWorkspace.QE[ 462 ]) ); +acado_setBlockH11( 1, 11, &(acadoWorkspace.E[ 474 ]), &(acadoWorkspace.QE[ 534 ]) ); +acado_setBlockH11( 1, 11, &(acadoWorkspace.E[ 552 ]), &(acadoWorkspace.QE[ 612 ]) ); +acado_setBlockH11( 1, 11, &(acadoWorkspace.E[ 636 ]), &(acadoWorkspace.QE[ 696 ]) ); +acado_setBlockH11( 1, 11, &(acadoWorkspace.E[ 726 ]), &(acadoWorkspace.QE[ 786 ]) ); +acado_setBlockH11( 1, 11, &(acadoWorkspace.E[ 822 ]), &(acadoWorkspace.QE[ 882 ]) ); +acado_setBlockH11( 1, 11, &(acadoWorkspace.E[ 924 ]), &(acadoWorkspace.QE[ 984 ]) ); +acado_setBlockH11( 1, 11, &(acadoWorkspace.E[ 1032 ]), &(acadoWorkspace.QE[ 1092 ]) ); +acado_setBlockH11( 1, 11, &(acadoWorkspace.E[ 1146 ]), &(acadoWorkspace.QE[ 1206 ]) ); + +acado_zeroBlockH11( 1, 12 ); +acado_setBlockH11( 1, 12, &(acadoWorkspace.E[ 474 ]), &(acadoWorkspace.QE[ 540 ]) ); +acado_setBlockH11( 1, 12, &(acadoWorkspace.E[ 552 ]), &(acadoWorkspace.QE[ 618 ]) ); +acado_setBlockH11( 1, 12, &(acadoWorkspace.E[ 636 ]), &(acadoWorkspace.QE[ 702 ]) ); +acado_setBlockH11( 1, 12, &(acadoWorkspace.E[ 726 ]), &(acadoWorkspace.QE[ 792 ]) ); +acado_setBlockH11( 1, 12, &(acadoWorkspace.E[ 822 ]), &(acadoWorkspace.QE[ 888 ]) ); +acado_setBlockH11( 1, 12, &(acadoWorkspace.E[ 924 ]), &(acadoWorkspace.QE[ 990 ]) ); +acado_setBlockH11( 1, 12, &(acadoWorkspace.E[ 1032 ]), &(acadoWorkspace.QE[ 1098 ]) ); +acado_setBlockH11( 1, 12, &(acadoWorkspace.E[ 1146 ]), &(acadoWorkspace.QE[ 1212 ]) ); + +acado_zeroBlockH11( 1, 13 ); +acado_setBlockH11( 1, 13, &(acadoWorkspace.E[ 552 ]), &(acadoWorkspace.QE[ 624 ]) ); +acado_setBlockH11( 1, 13, &(acadoWorkspace.E[ 636 ]), &(acadoWorkspace.QE[ 708 ]) ); +acado_setBlockH11( 1, 13, &(acadoWorkspace.E[ 726 ]), &(acadoWorkspace.QE[ 798 ]) ); +acado_setBlockH11( 1, 13, &(acadoWorkspace.E[ 822 ]), &(acadoWorkspace.QE[ 894 ]) ); +acado_setBlockH11( 1, 13, &(acadoWorkspace.E[ 924 ]), &(acadoWorkspace.QE[ 996 ]) ); +acado_setBlockH11( 1, 13, &(acadoWorkspace.E[ 1032 ]), &(acadoWorkspace.QE[ 1104 ]) ); +acado_setBlockH11( 1, 13, &(acadoWorkspace.E[ 1146 ]), &(acadoWorkspace.QE[ 1218 ]) ); + +acado_zeroBlockH11( 1, 14 ); +acado_setBlockH11( 1, 14, &(acadoWorkspace.E[ 636 ]), &(acadoWorkspace.QE[ 714 ]) ); +acado_setBlockH11( 1, 14, &(acadoWorkspace.E[ 726 ]), &(acadoWorkspace.QE[ 804 ]) ); +acado_setBlockH11( 1, 14, &(acadoWorkspace.E[ 822 ]), &(acadoWorkspace.QE[ 900 ]) ); +acado_setBlockH11( 1, 14, &(acadoWorkspace.E[ 924 ]), &(acadoWorkspace.QE[ 1002 ]) ); +acado_setBlockH11( 1, 14, &(acadoWorkspace.E[ 1032 ]), &(acadoWorkspace.QE[ 1110 ]) ); +acado_setBlockH11( 1, 14, &(acadoWorkspace.E[ 1146 ]), &(acadoWorkspace.QE[ 1224 ]) ); + +acado_zeroBlockH11( 1, 15 ); +acado_setBlockH11( 1, 15, &(acadoWorkspace.E[ 726 ]), &(acadoWorkspace.QE[ 810 ]) ); +acado_setBlockH11( 1, 15, &(acadoWorkspace.E[ 822 ]), &(acadoWorkspace.QE[ 906 ]) ); +acado_setBlockH11( 1, 15, &(acadoWorkspace.E[ 924 ]), &(acadoWorkspace.QE[ 1008 ]) ); +acado_setBlockH11( 1, 15, &(acadoWorkspace.E[ 1032 ]), &(acadoWorkspace.QE[ 1116 ]) ); +acado_setBlockH11( 1, 15, &(acadoWorkspace.E[ 1146 ]), &(acadoWorkspace.QE[ 1230 ]) ); + +acado_zeroBlockH11( 1, 16 ); +acado_setBlockH11( 1, 16, &(acadoWorkspace.E[ 822 ]), &(acadoWorkspace.QE[ 912 ]) ); +acado_setBlockH11( 1, 16, &(acadoWorkspace.E[ 924 ]), &(acadoWorkspace.QE[ 1014 ]) ); +acado_setBlockH11( 1, 16, &(acadoWorkspace.E[ 1032 ]), &(acadoWorkspace.QE[ 1122 ]) ); +acado_setBlockH11( 1, 16, &(acadoWorkspace.E[ 1146 ]), &(acadoWorkspace.QE[ 1236 ]) ); + +acado_zeroBlockH11( 1, 17 ); +acado_setBlockH11( 1, 17, &(acadoWorkspace.E[ 924 ]), &(acadoWorkspace.QE[ 1020 ]) ); +acado_setBlockH11( 1, 17, &(acadoWorkspace.E[ 1032 ]), &(acadoWorkspace.QE[ 1128 ]) ); +acado_setBlockH11( 1, 17, &(acadoWorkspace.E[ 1146 ]), &(acadoWorkspace.QE[ 1242 ]) ); + +acado_zeroBlockH11( 1, 18 ); +acado_setBlockH11( 1, 18, &(acadoWorkspace.E[ 1032 ]), &(acadoWorkspace.QE[ 1134 ]) ); +acado_setBlockH11( 1, 18, &(acadoWorkspace.E[ 1146 ]), &(acadoWorkspace.QE[ 1248 ]) ); + +acado_zeroBlockH11( 1, 19 ); +acado_setBlockH11( 1, 19, &(acadoWorkspace.E[ 1146 ]), &(acadoWorkspace.QE[ 1254 ]) ); + +acado_setBlockH11_R1( 2, 2, &(acadoWorkspace.R1[ 2 ]) ); +acado_setBlockH11( 2, 2, &(acadoWorkspace.E[ 30 ]), &(acadoWorkspace.QE[ 30 ]) ); +acado_setBlockH11( 2, 2, &(acadoWorkspace.E[ 48 ]), &(acadoWorkspace.QE[ 48 ]) ); +acado_setBlockH11( 2, 2, &(acadoWorkspace.E[ 72 ]), &(acadoWorkspace.QE[ 72 ]) ); +acado_setBlockH11( 2, 2, &(acadoWorkspace.E[ 102 ]), &(acadoWorkspace.QE[ 102 ]) ); +acado_setBlockH11( 2, 2, &(acadoWorkspace.E[ 138 ]), &(acadoWorkspace.QE[ 138 ]) ); +acado_setBlockH11( 2, 2, &(acadoWorkspace.E[ 180 ]), &(acadoWorkspace.QE[ 180 ]) ); +acado_setBlockH11( 2, 2, &(acadoWorkspace.E[ 228 ]), &(acadoWorkspace.QE[ 228 ]) ); +acado_setBlockH11( 2, 2, &(acadoWorkspace.E[ 282 ]), &(acadoWorkspace.QE[ 282 ]) ); +acado_setBlockH11( 2, 2, &(acadoWorkspace.E[ 342 ]), &(acadoWorkspace.QE[ 342 ]) ); +acado_setBlockH11( 2, 2, &(acadoWorkspace.E[ 408 ]), &(acadoWorkspace.QE[ 408 ]) ); +acado_setBlockH11( 2, 2, &(acadoWorkspace.E[ 480 ]), &(acadoWorkspace.QE[ 480 ]) ); +acado_setBlockH11( 2, 2, &(acadoWorkspace.E[ 558 ]), &(acadoWorkspace.QE[ 558 ]) ); +acado_setBlockH11( 2, 2, &(acadoWorkspace.E[ 642 ]), &(acadoWorkspace.QE[ 642 ]) ); +acado_setBlockH11( 2, 2, &(acadoWorkspace.E[ 732 ]), &(acadoWorkspace.QE[ 732 ]) ); +acado_setBlockH11( 2, 2, &(acadoWorkspace.E[ 828 ]), &(acadoWorkspace.QE[ 828 ]) ); +acado_setBlockH11( 2, 2, &(acadoWorkspace.E[ 930 ]), &(acadoWorkspace.QE[ 930 ]) ); +acado_setBlockH11( 2, 2, &(acadoWorkspace.E[ 1038 ]), &(acadoWorkspace.QE[ 1038 ]) ); +acado_setBlockH11( 2, 2, &(acadoWorkspace.E[ 1152 ]), &(acadoWorkspace.QE[ 1152 ]) ); + +acado_zeroBlockH11( 2, 3 ); +acado_setBlockH11( 2, 3, &(acadoWorkspace.E[ 48 ]), &(acadoWorkspace.QE[ 54 ]) ); +acado_setBlockH11( 2, 3, &(acadoWorkspace.E[ 72 ]), &(acadoWorkspace.QE[ 78 ]) ); +acado_setBlockH11( 2, 3, &(acadoWorkspace.E[ 102 ]), &(acadoWorkspace.QE[ 108 ]) ); +acado_setBlockH11( 2, 3, &(acadoWorkspace.E[ 138 ]), &(acadoWorkspace.QE[ 144 ]) ); +acado_setBlockH11( 2, 3, &(acadoWorkspace.E[ 180 ]), &(acadoWorkspace.QE[ 186 ]) ); +acado_setBlockH11( 2, 3, &(acadoWorkspace.E[ 228 ]), &(acadoWorkspace.QE[ 234 ]) ); +acado_setBlockH11( 2, 3, &(acadoWorkspace.E[ 282 ]), &(acadoWorkspace.QE[ 288 ]) ); +acado_setBlockH11( 2, 3, &(acadoWorkspace.E[ 342 ]), &(acadoWorkspace.QE[ 348 ]) ); +acado_setBlockH11( 2, 3, &(acadoWorkspace.E[ 408 ]), &(acadoWorkspace.QE[ 414 ]) ); +acado_setBlockH11( 2, 3, &(acadoWorkspace.E[ 480 ]), &(acadoWorkspace.QE[ 486 ]) ); +acado_setBlockH11( 2, 3, &(acadoWorkspace.E[ 558 ]), &(acadoWorkspace.QE[ 564 ]) ); +acado_setBlockH11( 2, 3, &(acadoWorkspace.E[ 642 ]), &(acadoWorkspace.QE[ 648 ]) ); +acado_setBlockH11( 2, 3, &(acadoWorkspace.E[ 732 ]), &(acadoWorkspace.QE[ 738 ]) ); +acado_setBlockH11( 2, 3, &(acadoWorkspace.E[ 828 ]), &(acadoWorkspace.QE[ 834 ]) ); +acado_setBlockH11( 2, 3, &(acadoWorkspace.E[ 930 ]), &(acadoWorkspace.QE[ 936 ]) ); +acado_setBlockH11( 2, 3, &(acadoWorkspace.E[ 1038 ]), &(acadoWorkspace.QE[ 1044 ]) ); +acado_setBlockH11( 2, 3, &(acadoWorkspace.E[ 1152 ]), &(acadoWorkspace.QE[ 1158 ]) ); + +acado_zeroBlockH11( 2, 4 ); +acado_setBlockH11( 2, 4, &(acadoWorkspace.E[ 72 ]), &(acadoWorkspace.QE[ 84 ]) ); +acado_setBlockH11( 2, 4, &(acadoWorkspace.E[ 102 ]), &(acadoWorkspace.QE[ 114 ]) ); +acado_setBlockH11( 2, 4, &(acadoWorkspace.E[ 138 ]), &(acadoWorkspace.QE[ 150 ]) ); +acado_setBlockH11( 2, 4, &(acadoWorkspace.E[ 180 ]), &(acadoWorkspace.QE[ 192 ]) ); +acado_setBlockH11( 2, 4, &(acadoWorkspace.E[ 228 ]), &(acadoWorkspace.QE[ 240 ]) ); +acado_setBlockH11( 2, 4, &(acadoWorkspace.E[ 282 ]), &(acadoWorkspace.QE[ 294 ]) ); +acado_setBlockH11( 2, 4, &(acadoWorkspace.E[ 342 ]), &(acadoWorkspace.QE[ 354 ]) ); +acado_setBlockH11( 2, 4, &(acadoWorkspace.E[ 408 ]), &(acadoWorkspace.QE[ 420 ]) ); +acado_setBlockH11( 2, 4, &(acadoWorkspace.E[ 480 ]), &(acadoWorkspace.QE[ 492 ]) ); +acado_setBlockH11( 2, 4, &(acadoWorkspace.E[ 558 ]), &(acadoWorkspace.QE[ 570 ]) ); +acado_setBlockH11( 2, 4, &(acadoWorkspace.E[ 642 ]), &(acadoWorkspace.QE[ 654 ]) ); +acado_setBlockH11( 2, 4, &(acadoWorkspace.E[ 732 ]), &(acadoWorkspace.QE[ 744 ]) ); +acado_setBlockH11( 2, 4, &(acadoWorkspace.E[ 828 ]), &(acadoWorkspace.QE[ 840 ]) ); +acado_setBlockH11( 2, 4, &(acadoWorkspace.E[ 930 ]), &(acadoWorkspace.QE[ 942 ]) ); +acado_setBlockH11( 2, 4, &(acadoWorkspace.E[ 1038 ]), &(acadoWorkspace.QE[ 1050 ]) ); +acado_setBlockH11( 2, 4, &(acadoWorkspace.E[ 1152 ]), &(acadoWorkspace.QE[ 1164 ]) ); + +acado_zeroBlockH11( 2, 5 ); +acado_setBlockH11( 2, 5, &(acadoWorkspace.E[ 102 ]), &(acadoWorkspace.QE[ 120 ]) ); +acado_setBlockH11( 2, 5, &(acadoWorkspace.E[ 138 ]), &(acadoWorkspace.QE[ 156 ]) ); +acado_setBlockH11( 2, 5, &(acadoWorkspace.E[ 180 ]), &(acadoWorkspace.QE[ 198 ]) ); +acado_setBlockH11( 2, 5, &(acadoWorkspace.E[ 228 ]), &(acadoWorkspace.QE[ 246 ]) ); +acado_setBlockH11( 2, 5, &(acadoWorkspace.E[ 282 ]), &(acadoWorkspace.QE[ 300 ]) ); +acado_setBlockH11( 2, 5, &(acadoWorkspace.E[ 342 ]), &(acadoWorkspace.QE[ 360 ]) ); +acado_setBlockH11( 2, 5, &(acadoWorkspace.E[ 408 ]), &(acadoWorkspace.QE[ 426 ]) ); +acado_setBlockH11( 2, 5, &(acadoWorkspace.E[ 480 ]), &(acadoWorkspace.QE[ 498 ]) ); +acado_setBlockH11( 2, 5, &(acadoWorkspace.E[ 558 ]), &(acadoWorkspace.QE[ 576 ]) ); +acado_setBlockH11( 2, 5, &(acadoWorkspace.E[ 642 ]), &(acadoWorkspace.QE[ 660 ]) ); +acado_setBlockH11( 2, 5, &(acadoWorkspace.E[ 732 ]), &(acadoWorkspace.QE[ 750 ]) ); +acado_setBlockH11( 2, 5, &(acadoWorkspace.E[ 828 ]), &(acadoWorkspace.QE[ 846 ]) ); +acado_setBlockH11( 2, 5, &(acadoWorkspace.E[ 930 ]), &(acadoWorkspace.QE[ 948 ]) ); +acado_setBlockH11( 2, 5, &(acadoWorkspace.E[ 1038 ]), &(acadoWorkspace.QE[ 1056 ]) ); +acado_setBlockH11( 2, 5, &(acadoWorkspace.E[ 1152 ]), &(acadoWorkspace.QE[ 1170 ]) ); + +acado_zeroBlockH11( 2, 6 ); +acado_setBlockH11( 2, 6, &(acadoWorkspace.E[ 138 ]), &(acadoWorkspace.QE[ 162 ]) ); +acado_setBlockH11( 2, 6, &(acadoWorkspace.E[ 180 ]), &(acadoWorkspace.QE[ 204 ]) ); +acado_setBlockH11( 2, 6, &(acadoWorkspace.E[ 228 ]), &(acadoWorkspace.QE[ 252 ]) ); +acado_setBlockH11( 2, 6, &(acadoWorkspace.E[ 282 ]), &(acadoWorkspace.QE[ 306 ]) ); +acado_setBlockH11( 2, 6, &(acadoWorkspace.E[ 342 ]), &(acadoWorkspace.QE[ 366 ]) ); +acado_setBlockH11( 2, 6, &(acadoWorkspace.E[ 408 ]), &(acadoWorkspace.QE[ 432 ]) ); +acado_setBlockH11( 2, 6, &(acadoWorkspace.E[ 480 ]), &(acadoWorkspace.QE[ 504 ]) ); +acado_setBlockH11( 2, 6, &(acadoWorkspace.E[ 558 ]), &(acadoWorkspace.QE[ 582 ]) ); +acado_setBlockH11( 2, 6, &(acadoWorkspace.E[ 642 ]), &(acadoWorkspace.QE[ 666 ]) ); +acado_setBlockH11( 2, 6, &(acadoWorkspace.E[ 732 ]), &(acadoWorkspace.QE[ 756 ]) ); +acado_setBlockH11( 2, 6, &(acadoWorkspace.E[ 828 ]), &(acadoWorkspace.QE[ 852 ]) ); +acado_setBlockH11( 2, 6, &(acadoWorkspace.E[ 930 ]), &(acadoWorkspace.QE[ 954 ]) ); +acado_setBlockH11( 2, 6, &(acadoWorkspace.E[ 1038 ]), &(acadoWorkspace.QE[ 1062 ]) ); +acado_setBlockH11( 2, 6, &(acadoWorkspace.E[ 1152 ]), &(acadoWorkspace.QE[ 1176 ]) ); + +acado_zeroBlockH11( 2, 7 ); +acado_setBlockH11( 2, 7, &(acadoWorkspace.E[ 180 ]), &(acadoWorkspace.QE[ 210 ]) ); +acado_setBlockH11( 2, 7, &(acadoWorkspace.E[ 228 ]), &(acadoWorkspace.QE[ 258 ]) ); +acado_setBlockH11( 2, 7, &(acadoWorkspace.E[ 282 ]), &(acadoWorkspace.QE[ 312 ]) ); +acado_setBlockH11( 2, 7, &(acadoWorkspace.E[ 342 ]), &(acadoWorkspace.QE[ 372 ]) ); +acado_setBlockH11( 2, 7, &(acadoWorkspace.E[ 408 ]), &(acadoWorkspace.QE[ 438 ]) ); +acado_setBlockH11( 2, 7, &(acadoWorkspace.E[ 480 ]), &(acadoWorkspace.QE[ 510 ]) ); +acado_setBlockH11( 2, 7, &(acadoWorkspace.E[ 558 ]), &(acadoWorkspace.QE[ 588 ]) ); +acado_setBlockH11( 2, 7, &(acadoWorkspace.E[ 642 ]), &(acadoWorkspace.QE[ 672 ]) ); +acado_setBlockH11( 2, 7, &(acadoWorkspace.E[ 732 ]), &(acadoWorkspace.QE[ 762 ]) ); +acado_setBlockH11( 2, 7, &(acadoWorkspace.E[ 828 ]), &(acadoWorkspace.QE[ 858 ]) ); +acado_setBlockH11( 2, 7, &(acadoWorkspace.E[ 930 ]), &(acadoWorkspace.QE[ 960 ]) ); +acado_setBlockH11( 2, 7, &(acadoWorkspace.E[ 1038 ]), &(acadoWorkspace.QE[ 1068 ]) ); +acado_setBlockH11( 2, 7, &(acadoWorkspace.E[ 1152 ]), &(acadoWorkspace.QE[ 1182 ]) ); + +acado_zeroBlockH11( 2, 8 ); +acado_setBlockH11( 2, 8, &(acadoWorkspace.E[ 228 ]), &(acadoWorkspace.QE[ 264 ]) ); +acado_setBlockH11( 2, 8, &(acadoWorkspace.E[ 282 ]), &(acadoWorkspace.QE[ 318 ]) ); +acado_setBlockH11( 2, 8, &(acadoWorkspace.E[ 342 ]), &(acadoWorkspace.QE[ 378 ]) ); +acado_setBlockH11( 2, 8, &(acadoWorkspace.E[ 408 ]), &(acadoWorkspace.QE[ 444 ]) ); +acado_setBlockH11( 2, 8, &(acadoWorkspace.E[ 480 ]), &(acadoWorkspace.QE[ 516 ]) ); +acado_setBlockH11( 2, 8, &(acadoWorkspace.E[ 558 ]), &(acadoWorkspace.QE[ 594 ]) ); +acado_setBlockH11( 2, 8, &(acadoWorkspace.E[ 642 ]), &(acadoWorkspace.QE[ 678 ]) ); +acado_setBlockH11( 2, 8, &(acadoWorkspace.E[ 732 ]), &(acadoWorkspace.QE[ 768 ]) ); +acado_setBlockH11( 2, 8, &(acadoWorkspace.E[ 828 ]), &(acadoWorkspace.QE[ 864 ]) ); +acado_setBlockH11( 2, 8, &(acadoWorkspace.E[ 930 ]), &(acadoWorkspace.QE[ 966 ]) ); +acado_setBlockH11( 2, 8, &(acadoWorkspace.E[ 1038 ]), &(acadoWorkspace.QE[ 1074 ]) ); +acado_setBlockH11( 2, 8, &(acadoWorkspace.E[ 1152 ]), &(acadoWorkspace.QE[ 1188 ]) ); + +acado_zeroBlockH11( 2, 9 ); +acado_setBlockH11( 2, 9, &(acadoWorkspace.E[ 282 ]), &(acadoWorkspace.QE[ 324 ]) ); +acado_setBlockH11( 2, 9, &(acadoWorkspace.E[ 342 ]), &(acadoWorkspace.QE[ 384 ]) ); +acado_setBlockH11( 2, 9, &(acadoWorkspace.E[ 408 ]), &(acadoWorkspace.QE[ 450 ]) ); +acado_setBlockH11( 2, 9, &(acadoWorkspace.E[ 480 ]), &(acadoWorkspace.QE[ 522 ]) ); +acado_setBlockH11( 2, 9, &(acadoWorkspace.E[ 558 ]), &(acadoWorkspace.QE[ 600 ]) ); +acado_setBlockH11( 2, 9, &(acadoWorkspace.E[ 642 ]), &(acadoWorkspace.QE[ 684 ]) ); +acado_setBlockH11( 2, 9, &(acadoWorkspace.E[ 732 ]), &(acadoWorkspace.QE[ 774 ]) ); +acado_setBlockH11( 2, 9, &(acadoWorkspace.E[ 828 ]), &(acadoWorkspace.QE[ 870 ]) ); +acado_setBlockH11( 2, 9, &(acadoWorkspace.E[ 930 ]), &(acadoWorkspace.QE[ 972 ]) ); +acado_setBlockH11( 2, 9, &(acadoWorkspace.E[ 1038 ]), &(acadoWorkspace.QE[ 1080 ]) ); +acado_setBlockH11( 2, 9, &(acadoWorkspace.E[ 1152 ]), &(acadoWorkspace.QE[ 1194 ]) ); + +acado_zeroBlockH11( 2, 10 ); +acado_setBlockH11( 2, 10, &(acadoWorkspace.E[ 342 ]), &(acadoWorkspace.QE[ 390 ]) ); +acado_setBlockH11( 2, 10, &(acadoWorkspace.E[ 408 ]), &(acadoWorkspace.QE[ 456 ]) ); +acado_setBlockH11( 2, 10, &(acadoWorkspace.E[ 480 ]), &(acadoWorkspace.QE[ 528 ]) ); +acado_setBlockH11( 2, 10, &(acadoWorkspace.E[ 558 ]), &(acadoWorkspace.QE[ 606 ]) ); +acado_setBlockH11( 2, 10, &(acadoWorkspace.E[ 642 ]), &(acadoWorkspace.QE[ 690 ]) ); +acado_setBlockH11( 2, 10, &(acadoWorkspace.E[ 732 ]), &(acadoWorkspace.QE[ 780 ]) ); +acado_setBlockH11( 2, 10, &(acadoWorkspace.E[ 828 ]), &(acadoWorkspace.QE[ 876 ]) ); +acado_setBlockH11( 2, 10, &(acadoWorkspace.E[ 930 ]), &(acadoWorkspace.QE[ 978 ]) ); +acado_setBlockH11( 2, 10, &(acadoWorkspace.E[ 1038 ]), &(acadoWorkspace.QE[ 1086 ]) ); +acado_setBlockH11( 2, 10, &(acadoWorkspace.E[ 1152 ]), &(acadoWorkspace.QE[ 1200 ]) ); + +acado_zeroBlockH11( 2, 11 ); +acado_setBlockH11( 2, 11, &(acadoWorkspace.E[ 408 ]), &(acadoWorkspace.QE[ 462 ]) ); +acado_setBlockH11( 2, 11, &(acadoWorkspace.E[ 480 ]), &(acadoWorkspace.QE[ 534 ]) ); +acado_setBlockH11( 2, 11, &(acadoWorkspace.E[ 558 ]), &(acadoWorkspace.QE[ 612 ]) ); +acado_setBlockH11( 2, 11, &(acadoWorkspace.E[ 642 ]), &(acadoWorkspace.QE[ 696 ]) ); +acado_setBlockH11( 2, 11, &(acadoWorkspace.E[ 732 ]), &(acadoWorkspace.QE[ 786 ]) ); +acado_setBlockH11( 2, 11, &(acadoWorkspace.E[ 828 ]), &(acadoWorkspace.QE[ 882 ]) ); +acado_setBlockH11( 2, 11, &(acadoWorkspace.E[ 930 ]), &(acadoWorkspace.QE[ 984 ]) ); +acado_setBlockH11( 2, 11, &(acadoWorkspace.E[ 1038 ]), &(acadoWorkspace.QE[ 1092 ]) ); +acado_setBlockH11( 2, 11, &(acadoWorkspace.E[ 1152 ]), &(acadoWorkspace.QE[ 1206 ]) ); + +acado_zeroBlockH11( 2, 12 ); +acado_setBlockH11( 2, 12, &(acadoWorkspace.E[ 480 ]), &(acadoWorkspace.QE[ 540 ]) ); +acado_setBlockH11( 2, 12, &(acadoWorkspace.E[ 558 ]), &(acadoWorkspace.QE[ 618 ]) ); +acado_setBlockH11( 2, 12, &(acadoWorkspace.E[ 642 ]), &(acadoWorkspace.QE[ 702 ]) ); +acado_setBlockH11( 2, 12, &(acadoWorkspace.E[ 732 ]), &(acadoWorkspace.QE[ 792 ]) ); +acado_setBlockH11( 2, 12, &(acadoWorkspace.E[ 828 ]), &(acadoWorkspace.QE[ 888 ]) ); +acado_setBlockH11( 2, 12, &(acadoWorkspace.E[ 930 ]), &(acadoWorkspace.QE[ 990 ]) ); +acado_setBlockH11( 2, 12, &(acadoWorkspace.E[ 1038 ]), &(acadoWorkspace.QE[ 1098 ]) ); +acado_setBlockH11( 2, 12, &(acadoWorkspace.E[ 1152 ]), &(acadoWorkspace.QE[ 1212 ]) ); + +acado_zeroBlockH11( 2, 13 ); +acado_setBlockH11( 2, 13, &(acadoWorkspace.E[ 558 ]), &(acadoWorkspace.QE[ 624 ]) ); +acado_setBlockH11( 2, 13, &(acadoWorkspace.E[ 642 ]), &(acadoWorkspace.QE[ 708 ]) ); +acado_setBlockH11( 2, 13, &(acadoWorkspace.E[ 732 ]), &(acadoWorkspace.QE[ 798 ]) ); +acado_setBlockH11( 2, 13, &(acadoWorkspace.E[ 828 ]), &(acadoWorkspace.QE[ 894 ]) ); +acado_setBlockH11( 2, 13, &(acadoWorkspace.E[ 930 ]), &(acadoWorkspace.QE[ 996 ]) ); +acado_setBlockH11( 2, 13, &(acadoWorkspace.E[ 1038 ]), &(acadoWorkspace.QE[ 1104 ]) ); +acado_setBlockH11( 2, 13, &(acadoWorkspace.E[ 1152 ]), &(acadoWorkspace.QE[ 1218 ]) ); + +acado_zeroBlockH11( 2, 14 ); +acado_setBlockH11( 2, 14, &(acadoWorkspace.E[ 642 ]), &(acadoWorkspace.QE[ 714 ]) ); +acado_setBlockH11( 2, 14, &(acadoWorkspace.E[ 732 ]), &(acadoWorkspace.QE[ 804 ]) ); +acado_setBlockH11( 2, 14, &(acadoWorkspace.E[ 828 ]), &(acadoWorkspace.QE[ 900 ]) ); +acado_setBlockH11( 2, 14, &(acadoWorkspace.E[ 930 ]), &(acadoWorkspace.QE[ 1002 ]) ); +acado_setBlockH11( 2, 14, &(acadoWorkspace.E[ 1038 ]), &(acadoWorkspace.QE[ 1110 ]) ); +acado_setBlockH11( 2, 14, &(acadoWorkspace.E[ 1152 ]), &(acadoWorkspace.QE[ 1224 ]) ); + +acado_zeroBlockH11( 2, 15 ); +acado_setBlockH11( 2, 15, &(acadoWorkspace.E[ 732 ]), &(acadoWorkspace.QE[ 810 ]) ); +acado_setBlockH11( 2, 15, &(acadoWorkspace.E[ 828 ]), &(acadoWorkspace.QE[ 906 ]) ); +acado_setBlockH11( 2, 15, &(acadoWorkspace.E[ 930 ]), &(acadoWorkspace.QE[ 1008 ]) ); +acado_setBlockH11( 2, 15, &(acadoWorkspace.E[ 1038 ]), &(acadoWorkspace.QE[ 1116 ]) ); +acado_setBlockH11( 2, 15, &(acadoWorkspace.E[ 1152 ]), &(acadoWorkspace.QE[ 1230 ]) ); + +acado_zeroBlockH11( 2, 16 ); +acado_setBlockH11( 2, 16, &(acadoWorkspace.E[ 828 ]), &(acadoWorkspace.QE[ 912 ]) ); +acado_setBlockH11( 2, 16, &(acadoWorkspace.E[ 930 ]), &(acadoWorkspace.QE[ 1014 ]) ); +acado_setBlockH11( 2, 16, &(acadoWorkspace.E[ 1038 ]), &(acadoWorkspace.QE[ 1122 ]) ); +acado_setBlockH11( 2, 16, &(acadoWorkspace.E[ 1152 ]), &(acadoWorkspace.QE[ 1236 ]) ); + +acado_zeroBlockH11( 2, 17 ); +acado_setBlockH11( 2, 17, &(acadoWorkspace.E[ 930 ]), &(acadoWorkspace.QE[ 1020 ]) ); +acado_setBlockH11( 2, 17, &(acadoWorkspace.E[ 1038 ]), &(acadoWorkspace.QE[ 1128 ]) ); +acado_setBlockH11( 2, 17, &(acadoWorkspace.E[ 1152 ]), &(acadoWorkspace.QE[ 1242 ]) ); + +acado_zeroBlockH11( 2, 18 ); +acado_setBlockH11( 2, 18, &(acadoWorkspace.E[ 1038 ]), &(acadoWorkspace.QE[ 1134 ]) ); +acado_setBlockH11( 2, 18, &(acadoWorkspace.E[ 1152 ]), &(acadoWorkspace.QE[ 1248 ]) ); + +acado_zeroBlockH11( 2, 19 ); +acado_setBlockH11( 2, 19, &(acadoWorkspace.E[ 1152 ]), &(acadoWorkspace.QE[ 1254 ]) ); + +acado_setBlockH11_R1( 3, 3, &(acadoWorkspace.R1[ 3 ]) ); +acado_setBlockH11( 3, 3, &(acadoWorkspace.E[ 54 ]), &(acadoWorkspace.QE[ 54 ]) ); +acado_setBlockH11( 3, 3, &(acadoWorkspace.E[ 78 ]), &(acadoWorkspace.QE[ 78 ]) ); +acado_setBlockH11( 3, 3, &(acadoWorkspace.E[ 108 ]), &(acadoWorkspace.QE[ 108 ]) ); +acado_setBlockH11( 3, 3, &(acadoWorkspace.E[ 144 ]), &(acadoWorkspace.QE[ 144 ]) ); +acado_setBlockH11( 3, 3, &(acadoWorkspace.E[ 186 ]), &(acadoWorkspace.QE[ 186 ]) ); +acado_setBlockH11( 3, 3, &(acadoWorkspace.E[ 234 ]), &(acadoWorkspace.QE[ 234 ]) ); +acado_setBlockH11( 3, 3, &(acadoWorkspace.E[ 288 ]), &(acadoWorkspace.QE[ 288 ]) ); +acado_setBlockH11( 3, 3, &(acadoWorkspace.E[ 348 ]), &(acadoWorkspace.QE[ 348 ]) ); +acado_setBlockH11( 3, 3, &(acadoWorkspace.E[ 414 ]), &(acadoWorkspace.QE[ 414 ]) ); +acado_setBlockH11( 3, 3, &(acadoWorkspace.E[ 486 ]), &(acadoWorkspace.QE[ 486 ]) ); +acado_setBlockH11( 3, 3, &(acadoWorkspace.E[ 564 ]), &(acadoWorkspace.QE[ 564 ]) ); +acado_setBlockH11( 3, 3, &(acadoWorkspace.E[ 648 ]), &(acadoWorkspace.QE[ 648 ]) ); +acado_setBlockH11( 3, 3, &(acadoWorkspace.E[ 738 ]), &(acadoWorkspace.QE[ 738 ]) ); +acado_setBlockH11( 3, 3, &(acadoWorkspace.E[ 834 ]), &(acadoWorkspace.QE[ 834 ]) ); +acado_setBlockH11( 3, 3, &(acadoWorkspace.E[ 936 ]), &(acadoWorkspace.QE[ 936 ]) ); +acado_setBlockH11( 3, 3, &(acadoWorkspace.E[ 1044 ]), &(acadoWorkspace.QE[ 1044 ]) ); +acado_setBlockH11( 3, 3, &(acadoWorkspace.E[ 1158 ]), &(acadoWorkspace.QE[ 1158 ]) ); + +acado_zeroBlockH11( 3, 4 ); +acado_setBlockH11( 3, 4, &(acadoWorkspace.E[ 78 ]), &(acadoWorkspace.QE[ 84 ]) ); +acado_setBlockH11( 3, 4, &(acadoWorkspace.E[ 108 ]), &(acadoWorkspace.QE[ 114 ]) ); +acado_setBlockH11( 3, 4, &(acadoWorkspace.E[ 144 ]), &(acadoWorkspace.QE[ 150 ]) ); +acado_setBlockH11( 3, 4, &(acadoWorkspace.E[ 186 ]), &(acadoWorkspace.QE[ 192 ]) ); +acado_setBlockH11( 3, 4, &(acadoWorkspace.E[ 234 ]), &(acadoWorkspace.QE[ 240 ]) ); +acado_setBlockH11( 3, 4, &(acadoWorkspace.E[ 288 ]), &(acadoWorkspace.QE[ 294 ]) ); +acado_setBlockH11( 3, 4, &(acadoWorkspace.E[ 348 ]), &(acadoWorkspace.QE[ 354 ]) ); +acado_setBlockH11( 3, 4, &(acadoWorkspace.E[ 414 ]), &(acadoWorkspace.QE[ 420 ]) ); +acado_setBlockH11( 3, 4, &(acadoWorkspace.E[ 486 ]), &(acadoWorkspace.QE[ 492 ]) ); +acado_setBlockH11( 3, 4, &(acadoWorkspace.E[ 564 ]), &(acadoWorkspace.QE[ 570 ]) ); +acado_setBlockH11( 3, 4, &(acadoWorkspace.E[ 648 ]), &(acadoWorkspace.QE[ 654 ]) ); +acado_setBlockH11( 3, 4, &(acadoWorkspace.E[ 738 ]), &(acadoWorkspace.QE[ 744 ]) ); +acado_setBlockH11( 3, 4, &(acadoWorkspace.E[ 834 ]), &(acadoWorkspace.QE[ 840 ]) ); +acado_setBlockH11( 3, 4, &(acadoWorkspace.E[ 936 ]), &(acadoWorkspace.QE[ 942 ]) ); +acado_setBlockH11( 3, 4, &(acadoWorkspace.E[ 1044 ]), &(acadoWorkspace.QE[ 1050 ]) ); +acado_setBlockH11( 3, 4, &(acadoWorkspace.E[ 1158 ]), &(acadoWorkspace.QE[ 1164 ]) ); + +acado_zeroBlockH11( 3, 5 ); +acado_setBlockH11( 3, 5, &(acadoWorkspace.E[ 108 ]), &(acadoWorkspace.QE[ 120 ]) ); +acado_setBlockH11( 3, 5, &(acadoWorkspace.E[ 144 ]), &(acadoWorkspace.QE[ 156 ]) ); +acado_setBlockH11( 3, 5, &(acadoWorkspace.E[ 186 ]), &(acadoWorkspace.QE[ 198 ]) ); +acado_setBlockH11( 3, 5, &(acadoWorkspace.E[ 234 ]), &(acadoWorkspace.QE[ 246 ]) ); +acado_setBlockH11( 3, 5, &(acadoWorkspace.E[ 288 ]), &(acadoWorkspace.QE[ 300 ]) ); +acado_setBlockH11( 3, 5, &(acadoWorkspace.E[ 348 ]), &(acadoWorkspace.QE[ 360 ]) ); +acado_setBlockH11( 3, 5, &(acadoWorkspace.E[ 414 ]), &(acadoWorkspace.QE[ 426 ]) ); +acado_setBlockH11( 3, 5, &(acadoWorkspace.E[ 486 ]), &(acadoWorkspace.QE[ 498 ]) ); +acado_setBlockH11( 3, 5, &(acadoWorkspace.E[ 564 ]), &(acadoWorkspace.QE[ 576 ]) ); +acado_setBlockH11( 3, 5, &(acadoWorkspace.E[ 648 ]), &(acadoWorkspace.QE[ 660 ]) ); +acado_setBlockH11( 3, 5, &(acadoWorkspace.E[ 738 ]), &(acadoWorkspace.QE[ 750 ]) ); +acado_setBlockH11( 3, 5, &(acadoWorkspace.E[ 834 ]), &(acadoWorkspace.QE[ 846 ]) ); +acado_setBlockH11( 3, 5, &(acadoWorkspace.E[ 936 ]), &(acadoWorkspace.QE[ 948 ]) ); +acado_setBlockH11( 3, 5, &(acadoWorkspace.E[ 1044 ]), &(acadoWorkspace.QE[ 1056 ]) ); +acado_setBlockH11( 3, 5, &(acadoWorkspace.E[ 1158 ]), &(acadoWorkspace.QE[ 1170 ]) ); + +acado_zeroBlockH11( 3, 6 ); +acado_setBlockH11( 3, 6, &(acadoWorkspace.E[ 144 ]), &(acadoWorkspace.QE[ 162 ]) ); +acado_setBlockH11( 3, 6, &(acadoWorkspace.E[ 186 ]), &(acadoWorkspace.QE[ 204 ]) ); +acado_setBlockH11( 3, 6, &(acadoWorkspace.E[ 234 ]), &(acadoWorkspace.QE[ 252 ]) ); +acado_setBlockH11( 3, 6, &(acadoWorkspace.E[ 288 ]), &(acadoWorkspace.QE[ 306 ]) ); +acado_setBlockH11( 3, 6, &(acadoWorkspace.E[ 348 ]), &(acadoWorkspace.QE[ 366 ]) ); +acado_setBlockH11( 3, 6, &(acadoWorkspace.E[ 414 ]), &(acadoWorkspace.QE[ 432 ]) ); +acado_setBlockH11( 3, 6, &(acadoWorkspace.E[ 486 ]), &(acadoWorkspace.QE[ 504 ]) ); +acado_setBlockH11( 3, 6, &(acadoWorkspace.E[ 564 ]), &(acadoWorkspace.QE[ 582 ]) ); +acado_setBlockH11( 3, 6, &(acadoWorkspace.E[ 648 ]), &(acadoWorkspace.QE[ 666 ]) ); +acado_setBlockH11( 3, 6, &(acadoWorkspace.E[ 738 ]), &(acadoWorkspace.QE[ 756 ]) ); +acado_setBlockH11( 3, 6, &(acadoWorkspace.E[ 834 ]), &(acadoWorkspace.QE[ 852 ]) ); +acado_setBlockH11( 3, 6, &(acadoWorkspace.E[ 936 ]), &(acadoWorkspace.QE[ 954 ]) ); +acado_setBlockH11( 3, 6, &(acadoWorkspace.E[ 1044 ]), &(acadoWorkspace.QE[ 1062 ]) ); +acado_setBlockH11( 3, 6, &(acadoWorkspace.E[ 1158 ]), &(acadoWorkspace.QE[ 1176 ]) ); + +acado_zeroBlockH11( 3, 7 ); +acado_setBlockH11( 3, 7, &(acadoWorkspace.E[ 186 ]), &(acadoWorkspace.QE[ 210 ]) ); +acado_setBlockH11( 3, 7, &(acadoWorkspace.E[ 234 ]), &(acadoWorkspace.QE[ 258 ]) ); +acado_setBlockH11( 3, 7, &(acadoWorkspace.E[ 288 ]), &(acadoWorkspace.QE[ 312 ]) ); +acado_setBlockH11( 3, 7, &(acadoWorkspace.E[ 348 ]), &(acadoWorkspace.QE[ 372 ]) ); +acado_setBlockH11( 3, 7, &(acadoWorkspace.E[ 414 ]), &(acadoWorkspace.QE[ 438 ]) ); +acado_setBlockH11( 3, 7, &(acadoWorkspace.E[ 486 ]), &(acadoWorkspace.QE[ 510 ]) ); +acado_setBlockH11( 3, 7, &(acadoWorkspace.E[ 564 ]), &(acadoWorkspace.QE[ 588 ]) ); +acado_setBlockH11( 3, 7, &(acadoWorkspace.E[ 648 ]), &(acadoWorkspace.QE[ 672 ]) ); +acado_setBlockH11( 3, 7, &(acadoWorkspace.E[ 738 ]), &(acadoWorkspace.QE[ 762 ]) ); +acado_setBlockH11( 3, 7, &(acadoWorkspace.E[ 834 ]), &(acadoWorkspace.QE[ 858 ]) ); +acado_setBlockH11( 3, 7, &(acadoWorkspace.E[ 936 ]), &(acadoWorkspace.QE[ 960 ]) ); +acado_setBlockH11( 3, 7, &(acadoWorkspace.E[ 1044 ]), &(acadoWorkspace.QE[ 1068 ]) ); +acado_setBlockH11( 3, 7, &(acadoWorkspace.E[ 1158 ]), &(acadoWorkspace.QE[ 1182 ]) ); + +acado_zeroBlockH11( 3, 8 ); +acado_setBlockH11( 3, 8, &(acadoWorkspace.E[ 234 ]), &(acadoWorkspace.QE[ 264 ]) ); +acado_setBlockH11( 3, 8, &(acadoWorkspace.E[ 288 ]), &(acadoWorkspace.QE[ 318 ]) ); +acado_setBlockH11( 3, 8, &(acadoWorkspace.E[ 348 ]), &(acadoWorkspace.QE[ 378 ]) ); +acado_setBlockH11( 3, 8, &(acadoWorkspace.E[ 414 ]), &(acadoWorkspace.QE[ 444 ]) ); +acado_setBlockH11( 3, 8, &(acadoWorkspace.E[ 486 ]), &(acadoWorkspace.QE[ 516 ]) ); +acado_setBlockH11( 3, 8, &(acadoWorkspace.E[ 564 ]), &(acadoWorkspace.QE[ 594 ]) ); +acado_setBlockH11( 3, 8, &(acadoWorkspace.E[ 648 ]), &(acadoWorkspace.QE[ 678 ]) ); +acado_setBlockH11( 3, 8, &(acadoWorkspace.E[ 738 ]), &(acadoWorkspace.QE[ 768 ]) ); +acado_setBlockH11( 3, 8, &(acadoWorkspace.E[ 834 ]), &(acadoWorkspace.QE[ 864 ]) ); +acado_setBlockH11( 3, 8, &(acadoWorkspace.E[ 936 ]), &(acadoWorkspace.QE[ 966 ]) ); +acado_setBlockH11( 3, 8, &(acadoWorkspace.E[ 1044 ]), &(acadoWorkspace.QE[ 1074 ]) ); +acado_setBlockH11( 3, 8, &(acadoWorkspace.E[ 1158 ]), &(acadoWorkspace.QE[ 1188 ]) ); + +acado_zeroBlockH11( 3, 9 ); +acado_setBlockH11( 3, 9, &(acadoWorkspace.E[ 288 ]), &(acadoWorkspace.QE[ 324 ]) ); +acado_setBlockH11( 3, 9, &(acadoWorkspace.E[ 348 ]), &(acadoWorkspace.QE[ 384 ]) ); +acado_setBlockH11( 3, 9, &(acadoWorkspace.E[ 414 ]), &(acadoWorkspace.QE[ 450 ]) ); +acado_setBlockH11( 3, 9, &(acadoWorkspace.E[ 486 ]), &(acadoWorkspace.QE[ 522 ]) ); +acado_setBlockH11( 3, 9, &(acadoWorkspace.E[ 564 ]), &(acadoWorkspace.QE[ 600 ]) ); +acado_setBlockH11( 3, 9, &(acadoWorkspace.E[ 648 ]), &(acadoWorkspace.QE[ 684 ]) ); +acado_setBlockH11( 3, 9, &(acadoWorkspace.E[ 738 ]), &(acadoWorkspace.QE[ 774 ]) ); +acado_setBlockH11( 3, 9, &(acadoWorkspace.E[ 834 ]), &(acadoWorkspace.QE[ 870 ]) ); +acado_setBlockH11( 3, 9, &(acadoWorkspace.E[ 936 ]), &(acadoWorkspace.QE[ 972 ]) ); +acado_setBlockH11( 3, 9, &(acadoWorkspace.E[ 1044 ]), &(acadoWorkspace.QE[ 1080 ]) ); +acado_setBlockH11( 3, 9, &(acadoWorkspace.E[ 1158 ]), &(acadoWorkspace.QE[ 1194 ]) ); + +acado_zeroBlockH11( 3, 10 ); +acado_setBlockH11( 3, 10, &(acadoWorkspace.E[ 348 ]), &(acadoWorkspace.QE[ 390 ]) ); +acado_setBlockH11( 3, 10, &(acadoWorkspace.E[ 414 ]), &(acadoWorkspace.QE[ 456 ]) ); +acado_setBlockH11( 3, 10, &(acadoWorkspace.E[ 486 ]), &(acadoWorkspace.QE[ 528 ]) ); +acado_setBlockH11( 3, 10, &(acadoWorkspace.E[ 564 ]), &(acadoWorkspace.QE[ 606 ]) ); +acado_setBlockH11( 3, 10, &(acadoWorkspace.E[ 648 ]), &(acadoWorkspace.QE[ 690 ]) ); +acado_setBlockH11( 3, 10, &(acadoWorkspace.E[ 738 ]), &(acadoWorkspace.QE[ 780 ]) ); +acado_setBlockH11( 3, 10, &(acadoWorkspace.E[ 834 ]), &(acadoWorkspace.QE[ 876 ]) ); +acado_setBlockH11( 3, 10, &(acadoWorkspace.E[ 936 ]), &(acadoWorkspace.QE[ 978 ]) ); +acado_setBlockH11( 3, 10, &(acadoWorkspace.E[ 1044 ]), &(acadoWorkspace.QE[ 1086 ]) ); +acado_setBlockH11( 3, 10, &(acadoWorkspace.E[ 1158 ]), &(acadoWorkspace.QE[ 1200 ]) ); + +acado_zeroBlockH11( 3, 11 ); +acado_setBlockH11( 3, 11, &(acadoWorkspace.E[ 414 ]), &(acadoWorkspace.QE[ 462 ]) ); +acado_setBlockH11( 3, 11, &(acadoWorkspace.E[ 486 ]), &(acadoWorkspace.QE[ 534 ]) ); +acado_setBlockH11( 3, 11, &(acadoWorkspace.E[ 564 ]), &(acadoWorkspace.QE[ 612 ]) ); +acado_setBlockH11( 3, 11, &(acadoWorkspace.E[ 648 ]), &(acadoWorkspace.QE[ 696 ]) ); +acado_setBlockH11( 3, 11, &(acadoWorkspace.E[ 738 ]), &(acadoWorkspace.QE[ 786 ]) ); +acado_setBlockH11( 3, 11, &(acadoWorkspace.E[ 834 ]), &(acadoWorkspace.QE[ 882 ]) ); +acado_setBlockH11( 3, 11, &(acadoWorkspace.E[ 936 ]), &(acadoWorkspace.QE[ 984 ]) ); +acado_setBlockH11( 3, 11, &(acadoWorkspace.E[ 1044 ]), &(acadoWorkspace.QE[ 1092 ]) ); +acado_setBlockH11( 3, 11, &(acadoWorkspace.E[ 1158 ]), &(acadoWorkspace.QE[ 1206 ]) ); + +acado_zeroBlockH11( 3, 12 ); +acado_setBlockH11( 3, 12, &(acadoWorkspace.E[ 486 ]), &(acadoWorkspace.QE[ 540 ]) ); +acado_setBlockH11( 3, 12, &(acadoWorkspace.E[ 564 ]), &(acadoWorkspace.QE[ 618 ]) ); +acado_setBlockH11( 3, 12, &(acadoWorkspace.E[ 648 ]), &(acadoWorkspace.QE[ 702 ]) ); +acado_setBlockH11( 3, 12, &(acadoWorkspace.E[ 738 ]), &(acadoWorkspace.QE[ 792 ]) ); +acado_setBlockH11( 3, 12, &(acadoWorkspace.E[ 834 ]), &(acadoWorkspace.QE[ 888 ]) ); +acado_setBlockH11( 3, 12, &(acadoWorkspace.E[ 936 ]), &(acadoWorkspace.QE[ 990 ]) ); +acado_setBlockH11( 3, 12, &(acadoWorkspace.E[ 1044 ]), &(acadoWorkspace.QE[ 1098 ]) ); +acado_setBlockH11( 3, 12, &(acadoWorkspace.E[ 1158 ]), &(acadoWorkspace.QE[ 1212 ]) ); + +acado_zeroBlockH11( 3, 13 ); +acado_setBlockH11( 3, 13, &(acadoWorkspace.E[ 564 ]), &(acadoWorkspace.QE[ 624 ]) ); +acado_setBlockH11( 3, 13, &(acadoWorkspace.E[ 648 ]), &(acadoWorkspace.QE[ 708 ]) ); +acado_setBlockH11( 3, 13, &(acadoWorkspace.E[ 738 ]), &(acadoWorkspace.QE[ 798 ]) ); +acado_setBlockH11( 3, 13, &(acadoWorkspace.E[ 834 ]), &(acadoWorkspace.QE[ 894 ]) ); +acado_setBlockH11( 3, 13, &(acadoWorkspace.E[ 936 ]), &(acadoWorkspace.QE[ 996 ]) ); +acado_setBlockH11( 3, 13, &(acadoWorkspace.E[ 1044 ]), &(acadoWorkspace.QE[ 1104 ]) ); +acado_setBlockH11( 3, 13, &(acadoWorkspace.E[ 1158 ]), &(acadoWorkspace.QE[ 1218 ]) ); + +acado_zeroBlockH11( 3, 14 ); +acado_setBlockH11( 3, 14, &(acadoWorkspace.E[ 648 ]), &(acadoWorkspace.QE[ 714 ]) ); +acado_setBlockH11( 3, 14, &(acadoWorkspace.E[ 738 ]), &(acadoWorkspace.QE[ 804 ]) ); +acado_setBlockH11( 3, 14, &(acadoWorkspace.E[ 834 ]), &(acadoWorkspace.QE[ 900 ]) ); +acado_setBlockH11( 3, 14, &(acadoWorkspace.E[ 936 ]), &(acadoWorkspace.QE[ 1002 ]) ); +acado_setBlockH11( 3, 14, &(acadoWorkspace.E[ 1044 ]), &(acadoWorkspace.QE[ 1110 ]) ); +acado_setBlockH11( 3, 14, &(acadoWorkspace.E[ 1158 ]), &(acadoWorkspace.QE[ 1224 ]) ); + +acado_zeroBlockH11( 3, 15 ); +acado_setBlockH11( 3, 15, &(acadoWorkspace.E[ 738 ]), &(acadoWorkspace.QE[ 810 ]) ); +acado_setBlockH11( 3, 15, &(acadoWorkspace.E[ 834 ]), &(acadoWorkspace.QE[ 906 ]) ); +acado_setBlockH11( 3, 15, &(acadoWorkspace.E[ 936 ]), &(acadoWorkspace.QE[ 1008 ]) ); +acado_setBlockH11( 3, 15, &(acadoWorkspace.E[ 1044 ]), &(acadoWorkspace.QE[ 1116 ]) ); +acado_setBlockH11( 3, 15, &(acadoWorkspace.E[ 1158 ]), &(acadoWorkspace.QE[ 1230 ]) ); + +acado_zeroBlockH11( 3, 16 ); +acado_setBlockH11( 3, 16, &(acadoWorkspace.E[ 834 ]), &(acadoWorkspace.QE[ 912 ]) ); +acado_setBlockH11( 3, 16, &(acadoWorkspace.E[ 936 ]), &(acadoWorkspace.QE[ 1014 ]) ); +acado_setBlockH11( 3, 16, &(acadoWorkspace.E[ 1044 ]), &(acadoWorkspace.QE[ 1122 ]) ); +acado_setBlockH11( 3, 16, &(acadoWorkspace.E[ 1158 ]), &(acadoWorkspace.QE[ 1236 ]) ); + +acado_zeroBlockH11( 3, 17 ); +acado_setBlockH11( 3, 17, &(acadoWorkspace.E[ 936 ]), &(acadoWorkspace.QE[ 1020 ]) ); +acado_setBlockH11( 3, 17, &(acadoWorkspace.E[ 1044 ]), &(acadoWorkspace.QE[ 1128 ]) ); +acado_setBlockH11( 3, 17, &(acadoWorkspace.E[ 1158 ]), &(acadoWorkspace.QE[ 1242 ]) ); + +acado_zeroBlockH11( 3, 18 ); +acado_setBlockH11( 3, 18, &(acadoWorkspace.E[ 1044 ]), &(acadoWorkspace.QE[ 1134 ]) ); +acado_setBlockH11( 3, 18, &(acadoWorkspace.E[ 1158 ]), &(acadoWorkspace.QE[ 1248 ]) ); + +acado_zeroBlockH11( 3, 19 ); +acado_setBlockH11( 3, 19, &(acadoWorkspace.E[ 1158 ]), &(acadoWorkspace.QE[ 1254 ]) ); + +acado_setBlockH11_R1( 4, 4, &(acadoWorkspace.R1[ 4 ]) ); +acado_setBlockH11( 4, 4, &(acadoWorkspace.E[ 84 ]), &(acadoWorkspace.QE[ 84 ]) ); +acado_setBlockH11( 4, 4, &(acadoWorkspace.E[ 114 ]), &(acadoWorkspace.QE[ 114 ]) ); +acado_setBlockH11( 4, 4, &(acadoWorkspace.E[ 150 ]), &(acadoWorkspace.QE[ 150 ]) ); +acado_setBlockH11( 4, 4, &(acadoWorkspace.E[ 192 ]), &(acadoWorkspace.QE[ 192 ]) ); +acado_setBlockH11( 4, 4, &(acadoWorkspace.E[ 240 ]), &(acadoWorkspace.QE[ 240 ]) ); +acado_setBlockH11( 4, 4, &(acadoWorkspace.E[ 294 ]), &(acadoWorkspace.QE[ 294 ]) ); +acado_setBlockH11( 4, 4, &(acadoWorkspace.E[ 354 ]), &(acadoWorkspace.QE[ 354 ]) ); +acado_setBlockH11( 4, 4, &(acadoWorkspace.E[ 420 ]), &(acadoWorkspace.QE[ 420 ]) ); +acado_setBlockH11( 4, 4, &(acadoWorkspace.E[ 492 ]), &(acadoWorkspace.QE[ 492 ]) ); +acado_setBlockH11( 4, 4, &(acadoWorkspace.E[ 570 ]), &(acadoWorkspace.QE[ 570 ]) ); +acado_setBlockH11( 4, 4, &(acadoWorkspace.E[ 654 ]), &(acadoWorkspace.QE[ 654 ]) ); +acado_setBlockH11( 4, 4, &(acadoWorkspace.E[ 744 ]), &(acadoWorkspace.QE[ 744 ]) ); +acado_setBlockH11( 4, 4, &(acadoWorkspace.E[ 840 ]), &(acadoWorkspace.QE[ 840 ]) ); +acado_setBlockH11( 4, 4, &(acadoWorkspace.E[ 942 ]), &(acadoWorkspace.QE[ 942 ]) ); +acado_setBlockH11( 4, 4, &(acadoWorkspace.E[ 1050 ]), &(acadoWorkspace.QE[ 1050 ]) ); +acado_setBlockH11( 4, 4, &(acadoWorkspace.E[ 1164 ]), &(acadoWorkspace.QE[ 1164 ]) ); + +acado_zeroBlockH11( 4, 5 ); +acado_setBlockH11( 4, 5, &(acadoWorkspace.E[ 114 ]), &(acadoWorkspace.QE[ 120 ]) ); +acado_setBlockH11( 4, 5, &(acadoWorkspace.E[ 150 ]), &(acadoWorkspace.QE[ 156 ]) ); +acado_setBlockH11( 4, 5, &(acadoWorkspace.E[ 192 ]), &(acadoWorkspace.QE[ 198 ]) ); +acado_setBlockH11( 4, 5, &(acadoWorkspace.E[ 240 ]), &(acadoWorkspace.QE[ 246 ]) ); +acado_setBlockH11( 4, 5, &(acadoWorkspace.E[ 294 ]), &(acadoWorkspace.QE[ 300 ]) ); +acado_setBlockH11( 4, 5, &(acadoWorkspace.E[ 354 ]), &(acadoWorkspace.QE[ 360 ]) ); +acado_setBlockH11( 4, 5, &(acadoWorkspace.E[ 420 ]), &(acadoWorkspace.QE[ 426 ]) ); +acado_setBlockH11( 4, 5, &(acadoWorkspace.E[ 492 ]), &(acadoWorkspace.QE[ 498 ]) ); +acado_setBlockH11( 4, 5, &(acadoWorkspace.E[ 570 ]), &(acadoWorkspace.QE[ 576 ]) ); +acado_setBlockH11( 4, 5, &(acadoWorkspace.E[ 654 ]), &(acadoWorkspace.QE[ 660 ]) ); +acado_setBlockH11( 4, 5, &(acadoWorkspace.E[ 744 ]), &(acadoWorkspace.QE[ 750 ]) ); +acado_setBlockH11( 4, 5, &(acadoWorkspace.E[ 840 ]), &(acadoWorkspace.QE[ 846 ]) ); +acado_setBlockH11( 4, 5, &(acadoWorkspace.E[ 942 ]), &(acadoWorkspace.QE[ 948 ]) ); +acado_setBlockH11( 4, 5, &(acadoWorkspace.E[ 1050 ]), &(acadoWorkspace.QE[ 1056 ]) ); +acado_setBlockH11( 4, 5, &(acadoWorkspace.E[ 1164 ]), &(acadoWorkspace.QE[ 1170 ]) ); + +acado_zeroBlockH11( 4, 6 ); +acado_setBlockH11( 4, 6, &(acadoWorkspace.E[ 150 ]), &(acadoWorkspace.QE[ 162 ]) ); +acado_setBlockH11( 4, 6, &(acadoWorkspace.E[ 192 ]), &(acadoWorkspace.QE[ 204 ]) ); +acado_setBlockH11( 4, 6, &(acadoWorkspace.E[ 240 ]), &(acadoWorkspace.QE[ 252 ]) ); +acado_setBlockH11( 4, 6, &(acadoWorkspace.E[ 294 ]), &(acadoWorkspace.QE[ 306 ]) ); +acado_setBlockH11( 4, 6, &(acadoWorkspace.E[ 354 ]), &(acadoWorkspace.QE[ 366 ]) ); +acado_setBlockH11( 4, 6, &(acadoWorkspace.E[ 420 ]), &(acadoWorkspace.QE[ 432 ]) ); +acado_setBlockH11( 4, 6, &(acadoWorkspace.E[ 492 ]), &(acadoWorkspace.QE[ 504 ]) ); +acado_setBlockH11( 4, 6, &(acadoWorkspace.E[ 570 ]), &(acadoWorkspace.QE[ 582 ]) ); +acado_setBlockH11( 4, 6, &(acadoWorkspace.E[ 654 ]), &(acadoWorkspace.QE[ 666 ]) ); +acado_setBlockH11( 4, 6, &(acadoWorkspace.E[ 744 ]), &(acadoWorkspace.QE[ 756 ]) ); +acado_setBlockH11( 4, 6, &(acadoWorkspace.E[ 840 ]), &(acadoWorkspace.QE[ 852 ]) ); +acado_setBlockH11( 4, 6, &(acadoWorkspace.E[ 942 ]), &(acadoWorkspace.QE[ 954 ]) ); +acado_setBlockH11( 4, 6, &(acadoWorkspace.E[ 1050 ]), &(acadoWorkspace.QE[ 1062 ]) ); +acado_setBlockH11( 4, 6, &(acadoWorkspace.E[ 1164 ]), &(acadoWorkspace.QE[ 1176 ]) ); + +acado_zeroBlockH11( 4, 7 ); +acado_setBlockH11( 4, 7, &(acadoWorkspace.E[ 192 ]), &(acadoWorkspace.QE[ 210 ]) ); +acado_setBlockH11( 4, 7, &(acadoWorkspace.E[ 240 ]), &(acadoWorkspace.QE[ 258 ]) ); +acado_setBlockH11( 4, 7, &(acadoWorkspace.E[ 294 ]), &(acadoWorkspace.QE[ 312 ]) ); +acado_setBlockH11( 4, 7, &(acadoWorkspace.E[ 354 ]), &(acadoWorkspace.QE[ 372 ]) ); +acado_setBlockH11( 4, 7, &(acadoWorkspace.E[ 420 ]), &(acadoWorkspace.QE[ 438 ]) ); +acado_setBlockH11( 4, 7, &(acadoWorkspace.E[ 492 ]), &(acadoWorkspace.QE[ 510 ]) ); +acado_setBlockH11( 4, 7, &(acadoWorkspace.E[ 570 ]), &(acadoWorkspace.QE[ 588 ]) ); +acado_setBlockH11( 4, 7, &(acadoWorkspace.E[ 654 ]), &(acadoWorkspace.QE[ 672 ]) ); +acado_setBlockH11( 4, 7, &(acadoWorkspace.E[ 744 ]), &(acadoWorkspace.QE[ 762 ]) ); +acado_setBlockH11( 4, 7, &(acadoWorkspace.E[ 840 ]), &(acadoWorkspace.QE[ 858 ]) ); +acado_setBlockH11( 4, 7, &(acadoWorkspace.E[ 942 ]), &(acadoWorkspace.QE[ 960 ]) ); +acado_setBlockH11( 4, 7, &(acadoWorkspace.E[ 1050 ]), &(acadoWorkspace.QE[ 1068 ]) ); +acado_setBlockH11( 4, 7, &(acadoWorkspace.E[ 1164 ]), &(acadoWorkspace.QE[ 1182 ]) ); + +acado_zeroBlockH11( 4, 8 ); +acado_setBlockH11( 4, 8, &(acadoWorkspace.E[ 240 ]), &(acadoWorkspace.QE[ 264 ]) ); +acado_setBlockH11( 4, 8, &(acadoWorkspace.E[ 294 ]), &(acadoWorkspace.QE[ 318 ]) ); +acado_setBlockH11( 4, 8, &(acadoWorkspace.E[ 354 ]), &(acadoWorkspace.QE[ 378 ]) ); +acado_setBlockH11( 4, 8, &(acadoWorkspace.E[ 420 ]), &(acadoWorkspace.QE[ 444 ]) ); +acado_setBlockH11( 4, 8, &(acadoWorkspace.E[ 492 ]), &(acadoWorkspace.QE[ 516 ]) ); +acado_setBlockH11( 4, 8, &(acadoWorkspace.E[ 570 ]), &(acadoWorkspace.QE[ 594 ]) ); +acado_setBlockH11( 4, 8, &(acadoWorkspace.E[ 654 ]), &(acadoWorkspace.QE[ 678 ]) ); +acado_setBlockH11( 4, 8, &(acadoWorkspace.E[ 744 ]), &(acadoWorkspace.QE[ 768 ]) ); +acado_setBlockH11( 4, 8, &(acadoWorkspace.E[ 840 ]), &(acadoWorkspace.QE[ 864 ]) ); +acado_setBlockH11( 4, 8, &(acadoWorkspace.E[ 942 ]), &(acadoWorkspace.QE[ 966 ]) ); +acado_setBlockH11( 4, 8, &(acadoWorkspace.E[ 1050 ]), &(acadoWorkspace.QE[ 1074 ]) ); +acado_setBlockH11( 4, 8, &(acadoWorkspace.E[ 1164 ]), &(acadoWorkspace.QE[ 1188 ]) ); + +acado_zeroBlockH11( 4, 9 ); +acado_setBlockH11( 4, 9, &(acadoWorkspace.E[ 294 ]), &(acadoWorkspace.QE[ 324 ]) ); +acado_setBlockH11( 4, 9, &(acadoWorkspace.E[ 354 ]), &(acadoWorkspace.QE[ 384 ]) ); +acado_setBlockH11( 4, 9, &(acadoWorkspace.E[ 420 ]), &(acadoWorkspace.QE[ 450 ]) ); +acado_setBlockH11( 4, 9, &(acadoWorkspace.E[ 492 ]), &(acadoWorkspace.QE[ 522 ]) ); +acado_setBlockH11( 4, 9, &(acadoWorkspace.E[ 570 ]), &(acadoWorkspace.QE[ 600 ]) ); +acado_setBlockH11( 4, 9, &(acadoWorkspace.E[ 654 ]), &(acadoWorkspace.QE[ 684 ]) ); +acado_setBlockH11( 4, 9, &(acadoWorkspace.E[ 744 ]), &(acadoWorkspace.QE[ 774 ]) ); +acado_setBlockH11( 4, 9, &(acadoWorkspace.E[ 840 ]), &(acadoWorkspace.QE[ 870 ]) ); +acado_setBlockH11( 4, 9, &(acadoWorkspace.E[ 942 ]), &(acadoWorkspace.QE[ 972 ]) ); +acado_setBlockH11( 4, 9, &(acadoWorkspace.E[ 1050 ]), &(acadoWorkspace.QE[ 1080 ]) ); +acado_setBlockH11( 4, 9, &(acadoWorkspace.E[ 1164 ]), &(acadoWorkspace.QE[ 1194 ]) ); + +acado_zeroBlockH11( 4, 10 ); +acado_setBlockH11( 4, 10, &(acadoWorkspace.E[ 354 ]), &(acadoWorkspace.QE[ 390 ]) ); +acado_setBlockH11( 4, 10, &(acadoWorkspace.E[ 420 ]), &(acadoWorkspace.QE[ 456 ]) ); +acado_setBlockH11( 4, 10, &(acadoWorkspace.E[ 492 ]), &(acadoWorkspace.QE[ 528 ]) ); +acado_setBlockH11( 4, 10, &(acadoWorkspace.E[ 570 ]), &(acadoWorkspace.QE[ 606 ]) ); +acado_setBlockH11( 4, 10, &(acadoWorkspace.E[ 654 ]), &(acadoWorkspace.QE[ 690 ]) ); +acado_setBlockH11( 4, 10, &(acadoWorkspace.E[ 744 ]), &(acadoWorkspace.QE[ 780 ]) ); +acado_setBlockH11( 4, 10, &(acadoWorkspace.E[ 840 ]), &(acadoWorkspace.QE[ 876 ]) ); +acado_setBlockH11( 4, 10, &(acadoWorkspace.E[ 942 ]), &(acadoWorkspace.QE[ 978 ]) ); +acado_setBlockH11( 4, 10, &(acadoWorkspace.E[ 1050 ]), &(acadoWorkspace.QE[ 1086 ]) ); +acado_setBlockH11( 4, 10, &(acadoWorkspace.E[ 1164 ]), &(acadoWorkspace.QE[ 1200 ]) ); + +acado_zeroBlockH11( 4, 11 ); +acado_setBlockH11( 4, 11, &(acadoWorkspace.E[ 420 ]), &(acadoWorkspace.QE[ 462 ]) ); +acado_setBlockH11( 4, 11, &(acadoWorkspace.E[ 492 ]), &(acadoWorkspace.QE[ 534 ]) ); +acado_setBlockH11( 4, 11, &(acadoWorkspace.E[ 570 ]), &(acadoWorkspace.QE[ 612 ]) ); +acado_setBlockH11( 4, 11, &(acadoWorkspace.E[ 654 ]), &(acadoWorkspace.QE[ 696 ]) ); +acado_setBlockH11( 4, 11, &(acadoWorkspace.E[ 744 ]), &(acadoWorkspace.QE[ 786 ]) ); +acado_setBlockH11( 4, 11, &(acadoWorkspace.E[ 840 ]), &(acadoWorkspace.QE[ 882 ]) ); +acado_setBlockH11( 4, 11, &(acadoWorkspace.E[ 942 ]), &(acadoWorkspace.QE[ 984 ]) ); +acado_setBlockH11( 4, 11, &(acadoWorkspace.E[ 1050 ]), &(acadoWorkspace.QE[ 1092 ]) ); +acado_setBlockH11( 4, 11, &(acadoWorkspace.E[ 1164 ]), &(acadoWorkspace.QE[ 1206 ]) ); + +acado_zeroBlockH11( 4, 12 ); +acado_setBlockH11( 4, 12, &(acadoWorkspace.E[ 492 ]), &(acadoWorkspace.QE[ 540 ]) ); +acado_setBlockH11( 4, 12, &(acadoWorkspace.E[ 570 ]), &(acadoWorkspace.QE[ 618 ]) ); +acado_setBlockH11( 4, 12, &(acadoWorkspace.E[ 654 ]), &(acadoWorkspace.QE[ 702 ]) ); +acado_setBlockH11( 4, 12, &(acadoWorkspace.E[ 744 ]), &(acadoWorkspace.QE[ 792 ]) ); +acado_setBlockH11( 4, 12, &(acadoWorkspace.E[ 840 ]), &(acadoWorkspace.QE[ 888 ]) ); +acado_setBlockH11( 4, 12, &(acadoWorkspace.E[ 942 ]), &(acadoWorkspace.QE[ 990 ]) ); +acado_setBlockH11( 4, 12, &(acadoWorkspace.E[ 1050 ]), &(acadoWorkspace.QE[ 1098 ]) ); +acado_setBlockH11( 4, 12, &(acadoWorkspace.E[ 1164 ]), &(acadoWorkspace.QE[ 1212 ]) ); + +acado_zeroBlockH11( 4, 13 ); +acado_setBlockH11( 4, 13, &(acadoWorkspace.E[ 570 ]), &(acadoWorkspace.QE[ 624 ]) ); +acado_setBlockH11( 4, 13, &(acadoWorkspace.E[ 654 ]), &(acadoWorkspace.QE[ 708 ]) ); +acado_setBlockH11( 4, 13, &(acadoWorkspace.E[ 744 ]), &(acadoWorkspace.QE[ 798 ]) ); +acado_setBlockH11( 4, 13, &(acadoWorkspace.E[ 840 ]), &(acadoWorkspace.QE[ 894 ]) ); +acado_setBlockH11( 4, 13, &(acadoWorkspace.E[ 942 ]), &(acadoWorkspace.QE[ 996 ]) ); +acado_setBlockH11( 4, 13, &(acadoWorkspace.E[ 1050 ]), &(acadoWorkspace.QE[ 1104 ]) ); +acado_setBlockH11( 4, 13, &(acadoWorkspace.E[ 1164 ]), &(acadoWorkspace.QE[ 1218 ]) ); + +acado_zeroBlockH11( 4, 14 ); +acado_setBlockH11( 4, 14, &(acadoWorkspace.E[ 654 ]), &(acadoWorkspace.QE[ 714 ]) ); +acado_setBlockH11( 4, 14, &(acadoWorkspace.E[ 744 ]), &(acadoWorkspace.QE[ 804 ]) ); +acado_setBlockH11( 4, 14, &(acadoWorkspace.E[ 840 ]), &(acadoWorkspace.QE[ 900 ]) ); +acado_setBlockH11( 4, 14, &(acadoWorkspace.E[ 942 ]), &(acadoWorkspace.QE[ 1002 ]) ); +acado_setBlockH11( 4, 14, &(acadoWorkspace.E[ 1050 ]), &(acadoWorkspace.QE[ 1110 ]) ); +acado_setBlockH11( 4, 14, &(acadoWorkspace.E[ 1164 ]), &(acadoWorkspace.QE[ 1224 ]) ); + +acado_zeroBlockH11( 4, 15 ); +acado_setBlockH11( 4, 15, &(acadoWorkspace.E[ 744 ]), &(acadoWorkspace.QE[ 810 ]) ); +acado_setBlockH11( 4, 15, &(acadoWorkspace.E[ 840 ]), &(acadoWorkspace.QE[ 906 ]) ); +acado_setBlockH11( 4, 15, &(acadoWorkspace.E[ 942 ]), &(acadoWorkspace.QE[ 1008 ]) ); +acado_setBlockH11( 4, 15, &(acadoWorkspace.E[ 1050 ]), &(acadoWorkspace.QE[ 1116 ]) ); +acado_setBlockH11( 4, 15, &(acadoWorkspace.E[ 1164 ]), &(acadoWorkspace.QE[ 1230 ]) ); + +acado_zeroBlockH11( 4, 16 ); +acado_setBlockH11( 4, 16, &(acadoWorkspace.E[ 840 ]), &(acadoWorkspace.QE[ 912 ]) ); +acado_setBlockH11( 4, 16, &(acadoWorkspace.E[ 942 ]), &(acadoWorkspace.QE[ 1014 ]) ); +acado_setBlockH11( 4, 16, &(acadoWorkspace.E[ 1050 ]), &(acadoWorkspace.QE[ 1122 ]) ); +acado_setBlockH11( 4, 16, &(acadoWorkspace.E[ 1164 ]), &(acadoWorkspace.QE[ 1236 ]) ); + +acado_zeroBlockH11( 4, 17 ); +acado_setBlockH11( 4, 17, &(acadoWorkspace.E[ 942 ]), &(acadoWorkspace.QE[ 1020 ]) ); +acado_setBlockH11( 4, 17, &(acadoWorkspace.E[ 1050 ]), &(acadoWorkspace.QE[ 1128 ]) ); +acado_setBlockH11( 4, 17, &(acadoWorkspace.E[ 1164 ]), &(acadoWorkspace.QE[ 1242 ]) ); + +acado_zeroBlockH11( 4, 18 ); +acado_setBlockH11( 4, 18, &(acadoWorkspace.E[ 1050 ]), &(acadoWorkspace.QE[ 1134 ]) ); +acado_setBlockH11( 4, 18, &(acadoWorkspace.E[ 1164 ]), &(acadoWorkspace.QE[ 1248 ]) ); + +acado_zeroBlockH11( 4, 19 ); +acado_setBlockH11( 4, 19, &(acadoWorkspace.E[ 1164 ]), &(acadoWorkspace.QE[ 1254 ]) ); + +acado_setBlockH11_R1( 5, 5, &(acadoWorkspace.R1[ 5 ]) ); +acado_setBlockH11( 5, 5, &(acadoWorkspace.E[ 120 ]), &(acadoWorkspace.QE[ 120 ]) ); +acado_setBlockH11( 5, 5, &(acadoWorkspace.E[ 156 ]), &(acadoWorkspace.QE[ 156 ]) ); +acado_setBlockH11( 5, 5, &(acadoWorkspace.E[ 198 ]), &(acadoWorkspace.QE[ 198 ]) ); +acado_setBlockH11( 5, 5, &(acadoWorkspace.E[ 246 ]), &(acadoWorkspace.QE[ 246 ]) ); +acado_setBlockH11( 5, 5, &(acadoWorkspace.E[ 300 ]), &(acadoWorkspace.QE[ 300 ]) ); +acado_setBlockH11( 5, 5, &(acadoWorkspace.E[ 360 ]), &(acadoWorkspace.QE[ 360 ]) ); +acado_setBlockH11( 5, 5, &(acadoWorkspace.E[ 426 ]), &(acadoWorkspace.QE[ 426 ]) ); +acado_setBlockH11( 5, 5, &(acadoWorkspace.E[ 498 ]), &(acadoWorkspace.QE[ 498 ]) ); +acado_setBlockH11( 5, 5, &(acadoWorkspace.E[ 576 ]), &(acadoWorkspace.QE[ 576 ]) ); +acado_setBlockH11( 5, 5, &(acadoWorkspace.E[ 660 ]), &(acadoWorkspace.QE[ 660 ]) ); +acado_setBlockH11( 5, 5, &(acadoWorkspace.E[ 750 ]), &(acadoWorkspace.QE[ 750 ]) ); +acado_setBlockH11( 5, 5, &(acadoWorkspace.E[ 846 ]), &(acadoWorkspace.QE[ 846 ]) ); +acado_setBlockH11( 5, 5, &(acadoWorkspace.E[ 948 ]), &(acadoWorkspace.QE[ 948 ]) ); +acado_setBlockH11( 5, 5, &(acadoWorkspace.E[ 1056 ]), &(acadoWorkspace.QE[ 1056 ]) ); +acado_setBlockH11( 5, 5, &(acadoWorkspace.E[ 1170 ]), &(acadoWorkspace.QE[ 1170 ]) ); + +acado_zeroBlockH11( 5, 6 ); +acado_setBlockH11( 5, 6, &(acadoWorkspace.E[ 156 ]), &(acadoWorkspace.QE[ 162 ]) ); +acado_setBlockH11( 5, 6, &(acadoWorkspace.E[ 198 ]), &(acadoWorkspace.QE[ 204 ]) ); +acado_setBlockH11( 5, 6, &(acadoWorkspace.E[ 246 ]), &(acadoWorkspace.QE[ 252 ]) ); +acado_setBlockH11( 5, 6, &(acadoWorkspace.E[ 300 ]), &(acadoWorkspace.QE[ 306 ]) ); +acado_setBlockH11( 5, 6, &(acadoWorkspace.E[ 360 ]), &(acadoWorkspace.QE[ 366 ]) ); +acado_setBlockH11( 5, 6, &(acadoWorkspace.E[ 426 ]), &(acadoWorkspace.QE[ 432 ]) ); +acado_setBlockH11( 5, 6, &(acadoWorkspace.E[ 498 ]), &(acadoWorkspace.QE[ 504 ]) ); +acado_setBlockH11( 5, 6, &(acadoWorkspace.E[ 576 ]), &(acadoWorkspace.QE[ 582 ]) ); +acado_setBlockH11( 5, 6, &(acadoWorkspace.E[ 660 ]), &(acadoWorkspace.QE[ 666 ]) ); +acado_setBlockH11( 5, 6, &(acadoWorkspace.E[ 750 ]), &(acadoWorkspace.QE[ 756 ]) ); +acado_setBlockH11( 5, 6, &(acadoWorkspace.E[ 846 ]), &(acadoWorkspace.QE[ 852 ]) ); +acado_setBlockH11( 5, 6, &(acadoWorkspace.E[ 948 ]), &(acadoWorkspace.QE[ 954 ]) ); +acado_setBlockH11( 5, 6, &(acadoWorkspace.E[ 1056 ]), &(acadoWorkspace.QE[ 1062 ]) ); +acado_setBlockH11( 5, 6, &(acadoWorkspace.E[ 1170 ]), &(acadoWorkspace.QE[ 1176 ]) ); + +acado_zeroBlockH11( 5, 7 ); +acado_setBlockH11( 5, 7, &(acadoWorkspace.E[ 198 ]), &(acadoWorkspace.QE[ 210 ]) ); +acado_setBlockH11( 5, 7, &(acadoWorkspace.E[ 246 ]), &(acadoWorkspace.QE[ 258 ]) ); +acado_setBlockH11( 5, 7, &(acadoWorkspace.E[ 300 ]), &(acadoWorkspace.QE[ 312 ]) ); +acado_setBlockH11( 5, 7, &(acadoWorkspace.E[ 360 ]), &(acadoWorkspace.QE[ 372 ]) ); +acado_setBlockH11( 5, 7, &(acadoWorkspace.E[ 426 ]), &(acadoWorkspace.QE[ 438 ]) ); +acado_setBlockH11( 5, 7, &(acadoWorkspace.E[ 498 ]), &(acadoWorkspace.QE[ 510 ]) ); +acado_setBlockH11( 5, 7, &(acadoWorkspace.E[ 576 ]), &(acadoWorkspace.QE[ 588 ]) ); +acado_setBlockH11( 5, 7, &(acadoWorkspace.E[ 660 ]), &(acadoWorkspace.QE[ 672 ]) ); +acado_setBlockH11( 5, 7, &(acadoWorkspace.E[ 750 ]), &(acadoWorkspace.QE[ 762 ]) ); +acado_setBlockH11( 5, 7, &(acadoWorkspace.E[ 846 ]), &(acadoWorkspace.QE[ 858 ]) ); +acado_setBlockH11( 5, 7, &(acadoWorkspace.E[ 948 ]), &(acadoWorkspace.QE[ 960 ]) ); +acado_setBlockH11( 5, 7, &(acadoWorkspace.E[ 1056 ]), &(acadoWorkspace.QE[ 1068 ]) ); +acado_setBlockH11( 5, 7, &(acadoWorkspace.E[ 1170 ]), &(acadoWorkspace.QE[ 1182 ]) ); + +acado_zeroBlockH11( 5, 8 ); +acado_setBlockH11( 5, 8, &(acadoWorkspace.E[ 246 ]), &(acadoWorkspace.QE[ 264 ]) ); +acado_setBlockH11( 5, 8, &(acadoWorkspace.E[ 300 ]), &(acadoWorkspace.QE[ 318 ]) ); +acado_setBlockH11( 5, 8, &(acadoWorkspace.E[ 360 ]), &(acadoWorkspace.QE[ 378 ]) ); +acado_setBlockH11( 5, 8, &(acadoWorkspace.E[ 426 ]), &(acadoWorkspace.QE[ 444 ]) ); +acado_setBlockH11( 5, 8, &(acadoWorkspace.E[ 498 ]), &(acadoWorkspace.QE[ 516 ]) ); +acado_setBlockH11( 5, 8, &(acadoWorkspace.E[ 576 ]), &(acadoWorkspace.QE[ 594 ]) ); +acado_setBlockH11( 5, 8, &(acadoWorkspace.E[ 660 ]), &(acadoWorkspace.QE[ 678 ]) ); +acado_setBlockH11( 5, 8, &(acadoWorkspace.E[ 750 ]), &(acadoWorkspace.QE[ 768 ]) ); +acado_setBlockH11( 5, 8, &(acadoWorkspace.E[ 846 ]), &(acadoWorkspace.QE[ 864 ]) ); +acado_setBlockH11( 5, 8, &(acadoWorkspace.E[ 948 ]), &(acadoWorkspace.QE[ 966 ]) ); +acado_setBlockH11( 5, 8, &(acadoWorkspace.E[ 1056 ]), &(acadoWorkspace.QE[ 1074 ]) ); +acado_setBlockH11( 5, 8, &(acadoWorkspace.E[ 1170 ]), &(acadoWorkspace.QE[ 1188 ]) ); + +acado_zeroBlockH11( 5, 9 ); +acado_setBlockH11( 5, 9, &(acadoWorkspace.E[ 300 ]), &(acadoWorkspace.QE[ 324 ]) ); +acado_setBlockH11( 5, 9, &(acadoWorkspace.E[ 360 ]), &(acadoWorkspace.QE[ 384 ]) ); +acado_setBlockH11( 5, 9, &(acadoWorkspace.E[ 426 ]), &(acadoWorkspace.QE[ 450 ]) ); +acado_setBlockH11( 5, 9, &(acadoWorkspace.E[ 498 ]), &(acadoWorkspace.QE[ 522 ]) ); +acado_setBlockH11( 5, 9, &(acadoWorkspace.E[ 576 ]), &(acadoWorkspace.QE[ 600 ]) ); +acado_setBlockH11( 5, 9, &(acadoWorkspace.E[ 660 ]), &(acadoWorkspace.QE[ 684 ]) ); +acado_setBlockH11( 5, 9, &(acadoWorkspace.E[ 750 ]), &(acadoWorkspace.QE[ 774 ]) ); +acado_setBlockH11( 5, 9, &(acadoWorkspace.E[ 846 ]), &(acadoWorkspace.QE[ 870 ]) ); +acado_setBlockH11( 5, 9, &(acadoWorkspace.E[ 948 ]), &(acadoWorkspace.QE[ 972 ]) ); +acado_setBlockH11( 5, 9, &(acadoWorkspace.E[ 1056 ]), &(acadoWorkspace.QE[ 1080 ]) ); +acado_setBlockH11( 5, 9, &(acadoWorkspace.E[ 1170 ]), &(acadoWorkspace.QE[ 1194 ]) ); + +acado_zeroBlockH11( 5, 10 ); +acado_setBlockH11( 5, 10, &(acadoWorkspace.E[ 360 ]), &(acadoWorkspace.QE[ 390 ]) ); +acado_setBlockH11( 5, 10, &(acadoWorkspace.E[ 426 ]), &(acadoWorkspace.QE[ 456 ]) ); +acado_setBlockH11( 5, 10, &(acadoWorkspace.E[ 498 ]), &(acadoWorkspace.QE[ 528 ]) ); +acado_setBlockH11( 5, 10, &(acadoWorkspace.E[ 576 ]), &(acadoWorkspace.QE[ 606 ]) ); +acado_setBlockH11( 5, 10, &(acadoWorkspace.E[ 660 ]), &(acadoWorkspace.QE[ 690 ]) ); +acado_setBlockH11( 5, 10, &(acadoWorkspace.E[ 750 ]), &(acadoWorkspace.QE[ 780 ]) ); +acado_setBlockH11( 5, 10, &(acadoWorkspace.E[ 846 ]), &(acadoWorkspace.QE[ 876 ]) ); +acado_setBlockH11( 5, 10, &(acadoWorkspace.E[ 948 ]), &(acadoWorkspace.QE[ 978 ]) ); +acado_setBlockH11( 5, 10, &(acadoWorkspace.E[ 1056 ]), &(acadoWorkspace.QE[ 1086 ]) ); +acado_setBlockH11( 5, 10, &(acadoWorkspace.E[ 1170 ]), &(acadoWorkspace.QE[ 1200 ]) ); + +acado_zeroBlockH11( 5, 11 ); +acado_setBlockH11( 5, 11, &(acadoWorkspace.E[ 426 ]), &(acadoWorkspace.QE[ 462 ]) ); +acado_setBlockH11( 5, 11, &(acadoWorkspace.E[ 498 ]), &(acadoWorkspace.QE[ 534 ]) ); +acado_setBlockH11( 5, 11, &(acadoWorkspace.E[ 576 ]), &(acadoWorkspace.QE[ 612 ]) ); +acado_setBlockH11( 5, 11, &(acadoWorkspace.E[ 660 ]), &(acadoWorkspace.QE[ 696 ]) ); +acado_setBlockH11( 5, 11, &(acadoWorkspace.E[ 750 ]), &(acadoWorkspace.QE[ 786 ]) ); +acado_setBlockH11( 5, 11, &(acadoWorkspace.E[ 846 ]), &(acadoWorkspace.QE[ 882 ]) ); +acado_setBlockH11( 5, 11, &(acadoWorkspace.E[ 948 ]), &(acadoWorkspace.QE[ 984 ]) ); +acado_setBlockH11( 5, 11, &(acadoWorkspace.E[ 1056 ]), &(acadoWorkspace.QE[ 1092 ]) ); +acado_setBlockH11( 5, 11, &(acadoWorkspace.E[ 1170 ]), &(acadoWorkspace.QE[ 1206 ]) ); + +acado_zeroBlockH11( 5, 12 ); +acado_setBlockH11( 5, 12, &(acadoWorkspace.E[ 498 ]), &(acadoWorkspace.QE[ 540 ]) ); +acado_setBlockH11( 5, 12, &(acadoWorkspace.E[ 576 ]), &(acadoWorkspace.QE[ 618 ]) ); +acado_setBlockH11( 5, 12, &(acadoWorkspace.E[ 660 ]), &(acadoWorkspace.QE[ 702 ]) ); +acado_setBlockH11( 5, 12, &(acadoWorkspace.E[ 750 ]), &(acadoWorkspace.QE[ 792 ]) ); +acado_setBlockH11( 5, 12, &(acadoWorkspace.E[ 846 ]), &(acadoWorkspace.QE[ 888 ]) ); +acado_setBlockH11( 5, 12, &(acadoWorkspace.E[ 948 ]), &(acadoWorkspace.QE[ 990 ]) ); +acado_setBlockH11( 5, 12, &(acadoWorkspace.E[ 1056 ]), &(acadoWorkspace.QE[ 1098 ]) ); +acado_setBlockH11( 5, 12, &(acadoWorkspace.E[ 1170 ]), &(acadoWorkspace.QE[ 1212 ]) ); + +acado_zeroBlockH11( 5, 13 ); +acado_setBlockH11( 5, 13, &(acadoWorkspace.E[ 576 ]), &(acadoWorkspace.QE[ 624 ]) ); +acado_setBlockH11( 5, 13, &(acadoWorkspace.E[ 660 ]), &(acadoWorkspace.QE[ 708 ]) ); +acado_setBlockH11( 5, 13, &(acadoWorkspace.E[ 750 ]), &(acadoWorkspace.QE[ 798 ]) ); +acado_setBlockH11( 5, 13, &(acadoWorkspace.E[ 846 ]), &(acadoWorkspace.QE[ 894 ]) ); +acado_setBlockH11( 5, 13, &(acadoWorkspace.E[ 948 ]), &(acadoWorkspace.QE[ 996 ]) ); +acado_setBlockH11( 5, 13, &(acadoWorkspace.E[ 1056 ]), &(acadoWorkspace.QE[ 1104 ]) ); +acado_setBlockH11( 5, 13, &(acadoWorkspace.E[ 1170 ]), &(acadoWorkspace.QE[ 1218 ]) ); + +acado_zeroBlockH11( 5, 14 ); +acado_setBlockH11( 5, 14, &(acadoWorkspace.E[ 660 ]), &(acadoWorkspace.QE[ 714 ]) ); +acado_setBlockH11( 5, 14, &(acadoWorkspace.E[ 750 ]), &(acadoWorkspace.QE[ 804 ]) ); +acado_setBlockH11( 5, 14, &(acadoWorkspace.E[ 846 ]), &(acadoWorkspace.QE[ 900 ]) ); +acado_setBlockH11( 5, 14, &(acadoWorkspace.E[ 948 ]), &(acadoWorkspace.QE[ 1002 ]) ); +acado_setBlockH11( 5, 14, &(acadoWorkspace.E[ 1056 ]), &(acadoWorkspace.QE[ 1110 ]) ); +acado_setBlockH11( 5, 14, &(acadoWorkspace.E[ 1170 ]), &(acadoWorkspace.QE[ 1224 ]) ); + +acado_zeroBlockH11( 5, 15 ); +acado_setBlockH11( 5, 15, &(acadoWorkspace.E[ 750 ]), &(acadoWorkspace.QE[ 810 ]) ); +acado_setBlockH11( 5, 15, &(acadoWorkspace.E[ 846 ]), &(acadoWorkspace.QE[ 906 ]) ); +acado_setBlockH11( 5, 15, &(acadoWorkspace.E[ 948 ]), &(acadoWorkspace.QE[ 1008 ]) ); +acado_setBlockH11( 5, 15, &(acadoWorkspace.E[ 1056 ]), &(acadoWorkspace.QE[ 1116 ]) ); +acado_setBlockH11( 5, 15, &(acadoWorkspace.E[ 1170 ]), &(acadoWorkspace.QE[ 1230 ]) ); + +acado_zeroBlockH11( 5, 16 ); +acado_setBlockH11( 5, 16, &(acadoWorkspace.E[ 846 ]), &(acadoWorkspace.QE[ 912 ]) ); +acado_setBlockH11( 5, 16, &(acadoWorkspace.E[ 948 ]), &(acadoWorkspace.QE[ 1014 ]) ); +acado_setBlockH11( 5, 16, &(acadoWorkspace.E[ 1056 ]), &(acadoWorkspace.QE[ 1122 ]) ); +acado_setBlockH11( 5, 16, &(acadoWorkspace.E[ 1170 ]), &(acadoWorkspace.QE[ 1236 ]) ); + +acado_zeroBlockH11( 5, 17 ); +acado_setBlockH11( 5, 17, &(acadoWorkspace.E[ 948 ]), &(acadoWorkspace.QE[ 1020 ]) ); +acado_setBlockH11( 5, 17, &(acadoWorkspace.E[ 1056 ]), &(acadoWorkspace.QE[ 1128 ]) ); +acado_setBlockH11( 5, 17, &(acadoWorkspace.E[ 1170 ]), &(acadoWorkspace.QE[ 1242 ]) ); + +acado_zeroBlockH11( 5, 18 ); +acado_setBlockH11( 5, 18, &(acadoWorkspace.E[ 1056 ]), &(acadoWorkspace.QE[ 1134 ]) ); +acado_setBlockH11( 5, 18, &(acadoWorkspace.E[ 1170 ]), &(acadoWorkspace.QE[ 1248 ]) ); + +acado_zeroBlockH11( 5, 19 ); +acado_setBlockH11( 5, 19, &(acadoWorkspace.E[ 1170 ]), &(acadoWorkspace.QE[ 1254 ]) ); + +acado_setBlockH11_R1( 6, 6, &(acadoWorkspace.R1[ 6 ]) ); +acado_setBlockH11( 6, 6, &(acadoWorkspace.E[ 162 ]), &(acadoWorkspace.QE[ 162 ]) ); +acado_setBlockH11( 6, 6, &(acadoWorkspace.E[ 204 ]), &(acadoWorkspace.QE[ 204 ]) ); +acado_setBlockH11( 6, 6, &(acadoWorkspace.E[ 252 ]), &(acadoWorkspace.QE[ 252 ]) ); +acado_setBlockH11( 6, 6, &(acadoWorkspace.E[ 306 ]), &(acadoWorkspace.QE[ 306 ]) ); +acado_setBlockH11( 6, 6, &(acadoWorkspace.E[ 366 ]), &(acadoWorkspace.QE[ 366 ]) ); +acado_setBlockH11( 6, 6, &(acadoWorkspace.E[ 432 ]), &(acadoWorkspace.QE[ 432 ]) ); +acado_setBlockH11( 6, 6, &(acadoWorkspace.E[ 504 ]), &(acadoWorkspace.QE[ 504 ]) ); +acado_setBlockH11( 6, 6, &(acadoWorkspace.E[ 582 ]), &(acadoWorkspace.QE[ 582 ]) ); +acado_setBlockH11( 6, 6, &(acadoWorkspace.E[ 666 ]), &(acadoWorkspace.QE[ 666 ]) ); +acado_setBlockH11( 6, 6, &(acadoWorkspace.E[ 756 ]), &(acadoWorkspace.QE[ 756 ]) ); +acado_setBlockH11( 6, 6, &(acadoWorkspace.E[ 852 ]), &(acadoWorkspace.QE[ 852 ]) ); +acado_setBlockH11( 6, 6, &(acadoWorkspace.E[ 954 ]), &(acadoWorkspace.QE[ 954 ]) ); +acado_setBlockH11( 6, 6, &(acadoWorkspace.E[ 1062 ]), &(acadoWorkspace.QE[ 1062 ]) ); +acado_setBlockH11( 6, 6, &(acadoWorkspace.E[ 1176 ]), &(acadoWorkspace.QE[ 1176 ]) ); + +acado_zeroBlockH11( 6, 7 ); +acado_setBlockH11( 6, 7, &(acadoWorkspace.E[ 204 ]), &(acadoWorkspace.QE[ 210 ]) ); +acado_setBlockH11( 6, 7, &(acadoWorkspace.E[ 252 ]), &(acadoWorkspace.QE[ 258 ]) ); +acado_setBlockH11( 6, 7, &(acadoWorkspace.E[ 306 ]), &(acadoWorkspace.QE[ 312 ]) ); +acado_setBlockH11( 6, 7, &(acadoWorkspace.E[ 366 ]), &(acadoWorkspace.QE[ 372 ]) ); +acado_setBlockH11( 6, 7, &(acadoWorkspace.E[ 432 ]), &(acadoWorkspace.QE[ 438 ]) ); +acado_setBlockH11( 6, 7, &(acadoWorkspace.E[ 504 ]), &(acadoWorkspace.QE[ 510 ]) ); +acado_setBlockH11( 6, 7, &(acadoWorkspace.E[ 582 ]), &(acadoWorkspace.QE[ 588 ]) ); +acado_setBlockH11( 6, 7, &(acadoWorkspace.E[ 666 ]), &(acadoWorkspace.QE[ 672 ]) ); +acado_setBlockH11( 6, 7, &(acadoWorkspace.E[ 756 ]), &(acadoWorkspace.QE[ 762 ]) ); +acado_setBlockH11( 6, 7, &(acadoWorkspace.E[ 852 ]), &(acadoWorkspace.QE[ 858 ]) ); +acado_setBlockH11( 6, 7, &(acadoWorkspace.E[ 954 ]), &(acadoWorkspace.QE[ 960 ]) ); +acado_setBlockH11( 6, 7, &(acadoWorkspace.E[ 1062 ]), &(acadoWorkspace.QE[ 1068 ]) ); +acado_setBlockH11( 6, 7, &(acadoWorkspace.E[ 1176 ]), &(acadoWorkspace.QE[ 1182 ]) ); + +acado_zeroBlockH11( 6, 8 ); +acado_setBlockH11( 6, 8, &(acadoWorkspace.E[ 252 ]), &(acadoWorkspace.QE[ 264 ]) ); +acado_setBlockH11( 6, 8, &(acadoWorkspace.E[ 306 ]), &(acadoWorkspace.QE[ 318 ]) ); +acado_setBlockH11( 6, 8, &(acadoWorkspace.E[ 366 ]), &(acadoWorkspace.QE[ 378 ]) ); +acado_setBlockH11( 6, 8, &(acadoWorkspace.E[ 432 ]), &(acadoWorkspace.QE[ 444 ]) ); +acado_setBlockH11( 6, 8, &(acadoWorkspace.E[ 504 ]), &(acadoWorkspace.QE[ 516 ]) ); +acado_setBlockH11( 6, 8, &(acadoWorkspace.E[ 582 ]), &(acadoWorkspace.QE[ 594 ]) ); +acado_setBlockH11( 6, 8, &(acadoWorkspace.E[ 666 ]), &(acadoWorkspace.QE[ 678 ]) ); +acado_setBlockH11( 6, 8, &(acadoWorkspace.E[ 756 ]), &(acadoWorkspace.QE[ 768 ]) ); +acado_setBlockH11( 6, 8, &(acadoWorkspace.E[ 852 ]), &(acadoWorkspace.QE[ 864 ]) ); +acado_setBlockH11( 6, 8, &(acadoWorkspace.E[ 954 ]), &(acadoWorkspace.QE[ 966 ]) ); +acado_setBlockH11( 6, 8, &(acadoWorkspace.E[ 1062 ]), &(acadoWorkspace.QE[ 1074 ]) ); +acado_setBlockH11( 6, 8, &(acadoWorkspace.E[ 1176 ]), &(acadoWorkspace.QE[ 1188 ]) ); + +acado_zeroBlockH11( 6, 9 ); +acado_setBlockH11( 6, 9, &(acadoWorkspace.E[ 306 ]), &(acadoWorkspace.QE[ 324 ]) ); +acado_setBlockH11( 6, 9, &(acadoWorkspace.E[ 366 ]), &(acadoWorkspace.QE[ 384 ]) ); +acado_setBlockH11( 6, 9, &(acadoWorkspace.E[ 432 ]), &(acadoWorkspace.QE[ 450 ]) ); +acado_setBlockH11( 6, 9, &(acadoWorkspace.E[ 504 ]), &(acadoWorkspace.QE[ 522 ]) ); +acado_setBlockH11( 6, 9, &(acadoWorkspace.E[ 582 ]), &(acadoWorkspace.QE[ 600 ]) ); +acado_setBlockH11( 6, 9, &(acadoWorkspace.E[ 666 ]), &(acadoWorkspace.QE[ 684 ]) ); +acado_setBlockH11( 6, 9, &(acadoWorkspace.E[ 756 ]), &(acadoWorkspace.QE[ 774 ]) ); +acado_setBlockH11( 6, 9, &(acadoWorkspace.E[ 852 ]), &(acadoWorkspace.QE[ 870 ]) ); +acado_setBlockH11( 6, 9, &(acadoWorkspace.E[ 954 ]), &(acadoWorkspace.QE[ 972 ]) ); +acado_setBlockH11( 6, 9, &(acadoWorkspace.E[ 1062 ]), &(acadoWorkspace.QE[ 1080 ]) ); +acado_setBlockH11( 6, 9, &(acadoWorkspace.E[ 1176 ]), &(acadoWorkspace.QE[ 1194 ]) ); + +acado_zeroBlockH11( 6, 10 ); +acado_setBlockH11( 6, 10, &(acadoWorkspace.E[ 366 ]), &(acadoWorkspace.QE[ 390 ]) ); +acado_setBlockH11( 6, 10, &(acadoWorkspace.E[ 432 ]), &(acadoWorkspace.QE[ 456 ]) ); +acado_setBlockH11( 6, 10, &(acadoWorkspace.E[ 504 ]), &(acadoWorkspace.QE[ 528 ]) ); +acado_setBlockH11( 6, 10, &(acadoWorkspace.E[ 582 ]), &(acadoWorkspace.QE[ 606 ]) ); +acado_setBlockH11( 6, 10, &(acadoWorkspace.E[ 666 ]), &(acadoWorkspace.QE[ 690 ]) ); +acado_setBlockH11( 6, 10, &(acadoWorkspace.E[ 756 ]), &(acadoWorkspace.QE[ 780 ]) ); +acado_setBlockH11( 6, 10, &(acadoWorkspace.E[ 852 ]), &(acadoWorkspace.QE[ 876 ]) ); +acado_setBlockH11( 6, 10, &(acadoWorkspace.E[ 954 ]), &(acadoWorkspace.QE[ 978 ]) ); +acado_setBlockH11( 6, 10, &(acadoWorkspace.E[ 1062 ]), &(acadoWorkspace.QE[ 1086 ]) ); +acado_setBlockH11( 6, 10, &(acadoWorkspace.E[ 1176 ]), &(acadoWorkspace.QE[ 1200 ]) ); + +acado_zeroBlockH11( 6, 11 ); +acado_setBlockH11( 6, 11, &(acadoWorkspace.E[ 432 ]), &(acadoWorkspace.QE[ 462 ]) ); +acado_setBlockH11( 6, 11, &(acadoWorkspace.E[ 504 ]), &(acadoWorkspace.QE[ 534 ]) ); +acado_setBlockH11( 6, 11, &(acadoWorkspace.E[ 582 ]), &(acadoWorkspace.QE[ 612 ]) ); +acado_setBlockH11( 6, 11, &(acadoWorkspace.E[ 666 ]), &(acadoWorkspace.QE[ 696 ]) ); +acado_setBlockH11( 6, 11, &(acadoWorkspace.E[ 756 ]), &(acadoWorkspace.QE[ 786 ]) ); +acado_setBlockH11( 6, 11, &(acadoWorkspace.E[ 852 ]), &(acadoWorkspace.QE[ 882 ]) ); +acado_setBlockH11( 6, 11, &(acadoWorkspace.E[ 954 ]), &(acadoWorkspace.QE[ 984 ]) ); +acado_setBlockH11( 6, 11, &(acadoWorkspace.E[ 1062 ]), &(acadoWorkspace.QE[ 1092 ]) ); +acado_setBlockH11( 6, 11, &(acadoWorkspace.E[ 1176 ]), &(acadoWorkspace.QE[ 1206 ]) ); + +acado_zeroBlockH11( 6, 12 ); +acado_setBlockH11( 6, 12, &(acadoWorkspace.E[ 504 ]), &(acadoWorkspace.QE[ 540 ]) ); +acado_setBlockH11( 6, 12, &(acadoWorkspace.E[ 582 ]), &(acadoWorkspace.QE[ 618 ]) ); +acado_setBlockH11( 6, 12, &(acadoWorkspace.E[ 666 ]), &(acadoWorkspace.QE[ 702 ]) ); +acado_setBlockH11( 6, 12, &(acadoWorkspace.E[ 756 ]), &(acadoWorkspace.QE[ 792 ]) ); +acado_setBlockH11( 6, 12, &(acadoWorkspace.E[ 852 ]), &(acadoWorkspace.QE[ 888 ]) ); +acado_setBlockH11( 6, 12, &(acadoWorkspace.E[ 954 ]), &(acadoWorkspace.QE[ 990 ]) ); +acado_setBlockH11( 6, 12, &(acadoWorkspace.E[ 1062 ]), &(acadoWorkspace.QE[ 1098 ]) ); +acado_setBlockH11( 6, 12, &(acadoWorkspace.E[ 1176 ]), &(acadoWorkspace.QE[ 1212 ]) ); + +acado_zeroBlockH11( 6, 13 ); +acado_setBlockH11( 6, 13, &(acadoWorkspace.E[ 582 ]), &(acadoWorkspace.QE[ 624 ]) ); +acado_setBlockH11( 6, 13, &(acadoWorkspace.E[ 666 ]), &(acadoWorkspace.QE[ 708 ]) ); +acado_setBlockH11( 6, 13, &(acadoWorkspace.E[ 756 ]), &(acadoWorkspace.QE[ 798 ]) ); +acado_setBlockH11( 6, 13, &(acadoWorkspace.E[ 852 ]), &(acadoWorkspace.QE[ 894 ]) ); +acado_setBlockH11( 6, 13, &(acadoWorkspace.E[ 954 ]), &(acadoWorkspace.QE[ 996 ]) ); +acado_setBlockH11( 6, 13, &(acadoWorkspace.E[ 1062 ]), &(acadoWorkspace.QE[ 1104 ]) ); +acado_setBlockH11( 6, 13, &(acadoWorkspace.E[ 1176 ]), &(acadoWorkspace.QE[ 1218 ]) ); + +acado_zeroBlockH11( 6, 14 ); +acado_setBlockH11( 6, 14, &(acadoWorkspace.E[ 666 ]), &(acadoWorkspace.QE[ 714 ]) ); +acado_setBlockH11( 6, 14, &(acadoWorkspace.E[ 756 ]), &(acadoWorkspace.QE[ 804 ]) ); +acado_setBlockH11( 6, 14, &(acadoWorkspace.E[ 852 ]), &(acadoWorkspace.QE[ 900 ]) ); +acado_setBlockH11( 6, 14, &(acadoWorkspace.E[ 954 ]), &(acadoWorkspace.QE[ 1002 ]) ); +acado_setBlockH11( 6, 14, &(acadoWorkspace.E[ 1062 ]), &(acadoWorkspace.QE[ 1110 ]) ); +acado_setBlockH11( 6, 14, &(acadoWorkspace.E[ 1176 ]), &(acadoWorkspace.QE[ 1224 ]) ); + +acado_zeroBlockH11( 6, 15 ); +acado_setBlockH11( 6, 15, &(acadoWorkspace.E[ 756 ]), &(acadoWorkspace.QE[ 810 ]) ); +acado_setBlockH11( 6, 15, &(acadoWorkspace.E[ 852 ]), &(acadoWorkspace.QE[ 906 ]) ); +acado_setBlockH11( 6, 15, &(acadoWorkspace.E[ 954 ]), &(acadoWorkspace.QE[ 1008 ]) ); +acado_setBlockH11( 6, 15, &(acadoWorkspace.E[ 1062 ]), &(acadoWorkspace.QE[ 1116 ]) ); +acado_setBlockH11( 6, 15, &(acadoWorkspace.E[ 1176 ]), &(acadoWorkspace.QE[ 1230 ]) ); + +acado_zeroBlockH11( 6, 16 ); +acado_setBlockH11( 6, 16, &(acadoWorkspace.E[ 852 ]), &(acadoWorkspace.QE[ 912 ]) ); +acado_setBlockH11( 6, 16, &(acadoWorkspace.E[ 954 ]), &(acadoWorkspace.QE[ 1014 ]) ); +acado_setBlockH11( 6, 16, &(acadoWorkspace.E[ 1062 ]), &(acadoWorkspace.QE[ 1122 ]) ); +acado_setBlockH11( 6, 16, &(acadoWorkspace.E[ 1176 ]), &(acadoWorkspace.QE[ 1236 ]) ); + +acado_zeroBlockH11( 6, 17 ); +acado_setBlockH11( 6, 17, &(acadoWorkspace.E[ 954 ]), &(acadoWorkspace.QE[ 1020 ]) ); +acado_setBlockH11( 6, 17, &(acadoWorkspace.E[ 1062 ]), &(acadoWorkspace.QE[ 1128 ]) ); +acado_setBlockH11( 6, 17, &(acadoWorkspace.E[ 1176 ]), &(acadoWorkspace.QE[ 1242 ]) ); + +acado_zeroBlockH11( 6, 18 ); +acado_setBlockH11( 6, 18, &(acadoWorkspace.E[ 1062 ]), &(acadoWorkspace.QE[ 1134 ]) ); +acado_setBlockH11( 6, 18, &(acadoWorkspace.E[ 1176 ]), &(acadoWorkspace.QE[ 1248 ]) ); + +acado_zeroBlockH11( 6, 19 ); +acado_setBlockH11( 6, 19, &(acadoWorkspace.E[ 1176 ]), &(acadoWorkspace.QE[ 1254 ]) ); + +acado_setBlockH11_R1( 7, 7, &(acadoWorkspace.R1[ 7 ]) ); +acado_setBlockH11( 7, 7, &(acadoWorkspace.E[ 210 ]), &(acadoWorkspace.QE[ 210 ]) ); +acado_setBlockH11( 7, 7, &(acadoWorkspace.E[ 258 ]), &(acadoWorkspace.QE[ 258 ]) ); +acado_setBlockH11( 7, 7, &(acadoWorkspace.E[ 312 ]), &(acadoWorkspace.QE[ 312 ]) ); +acado_setBlockH11( 7, 7, &(acadoWorkspace.E[ 372 ]), &(acadoWorkspace.QE[ 372 ]) ); +acado_setBlockH11( 7, 7, &(acadoWorkspace.E[ 438 ]), &(acadoWorkspace.QE[ 438 ]) ); +acado_setBlockH11( 7, 7, &(acadoWorkspace.E[ 510 ]), &(acadoWorkspace.QE[ 510 ]) ); +acado_setBlockH11( 7, 7, &(acadoWorkspace.E[ 588 ]), &(acadoWorkspace.QE[ 588 ]) ); +acado_setBlockH11( 7, 7, &(acadoWorkspace.E[ 672 ]), &(acadoWorkspace.QE[ 672 ]) ); +acado_setBlockH11( 7, 7, &(acadoWorkspace.E[ 762 ]), &(acadoWorkspace.QE[ 762 ]) ); +acado_setBlockH11( 7, 7, &(acadoWorkspace.E[ 858 ]), &(acadoWorkspace.QE[ 858 ]) ); +acado_setBlockH11( 7, 7, &(acadoWorkspace.E[ 960 ]), &(acadoWorkspace.QE[ 960 ]) ); +acado_setBlockH11( 7, 7, &(acadoWorkspace.E[ 1068 ]), &(acadoWorkspace.QE[ 1068 ]) ); +acado_setBlockH11( 7, 7, &(acadoWorkspace.E[ 1182 ]), &(acadoWorkspace.QE[ 1182 ]) ); + +acado_zeroBlockH11( 7, 8 ); +acado_setBlockH11( 7, 8, &(acadoWorkspace.E[ 258 ]), &(acadoWorkspace.QE[ 264 ]) ); +acado_setBlockH11( 7, 8, &(acadoWorkspace.E[ 312 ]), &(acadoWorkspace.QE[ 318 ]) ); +acado_setBlockH11( 7, 8, &(acadoWorkspace.E[ 372 ]), &(acadoWorkspace.QE[ 378 ]) ); +acado_setBlockH11( 7, 8, &(acadoWorkspace.E[ 438 ]), &(acadoWorkspace.QE[ 444 ]) ); +acado_setBlockH11( 7, 8, &(acadoWorkspace.E[ 510 ]), &(acadoWorkspace.QE[ 516 ]) ); +acado_setBlockH11( 7, 8, &(acadoWorkspace.E[ 588 ]), &(acadoWorkspace.QE[ 594 ]) ); +acado_setBlockH11( 7, 8, &(acadoWorkspace.E[ 672 ]), &(acadoWorkspace.QE[ 678 ]) ); +acado_setBlockH11( 7, 8, &(acadoWorkspace.E[ 762 ]), &(acadoWorkspace.QE[ 768 ]) ); +acado_setBlockH11( 7, 8, &(acadoWorkspace.E[ 858 ]), &(acadoWorkspace.QE[ 864 ]) ); +acado_setBlockH11( 7, 8, &(acadoWorkspace.E[ 960 ]), &(acadoWorkspace.QE[ 966 ]) ); +acado_setBlockH11( 7, 8, &(acadoWorkspace.E[ 1068 ]), &(acadoWorkspace.QE[ 1074 ]) ); +acado_setBlockH11( 7, 8, &(acadoWorkspace.E[ 1182 ]), &(acadoWorkspace.QE[ 1188 ]) ); + +acado_zeroBlockH11( 7, 9 ); +acado_setBlockH11( 7, 9, &(acadoWorkspace.E[ 312 ]), &(acadoWorkspace.QE[ 324 ]) ); +acado_setBlockH11( 7, 9, &(acadoWorkspace.E[ 372 ]), &(acadoWorkspace.QE[ 384 ]) ); +acado_setBlockH11( 7, 9, &(acadoWorkspace.E[ 438 ]), &(acadoWorkspace.QE[ 450 ]) ); +acado_setBlockH11( 7, 9, &(acadoWorkspace.E[ 510 ]), &(acadoWorkspace.QE[ 522 ]) ); +acado_setBlockH11( 7, 9, &(acadoWorkspace.E[ 588 ]), &(acadoWorkspace.QE[ 600 ]) ); +acado_setBlockH11( 7, 9, &(acadoWorkspace.E[ 672 ]), &(acadoWorkspace.QE[ 684 ]) ); +acado_setBlockH11( 7, 9, &(acadoWorkspace.E[ 762 ]), &(acadoWorkspace.QE[ 774 ]) ); +acado_setBlockH11( 7, 9, &(acadoWorkspace.E[ 858 ]), &(acadoWorkspace.QE[ 870 ]) ); +acado_setBlockH11( 7, 9, &(acadoWorkspace.E[ 960 ]), &(acadoWorkspace.QE[ 972 ]) ); +acado_setBlockH11( 7, 9, &(acadoWorkspace.E[ 1068 ]), &(acadoWorkspace.QE[ 1080 ]) ); +acado_setBlockH11( 7, 9, &(acadoWorkspace.E[ 1182 ]), &(acadoWorkspace.QE[ 1194 ]) ); + +acado_zeroBlockH11( 7, 10 ); +acado_setBlockH11( 7, 10, &(acadoWorkspace.E[ 372 ]), &(acadoWorkspace.QE[ 390 ]) ); +acado_setBlockH11( 7, 10, &(acadoWorkspace.E[ 438 ]), &(acadoWorkspace.QE[ 456 ]) ); +acado_setBlockH11( 7, 10, &(acadoWorkspace.E[ 510 ]), &(acadoWorkspace.QE[ 528 ]) ); +acado_setBlockH11( 7, 10, &(acadoWorkspace.E[ 588 ]), &(acadoWorkspace.QE[ 606 ]) ); +acado_setBlockH11( 7, 10, &(acadoWorkspace.E[ 672 ]), &(acadoWorkspace.QE[ 690 ]) ); +acado_setBlockH11( 7, 10, &(acadoWorkspace.E[ 762 ]), &(acadoWorkspace.QE[ 780 ]) ); +acado_setBlockH11( 7, 10, &(acadoWorkspace.E[ 858 ]), &(acadoWorkspace.QE[ 876 ]) ); +acado_setBlockH11( 7, 10, &(acadoWorkspace.E[ 960 ]), &(acadoWorkspace.QE[ 978 ]) ); +acado_setBlockH11( 7, 10, &(acadoWorkspace.E[ 1068 ]), &(acadoWorkspace.QE[ 1086 ]) ); +acado_setBlockH11( 7, 10, &(acadoWorkspace.E[ 1182 ]), &(acadoWorkspace.QE[ 1200 ]) ); + +acado_zeroBlockH11( 7, 11 ); +acado_setBlockH11( 7, 11, &(acadoWorkspace.E[ 438 ]), &(acadoWorkspace.QE[ 462 ]) ); +acado_setBlockH11( 7, 11, &(acadoWorkspace.E[ 510 ]), &(acadoWorkspace.QE[ 534 ]) ); +acado_setBlockH11( 7, 11, &(acadoWorkspace.E[ 588 ]), &(acadoWorkspace.QE[ 612 ]) ); +acado_setBlockH11( 7, 11, &(acadoWorkspace.E[ 672 ]), &(acadoWorkspace.QE[ 696 ]) ); +acado_setBlockH11( 7, 11, &(acadoWorkspace.E[ 762 ]), &(acadoWorkspace.QE[ 786 ]) ); +acado_setBlockH11( 7, 11, &(acadoWorkspace.E[ 858 ]), &(acadoWorkspace.QE[ 882 ]) ); +acado_setBlockH11( 7, 11, &(acadoWorkspace.E[ 960 ]), &(acadoWorkspace.QE[ 984 ]) ); +acado_setBlockH11( 7, 11, &(acadoWorkspace.E[ 1068 ]), &(acadoWorkspace.QE[ 1092 ]) ); +acado_setBlockH11( 7, 11, &(acadoWorkspace.E[ 1182 ]), &(acadoWorkspace.QE[ 1206 ]) ); + +acado_zeroBlockH11( 7, 12 ); +acado_setBlockH11( 7, 12, &(acadoWorkspace.E[ 510 ]), &(acadoWorkspace.QE[ 540 ]) ); +acado_setBlockH11( 7, 12, &(acadoWorkspace.E[ 588 ]), &(acadoWorkspace.QE[ 618 ]) ); +acado_setBlockH11( 7, 12, &(acadoWorkspace.E[ 672 ]), &(acadoWorkspace.QE[ 702 ]) ); +acado_setBlockH11( 7, 12, &(acadoWorkspace.E[ 762 ]), &(acadoWorkspace.QE[ 792 ]) ); +acado_setBlockH11( 7, 12, &(acadoWorkspace.E[ 858 ]), &(acadoWorkspace.QE[ 888 ]) ); +acado_setBlockH11( 7, 12, &(acadoWorkspace.E[ 960 ]), &(acadoWorkspace.QE[ 990 ]) ); +acado_setBlockH11( 7, 12, &(acadoWorkspace.E[ 1068 ]), &(acadoWorkspace.QE[ 1098 ]) ); +acado_setBlockH11( 7, 12, &(acadoWorkspace.E[ 1182 ]), &(acadoWorkspace.QE[ 1212 ]) ); + +acado_zeroBlockH11( 7, 13 ); +acado_setBlockH11( 7, 13, &(acadoWorkspace.E[ 588 ]), &(acadoWorkspace.QE[ 624 ]) ); +acado_setBlockH11( 7, 13, &(acadoWorkspace.E[ 672 ]), &(acadoWorkspace.QE[ 708 ]) ); +acado_setBlockH11( 7, 13, &(acadoWorkspace.E[ 762 ]), &(acadoWorkspace.QE[ 798 ]) ); +acado_setBlockH11( 7, 13, &(acadoWorkspace.E[ 858 ]), &(acadoWorkspace.QE[ 894 ]) ); +acado_setBlockH11( 7, 13, &(acadoWorkspace.E[ 960 ]), &(acadoWorkspace.QE[ 996 ]) ); +acado_setBlockH11( 7, 13, &(acadoWorkspace.E[ 1068 ]), &(acadoWorkspace.QE[ 1104 ]) ); +acado_setBlockH11( 7, 13, &(acadoWorkspace.E[ 1182 ]), &(acadoWorkspace.QE[ 1218 ]) ); + +acado_zeroBlockH11( 7, 14 ); +acado_setBlockH11( 7, 14, &(acadoWorkspace.E[ 672 ]), &(acadoWorkspace.QE[ 714 ]) ); +acado_setBlockH11( 7, 14, &(acadoWorkspace.E[ 762 ]), &(acadoWorkspace.QE[ 804 ]) ); +acado_setBlockH11( 7, 14, &(acadoWorkspace.E[ 858 ]), &(acadoWorkspace.QE[ 900 ]) ); +acado_setBlockH11( 7, 14, &(acadoWorkspace.E[ 960 ]), &(acadoWorkspace.QE[ 1002 ]) ); +acado_setBlockH11( 7, 14, &(acadoWorkspace.E[ 1068 ]), &(acadoWorkspace.QE[ 1110 ]) ); +acado_setBlockH11( 7, 14, &(acadoWorkspace.E[ 1182 ]), &(acadoWorkspace.QE[ 1224 ]) ); + +acado_zeroBlockH11( 7, 15 ); +acado_setBlockH11( 7, 15, &(acadoWorkspace.E[ 762 ]), &(acadoWorkspace.QE[ 810 ]) ); +acado_setBlockH11( 7, 15, &(acadoWorkspace.E[ 858 ]), &(acadoWorkspace.QE[ 906 ]) ); +acado_setBlockH11( 7, 15, &(acadoWorkspace.E[ 960 ]), &(acadoWorkspace.QE[ 1008 ]) ); +acado_setBlockH11( 7, 15, &(acadoWorkspace.E[ 1068 ]), &(acadoWorkspace.QE[ 1116 ]) ); +acado_setBlockH11( 7, 15, &(acadoWorkspace.E[ 1182 ]), &(acadoWorkspace.QE[ 1230 ]) ); + +acado_zeroBlockH11( 7, 16 ); +acado_setBlockH11( 7, 16, &(acadoWorkspace.E[ 858 ]), &(acadoWorkspace.QE[ 912 ]) ); +acado_setBlockH11( 7, 16, &(acadoWorkspace.E[ 960 ]), &(acadoWorkspace.QE[ 1014 ]) ); +acado_setBlockH11( 7, 16, &(acadoWorkspace.E[ 1068 ]), &(acadoWorkspace.QE[ 1122 ]) ); +acado_setBlockH11( 7, 16, &(acadoWorkspace.E[ 1182 ]), &(acadoWorkspace.QE[ 1236 ]) ); + +acado_zeroBlockH11( 7, 17 ); +acado_setBlockH11( 7, 17, &(acadoWorkspace.E[ 960 ]), &(acadoWorkspace.QE[ 1020 ]) ); +acado_setBlockH11( 7, 17, &(acadoWorkspace.E[ 1068 ]), &(acadoWorkspace.QE[ 1128 ]) ); +acado_setBlockH11( 7, 17, &(acadoWorkspace.E[ 1182 ]), &(acadoWorkspace.QE[ 1242 ]) ); + +acado_zeroBlockH11( 7, 18 ); +acado_setBlockH11( 7, 18, &(acadoWorkspace.E[ 1068 ]), &(acadoWorkspace.QE[ 1134 ]) ); +acado_setBlockH11( 7, 18, &(acadoWorkspace.E[ 1182 ]), &(acadoWorkspace.QE[ 1248 ]) ); + +acado_zeroBlockH11( 7, 19 ); +acado_setBlockH11( 7, 19, &(acadoWorkspace.E[ 1182 ]), &(acadoWorkspace.QE[ 1254 ]) ); + +acado_setBlockH11_R1( 8, 8, &(acadoWorkspace.R1[ 8 ]) ); +acado_setBlockH11( 8, 8, &(acadoWorkspace.E[ 264 ]), &(acadoWorkspace.QE[ 264 ]) ); +acado_setBlockH11( 8, 8, &(acadoWorkspace.E[ 318 ]), &(acadoWorkspace.QE[ 318 ]) ); +acado_setBlockH11( 8, 8, &(acadoWorkspace.E[ 378 ]), &(acadoWorkspace.QE[ 378 ]) ); +acado_setBlockH11( 8, 8, &(acadoWorkspace.E[ 444 ]), &(acadoWorkspace.QE[ 444 ]) ); +acado_setBlockH11( 8, 8, &(acadoWorkspace.E[ 516 ]), &(acadoWorkspace.QE[ 516 ]) ); +acado_setBlockH11( 8, 8, &(acadoWorkspace.E[ 594 ]), &(acadoWorkspace.QE[ 594 ]) ); +acado_setBlockH11( 8, 8, &(acadoWorkspace.E[ 678 ]), &(acadoWorkspace.QE[ 678 ]) ); +acado_setBlockH11( 8, 8, &(acadoWorkspace.E[ 768 ]), &(acadoWorkspace.QE[ 768 ]) ); +acado_setBlockH11( 8, 8, &(acadoWorkspace.E[ 864 ]), &(acadoWorkspace.QE[ 864 ]) ); +acado_setBlockH11( 8, 8, &(acadoWorkspace.E[ 966 ]), &(acadoWorkspace.QE[ 966 ]) ); +acado_setBlockH11( 8, 8, &(acadoWorkspace.E[ 1074 ]), &(acadoWorkspace.QE[ 1074 ]) ); +acado_setBlockH11( 8, 8, &(acadoWorkspace.E[ 1188 ]), &(acadoWorkspace.QE[ 1188 ]) ); + +acado_zeroBlockH11( 8, 9 ); +acado_setBlockH11( 8, 9, &(acadoWorkspace.E[ 318 ]), &(acadoWorkspace.QE[ 324 ]) ); +acado_setBlockH11( 8, 9, &(acadoWorkspace.E[ 378 ]), &(acadoWorkspace.QE[ 384 ]) ); +acado_setBlockH11( 8, 9, &(acadoWorkspace.E[ 444 ]), &(acadoWorkspace.QE[ 450 ]) ); +acado_setBlockH11( 8, 9, &(acadoWorkspace.E[ 516 ]), &(acadoWorkspace.QE[ 522 ]) ); +acado_setBlockH11( 8, 9, &(acadoWorkspace.E[ 594 ]), &(acadoWorkspace.QE[ 600 ]) ); +acado_setBlockH11( 8, 9, &(acadoWorkspace.E[ 678 ]), &(acadoWorkspace.QE[ 684 ]) ); +acado_setBlockH11( 8, 9, &(acadoWorkspace.E[ 768 ]), &(acadoWorkspace.QE[ 774 ]) ); +acado_setBlockH11( 8, 9, &(acadoWorkspace.E[ 864 ]), &(acadoWorkspace.QE[ 870 ]) ); +acado_setBlockH11( 8, 9, &(acadoWorkspace.E[ 966 ]), &(acadoWorkspace.QE[ 972 ]) ); +acado_setBlockH11( 8, 9, &(acadoWorkspace.E[ 1074 ]), &(acadoWorkspace.QE[ 1080 ]) ); +acado_setBlockH11( 8, 9, &(acadoWorkspace.E[ 1188 ]), &(acadoWorkspace.QE[ 1194 ]) ); + +acado_zeroBlockH11( 8, 10 ); +acado_setBlockH11( 8, 10, &(acadoWorkspace.E[ 378 ]), &(acadoWorkspace.QE[ 390 ]) ); +acado_setBlockH11( 8, 10, &(acadoWorkspace.E[ 444 ]), &(acadoWorkspace.QE[ 456 ]) ); +acado_setBlockH11( 8, 10, &(acadoWorkspace.E[ 516 ]), &(acadoWorkspace.QE[ 528 ]) ); +acado_setBlockH11( 8, 10, &(acadoWorkspace.E[ 594 ]), &(acadoWorkspace.QE[ 606 ]) ); +acado_setBlockH11( 8, 10, &(acadoWorkspace.E[ 678 ]), &(acadoWorkspace.QE[ 690 ]) ); +acado_setBlockH11( 8, 10, &(acadoWorkspace.E[ 768 ]), &(acadoWorkspace.QE[ 780 ]) ); +acado_setBlockH11( 8, 10, &(acadoWorkspace.E[ 864 ]), &(acadoWorkspace.QE[ 876 ]) ); +acado_setBlockH11( 8, 10, &(acadoWorkspace.E[ 966 ]), &(acadoWorkspace.QE[ 978 ]) ); +acado_setBlockH11( 8, 10, &(acadoWorkspace.E[ 1074 ]), &(acadoWorkspace.QE[ 1086 ]) ); +acado_setBlockH11( 8, 10, &(acadoWorkspace.E[ 1188 ]), &(acadoWorkspace.QE[ 1200 ]) ); + +acado_zeroBlockH11( 8, 11 ); +acado_setBlockH11( 8, 11, &(acadoWorkspace.E[ 444 ]), &(acadoWorkspace.QE[ 462 ]) ); +acado_setBlockH11( 8, 11, &(acadoWorkspace.E[ 516 ]), &(acadoWorkspace.QE[ 534 ]) ); +acado_setBlockH11( 8, 11, &(acadoWorkspace.E[ 594 ]), &(acadoWorkspace.QE[ 612 ]) ); +acado_setBlockH11( 8, 11, &(acadoWorkspace.E[ 678 ]), &(acadoWorkspace.QE[ 696 ]) ); +acado_setBlockH11( 8, 11, &(acadoWorkspace.E[ 768 ]), &(acadoWorkspace.QE[ 786 ]) ); +acado_setBlockH11( 8, 11, &(acadoWorkspace.E[ 864 ]), &(acadoWorkspace.QE[ 882 ]) ); +acado_setBlockH11( 8, 11, &(acadoWorkspace.E[ 966 ]), &(acadoWorkspace.QE[ 984 ]) ); +acado_setBlockH11( 8, 11, &(acadoWorkspace.E[ 1074 ]), &(acadoWorkspace.QE[ 1092 ]) ); +acado_setBlockH11( 8, 11, &(acadoWorkspace.E[ 1188 ]), &(acadoWorkspace.QE[ 1206 ]) ); + +acado_zeroBlockH11( 8, 12 ); +acado_setBlockH11( 8, 12, &(acadoWorkspace.E[ 516 ]), &(acadoWorkspace.QE[ 540 ]) ); +acado_setBlockH11( 8, 12, &(acadoWorkspace.E[ 594 ]), &(acadoWorkspace.QE[ 618 ]) ); +acado_setBlockH11( 8, 12, &(acadoWorkspace.E[ 678 ]), &(acadoWorkspace.QE[ 702 ]) ); +acado_setBlockH11( 8, 12, &(acadoWorkspace.E[ 768 ]), &(acadoWorkspace.QE[ 792 ]) ); +acado_setBlockH11( 8, 12, &(acadoWorkspace.E[ 864 ]), &(acadoWorkspace.QE[ 888 ]) ); +acado_setBlockH11( 8, 12, &(acadoWorkspace.E[ 966 ]), &(acadoWorkspace.QE[ 990 ]) ); +acado_setBlockH11( 8, 12, &(acadoWorkspace.E[ 1074 ]), &(acadoWorkspace.QE[ 1098 ]) ); +acado_setBlockH11( 8, 12, &(acadoWorkspace.E[ 1188 ]), &(acadoWorkspace.QE[ 1212 ]) ); + +acado_zeroBlockH11( 8, 13 ); +acado_setBlockH11( 8, 13, &(acadoWorkspace.E[ 594 ]), &(acadoWorkspace.QE[ 624 ]) ); +acado_setBlockH11( 8, 13, &(acadoWorkspace.E[ 678 ]), &(acadoWorkspace.QE[ 708 ]) ); +acado_setBlockH11( 8, 13, &(acadoWorkspace.E[ 768 ]), &(acadoWorkspace.QE[ 798 ]) ); +acado_setBlockH11( 8, 13, &(acadoWorkspace.E[ 864 ]), &(acadoWorkspace.QE[ 894 ]) ); +acado_setBlockH11( 8, 13, &(acadoWorkspace.E[ 966 ]), &(acadoWorkspace.QE[ 996 ]) ); +acado_setBlockH11( 8, 13, &(acadoWorkspace.E[ 1074 ]), &(acadoWorkspace.QE[ 1104 ]) ); +acado_setBlockH11( 8, 13, &(acadoWorkspace.E[ 1188 ]), &(acadoWorkspace.QE[ 1218 ]) ); + +acado_zeroBlockH11( 8, 14 ); +acado_setBlockH11( 8, 14, &(acadoWorkspace.E[ 678 ]), &(acadoWorkspace.QE[ 714 ]) ); +acado_setBlockH11( 8, 14, &(acadoWorkspace.E[ 768 ]), &(acadoWorkspace.QE[ 804 ]) ); +acado_setBlockH11( 8, 14, &(acadoWorkspace.E[ 864 ]), &(acadoWorkspace.QE[ 900 ]) ); +acado_setBlockH11( 8, 14, &(acadoWorkspace.E[ 966 ]), &(acadoWorkspace.QE[ 1002 ]) ); +acado_setBlockH11( 8, 14, &(acadoWorkspace.E[ 1074 ]), &(acadoWorkspace.QE[ 1110 ]) ); +acado_setBlockH11( 8, 14, &(acadoWorkspace.E[ 1188 ]), &(acadoWorkspace.QE[ 1224 ]) ); + +acado_zeroBlockH11( 8, 15 ); +acado_setBlockH11( 8, 15, &(acadoWorkspace.E[ 768 ]), &(acadoWorkspace.QE[ 810 ]) ); +acado_setBlockH11( 8, 15, &(acadoWorkspace.E[ 864 ]), &(acadoWorkspace.QE[ 906 ]) ); +acado_setBlockH11( 8, 15, &(acadoWorkspace.E[ 966 ]), &(acadoWorkspace.QE[ 1008 ]) ); +acado_setBlockH11( 8, 15, &(acadoWorkspace.E[ 1074 ]), &(acadoWorkspace.QE[ 1116 ]) ); +acado_setBlockH11( 8, 15, &(acadoWorkspace.E[ 1188 ]), &(acadoWorkspace.QE[ 1230 ]) ); + +acado_zeroBlockH11( 8, 16 ); +acado_setBlockH11( 8, 16, &(acadoWorkspace.E[ 864 ]), &(acadoWorkspace.QE[ 912 ]) ); +acado_setBlockH11( 8, 16, &(acadoWorkspace.E[ 966 ]), &(acadoWorkspace.QE[ 1014 ]) ); +acado_setBlockH11( 8, 16, &(acadoWorkspace.E[ 1074 ]), &(acadoWorkspace.QE[ 1122 ]) ); +acado_setBlockH11( 8, 16, &(acadoWorkspace.E[ 1188 ]), &(acadoWorkspace.QE[ 1236 ]) ); + +acado_zeroBlockH11( 8, 17 ); +acado_setBlockH11( 8, 17, &(acadoWorkspace.E[ 966 ]), &(acadoWorkspace.QE[ 1020 ]) ); +acado_setBlockH11( 8, 17, &(acadoWorkspace.E[ 1074 ]), &(acadoWorkspace.QE[ 1128 ]) ); +acado_setBlockH11( 8, 17, &(acadoWorkspace.E[ 1188 ]), &(acadoWorkspace.QE[ 1242 ]) ); + +acado_zeroBlockH11( 8, 18 ); +acado_setBlockH11( 8, 18, &(acadoWorkspace.E[ 1074 ]), &(acadoWorkspace.QE[ 1134 ]) ); +acado_setBlockH11( 8, 18, &(acadoWorkspace.E[ 1188 ]), &(acadoWorkspace.QE[ 1248 ]) ); + +acado_zeroBlockH11( 8, 19 ); +acado_setBlockH11( 8, 19, &(acadoWorkspace.E[ 1188 ]), &(acadoWorkspace.QE[ 1254 ]) ); + +acado_setBlockH11_R1( 9, 9, &(acadoWorkspace.R1[ 9 ]) ); +acado_setBlockH11( 9, 9, &(acadoWorkspace.E[ 324 ]), &(acadoWorkspace.QE[ 324 ]) ); +acado_setBlockH11( 9, 9, &(acadoWorkspace.E[ 384 ]), &(acadoWorkspace.QE[ 384 ]) ); +acado_setBlockH11( 9, 9, &(acadoWorkspace.E[ 450 ]), &(acadoWorkspace.QE[ 450 ]) ); +acado_setBlockH11( 9, 9, &(acadoWorkspace.E[ 522 ]), &(acadoWorkspace.QE[ 522 ]) ); +acado_setBlockH11( 9, 9, &(acadoWorkspace.E[ 600 ]), &(acadoWorkspace.QE[ 600 ]) ); +acado_setBlockH11( 9, 9, &(acadoWorkspace.E[ 684 ]), &(acadoWorkspace.QE[ 684 ]) ); +acado_setBlockH11( 9, 9, &(acadoWorkspace.E[ 774 ]), &(acadoWorkspace.QE[ 774 ]) ); +acado_setBlockH11( 9, 9, &(acadoWorkspace.E[ 870 ]), &(acadoWorkspace.QE[ 870 ]) ); +acado_setBlockH11( 9, 9, &(acadoWorkspace.E[ 972 ]), &(acadoWorkspace.QE[ 972 ]) ); +acado_setBlockH11( 9, 9, &(acadoWorkspace.E[ 1080 ]), &(acadoWorkspace.QE[ 1080 ]) ); +acado_setBlockH11( 9, 9, &(acadoWorkspace.E[ 1194 ]), &(acadoWorkspace.QE[ 1194 ]) ); + +acado_zeroBlockH11( 9, 10 ); +acado_setBlockH11( 9, 10, &(acadoWorkspace.E[ 384 ]), &(acadoWorkspace.QE[ 390 ]) ); +acado_setBlockH11( 9, 10, &(acadoWorkspace.E[ 450 ]), &(acadoWorkspace.QE[ 456 ]) ); +acado_setBlockH11( 9, 10, &(acadoWorkspace.E[ 522 ]), &(acadoWorkspace.QE[ 528 ]) ); +acado_setBlockH11( 9, 10, &(acadoWorkspace.E[ 600 ]), &(acadoWorkspace.QE[ 606 ]) ); +acado_setBlockH11( 9, 10, &(acadoWorkspace.E[ 684 ]), &(acadoWorkspace.QE[ 690 ]) ); +acado_setBlockH11( 9, 10, &(acadoWorkspace.E[ 774 ]), &(acadoWorkspace.QE[ 780 ]) ); +acado_setBlockH11( 9, 10, &(acadoWorkspace.E[ 870 ]), &(acadoWorkspace.QE[ 876 ]) ); +acado_setBlockH11( 9, 10, &(acadoWorkspace.E[ 972 ]), &(acadoWorkspace.QE[ 978 ]) ); +acado_setBlockH11( 9, 10, &(acadoWorkspace.E[ 1080 ]), &(acadoWorkspace.QE[ 1086 ]) ); +acado_setBlockH11( 9, 10, &(acadoWorkspace.E[ 1194 ]), &(acadoWorkspace.QE[ 1200 ]) ); + +acado_zeroBlockH11( 9, 11 ); +acado_setBlockH11( 9, 11, &(acadoWorkspace.E[ 450 ]), &(acadoWorkspace.QE[ 462 ]) ); +acado_setBlockH11( 9, 11, &(acadoWorkspace.E[ 522 ]), &(acadoWorkspace.QE[ 534 ]) ); +acado_setBlockH11( 9, 11, &(acadoWorkspace.E[ 600 ]), &(acadoWorkspace.QE[ 612 ]) ); +acado_setBlockH11( 9, 11, &(acadoWorkspace.E[ 684 ]), &(acadoWorkspace.QE[ 696 ]) ); +acado_setBlockH11( 9, 11, &(acadoWorkspace.E[ 774 ]), &(acadoWorkspace.QE[ 786 ]) ); +acado_setBlockH11( 9, 11, &(acadoWorkspace.E[ 870 ]), &(acadoWorkspace.QE[ 882 ]) ); +acado_setBlockH11( 9, 11, &(acadoWorkspace.E[ 972 ]), &(acadoWorkspace.QE[ 984 ]) ); +acado_setBlockH11( 9, 11, &(acadoWorkspace.E[ 1080 ]), &(acadoWorkspace.QE[ 1092 ]) ); +acado_setBlockH11( 9, 11, &(acadoWorkspace.E[ 1194 ]), &(acadoWorkspace.QE[ 1206 ]) ); + +acado_zeroBlockH11( 9, 12 ); +acado_setBlockH11( 9, 12, &(acadoWorkspace.E[ 522 ]), &(acadoWorkspace.QE[ 540 ]) ); +acado_setBlockH11( 9, 12, &(acadoWorkspace.E[ 600 ]), &(acadoWorkspace.QE[ 618 ]) ); +acado_setBlockH11( 9, 12, &(acadoWorkspace.E[ 684 ]), &(acadoWorkspace.QE[ 702 ]) ); +acado_setBlockH11( 9, 12, &(acadoWorkspace.E[ 774 ]), &(acadoWorkspace.QE[ 792 ]) ); +acado_setBlockH11( 9, 12, &(acadoWorkspace.E[ 870 ]), &(acadoWorkspace.QE[ 888 ]) ); +acado_setBlockH11( 9, 12, &(acadoWorkspace.E[ 972 ]), &(acadoWorkspace.QE[ 990 ]) ); +acado_setBlockH11( 9, 12, &(acadoWorkspace.E[ 1080 ]), &(acadoWorkspace.QE[ 1098 ]) ); +acado_setBlockH11( 9, 12, &(acadoWorkspace.E[ 1194 ]), &(acadoWorkspace.QE[ 1212 ]) ); + +acado_zeroBlockH11( 9, 13 ); +acado_setBlockH11( 9, 13, &(acadoWorkspace.E[ 600 ]), &(acadoWorkspace.QE[ 624 ]) ); +acado_setBlockH11( 9, 13, &(acadoWorkspace.E[ 684 ]), &(acadoWorkspace.QE[ 708 ]) ); +acado_setBlockH11( 9, 13, &(acadoWorkspace.E[ 774 ]), &(acadoWorkspace.QE[ 798 ]) ); +acado_setBlockH11( 9, 13, &(acadoWorkspace.E[ 870 ]), &(acadoWorkspace.QE[ 894 ]) ); +acado_setBlockH11( 9, 13, &(acadoWorkspace.E[ 972 ]), &(acadoWorkspace.QE[ 996 ]) ); +acado_setBlockH11( 9, 13, &(acadoWorkspace.E[ 1080 ]), &(acadoWorkspace.QE[ 1104 ]) ); +acado_setBlockH11( 9, 13, &(acadoWorkspace.E[ 1194 ]), &(acadoWorkspace.QE[ 1218 ]) ); + +acado_zeroBlockH11( 9, 14 ); +acado_setBlockH11( 9, 14, &(acadoWorkspace.E[ 684 ]), &(acadoWorkspace.QE[ 714 ]) ); +acado_setBlockH11( 9, 14, &(acadoWorkspace.E[ 774 ]), &(acadoWorkspace.QE[ 804 ]) ); +acado_setBlockH11( 9, 14, &(acadoWorkspace.E[ 870 ]), &(acadoWorkspace.QE[ 900 ]) ); +acado_setBlockH11( 9, 14, &(acadoWorkspace.E[ 972 ]), &(acadoWorkspace.QE[ 1002 ]) ); +acado_setBlockH11( 9, 14, &(acadoWorkspace.E[ 1080 ]), &(acadoWorkspace.QE[ 1110 ]) ); +acado_setBlockH11( 9, 14, &(acadoWorkspace.E[ 1194 ]), &(acadoWorkspace.QE[ 1224 ]) ); + +acado_zeroBlockH11( 9, 15 ); +acado_setBlockH11( 9, 15, &(acadoWorkspace.E[ 774 ]), &(acadoWorkspace.QE[ 810 ]) ); +acado_setBlockH11( 9, 15, &(acadoWorkspace.E[ 870 ]), &(acadoWorkspace.QE[ 906 ]) ); +acado_setBlockH11( 9, 15, &(acadoWorkspace.E[ 972 ]), &(acadoWorkspace.QE[ 1008 ]) ); +acado_setBlockH11( 9, 15, &(acadoWorkspace.E[ 1080 ]), &(acadoWorkspace.QE[ 1116 ]) ); +acado_setBlockH11( 9, 15, &(acadoWorkspace.E[ 1194 ]), &(acadoWorkspace.QE[ 1230 ]) ); + +acado_zeroBlockH11( 9, 16 ); +acado_setBlockH11( 9, 16, &(acadoWorkspace.E[ 870 ]), &(acadoWorkspace.QE[ 912 ]) ); +acado_setBlockH11( 9, 16, &(acadoWorkspace.E[ 972 ]), &(acadoWorkspace.QE[ 1014 ]) ); +acado_setBlockH11( 9, 16, &(acadoWorkspace.E[ 1080 ]), &(acadoWorkspace.QE[ 1122 ]) ); +acado_setBlockH11( 9, 16, &(acadoWorkspace.E[ 1194 ]), &(acadoWorkspace.QE[ 1236 ]) ); + +acado_zeroBlockH11( 9, 17 ); +acado_setBlockH11( 9, 17, &(acadoWorkspace.E[ 972 ]), &(acadoWorkspace.QE[ 1020 ]) ); +acado_setBlockH11( 9, 17, &(acadoWorkspace.E[ 1080 ]), &(acadoWorkspace.QE[ 1128 ]) ); +acado_setBlockH11( 9, 17, &(acadoWorkspace.E[ 1194 ]), &(acadoWorkspace.QE[ 1242 ]) ); + +acado_zeroBlockH11( 9, 18 ); +acado_setBlockH11( 9, 18, &(acadoWorkspace.E[ 1080 ]), &(acadoWorkspace.QE[ 1134 ]) ); +acado_setBlockH11( 9, 18, &(acadoWorkspace.E[ 1194 ]), &(acadoWorkspace.QE[ 1248 ]) ); + +acado_zeroBlockH11( 9, 19 ); +acado_setBlockH11( 9, 19, &(acadoWorkspace.E[ 1194 ]), &(acadoWorkspace.QE[ 1254 ]) ); + +acado_setBlockH11_R1( 10, 10, &(acadoWorkspace.R1[ 10 ]) ); +acado_setBlockH11( 10, 10, &(acadoWorkspace.E[ 390 ]), &(acadoWorkspace.QE[ 390 ]) ); +acado_setBlockH11( 10, 10, &(acadoWorkspace.E[ 456 ]), &(acadoWorkspace.QE[ 456 ]) ); +acado_setBlockH11( 10, 10, &(acadoWorkspace.E[ 528 ]), &(acadoWorkspace.QE[ 528 ]) ); +acado_setBlockH11( 10, 10, &(acadoWorkspace.E[ 606 ]), &(acadoWorkspace.QE[ 606 ]) ); +acado_setBlockH11( 10, 10, &(acadoWorkspace.E[ 690 ]), &(acadoWorkspace.QE[ 690 ]) ); +acado_setBlockH11( 10, 10, &(acadoWorkspace.E[ 780 ]), &(acadoWorkspace.QE[ 780 ]) ); +acado_setBlockH11( 10, 10, &(acadoWorkspace.E[ 876 ]), &(acadoWorkspace.QE[ 876 ]) ); +acado_setBlockH11( 10, 10, &(acadoWorkspace.E[ 978 ]), &(acadoWorkspace.QE[ 978 ]) ); +acado_setBlockH11( 10, 10, &(acadoWorkspace.E[ 1086 ]), &(acadoWorkspace.QE[ 1086 ]) ); +acado_setBlockH11( 10, 10, &(acadoWorkspace.E[ 1200 ]), &(acadoWorkspace.QE[ 1200 ]) ); + +acado_zeroBlockH11( 10, 11 ); +acado_setBlockH11( 10, 11, &(acadoWorkspace.E[ 456 ]), &(acadoWorkspace.QE[ 462 ]) ); +acado_setBlockH11( 10, 11, &(acadoWorkspace.E[ 528 ]), &(acadoWorkspace.QE[ 534 ]) ); +acado_setBlockH11( 10, 11, &(acadoWorkspace.E[ 606 ]), &(acadoWorkspace.QE[ 612 ]) ); +acado_setBlockH11( 10, 11, &(acadoWorkspace.E[ 690 ]), &(acadoWorkspace.QE[ 696 ]) ); +acado_setBlockH11( 10, 11, &(acadoWorkspace.E[ 780 ]), &(acadoWorkspace.QE[ 786 ]) ); +acado_setBlockH11( 10, 11, &(acadoWorkspace.E[ 876 ]), &(acadoWorkspace.QE[ 882 ]) ); +acado_setBlockH11( 10, 11, &(acadoWorkspace.E[ 978 ]), &(acadoWorkspace.QE[ 984 ]) ); +acado_setBlockH11( 10, 11, &(acadoWorkspace.E[ 1086 ]), &(acadoWorkspace.QE[ 1092 ]) ); +acado_setBlockH11( 10, 11, &(acadoWorkspace.E[ 1200 ]), &(acadoWorkspace.QE[ 1206 ]) ); + +acado_zeroBlockH11( 10, 12 ); +acado_setBlockH11( 10, 12, &(acadoWorkspace.E[ 528 ]), &(acadoWorkspace.QE[ 540 ]) ); +acado_setBlockH11( 10, 12, &(acadoWorkspace.E[ 606 ]), &(acadoWorkspace.QE[ 618 ]) ); +acado_setBlockH11( 10, 12, &(acadoWorkspace.E[ 690 ]), &(acadoWorkspace.QE[ 702 ]) ); +acado_setBlockH11( 10, 12, &(acadoWorkspace.E[ 780 ]), &(acadoWorkspace.QE[ 792 ]) ); +acado_setBlockH11( 10, 12, &(acadoWorkspace.E[ 876 ]), &(acadoWorkspace.QE[ 888 ]) ); +acado_setBlockH11( 10, 12, &(acadoWorkspace.E[ 978 ]), &(acadoWorkspace.QE[ 990 ]) ); +acado_setBlockH11( 10, 12, &(acadoWorkspace.E[ 1086 ]), &(acadoWorkspace.QE[ 1098 ]) ); +acado_setBlockH11( 10, 12, &(acadoWorkspace.E[ 1200 ]), &(acadoWorkspace.QE[ 1212 ]) ); + +acado_zeroBlockH11( 10, 13 ); +acado_setBlockH11( 10, 13, &(acadoWorkspace.E[ 606 ]), &(acadoWorkspace.QE[ 624 ]) ); +acado_setBlockH11( 10, 13, &(acadoWorkspace.E[ 690 ]), &(acadoWorkspace.QE[ 708 ]) ); +acado_setBlockH11( 10, 13, &(acadoWorkspace.E[ 780 ]), &(acadoWorkspace.QE[ 798 ]) ); +acado_setBlockH11( 10, 13, &(acadoWorkspace.E[ 876 ]), &(acadoWorkspace.QE[ 894 ]) ); +acado_setBlockH11( 10, 13, &(acadoWorkspace.E[ 978 ]), &(acadoWorkspace.QE[ 996 ]) ); +acado_setBlockH11( 10, 13, &(acadoWorkspace.E[ 1086 ]), &(acadoWorkspace.QE[ 1104 ]) ); +acado_setBlockH11( 10, 13, &(acadoWorkspace.E[ 1200 ]), &(acadoWorkspace.QE[ 1218 ]) ); + +acado_zeroBlockH11( 10, 14 ); +acado_setBlockH11( 10, 14, &(acadoWorkspace.E[ 690 ]), &(acadoWorkspace.QE[ 714 ]) ); +acado_setBlockH11( 10, 14, &(acadoWorkspace.E[ 780 ]), &(acadoWorkspace.QE[ 804 ]) ); +acado_setBlockH11( 10, 14, &(acadoWorkspace.E[ 876 ]), &(acadoWorkspace.QE[ 900 ]) ); +acado_setBlockH11( 10, 14, &(acadoWorkspace.E[ 978 ]), &(acadoWorkspace.QE[ 1002 ]) ); +acado_setBlockH11( 10, 14, &(acadoWorkspace.E[ 1086 ]), &(acadoWorkspace.QE[ 1110 ]) ); +acado_setBlockH11( 10, 14, &(acadoWorkspace.E[ 1200 ]), &(acadoWorkspace.QE[ 1224 ]) ); + +acado_zeroBlockH11( 10, 15 ); +acado_setBlockH11( 10, 15, &(acadoWorkspace.E[ 780 ]), &(acadoWorkspace.QE[ 810 ]) ); +acado_setBlockH11( 10, 15, &(acadoWorkspace.E[ 876 ]), &(acadoWorkspace.QE[ 906 ]) ); +acado_setBlockH11( 10, 15, &(acadoWorkspace.E[ 978 ]), &(acadoWorkspace.QE[ 1008 ]) ); +acado_setBlockH11( 10, 15, &(acadoWorkspace.E[ 1086 ]), &(acadoWorkspace.QE[ 1116 ]) ); +acado_setBlockH11( 10, 15, &(acadoWorkspace.E[ 1200 ]), &(acadoWorkspace.QE[ 1230 ]) ); + +acado_zeroBlockH11( 10, 16 ); +acado_setBlockH11( 10, 16, &(acadoWorkspace.E[ 876 ]), &(acadoWorkspace.QE[ 912 ]) ); +acado_setBlockH11( 10, 16, &(acadoWorkspace.E[ 978 ]), &(acadoWorkspace.QE[ 1014 ]) ); +acado_setBlockH11( 10, 16, &(acadoWorkspace.E[ 1086 ]), &(acadoWorkspace.QE[ 1122 ]) ); +acado_setBlockH11( 10, 16, &(acadoWorkspace.E[ 1200 ]), &(acadoWorkspace.QE[ 1236 ]) ); + +acado_zeroBlockH11( 10, 17 ); +acado_setBlockH11( 10, 17, &(acadoWorkspace.E[ 978 ]), &(acadoWorkspace.QE[ 1020 ]) ); +acado_setBlockH11( 10, 17, &(acadoWorkspace.E[ 1086 ]), &(acadoWorkspace.QE[ 1128 ]) ); +acado_setBlockH11( 10, 17, &(acadoWorkspace.E[ 1200 ]), &(acadoWorkspace.QE[ 1242 ]) ); + +acado_zeroBlockH11( 10, 18 ); +acado_setBlockH11( 10, 18, &(acadoWorkspace.E[ 1086 ]), &(acadoWorkspace.QE[ 1134 ]) ); +acado_setBlockH11( 10, 18, &(acadoWorkspace.E[ 1200 ]), &(acadoWorkspace.QE[ 1248 ]) ); + +acado_zeroBlockH11( 10, 19 ); +acado_setBlockH11( 10, 19, &(acadoWorkspace.E[ 1200 ]), &(acadoWorkspace.QE[ 1254 ]) ); + +acado_setBlockH11_R1( 11, 11, &(acadoWorkspace.R1[ 11 ]) ); +acado_setBlockH11( 11, 11, &(acadoWorkspace.E[ 462 ]), &(acadoWorkspace.QE[ 462 ]) ); +acado_setBlockH11( 11, 11, &(acadoWorkspace.E[ 534 ]), &(acadoWorkspace.QE[ 534 ]) ); +acado_setBlockH11( 11, 11, &(acadoWorkspace.E[ 612 ]), &(acadoWorkspace.QE[ 612 ]) ); +acado_setBlockH11( 11, 11, &(acadoWorkspace.E[ 696 ]), &(acadoWorkspace.QE[ 696 ]) ); +acado_setBlockH11( 11, 11, &(acadoWorkspace.E[ 786 ]), &(acadoWorkspace.QE[ 786 ]) ); +acado_setBlockH11( 11, 11, &(acadoWorkspace.E[ 882 ]), &(acadoWorkspace.QE[ 882 ]) ); +acado_setBlockH11( 11, 11, &(acadoWorkspace.E[ 984 ]), &(acadoWorkspace.QE[ 984 ]) ); +acado_setBlockH11( 11, 11, &(acadoWorkspace.E[ 1092 ]), &(acadoWorkspace.QE[ 1092 ]) ); +acado_setBlockH11( 11, 11, &(acadoWorkspace.E[ 1206 ]), &(acadoWorkspace.QE[ 1206 ]) ); + +acado_zeroBlockH11( 11, 12 ); +acado_setBlockH11( 11, 12, &(acadoWorkspace.E[ 534 ]), &(acadoWorkspace.QE[ 540 ]) ); +acado_setBlockH11( 11, 12, &(acadoWorkspace.E[ 612 ]), &(acadoWorkspace.QE[ 618 ]) ); +acado_setBlockH11( 11, 12, &(acadoWorkspace.E[ 696 ]), &(acadoWorkspace.QE[ 702 ]) ); +acado_setBlockH11( 11, 12, &(acadoWorkspace.E[ 786 ]), &(acadoWorkspace.QE[ 792 ]) ); +acado_setBlockH11( 11, 12, &(acadoWorkspace.E[ 882 ]), &(acadoWorkspace.QE[ 888 ]) ); +acado_setBlockH11( 11, 12, &(acadoWorkspace.E[ 984 ]), &(acadoWorkspace.QE[ 990 ]) ); +acado_setBlockH11( 11, 12, &(acadoWorkspace.E[ 1092 ]), &(acadoWorkspace.QE[ 1098 ]) ); +acado_setBlockH11( 11, 12, &(acadoWorkspace.E[ 1206 ]), &(acadoWorkspace.QE[ 1212 ]) ); + +acado_zeroBlockH11( 11, 13 ); +acado_setBlockH11( 11, 13, &(acadoWorkspace.E[ 612 ]), &(acadoWorkspace.QE[ 624 ]) ); +acado_setBlockH11( 11, 13, &(acadoWorkspace.E[ 696 ]), &(acadoWorkspace.QE[ 708 ]) ); +acado_setBlockH11( 11, 13, &(acadoWorkspace.E[ 786 ]), &(acadoWorkspace.QE[ 798 ]) ); +acado_setBlockH11( 11, 13, &(acadoWorkspace.E[ 882 ]), &(acadoWorkspace.QE[ 894 ]) ); +acado_setBlockH11( 11, 13, &(acadoWorkspace.E[ 984 ]), &(acadoWorkspace.QE[ 996 ]) ); +acado_setBlockH11( 11, 13, &(acadoWorkspace.E[ 1092 ]), &(acadoWorkspace.QE[ 1104 ]) ); +acado_setBlockH11( 11, 13, &(acadoWorkspace.E[ 1206 ]), &(acadoWorkspace.QE[ 1218 ]) ); + +acado_zeroBlockH11( 11, 14 ); +acado_setBlockH11( 11, 14, &(acadoWorkspace.E[ 696 ]), &(acadoWorkspace.QE[ 714 ]) ); +acado_setBlockH11( 11, 14, &(acadoWorkspace.E[ 786 ]), &(acadoWorkspace.QE[ 804 ]) ); +acado_setBlockH11( 11, 14, &(acadoWorkspace.E[ 882 ]), &(acadoWorkspace.QE[ 900 ]) ); +acado_setBlockH11( 11, 14, &(acadoWorkspace.E[ 984 ]), &(acadoWorkspace.QE[ 1002 ]) ); +acado_setBlockH11( 11, 14, &(acadoWorkspace.E[ 1092 ]), &(acadoWorkspace.QE[ 1110 ]) ); +acado_setBlockH11( 11, 14, &(acadoWorkspace.E[ 1206 ]), &(acadoWorkspace.QE[ 1224 ]) ); + +acado_zeroBlockH11( 11, 15 ); +acado_setBlockH11( 11, 15, &(acadoWorkspace.E[ 786 ]), &(acadoWorkspace.QE[ 810 ]) ); +acado_setBlockH11( 11, 15, &(acadoWorkspace.E[ 882 ]), &(acadoWorkspace.QE[ 906 ]) ); +acado_setBlockH11( 11, 15, &(acadoWorkspace.E[ 984 ]), &(acadoWorkspace.QE[ 1008 ]) ); +acado_setBlockH11( 11, 15, &(acadoWorkspace.E[ 1092 ]), &(acadoWorkspace.QE[ 1116 ]) ); +acado_setBlockH11( 11, 15, &(acadoWorkspace.E[ 1206 ]), &(acadoWorkspace.QE[ 1230 ]) ); + +acado_zeroBlockH11( 11, 16 ); +acado_setBlockH11( 11, 16, &(acadoWorkspace.E[ 882 ]), &(acadoWorkspace.QE[ 912 ]) ); +acado_setBlockH11( 11, 16, &(acadoWorkspace.E[ 984 ]), &(acadoWorkspace.QE[ 1014 ]) ); +acado_setBlockH11( 11, 16, &(acadoWorkspace.E[ 1092 ]), &(acadoWorkspace.QE[ 1122 ]) ); +acado_setBlockH11( 11, 16, &(acadoWorkspace.E[ 1206 ]), &(acadoWorkspace.QE[ 1236 ]) ); + +acado_zeroBlockH11( 11, 17 ); +acado_setBlockH11( 11, 17, &(acadoWorkspace.E[ 984 ]), &(acadoWorkspace.QE[ 1020 ]) ); +acado_setBlockH11( 11, 17, &(acadoWorkspace.E[ 1092 ]), &(acadoWorkspace.QE[ 1128 ]) ); +acado_setBlockH11( 11, 17, &(acadoWorkspace.E[ 1206 ]), &(acadoWorkspace.QE[ 1242 ]) ); + +acado_zeroBlockH11( 11, 18 ); +acado_setBlockH11( 11, 18, &(acadoWorkspace.E[ 1092 ]), &(acadoWorkspace.QE[ 1134 ]) ); +acado_setBlockH11( 11, 18, &(acadoWorkspace.E[ 1206 ]), &(acadoWorkspace.QE[ 1248 ]) ); + +acado_zeroBlockH11( 11, 19 ); +acado_setBlockH11( 11, 19, &(acadoWorkspace.E[ 1206 ]), &(acadoWorkspace.QE[ 1254 ]) ); + +acado_setBlockH11_R1( 12, 12, &(acadoWorkspace.R1[ 12 ]) ); +acado_setBlockH11( 12, 12, &(acadoWorkspace.E[ 540 ]), &(acadoWorkspace.QE[ 540 ]) ); +acado_setBlockH11( 12, 12, &(acadoWorkspace.E[ 618 ]), &(acadoWorkspace.QE[ 618 ]) ); +acado_setBlockH11( 12, 12, &(acadoWorkspace.E[ 702 ]), &(acadoWorkspace.QE[ 702 ]) ); +acado_setBlockH11( 12, 12, &(acadoWorkspace.E[ 792 ]), &(acadoWorkspace.QE[ 792 ]) ); +acado_setBlockH11( 12, 12, &(acadoWorkspace.E[ 888 ]), &(acadoWorkspace.QE[ 888 ]) ); +acado_setBlockH11( 12, 12, &(acadoWorkspace.E[ 990 ]), &(acadoWorkspace.QE[ 990 ]) ); +acado_setBlockH11( 12, 12, &(acadoWorkspace.E[ 1098 ]), &(acadoWorkspace.QE[ 1098 ]) ); +acado_setBlockH11( 12, 12, &(acadoWorkspace.E[ 1212 ]), &(acadoWorkspace.QE[ 1212 ]) ); + +acado_zeroBlockH11( 12, 13 ); +acado_setBlockH11( 12, 13, &(acadoWorkspace.E[ 618 ]), &(acadoWorkspace.QE[ 624 ]) ); +acado_setBlockH11( 12, 13, &(acadoWorkspace.E[ 702 ]), &(acadoWorkspace.QE[ 708 ]) ); +acado_setBlockH11( 12, 13, &(acadoWorkspace.E[ 792 ]), &(acadoWorkspace.QE[ 798 ]) ); +acado_setBlockH11( 12, 13, &(acadoWorkspace.E[ 888 ]), &(acadoWorkspace.QE[ 894 ]) ); +acado_setBlockH11( 12, 13, &(acadoWorkspace.E[ 990 ]), &(acadoWorkspace.QE[ 996 ]) ); +acado_setBlockH11( 12, 13, &(acadoWorkspace.E[ 1098 ]), &(acadoWorkspace.QE[ 1104 ]) ); +acado_setBlockH11( 12, 13, &(acadoWorkspace.E[ 1212 ]), &(acadoWorkspace.QE[ 1218 ]) ); + +acado_zeroBlockH11( 12, 14 ); +acado_setBlockH11( 12, 14, &(acadoWorkspace.E[ 702 ]), &(acadoWorkspace.QE[ 714 ]) ); +acado_setBlockH11( 12, 14, &(acadoWorkspace.E[ 792 ]), &(acadoWorkspace.QE[ 804 ]) ); +acado_setBlockH11( 12, 14, &(acadoWorkspace.E[ 888 ]), &(acadoWorkspace.QE[ 900 ]) ); +acado_setBlockH11( 12, 14, &(acadoWorkspace.E[ 990 ]), &(acadoWorkspace.QE[ 1002 ]) ); +acado_setBlockH11( 12, 14, &(acadoWorkspace.E[ 1098 ]), &(acadoWorkspace.QE[ 1110 ]) ); +acado_setBlockH11( 12, 14, &(acadoWorkspace.E[ 1212 ]), &(acadoWorkspace.QE[ 1224 ]) ); + +acado_zeroBlockH11( 12, 15 ); +acado_setBlockH11( 12, 15, &(acadoWorkspace.E[ 792 ]), &(acadoWorkspace.QE[ 810 ]) ); +acado_setBlockH11( 12, 15, &(acadoWorkspace.E[ 888 ]), &(acadoWorkspace.QE[ 906 ]) ); +acado_setBlockH11( 12, 15, &(acadoWorkspace.E[ 990 ]), &(acadoWorkspace.QE[ 1008 ]) ); +acado_setBlockH11( 12, 15, &(acadoWorkspace.E[ 1098 ]), &(acadoWorkspace.QE[ 1116 ]) ); +acado_setBlockH11( 12, 15, &(acadoWorkspace.E[ 1212 ]), &(acadoWorkspace.QE[ 1230 ]) ); + +acado_zeroBlockH11( 12, 16 ); +acado_setBlockH11( 12, 16, &(acadoWorkspace.E[ 888 ]), &(acadoWorkspace.QE[ 912 ]) ); +acado_setBlockH11( 12, 16, &(acadoWorkspace.E[ 990 ]), &(acadoWorkspace.QE[ 1014 ]) ); +acado_setBlockH11( 12, 16, &(acadoWorkspace.E[ 1098 ]), &(acadoWorkspace.QE[ 1122 ]) ); +acado_setBlockH11( 12, 16, &(acadoWorkspace.E[ 1212 ]), &(acadoWorkspace.QE[ 1236 ]) ); + +acado_zeroBlockH11( 12, 17 ); +acado_setBlockH11( 12, 17, &(acadoWorkspace.E[ 990 ]), &(acadoWorkspace.QE[ 1020 ]) ); +acado_setBlockH11( 12, 17, &(acadoWorkspace.E[ 1098 ]), &(acadoWorkspace.QE[ 1128 ]) ); +acado_setBlockH11( 12, 17, &(acadoWorkspace.E[ 1212 ]), &(acadoWorkspace.QE[ 1242 ]) ); + +acado_zeroBlockH11( 12, 18 ); +acado_setBlockH11( 12, 18, &(acadoWorkspace.E[ 1098 ]), &(acadoWorkspace.QE[ 1134 ]) ); +acado_setBlockH11( 12, 18, &(acadoWorkspace.E[ 1212 ]), &(acadoWorkspace.QE[ 1248 ]) ); + +acado_zeroBlockH11( 12, 19 ); +acado_setBlockH11( 12, 19, &(acadoWorkspace.E[ 1212 ]), &(acadoWorkspace.QE[ 1254 ]) ); + +acado_setBlockH11_R1( 13, 13, &(acadoWorkspace.R1[ 13 ]) ); +acado_setBlockH11( 13, 13, &(acadoWorkspace.E[ 624 ]), &(acadoWorkspace.QE[ 624 ]) ); +acado_setBlockH11( 13, 13, &(acadoWorkspace.E[ 708 ]), &(acadoWorkspace.QE[ 708 ]) ); +acado_setBlockH11( 13, 13, &(acadoWorkspace.E[ 798 ]), &(acadoWorkspace.QE[ 798 ]) ); +acado_setBlockH11( 13, 13, &(acadoWorkspace.E[ 894 ]), &(acadoWorkspace.QE[ 894 ]) ); +acado_setBlockH11( 13, 13, &(acadoWorkspace.E[ 996 ]), &(acadoWorkspace.QE[ 996 ]) ); +acado_setBlockH11( 13, 13, &(acadoWorkspace.E[ 1104 ]), &(acadoWorkspace.QE[ 1104 ]) ); +acado_setBlockH11( 13, 13, &(acadoWorkspace.E[ 1218 ]), &(acadoWorkspace.QE[ 1218 ]) ); + +acado_zeroBlockH11( 13, 14 ); +acado_setBlockH11( 13, 14, &(acadoWorkspace.E[ 708 ]), &(acadoWorkspace.QE[ 714 ]) ); +acado_setBlockH11( 13, 14, &(acadoWorkspace.E[ 798 ]), &(acadoWorkspace.QE[ 804 ]) ); +acado_setBlockH11( 13, 14, &(acadoWorkspace.E[ 894 ]), &(acadoWorkspace.QE[ 900 ]) ); +acado_setBlockH11( 13, 14, &(acadoWorkspace.E[ 996 ]), &(acadoWorkspace.QE[ 1002 ]) ); +acado_setBlockH11( 13, 14, &(acadoWorkspace.E[ 1104 ]), &(acadoWorkspace.QE[ 1110 ]) ); +acado_setBlockH11( 13, 14, &(acadoWorkspace.E[ 1218 ]), &(acadoWorkspace.QE[ 1224 ]) ); + +acado_zeroBlockH11( 13, 15 ); +acado_setBlockH11( 13, 15, &(acadoWorkspace.E[ 798 ]), &(acadoWorkspace.QE[ 810 ]) ); +acado_setBlockH11( 13, 15, &(acadoWorkspace.E[ 894 ]), &(acadoWorkspace.QE[ 906 ]) ); +acado_setBlockH11( 13, 15, &(acadoWorkspace.E[ 996 ]), &(acadoWorkspace.QE[ 1008 ]) ); +acado_setBlockH11( 13, 15, &(acadoWorkspace.E[ 1104 ]), &(acadoWorkspace.QE[ 1116 ]) ); +acado_setBlockH11( 13, 15, &(acadoWorkspace.E[ 1218 ]), &(acadoWorkspace.QE[ 1230 ]) ); + +acado_zeroBlockH11( 13, 16 ); +acado_setBlockH11( 13, 16, &(acadoWorkspace.E[ 894 ]), &(acadoWorkspace.QE[ 912 ]) ); +acado_setBlockH11( 13, 16, &(acadoWorkspace.E[ 996 ]), &(acadoWorkspace.QE[ 1014 ]) ); +acado_setBlockH11( 13, 16, &(acadoWorkspace.E[ 1104 ]), &(acadoWorkspace.QE[ 1122 ]) ); +acado_setBlockH11( 13, 16, &(acadoWorkspace.E[ 1218 ]), &(acadoWorkspace.QE[ 1236 ]) ); + +acado_zeroBlockH11( 13, 17 ); +acado_setBlockH11( 13, 17, &(acadoWorkspace.E[ 996 ]), &(acadoWorkspace.QE[ 1020 ]) ); +acado_setBlockH11( 13, 17, &(acadoWorkspace.E[ 1104 ]), &(acadoWorkspace.QE[ 1128 ]) ); +acado_setBlockH11( 13, 17, &(acadoWorkspace.E[ 1218 ]), &(acadoWorkspace.QE[ 1242 ]) ); + +acado_zeroBlockH11( 13, 18 ); +acado_setBlockH11( 13, 18, &(acadoWorkspace.E[ 1104 ]), &(acadoWorkspace.QE[ 1134 ]) ); +acado_setBlockH11( 13, 18, &(acadoWorkspace.E[ 1218 ]), &(acadoWorkspace.QE[ 1248 ]) ); + +acado_zeroBlockH11( 13, 19 ); +acado_setBlockH11( 13, 19, &(acadoWorkspace.E[ 1218 ]), &(acadoWorkspace.QE[ 1254 ]) ); + +acado_setBlockH11_R1( 14, 14, &(acadoWorkspace.R1[ 14 ]) ); +acado_setBlockH11( 14, 14, &(acadoWorkspace.E[ 714 ]), &(acadoWorkspace.QE[ 714 ]) ); +acado_setBlockH11( 14, 14, &(acadoWorkspace.E[ 804 ]), &(acadoWorkspace.QE[ 804 ]) ); +acado_setBlockH11( 14, 14, &(acadoWorkspace.E[ 900 ]), &(acadoWorkspace.QE[ 900 ]) ); +acado_setBlockH11( 14, 14, &(acadoWorkspace.E[ 1002 ]), &(acadoWorkspace.QE[ 1002 ]) ); +acado_setBlockH11( 14, 14, &(acadoWorkspace.E[ 1110 ]), &(acadoWorkspace.QE[ 1110 ]) ); +acado_setBlockH11( 14, 14, &(acadoWorkspace.E[ 1224 ]), &(acadoWorkspace.QE[ 1224 ]) ); + +acado_zeroBlockH11( 14, 15 ); +acado_setBlockH11( 14, 15, &(acadoWorkspace.E[ 804 ]), &(acadoWorkspace.QE[ 810 ]) ); +acado_setBlockH11( 14, 15, &(acadoWorkspace.E[ 900 ]), &(acadoWorkspace.QE[ 906 ]) ); +acado_setBlockH11( 14, 15, &(acadoWorkspace.E[ 1002 ]), &(acadoWorkspace.QE[ 1008 ]) ); +acado_setBlockH11( 14, 15, &(acadoWorkspace.E[ 1110 ]), &(acadoWorkspace.QE[ 1116 ]) ); +acado_setBlockH11( 14, 15, &(acadoWorkspace.E[ 1224 ]), &(acadoWorkspace.QE[ 1230 ]) ); + +acado_zeroBlockH11( 14, 16 ); +acado_setBlockH11( 14, 16, &(acadoWorkspace.E[ 900 ]), &(acadoWorkspace.QE[ 912 ]) ); +acado_setBlockH11( 14, 16, &(acadoWorkspace.E[ 1002 ]), &(acadoWorkspace.QE[ 1014 ]) ); +acado_setBlockH11( 14, 16, &(acadoWorkspace.E[ 1110 ]), &(acadoWorkspace.QE[ 1122 ]) ); +acado_setBlockH11( 14, 16, &(acadoWorkspace.E[ 1224 ]), &(acadoWorkspace.QE[ 1236 ]) ); + +acado_zeroBlockH11( 14, 17 ); +acado_setBlockH11( 14, 17, &(acadoWorkspace.E[ 1002 ]), &(acadoWorkspace.QE[ 1020 ]) ); +acado_setBlockH11( 14, 17, &(acadoWorkspace.E[ 1110 ]), &(acadoWorkspace.QE[ 1128 ]) ); +acado_setBlockH11( 14, 17, &(acadoWorkspace.E[ 1224 ]), &(acadoWorkspace.QE[ 1242 ]) ); + +acado_zeroBlockH11( 14, 18 ); +acado_setBlockH11( 14, 18, &(acadoWorkspace.E[ 1110 ]), &(acadoWorkspace.QE[ 1134 ]) ); +acado_setBlockH11( 14, 18, &(acadoWorkspace.E[ 1224 ]), &(acadoWorkspace.QE[ 1248 ]) ); + +acado_zeroBlockH11( 14, 19 ); +acado_setBlockH11( 14, 19, &(acadoWorkspace.E[ 1224 ]), &(acadoWorkspace.QE[ 1254 ]) ); + +acado_setBlockH11_R1( 15, 15, &(acadoWorkspace.R1[ 15 ]) ); +acado_setBlockH11( 15, 15, &(acadoWorkspace.E[ 810 ]), &(acadoWorkspace.QE[ 810 ]) ); +acado_setBlockH11( 15, 15, &(acadoWorkspace.E[ 906 ]), &(acadoWorkspace.QE[ 906 ]) ); +acado_setBlockH11( 15, 15, &(acadoWorkspace.E[ 1008 ]), &(acadoWorkspace.QE[ 1008 ]) ); +acado_setBlockH11( 15, 15, &(acadoWorkspace.E[ 1116 ]), &(acadoWorkspace.QE[ 1116 ]) ); +acado_setBlockH11( 15, 15, &(acadoWorkspace.E[ 1230 ]), &(acadoWorkspace.QE[ 1230 ]) ); + +acado_zeroBlockH11( 15, 16 ); +acado_setBlockH11( 15, 16, &(acadoWorkspace.E[ 906 ]), &(acadoWorkspace.QE[ 912 ]) ); +acado_setBlockH11( 15, 16, &(acadoWorkspace.E[ 1008 ]), &(acadoWorkspace.QE[ 1014 ]) ); +acado_setBlockH11( 15, 16, &(acadoWorkspace.E[ 1116 ]), &(acadoWorkspace.QE[ 1122 ]) ); +acado_setBlockH11( 15, 16, &(acadoWorkspace.E[ 1230 ]), &(acadoWorkspace.QE[ 1236 ]) ); + +acado_zeroBlockH11( 15, 17 ); +acado_setBlockH11( 15, 17, &(acadoWorkspace.E[ 1008 ]), &(acadoWorkspace.QE[ 1020 ]) ); +acado_setBlockH11( 15, 17, &(acadoWorkspace.E[ 1116 ]), &(acadoWorkspace.QE[ 1128 ]) ); +acado_setBlockH11( 15, 17, &(acadoWorkspace.E[ 1230 ]), &(acadoWorkspace.QE[ 1242 ]) ); + +acado_zeroBlockH11( 15, 18 ); +acado_setBlockH11( 15, 18, &(acadoWorkspace.E[ 1116 ]), &(acadoWorkspace.QE[ 1134 ]) ); +acado_setBlockH11( 15, 18, &(acadoWorkspace.E[ 1230 ]), &(acadoWorkspace.QE[ 1248 ]) ); + +acado_zeroBlockH11( 15, 19 ); +acado_setBlockH11( 15, 19, &(acadoWorkspace.E[ 1230 ]), &(acadoWorkspace.QE[ 1254 ]) ); + +acado_setBlockH11_R1( 16, 16, &(acadoWorkspace.R1[ 16 ]) ); +acado_setBlockH11( 16, 16, &(acadoWorkspace.E[ 912 ]), &(acadoWorkspace.QE[ 912 ]) ); +acado_setBlockH11( 16, 16, &(acadoWorkspace.E[ 1014 ]), &(acadoWorkspace.QE[ 1014 ]) ); +acado_setBlockH11( 16, 16, &(acadoWorkspace.E[ 1122 ]), &(acadoWorkspace.QE[ 1122 ]) ); +acado_setBlockH11( 16, 16, &(acadoWorkspace.E[ 1236 ]), &(acadoWorkspace.QE[ 1236 ]) ); + +acado_zeroBlockH11( 16, 17 ); +acado_setBlockH11( 16, 17, &(acadoWorkspace.E[ 1014 ]), &(acadoWorkspace.QE[ 1020 ]) ); +acado_setBlockH11( 16, 17, &(acadoWorkspace.E[ 1122 ]), &(acadoWorkspace.QE[ 1128 ]) ); +acado_setBlockH11( 16, 17, &(acadoWorkspace.E[ 1236 ]), &(acadoWorkspace.QE[ 1242 ]) ); + +acado_zeroBlockH11( 16, 18 ); +acado_setBlockH11( 16, 18, &(acadoWorkspace.E[ 1122 ]), &(acadoWorkspace.QE[ 1134 ]) ); +acado_setBlockH11( 16, 18, &(acadoWorkspace.E[ 1236 ]), &(acadoWorkspace.QE[ 1248 ]) ); + +acado_zeroBlockH11( 16, 19 ); +acado_setBlockH11( 16, 19, &(acadoWorkspace.E[ 1236 ]), &(acadoWorkspace.QE[ 1254 ]) ); + +acado_setBlockH11_R1( 17, 17, &(acadoWorkspace.R1[ 17 ]) ); +acado_setBlockH11( 17, 17, &(acadoWorkspace.E[ 1020 ]), &(acadoWorkspace.QE[ 1020 ]) ); +acado_setBlockH11( 17, 17, &(acadoWorkspace.E[ 1128 ]), &(acadoWorkspace.QE[ 1128 ]) ); +acado_setBlockH11( 17, 17, &(acadoWorkspace.E[ 1242 ]), &(acadoWorkspace.QE[ 1242 ]) ); + +acado_zeroBlockH11( 17, 18 ); +acado_setBlockH11( 17, 18, &(acadoWorkspace.E[ 1128 ]), &(acadoWorkspace.QE[ 1134 ]) ); +acado_setBlockH11( 17, 18, &(acadoWorkspace.E[ 1242 ]), &(acadoWorkspace.QE[ 1248 ]) ); + +acado_zeroBlockH11( 17, 19 ); +acado_setBlockH11( 17, 19, &(acadoWorkspace.E[ 1242 ]), &(acadoWorkspace.QE[ 1254 ]) ); + +acado_setBlockH11_R1( 18, 18, &(acadoWorkspace.R1[ 18 ]) ); +acado_setBlockH11( 18, 18, &(acadoWorkspace.E[ 1134 ]), &(acadoWorkspace.QE[ 1134 ]) ); +acado_setBlockH11( 18, 18, &(acadoWorkspace.E[ 1248 ]), &(acadoWorkspace.QE[ 1248 ]) ); + +acado_zeroBlockH11( 18, 19 ); +acado_setBlockH11( 18, 19, &(acadoWorkspace.E[ 1248 ]), &(acadoWorkspace.QE[ 1254 ]) ); + +acado_setBlockH11_R1( 19, 19, &(acadoWorkspace.R1[ 19 ]) ); +acado_setBlockH11( 19, 19, &(acadoWorkspace.E[ 1254 ]), &(acadoWorkspace.QE[ 1254 ]) ); + + +acado_copyHTH( 1, 0 ); +acado_copyHTH( 2, 0 ); +acado_copyHTH( 2, 1 ); +acado_copyHTH( 3, 0 ); +acado_copyHTH( 3, 1 ); +acado_copyHTH( 3, 2 ); +acado_copyHTH( 4, 0 ); +acado_copyHTH( 4, 1 ); +acado_copyHTH( 4, 2 ); +acado_copyHTH( 4, 3 ); +acado_copyHTH( 5, 0 ); +acado_copyHTH( 5, 1 ); +acado_copyHTH( 5, 2 ); +acado_copyHTH( 5, 3 ); +acado_copyHTH( 5, 4 ); +acado_copyHTH( 6, 0 ); +acado_copyHTH( 6, 1 ); +acado_copyHTH( 6, 2 ); +acado_copyHTH( 6, 3 ); +acado_copyHTH( 6, 4 ); +acado_copyHTH( 6, 5 ); +acado_copyHTH( 7, 0 ); +acado_copyHTH( 7, 1 ); +acado_copyHTH( 7, 2 ); +acado_copyHTH( 7, 3 ); +acado_copyHTH( 7, 4 ); +acado_copyHTH( 7, 5 ); +acado_copyHTH( 7, 6 ); +acado_copyHTH( 8, 0 ); +acado_copyHTH( 8, 1 ); +acado_copyHTH( 8, 2 ); +acado_copyHTH( 8, 3 ); +acado_copyHTH( 8, 4 ); +acado_copyHTH( 8, 5 ); +acado_copyHTH( 8, 6 ); +acado_copyHTH( 8, 7 ); +acado_copyHTH( 9, 0 ); +acado_copyHTH( 9, 1 ); +acado_copyHTH( 9, 2 ); +acado_copyHTH( 9, 3 ); +acado_copyHTH( 9, 4 ); +acado_copyHTH( 9, 5 ); +acado_copyHTH( 9, 6 ); +acado_copyHTH( 9, 7 ); +acado_copyHTH( 9, 8 ); +acado_copyHTH( 10, 0 ); +acado_copyHTH( 10, 1 ); +acado_copyHTH( 10, 2 ); +acado_copyHTH( 10, 3 ); +acado_copyHTH( 10, 4 ); +acado_copyHTH( 10, 5 ); +acado_copyHTH( 10, 6 ); +acado_copyHTH( 10, 7 ); +acado_copyHTH( 10, 8 ); +acado_copyHTH( 10, 9 ); +acado_copyHTH( 11, 0 ); +acado_copyHTH( 11, 1 ); +acado_copyHTH( 11, 2 ); +acado_copyHTH( 11, 3 ); +acado_copyHTH( 11, 4 ); +acado_copyHTH( 11, 5 ); +acado_copyHTH( 11, 6 ); +acado_copyHTH( 11, 7 ); +acado_copyHTH( 11, 8 ); +acado_copyHTH( 11, 9 ); +acado_copyHTH( 11, 10 ); +acado_copyHTH( 12, 0 ); +acado_copyHTH( 12, 1 ); +acado_copyHTH( 12, 2 ); +acado_copyHTH( 12, 3 ); +acado_copyHTH( 12, 4 ); +acado_copyHTH( 12, 5 ); +acado_copyHTH( 12, 6 ); +acado_copyHTH( 12, 7 ); +acado_copyHTH( 12, 8 ); +acado_copyHTH( 12, 9 ); +acado_copyHTH( 12, 10 ); +acado_copyHTH( 12, 11 ); +acado_copyHTH( 13, 0 ); +acado_copyHTH( 13, 1 ); +acado_copyHTH( 13, 2 ); +acado_copyHTH( 13, 3 ); +acado_copyHTH( 13, 4 ); +acado_copyHTH( 13, 5 ); +acado_copyHTH( 13, 6 ); +acado_copyHTH( 13, 7 ); +acado_copyHTH( 13, 8 ); +acado_copyHTH( 13, 9 ); +acado_copyHTH( 13, 10 ); +acado_copyHTH( 13, 11 ); +acado_copyHTH( 13, 12 ); +acado_copyHTH( 14, 0 ); +acado_copyHTH( 14, 1 ); +acado_copyHTH( 14, 2 ); +acado_copyHTH( 14, 3 ); +acado_copyHTH( 14, 4 ); +acado_copyHTH( 14, 5 ); +acado_copyHTH( 14, 6 ); +acado_copyHTH( 14, 7 ); +acado_copyHTH( 14, 8 ); +acado_copyHTH( 14, 9 ); +acado_copyHTH( 14, 10 ); +acado_copyHTH( 14, 11 ); +acado_copyHTH( 14, 12 ); +acado_copyHTH( 14, 13 ); +acado_copyHTH( 15, 0 ); +acado_copyHTH( 15, 1 ); +acado_copyHTH( 15, 2 ); +acado_copyHTH( 15, 3 ); +acado_copyHTH( 15, 4 ); +acado_copyHTH( 15, 5 ); +acado_copyHTH( 15, 6 ); +acado_copyHTH( 15, 7 ); +acado_copyHTH( 15, 8 ); +acado_copyHTH( 15, 9 ); +acado_copyHTH( 15, 10 ); +acado_copyHTH( 15, 11 ); +acado_copyHTH( 15, 12 ); +acado_copyHTH( 15, 13 ); +acado_copyHTH( 15, 14 ); +acado_copyHTH( 16, 0 ); +acado_copyHTH( 16, 1 ); +acado_copyHTH( 16, 2 ); +acado_copyHTH( 16, 3 ); +acado_copyHTH( 16, 4 ); +acado_copyHTH( 16, 5 ); +acado_copyHTH( 16, 6 ); +acado_copyHTH( 16, 7 ); +acado_copyHTH( 16, 8 ); +acado_copyHTH( 16, 9 ); +acado_copyHTH( 16, 10 ); +acado_copyHTH( 16, 11 ); +acado_copyHTH( 16, 12 ); +acado_copyHTH( 16, 13 ); +acado_copyHTH( 16, 14 ); +acado_copyHTH( 16, 15 ); +acado_copyHTH( 17, 0 ); +acado_copyHTH( 17, 1 ); +acado_copyHTH( 17, 2 ); +acado_copyHTH( 17, 3 ); +acado_copyHTH( 17, 4 ); +acado_copyHTH( 17, 5 ); +acado_copyHTH( 17, 6 ); +acado_copyHTH( 17, 7 ); +acado_copyHTH( 17, 8 ); +acado_copyHTH( 17, 9 ); +acado_copyHTH( 17, 10 ); +acado_copyHTH( 17, 11 ); +acado_copyHTH( 17, 12 ); +acado_copyHTH( 17, 13 ); +acado_copyHTH( 17, 14 ); +acado_copyHTH( 17, 15 ); +acado_copyHTH( 17, 16 ); +acado_copyHTH( 18, 0 ); +acado_copyHTH( 18, 1 ); +acado_copyHTH( 18, 2 ); +acado_copyHTH( 18, 3 ); +acado_copyHTH( 18, 4 ); +acado_copyHTH( 18, 5 ); +acado_copyHTH( 18, 6 ); +acado_copyHTH( 18, 7 ); +acado_copyHTH( 18, 8 ); +acado_copyHTH( 18, 9 ); +acado_copyHTH( 18, 10 ); +acado_copyHTH( 18, 11 ); +acado_copyHTH( 18, 12 ); +acado_copyHTH( 18, 13 ); +acado_copyHTH( 18, 14 ); +acado_copyHTH( 18, 15 ); +acado_copyHTH( 18, 16 ); +acado_copyHTH( 18, 17 ); +acado_copyHTH( 19, 0 ); +acado_copyHTH( 19, 1 ); +acado_copyHTH( 19, 2 ); +acado_copyHTH( 19, 3 ); +acado_copyHTH( 19, 4 ); +acado_copyHTH( 19, 5 ); +acado_copyHTH( 19, 6 ); +acado_copyHTH( 19, 7 ); +acado_copyHTH( 19, 8 ); +acado_copyHTH( 19, 9 ); +acado_copyHTH( 19, 10 ); +acado_copyHTH( 19, 11 ); +acado_copyHTH( 19, 12 ); +acado_copyHTH( 19, 13 ); +acado_copyHTH( 19, 14 ); +acado_copyHTH( 19, 15 ); +acado_copyHTH( 19, 16 ); +acado_copyHTH( 19, 17 ); +acado_copyHTH( 19, 18 ); + +acadoWorkspace.H[156] = acadoWorkspace.H10[0]; +acadoWorkspace.H[157] = acadoWorkspace.H10[1]; +acadoWorkspace.H[158] = acadoWorkspace.H10[2]; +acadoWorkspace.H[159] = acadoWorkspace.H10[3]; +acadoWorkspace.H[160] = acadoWorkspace.H10[4]; +acadoWorkspace.H[161] = acadoWorkspace.H10[5]; +acadoWorkspace.H[182] = acadoWorkspace.H10[6]; +acadoWorkspace.H[183] = acadoWorkspace.H10[7]; +acadoWorkspace.H[184] = acadoWorkspace.H10[8]; +acadoWorkspace.H[185] = acadoWorkspace.H10[9]; +acadoWorkspace.H[186] = acadoWorkspace.H10[10]; +acadoWorkspace.H[187] = acadoWorkspace.H10[11]; +acadoWorkspace.H[208] = acadoWorkspace.H10[12]; +acadoWorkspace.H[209] = acadoWorkspace.H10[13]; +acadoWorkspace.H[210] = acadoWorkspace.H10[14]; +acadoWorkspace.H[211] = acadoWorkspace.H10[15]; +acadoWorkspace.H[212] = acadoWorkspace.H10[16]; +acadoWorkspace.H[213] = acadoWorkspace.H10[17]; +acadoWorkspace.H[234] = acadoWorkspace.H10[18]; +acadoWorkspace.H[235] = acadoWorkspace.H10[19]; +acadoWorkspace.H[236] = acadoWorkspace.H10[20]; +acadoWorkspace.H[237] = acadoWorkspace.H10[21]; +acadoWorkspace.H[238] = acadoWorkspace.H10[22]; +acadoWorkspace.H[239] = acadoWorkspace.H10[23]; +acadoWorkspace.H[260] = acadoWorkspace.H10[24]; +acadoWorkspace.H[261] = acadoWorkspace.H10[25]; +acadoWorkspace.H[262] = acadoWorkspace.H10[26]; +acadoWorkspace.H[263] = acadoWorkspace.H10[27]; +acadoWorkspace.H[264] = acadoWorkspace.H10[28]; +acadoWorkspace.H[265] = acadoWorkspace.H10[29]; +acadoWorkspace.H[286] = acadoWorkspace.H10[30]; +acadoWorkspace.H[287] = acadoWorkspace.H10[31]; +acadoWorkspace.H[288] = acadoWorkspace.H10[32]; +acadoWorkspace.H[289] = acadoWorkspace.H10[33]; +acadoWorkspace.H[290] = acadoWorkspace.H10[34]; +acadoWorkspace.H[291] = acadoWorkspace.H10[35]; +acadoWorkspace.H[312] = acadoWorkspace.H10[36]; +acadoWorkspace.H[313] = acadoWorkspace.H10[37]; +acadoWorkspace.H[314] = acadoWorkspace.H10[38]; +acadoWorkspace.H[315] = acadoWorkspace.H10[39]; +acadoWorkspace.H[316] = acadoWorkspace.H10[40]; +acadoWorkspace.H[317] = acadoWorkspace.H10[41]; +acadoWorkspace.H[338] = acadoWorkspace.H10[42]; +acadoWorkspace.H[339] = acadoWorkspace.H10[43]; +acadoWorkspace.H[340] = acadoWorkspace.H10[44]; +acadoWorkspace.H[341] = acadoWorkspace.H10[45]; +acadoWorkspace.H[342] = acadoWorkspace.H10[46]; +acadoWorkspace.H[343] = acadoWorkspace.H10[47]; +acadoWorkspace.H[364] = acadoWorkspace.H10[48]; +acadoWorkspace.H[365] = acadoWorkspace.H10[49]; +acadoWorkspace.H[366] = acadoWorkspace.H10[50]; +acadoWorkspace.H[367] = acadoWorkspace.H10[51]; +acadoWorkspace.H[368] = acadoWorkspace.H10[52]; +acadoWorkspace.H[369] = acadoWorkspace.H10[53]; +acadoWorkspace.H[390] = acadoWorkspace.H10[54]; +acadoWorkspace.H[391] = acadoWorkspace.H10[55]; +acadoWorkspace.H[392] = acadoWorkspace.H10[56]; +acadoWorkspace.H[393] = acadoWorkspace.H10[57]; +acadoWorkspace.H[394] = acadoWorkspace.H10[58]; +acadoWorkspace.H[395] = acadoWorkspace.H10[59]; +acadoWorkspace.H[416] = acadoWorkspace.H10[60]; +acadoWorkspace.H[417] = acadoWorkspace.H10[61]; +acadoWorkspace.H[418] = acadoWorkspace.H10[62]; +acadoWorkspace.H[419] = acadoWorkspace.H10[63]; +acadoWorkspace.H[420] = acadoWorkspace.H10[64]; +acadoWorkspace.H[421] = acadoWorkspace.H10[65]; +acadoWorkspace.H[442] = acadoWorkspace.H10[66]; +acadoWorkspace.H[443] = acadoWorkspace.H10[67]; +acadoWorkspace.H[444] = acadoWorkspace.H10[68]; +acadoWorkspace.H[445] = acadoWorkspace.H10[69]; +acadoWorkspace.H[446] = acadoWorkspace.H10[70]; +acadoWorkspace.H[447] = acadoWorkspace.H10[71]; +acadoWorkspace.H[468] = acadoWorkspace.H10[72]; +acadoWorkspace.H[469] = acadoWorkspace.H10[73]; +acadoWorkspace.H[470] = acadoWorkspace.H10[74]; +acadoWorkspace.H[471] = acadoWorkspace.H10[75]; +acadoWorkspace.H[472] = acadoWorkspace.H10[76]; +acadoWorkspace.H[473] = acadoWorkspace.H10[77]; +acadoWorkspace.H[494] = acadoWorkspace.H10[78]; +acadoWorkspace.H[495] = acadoWorkspace.H10[79]; +acadoWorkspace.H[496] = acadoWorkspace.H10[80]; +acadoWorkspace.H[497] = acadoWorkspace.H10[81]; +acadoWorkspace.H[498] = acadoWorkspace.H10[82]; +acadoWorkspace.H[499] = acadoWorkspace.H10[83]; +acadoWorkspace.H[520] = acadoWorkspace.H10[84]; +acadoWorkspace.H[521] = acadoWorkspace.H10[85]; +acadoWorkspace.H[522] = acadoWorkspace.H10[86]; +acadoWorkspace.H[523] = acadoWorkspace.H10[87]; +acadoWorkspace.H[524] = acadoWorkspace.H10[88]; +acadoWorkspace.H[525] = acadoWorkspace.H10[89]; +acadoWorkspace.H[546] = acadoWorkspace.H10[90]; +acadoWorkspace.H[547] = acadoWorkspace.H10[91]; +acadoWorkspace.H[548] = acadoWorkspace.H10[92]; +acadoWorkspace.H[549] = acadoWorkspace.H10[93]; +acadoWorkspace.H[550] = acadoWorkspace.H10[94]; +acadoWorkspace.H[551] = acadoWorkspace.H10[95]; +acadoWorkspace.H[572] = acadoWorkspace.H10[96]; +acadoWorkspace.H[573] = acadoWorkspace.H10[97]; +acadoWorkspace.H[574] = acadoWorkspace.H10[98]; +acadoWorkspace.H[575] = acadoWorkspace.H10[99]; +acadoWorkspace.H[576] = acadoWorkspace.H10[100]; +acadoWorkspace.H[577] = acadoWorkspace.H10[101]; +acadoWorkspace.H[598] = acadoWorkspace.H10[102]; +acadoWorkspace.H[599] = acadoWorkspace.H10[103]; +acadoWorkspace.H[600] = acadoWorkspace.H10[104]; +acadoWorkspace.H[601] = acadoWorkspace.H10[105]; +acadoWorkspace.H[602] = acadoWorkspace.H10[106]; +acadoWorkspace.H[603] = acadoWorkspace.H10[107]; +acadoWorkspace.H[624] = acadoWorkspace.H10[108]; +acadoWorkspace.H[625] = acadoWorkspace.H10[109]; +acadoWorkspace.H[626] = acadoWorkspace.H10[110]; +acadoWorkspace.H[627] = acadoWorkspace.H10[111]; +acadoWorkspace.H[628] = acadoWorkspace.H10[112]; +acadoWorkspace.H[629] = acadoWorkspace.H10[113]; +acadoWorkspace.H[650] = acadoWorkspace.H10[114]; +acadoWorkspace.H[651] = acadoWorkspace.H10[115]; +acadoWorkspace.H[652] = acadoWorkspace.H10[116]; +acadoWorkspace.H[653] = acadoWorkspace.H10[117]; +acadoWorkspace.H[654] = acadoWorkspace.H10[118]; +acadoWorkspace.H[655] = acadoWorkspace.H10[119]; + +acado_multQ1d( &(acadoWorkspace.Q1[ 36 ]), acadoWorkspace.d, acadoWorkspace.Qd ); +acado_multQ1d( &(acadoWorkspace.Q1[ 72 ]), &(acadoWorkspace.d[ 6 ]), &(acadoWorkspace.Qd[ 6 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 108 ]), &(acadoWorkspace.d[ 12 ]), &(acadoWorkspace.Qd[ 12 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 144 ]), &(acadoWorkspace.d[ 18 ]), &(acadoWorkspace.Qd[ 18 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 180 ]), &(acadoWorkspace.d[ 24 ]), &(acadoWorkspace.Qd[ 24 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 216 ]), &(acadoWorkspace.d[ 30 ]), &(acadoWorkspace.Qd[ 30 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 252 ]), &(acadoWorkspace.d[ 36 ]), &(acadoWorkspace.Qd[ 36 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 288 ]), &(acadoWorkspace.d[ 42 ]), &(acadoWorkspace.Qd[ 42 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 324 ]), &(acadoWorkspace.d[ 48 ]), &(acadoWorkspace.Qd[ 48 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 360 ]), &(acadoWorkspace.d[ 54 ]), &(acadoWorkspace.Qd[ 54 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 396 ]), &(acadoWorkspace.d[ 60 ]), &(acadoWorkspace.Qd[ 60 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 432 ]), &(acadoWorkspace.d[ 66 ]), &(acadoWorkspace.Qd[ 66 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 468 ]), &(acadoWorkspace.d[ 72 ]), &(acadoWorkspace.Qd[ 72 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 504 ]), &(acadoWorkspace.d[ 78 ]), &(acadoWorkspace.Qd[ 78 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 540 ]), &(acadoWorkspace.d[ 84 ]), &(acadoWorkspace.Qd[ 84 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 576 ]), &(acadoWorkspace.d[ 90 ]), &(acadoWorkspace.Qd[ 90 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 612 ]), &(acadoWorkspace.d[ 96 ]), &(acadoWorkspace.Qd[ 96 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 648 ]), &(acadoWorkspace.d[ 102 ]), &(acadoWorkspace.Qd[ 102 ]) ); +acado_multQ1d( &(acadoWorkspace.Q1[ 684 ]), &(acadoWorkspace.d[ 108 ]), &(acadoWorkspace.Qd[ 108 ]) ); +acado_multQN1d( acadoWorkspace.QN1, &(acadoWorkspace.d[ 114 ]), &(acadoWorkspace.Qd[ 114 ]) ); + +acado_macCTSlx( acadoWorkspace.evGx, acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 36 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 72 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 108 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 144 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 180 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 216 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 252 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 288 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 324 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 360 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 396 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 432 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 468 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 504 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 540 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 576 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 612 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 648 ]), acadoWorkspace.g ); +acado_macCTSlx( &(acadoWorkspace.evGx[ 684 ]), acadoWorkspace.g ); +acado_macETSlu( acadoWorkspace.QE, &(acadoWorkspace.g[ 6 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 6 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 18 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 36 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 60 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 90 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 126 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 168 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 216 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 270 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 330 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 396 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 468 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 546 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 630 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 720 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 816 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 918 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 1026 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 1140 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 12 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 24 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 42 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 66 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 96 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 132 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 174 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 222 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 276 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 336 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 402 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 474 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 552 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 636 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 726 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 822 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 924 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 1032 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 1146 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 30 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 48 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 72 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 102 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 138 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 180 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 228 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 282 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 342 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 408 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 480 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 558 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 642 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 732 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 828 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 930 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 1038 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 1152 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 54 ]), &(acadoWorkspace.g[ 9 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 78 ]), &(acadoWorkspace.g[ 9 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 108 ]), &(acadoWorkspace.g[ 9 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 144 ]), &(acadoWorkspace.g[ 9 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 186 ]), &(acadoWorkspace.g[ 9 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 234 ]), &(acadoWorkspace.g[ 9 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 288 ]), &(acadoWorkspace.g[ 9 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 348 ]), &(acadoWorkspace.g[ 9 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 414 ]), &(acadoWorkspace.g[ 9 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 486 ]), &(acadoWorkspace.g[ 9 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 564 ]), &(acadoWorkspace.g[ 9 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 648 ]), &(acadoWorkspace.g[ 9 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 738 ]), &(acadoWorkspace.g[ 9 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 834 ]), &(acadoWorkspace.g[ 9 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 936 ]), &(acadoWorkspace.g[ 9 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 1044 ]), &(acadoWorkspace.g[ 9 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 1158 ]), &(acadoWorkspace.g[ 9 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 84 ]), &(acadoWorkspace.g[ 10 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 114 ]), &(acadoWorkspace.g[ 10 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 150 ]), &(acadoWorkspace.g[ 10 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 192 ]), &(acadoWorkspace.g[ 10 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 240 ]), &(acadoWorkspace.g[ 10 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 294 ]), &(acadoWorkspace.g[ 10 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 354 ]), &(acadoWorkspace.g[ 10 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 420 ]), &(acadoWorkspace.g[ 10 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 492 ]), &(acadoWorkspace.g[ 10 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 570 ]), &(acadoWorkspace.g[ 10 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 654 ]), &(acadoWorkspace.g[ 10 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 744 ]), &(acadoWorkspace.g[ 10 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 840 ]), &(acadoWorkspace.g[ 10 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 942 ]), &(acadoWorkspace.g[ 10 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 1050 ]), &(acadoWorkspace.g[ 10 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 1164 ]), &(acadoWorkspace.g[ 10 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 120 ]), &(acadoWorkspace.g[ 11 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 156 ]), &(acadoWorkspace.g[ 11 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 198 ]), &(acadoWorkspace.g[ 11 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 246 ]), &(acadoWorkspace.g[ 11 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 300 ]), &(acadoWorkspace.g[ 11 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 360 ]), &(acadoWorkspace.g[ 11 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 426 ]), &(acadoWorkspace.g[ 11 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 498 ]), &(acadoWorkspace.g[ 11 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 576 ]), &(acadoWorkspace.g[ 11 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 660 ]), &(acadoWorkspace.g[ 11 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 750 ]), &(acadoWorkspace.g[ 11 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 846 ]), &(acadoWorkspace.g[ 11 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 948 ]), &(acadoWorkspace.g[ 11 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 1056 ]), &(acadoWorkspace.g[ 11 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 1170 ]), &(acadoWorkspace.g[ 11 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 162 ]), &(acadoWorkspace.g[ 12 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 204 ]), &(acadoWorkspace.g[ 12 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 252 ]), &(acadoWorkspace.g[ 12 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 306 ]), &(acadoWorkspace.g[ 12 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 366 ]), &(acadoWorkspace.g[ 12 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 432 ]), &(acadoWorkspace.g[ 12 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 504 ]), &(acadoWorkspace.g[ 12 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 582 ]), &(acadoWorkspace.g[ 12 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 666 ]), &(acadoWorkspace.g[ 12 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 756 ]), &(acadoWorkspace.g[ 12 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 852 ]), &(acadoWorkspace.g[ 12 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 954 ]), &(acadoWorkspace.g[ 12 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 1062 ]), &(acadoWorkspace.g[ 12 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 1176 ]), &(acadoWorkspace.g[ 12 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 210 ]), &(acadoWorkspace.g[ 13 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 258 ]), &(acadoWorkspace.g[ 13 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 312 ]), &(acadoWorkspace.g[ 13 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 372 ]), &(acadoWorkspace.g[ 13 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 438 ]), &(acadoWorkspace.g[ 13 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 510 ]), &(acadoWorkspace.g[ 13 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 588 ]), &(acadoWorkspace.g[ 13 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 672 ]), &(acadoWorkspace.g[ 13 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 762 ]), &(acadoWorkspace.g[ 13 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 858 ]), &(acadoWorkspace.g[ 13 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 960 ]), &(acadoWorkspace.g[ 13 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 1068 ]), &(acadoWorkspace.g[ 13 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 1182 ]), &(acadoWorkspace.g[ 13 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 264 ]), &(acadoWorkspace.g[ 14 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 318 ]), &(acadoWorkspace.g[ 14 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 378 ]), &(acadoWorkspace.g[ 14 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 444 ]), &(acadoWorkspace.g[ 14 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 516 ]), &(acadoWorkspace.g[ 14 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 594 ]), &(acadoWorkspace.g[ 14 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 678 ]), &(acadoWorkspace.g[ 14 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 768 ]), &(acadoWorkspace.g[ 14 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 864 ]), &(acadoWorkspace.g[ 14 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 966 ]), &(acadoWorkspace.g[ 14 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 1074 ]), &(acadoWorkspace.g[ 14 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 1188 ]), &(acadoWorkspace.g[ 14 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 324 ]), &(acadoWorkspace.g[ 15 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 384 ]), &(acadoWorkspace.g[ 15 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 450 ]), &(acadoWorkspace.g[ 15 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 522 ]), &(acadoWorkspace.g[ 15 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 600 ]), &(acadoWorkspace.g[ 15 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 684 ]), &(acadoWorkspace.g[ 15 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 774 ]), &(acadoWorkspace.g[ 15 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 870 ]), &(acadoWorkspace.g[ 15 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 972 ]), &(acadoWorkspace.g[ 15 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 1080 ]), &(acadoWorkspace.g[ 15 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 1194 ]), &(acadoWorkspace.g[ 15 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 390 ]), &(acadoWorkspace.g[ 16 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 456 ]), &(acadoWorkspace.g[ 16 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 528 ]), &(acadoWorkspace.g[ 16 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 606 ]), &(acadoWorkspace.g[ 16 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 690 ]), &(acadoWorkspace.g[ 16 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 780 ]), &(acadoWorkspace.g[ 16 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 876 ]), &(acadoWorkspace.g[ 16 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 978 ]), &(acadoWorkspace.g[ 16 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 1086 ]), &(acadoWorkspace.g[ 16 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 1200 ]), &(acadoWorkspace.g[ 16 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 462 ]), &(acadoWorkspace.g[ 17 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 534 ]), &(acadoWorkspace.g[ 17 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 612 ]), &(acadoWorkspace.g[ 17 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 696 ]), &(acadoWorkspace.g[ 17 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 786 ]), &(acadoWorkspace.g[ 17 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 882 ]), &(acadoWorkspace.g[ 17 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 984 ]), &(acadoWorkspace.g[ 17 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 1092 ]), &(acadoWorkspace.g[ 17 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 1206 ]), &(acadoWorkspace.g[ 17 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 540 ]), &(acadoWorkspace.g[ 18 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 618 ]), &(acadoWorkspace.g[ 18 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 702 ]), &(acadoWorkspace.g[ 18 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 792 ]), &(acadoWorkspace.g[ 18 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 888 ]), &(acadoWorkspace.g[ 18 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 990 ]), &(acadoWorkspace.g[ 18 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 1098 ]), &(acadoWorkspace.g[ 18 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 1212 ]), &(acadoWorkspace.g[ 18 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 624 ]), &(acadoWorkspace.g[ 19 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 708 ]), &(acadoWorkspace.g[ 19 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 798 ]), &(acadoWorkspace.g[ 19 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 894 ]), &(acadoWorkspace.g[ 19 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 996 ]), &(acadoWorkspace.g[ 19 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 1104 ]), &(acadoWorkspace.g[ 19 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 1218 ]), &(acadoWorkspace.g[ 19 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 714 ]), &(acadoWorkspace.g[ 20 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 804 ]), &(acadoWorkspace.g[ 20 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 900 ]), &(acadoWorkspace.g[ 20 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 1002 ]), &(acadoWorkspace.g[ 20 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 1110 ]), &(acadoWorkspace.g[ 20 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 1224 ]), &(acadoWorkspace.g[ 20 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 810 ]), &(acadoWorkspace.g[ 21 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 906 ]), &(acadoWorkspace.g[ 21 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 1008 ]), &(acadoWorkspace.g[ 21 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 1116 ]), &(acadoWorkspace.g[ 21 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 1230 ]), &(acadoWorkspace.g[ 21 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 912 ]), &(acadoWorkspace.g[ 22 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 1014 ]), &(acadoWorkspace.g[ 22 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 1122 ]), &(acadoWorkspace.g[ 22 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 1236 ]), &(acadoWorkspace.g[ 22 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 1020 ]), &(acadoWorkspace.g[ 23 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 1128 ]), &(acadoWorkspace.g[ 23 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 1242 ]), &(acadoWorkspace.g[ 23 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 1134 ]), &(acadoWorkspace.g[ 24 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 1248 ]), &(acadoWorkspace.g[ 24 ]) ); +acado_macETSlu( &(acadoWorkspace.QE[ 1254 ]), &(acadoWorkspace.g[ 25 ]) ); +acadoWorkspace.lb[6] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[0]; +acadoWorkspace.lb[7] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[1]; +acadoWorkspace.lb[8] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[2]; +acadoWorkspace.lb[9] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[3]; +acadoWorkspace.lb[10] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[4]; +acadoWorkspace.lb[11] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[5]; +acadoWorkspace.lb[12] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[6]; +acadoWorkspace.lb[13] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[7]; +acadoWorkspace.lb[14] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[8]; +acadoWorkspace.lb[15] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[9]; +acadoWorkspace.lb[16] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[10]; +acadoWorkspace.lb[17] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[11]; +acadoWorkspace.lb[18] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[12]; +acadoWorkspace.lb[19] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[13]; +acadoWorkspace.lb[20] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[14]; +acadoWorkspace.lb[21] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[15]; +acadoWorkspace.lb[22] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[16]; +acadoWorkspace.lb[23] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[17]; +acadoWorkspace.lb[24] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[18]; +acadoWorkspace.lb[25] = (real_t)-1.0000000000000000e+12 - acadoVariables.u[19]; +acadoWorkspace.ub[6] = (real_t)1.0000000000000000e+12 - acadoVariables.u[0]; +acadoWorkspace.ub[7] = (real_t)1.0000000000000000e+12 - acadoVariables.u[1]; +acadoWorkspace.ub[8] = (real_t)1.0000000000000000e+12 - acadoVariables.u[2]; +acadoWorkspace.ub[9] = (real_t)1.0000000000000000e+12 - acadoVariables.u[3]; +acadoWorkspace.ub[10] = (real_t)1.0000000000000000e+12 - acadoVariables.u[4]; +acadoWorkspace.ub[11] = (real_t)1.0000000000000000e+12 - acadoVariables.u[5]; +acadoWorkspace.ub[12] = (real_t)1.0000000000000000e+12 - acadoVariables.u[6]; +acadoWorkspace.ub[13] = (real_t)1.0000000000000000e+12 - acadoVariables.u[7]; +acadoWorkspace.ub[14] = (real_t)1.0000000000000000e+12 - acadoVariables.u[8]; +acadoWorkspace.ub[15] = (real_t)1.0000000000000000e+12 - acadoVariables.u[9]; +acadoWorkspace.ub[16] = (real_t)1.0000000000000000e+12 - acadoVariables.u[10]; +acadoWorkspace.ub[17] = (real_t)1.0000000000000000e+12 - acadoVariables.u[11]; +acadoWorkspace.ub[18] = (real_t)1.0000000000000000e+12 - acadoVariables.u[12]; +acadoWorkspace.ub[19] = (real_t)1.0000000000000000e+12 - acadoVariables.u[13]; +acadoWorkspace.ub[20] = (real_t)1.0000000000000000e+12 - acadoVariables.u[14]; +acadoWorkspace.ub[21] = (real_t)1.0000000000000000e+12 - acadoVariables.u[15]; +acadoWorkspace.ub[22] = (real_t)1.0000000000000000e+12 - acadoVariables.u[16]; +acadoWorkspace.ub[23] = (real_t)1.0000000000000000e+12 - acadoVariables.u[17]; +acadoWorkspace.ub[24] = (real_t)1.0000000000000000e+12 - acadoVariables.u[18]; +acadoWorkspace.ub[25] = (real_t)1.0000000000000000e+12 - acadoVariables.u[19]; + +for (lRun1 = 0; lRun1 < 20; ++lRun1) +{ +lRun3 = xBoundIndices[ lRun1 ] - 6; +lRun4 = ((lRun3) / (6)) + (1); +acadoWorkspace.A[lRun1 * 26] = acadoWorkspace.evGx[lRun3 * 6]; +acadoWorkspace.A[lRun1 * 26 + 1] = acadoWorkspace.evGx[lRun3 * 6 + 1]; +acadoWorkspace.A[lRun1 * 26 + 2] = acadoWorkspace.evGx[lRun3 * 6 + 2]; +acadoWorkspace.A[lRun1 * 26 + 3] = acadoWorkspace.evGx[lRun3 * 6 + 3]; +acadoWorkspace.A[lRun1 * 26 + 4] = acadoWorkspace.evGx[lRun3 * 6 + 4]; +acadoWorkspace.A[lRun1 * 26 + 5] = acadoWorkspace.evGx[lRun3 * 6 + 5]; +for (lRun2 = 0; lRun2 < lRun4; ++lRun2) +{ +lRun5 = (((((lRun4) * (lRun4-1)) / (2)) + (lRun2)) * (6)) + ((lRun3) % (6)); +acadoWorkspace.A[(lRun1 * 26) + (lRun2 + 6)] = acadoWorkspace.E[lRun5]; +} +} + +} + +void acado_condenseFdb( ) +{ +real_t tmp; + +acadoWorkspace.Dx0[0] = acadoVariables.x0[0] - acadoVariables.x[0]; +acadoWorkspace.Dx0[1] = acadoVariables.x0[1] - acadoVariables.x[1]; +acadoWorkspace.Dx0[2] = acadoVariables.x0[2] - acadoVariables.x[2]; +acadoWorkspace.Dx0[3] = acadoVariables.x0[3] - acadoVariables.x[3]; +acadoWorkspace.Dx0[4] = acadoVariables.x0[4] - acadoVariables.x[4]; +acadoWorkspace.Dx0[5] = acadoVariables.x0[5] - acadoVariables.x[5]; + +acadoWorkspace.Dy[0] -= acadoVariables.y[0]; +acadoWorkspace.Dy[1] -= acadoVariables.y[1]; +acadoWorkspace.Dy[2] -= acadoVariables.y[2]; +acadoWorkspace.Dy[3] -= acadoVariables.y[3]; +acadoWorkspace.Dy[4] -= acadoVariables.y[4]; +acadoWorkspace.Dy[5] -= acadoVariables.y[5]; +acadoWorkspace.Dy[6] -= acadoVariables.y[6]; +acadoWorkspace.Dy[7] -= acadoVariables.y[7]; +acadoWorkspace.Dy[8] -= acadoVariables.y[8]; +acadoWorkspace.Dy[9] -= acadoVariables.y[9]; +acadoWorkspace.Dy[10] -= acadoVariables.y[10]; +acadoWorkspace.Dy[11] -= acadoVariables.y[11]; +acadoWorkspace.Dy[12] -= acadoVariables.y[12]; +acadoWorkspace.Dy[13] -= acadoVariables.y[13]; +acadoWorkspace.Dy[14] -= acadoVariables.y[14]; +acadoWorkspace.Dy[15] -= acadoVariables.y[15]; +acadoWorkspace.Dy[16] -= acadoVariables.y[16]; +acadoWorkspace.Dy[17] -= acadoVariables.y[17]; +acadoWorkspace.Dy[18] -= acadoVariables.y[18]; +acadoWorkspace.Dy[19] -= acadoVariables.y[19]; +acadoWorkspace.Dy[20] -= acadoVariables.y[20]; +acadoWorkspace.Dy[21] -= acadoVariables.y[21]; +acadoWorkspace.Dy[22] -= acadoVariables.y[22]; +acadoWorkspace.Dy[23] -= acadoVariables.y[23]; +acadoWorkspace.Dy[24] -= acadoVariables.y[24]; +acadoWorkspace.Dy[25] -= acadoVariables.y[25]; +acadoWorkspace.Dy[26] -= acadoVariables.y[26]; +acadoWorkspace.Dy[27] -= acadoVariables.y[27]; +acadoWorkspace.Dy[28] -= acadoVariables.y[28]; +acadoWorkspace.Dy[29] -= acadoVariables.y[29]; +acadoWorkspace.Dy[30] -= acadoVariables.y[30]; +acadoWorkspace.Dy[31] -= acadoVariables.y[31]; +acadoWorkspace.Dy[32] -= acadoVariables.y[32]; +acadoWorkspace.Dy[33] -= acadoVariables.y[33]; +acadoWorkspace.Dy[34] -= acadoVariables.y[34]; +acadoWorkspace.Dy[35] -= acadoVariables.y[35]; +acadoWorkspace.Dy[36] -= acadoVariables.y[36]; +acadoWorkspace.Dy[37] -= acadoVariables.y[37]; +acadoWorkspace.Dy[38] -= acadoVariables.y[38]; +acadoWorkspace.Dy[39] -= acadoVariables.y[39]; +acadoWorkspace.Dy[40] -= acadoVariables.y[40]; +acadoWorkspace.Dy[41] -= acadoVariables.y[41]; +acadoWorkspace.Dy[42] -= acadoVariables.y[42]; +acadoWorkspace.Dy[43] -= acadoVariables.y[43]; +acadoWorkspace.Dy[44] -= acadoVariables.y[44]; +acadoWorkspace.Dy[45] -= acadoVariables.y[45]; +acadoWorkspace.Dy[46] -= acadoVariables.y[46]; +acadoWorkspace.Dy[47] -= acadoVariables.y[47]; +acadoWorkspace.Dy[48] -= acadoVariables.y[48]; +acadoWorkspace.Dy[49] -= acadoVariables.y[49]; +acadoWorkspace.Dy[50] -= acadoVariables.y[50]; +acadoWorkspace.Dy[51] -= acadoVariables.y[51]; +acadoWorkspace.Dy[52] -= acadoVariables.y[52]; +acadoWorkspace.Dy[53] -= acadoVariables.y[53]; +acadoWorkspace.Dy[54] -= acadoVariables.y[54]; +acadoWorkspace.Dy[55] -= acadoVariables.y[55]; +acadoWorkspace.Dy[56] -= acadoVariables.y[56]; +acadoWorkspace.Dy[57] -= acadoVariables.y[57]; +acadoWorkspace.Dy[58] -= acadoVariables.y[58]; +acadoWorkspace.Dy[59] -= acadoVariables.y[59]; +acadoWorkspace.Dy[60] -= acadoVariables.y[60]; +acadoWorkspace.Dy[61] -= acadoVariables.y[61]; +acadoWorkspace.Dy[62] -= acadoVariables.y[62]; +acadoWorkspace.Dy[63] -= acadoVariables.y[63]; +acadoWorkspace.Dy[64] -= acadoVariables.y[64]; +acadoWorkspace.Dy[65] -= acadoVariables.y[65]; +acadoWorkspace.Dy[66] -= acadoVariables.y[66]; +acadoWorkspace.Dy[67] -= acadoVariables.y[67]; +acadoWorkspace.Dy[68] -= acadoVariables.y[68]; +acadoWorkspace.Dy[69] -= acadoVariables.y[69]; +acadoWorkspace.Dy[70] -= acadoVariables.y[70]; +acadoWorkspace.Dy[71] -= acadoVariables.y[71]; +acadoWorkspace.Dy[72] -= acadoVariables.y[72]; +acadoWorkspace.Dy[73] -= acadoVariables.y[73]; +acadoWorkspace.Dy[74] -= acadoVariables.y[74]; +acadoWorkspace.Dy[75] -= acadoVariables.y[75]; +acadoWorkspace.Dy[76] -= acadoVariables.y[76]; +acadoWorkspace.Dy[77] -= acadoVariables.y[77]; +acadoWorkspace.Dy[78] -= acadoVariables.y[78]; +acadoWorkspace.Dy[79] -= acadoVariables.y[79]; +acadoWorkspace.DyN[0] -= acadoVariables.yN[0]; +acadoWorkspace.DyN[1] -= acadoVariables.yN[1]; +acadoWorkspace.DyN[2] -= acadoVariables.yN[2]; + +acado_multRDy( acadoWorkspace.R2, acadoWorkspace.Dy, &(acadoWorkspace.g[ 6 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 4 ]), &(acadoWorkspace.Dy[ 4 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 8 ]), &(acadoWorkspace.Dy[ 8 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 12 ]), &(acadoWorkspace.Dy[ 12 ]), &(acadoWorkspace.g[ 9 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 16 ]), &(acadoWorkspace.Dy[ 16 ]), &(acadoWorkspace.g[ 10 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 20 ]), &(acadoWorkspace.Dy[ 20 ]), &(acadoWorkspace.g[ 11 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 24 ]), &(acadoWorkspace.Dy[ 24 ]), &(acadoWorkspace.g[ 12 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 28 ]), &(acadoWorkspace.Dy[ 28 ]), &(acadoWorkspace.g[ 13 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 32 ]), &(acadoWorkspace.Dy[ 32 ]), &(acadoWorkspace.g[ 14 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 36 ]), &(acadoWorkspace.Dy[ 36 ]), &(acadoWorkspace.g[ 15 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 40 ]), &(acadoWorkspace.Dy[ 40 ]), &(acadoWorkspace.g[ 16 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 44 ]), &(acadoWorkspace.Dy[ 44 ]), &(acadoWorkspace.g[ 17 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 48 ]), &(acadoWorkspace.Dy[ 48 ]), &(acadoWorkspace.g[ 18 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 52 ]), &(acadoWorkspace.Dy[ 52 ]), &(acadoWorkspace.g[ 19 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 56 ]), &(acadoWorkspace.Dy[ 56 ]), &(acadoWorkspace.g[ 20 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 60 ]), &(acadoWorkspace.Dy[ 60 ]), &(acadoWorkspace.g[ 21 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 64 ]), &(acadoWorkspace.Dy[ 64 ]), &(acadoWorkspace.g[ 22 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 68 ]), &(acadoWorkspace.Dy[ 68 ]), &(acadoWorkspace.g[ 23 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 72 ]), &(acadoWorkspace.Dy[ 72 ]), &(acadoWorkspace.g[ 24 ]) ); +acado_multRDy( &(acadoWorkspace.R2[ 76 ]), &(acadoWorkspace.Dy[ 76 ]), &(acadoWorkspace.g[ 25 ]) ); + +acado_multQDy( acadoWorkspace.Q2, acadoWorkspace.Dy, acadoWorkspace.QDy ); +acado_multQDy( &(acadoWorkspace.Q2[ 24 ]), &(acadoWorkspace.Dy[ 4 ]), &(acadoWorkspace.QDy[ 6 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 48 ]), &(acadoWorkspace.Dy[ 8 ]), &(acadoWorkspace.QDy[ 12 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 72 ]), &(acadoWorkspace.Dy[ 12 ]), &(acadoWorkspace.QDy[ 18 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 96 ]), &(acadoWorkspace.Dy[ 16 ]), &(acadoWorkspace.QDy[ 24 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 120 ]), &(acadoWorkspace.Dy[ 20 ]), &(acadoWorkspace.QDy[ 30 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 144 ]), &(acadoWorkspace.Dy[ 24 ]), &(acadoWorkspace.QDy[ 36 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 168 ]), &(acadoWorkspace.Dy[ 28 ]), &(acadoWorkspace.QDy[ 42 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 192 ]), &(acadoWorkspace.Dy[ 32 ]), &(acadoWorkspace.QDy[ 48 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 216 ]), &(acadoWorkspace.Dy[ 36 ]), &(acadoWorkspace.QDy[ 54 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 240 ]), &(acadoWorkspace.Dy[ 40 ]), &(acadoWorkspace.QDy[ 60 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 264 ]), &(acadoWorkspace.Dy[ 44 ]), &(acadoWorkspace.QDy[ 66 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 288 ]), &(acadoWorkspace.Dy[ 48 ]), &(acadoWorkspace.QDy[ 72 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 312 ]), &(acadoWorkspace.Dy[ 52 ]), &(acadoWorkspace.QDy[ 78 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 336 ]), &(acadoWorkspace.Dy[ 56 ]), &(acadoWorkspace.QDy[ 84 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 360 ]), &(acadoWorkspace.Dy[ 60 ]), &(acadoWorkspace.QDy[ 90 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 384 ]), &(acadoWorkspace.Dy[ 64 ]), &(acadoWorkspace.QDy[ 96 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 408 ]), &(acadoWorkspace.Dy[ 68 ]), &(acadoWorkspace.QDy[ 102 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 432 ]), &(acadoWorkspace.Dy[ 72 ]), &(acadoWorkspace.QDy[ 108 ]) ); +acado_multQDy( &(acadoWorkspace.Q2[ 456 ]), &(acadoWorkspace.Dy[ 76 ]), &(acadoWorkspace.QDy[ 114 ]) ); + +acadoWorkspace.QDy[120] = + acadoWorkspace.QN2[0]*acadoWorkspace.DyN[0] + acadoWorkspace.QN2[1]*acadoWorkspace.DyN[1] + acadoWorkspace.QN2[2]*acadoWorkspace.DyN[2]; +acadoWorkspace.QDy[121] = + acadoWorkspace.QN2[3]*acadoWorkspace.DyN[0] + acadoWorkspace.QN2[4]*acadoWorkspace.DyN[1] + acadoWorkspace.QN2[5]*acadoWorkspace.DyN[2]; +acadoWorkspace.QDy[122] = + acadoWorkspace.QN2[6]*acadoWorkspace.DyN[0] + acadoWorkspace.QN2[7]*acadoWorkspace.DyN[1] + acadoWorkspace.QN2[8]*acadoWorkspace.DyN[2]; +acadoWorkspace.QDy[123] = + acadoWorkspace.QN2[9]*acadoWorkspace.DyN[0] + acadoWorkspace.QN2[10]*acadoWorkspace.DyN[1] + acadoWorkspace.QN2[11]*acadoWorkspace.DyN[2]; +acadoWorkspace.QDy[124] = + acadoWorkspace.QN2[12]*acadoWorkspace.DyN[0] + acadoWorkspace.QN2[13]*acadoWorkspace.DyN[1] + acadoWorkspace.QN2[14]*acadoWorkspace.DyN[2]; +acadoWorkspace.QDy[125] = + acadoWorkspace.QN2[15]*acadoWorkspace.DyN[0] + acadoWorkspace.QN2[16]*acadoWorkspace.DyN[1] + acadoWorkspace.QN2[17]*acadoWorkspace.DyN[2]; + +acadoWorkspace.QDy[6] += acadoWorkspace.Qd[0]; +acadoWorkspace.QDy[7] += acadoWorkspace.Qd[1]; +acadoWorkspace.QDy[8] += acadoWorkspace.Qd[2]; +acadoWorkspace.QDy[9] += acadoWorkspace.Qd[3]; +acadoWorkspace.QDy[10] += acadoWorkspace.Qd[4]; +acadoWorkspace.QDy[11] += acadoWorkspace.Qd[5]; +acadoWorkspace.QDy[12] += acadoWorkspace.Qd[6]; +acadoWorkspace.QDy[13] += acadoWorkspace.Qd[7]; +acadoWorkspace.QDy[14] += acadoWorkspace.Qd[8]; +acadoWorkspace.QDy[15] += acadoWorkspace.Qd[9]; +acadoWorkspace.QDy[16] += acadoWorkspace.Qd[10]; +acadoWorkspace.QDy[17] += acadoWorkspace.Qd[11]; +acadoWorkspace.QDy[18] += acadoWorkspace.Qd[12]; +acadoWorkspace.QDy[19] += acadoWorkspace.Qd[13]; +acadoWorkspace.QDy[20] += acadoWorkspace.Qd[14]; +acadoWorkspace.QDy[21] += acadoWorkspace.Qd[15]; +acadoWorkspace.QDy[22] += acadoWorkspace.Qd[16]; +acadoWorkspace.QDy[23] += acadoWorkspace.Qd[17]; +acadoWorkspace.QDy[24] += acadoWorkspace.Qd[18]; +acadoWorkspace.QDy[25] += acadoWorkspace.Qd[19]; +acadoWorkspace.QDy[26] += acadoWorkspace.Qd[20]; +acadoWorkspace.QDy[27] += acadoWorkspace.Qd[21]; +acadoWorkspace.QDy[28] += acadoWorkspace.Qd[22]; +acadoWorkspace.QDy[29] += acadoWorkspace.Qd[23]; +acadoWorkspace.QDy[30] += acadoWorkspace.Qd[24]; +acadoWorkspace.QDy[31] += acadoWorkspace.Qd[25]; +acadoWorkspace.QDy[32] += acadoWorkspace.Qd[26]; +acadoWorkspace.QDy[33] += acadoWorkspace.Qd[27]; +acadoWorkspace.QDy[34] += acadoWorkspace.Qd[28]; +acadoWorkspace.QDy[35] += acadoWorkspace.Qd[29]; +acadoWorkspace.QDy[36] += acadoWorkspace.Qd[30]; +acadoWorkspace.QDy[37] += acadoWorkspace.Qd[31]; +acadoWorkspace.QDy[38] += acadoWorkspace.Qd[32]; +acadoWorkspace.QDy[39] += acadoWorkspace.Qd[33]; +acadoWorkspace.QDy[40] += acadoWorkspace.Qd[34]; +acadoWorkspace.QDy[41] += acadoWorkspace.Qd[35]; +acadoWorkspace.QDy[42] += acadoWorkspace.Qd[36]; +acadoWorkspace.QDy[43] += acadoWorkspace.Qd[37]; +acadoWorkspace.QDy[44] += acadoWorkspace.Qd[38]; +acadoWorkspace.QDy[45] += acadoWorkspace.Qd[39]; +acadoWorkspace.QDy[46] += acadoWorkspace.Qd[40]; +acadoWorkspace.QDy[47] += acadoWorkspace.Qd[41]; +acadoWorkspace.QDy[48] += acadoWorkspace.Qd[42]; +acadoWorkspace.QDy[49] += acadoWorkspace.Qd[43]; +acadoWorkspace.QDy[50] += acadoWorkspace.Qd[44]; +acadoWorkspace.QDy[51] += acadoWorkspace.Qd[45]; +acadoWorkspace.QDy[52] += acadoWorkspace.Qd[46]; +acadoWorkspace.QDy[53] += acadoWorkspace.Qd[47]; +acadoWorkspace.QDy[54] += acadoWorkspace.Qd[48]; +acadoWorkspace.QDy[55] += acadoWorkspace.Qd[49]; +acadoWorkspace.QDy[56] += acadoWorkspace.Qd[50]; +acadoWorkspace.QDy[57] += acadoWorkspace.Qd[51]; +acadoWorkspace.QDy[58] += acadoWorkspace.Qd[52]; +acadoWorkspace.QDy[59] += acadoWorkspace.Qd[53]; +acadoWorkspace.QDy[60] += acadoWorkspace.Qd[54]; +acadoWorkspace.QDy[61] += acadoWorkspace.Qd[55]; +acadoWorkspace.QDy[62] += acadoWorkspace.Qd[56]; +acadoWorkspace.QDy[63] += acadoWorkspace.Qd[57]; +acadoWorkspace.QDy[64] += acadoWorkspace.Qd[58]; +acadoWorkspace.QDy[65] += acadoWorkspace.Qd[59]; +acadoWorkspace.QDy[66] += acadoWorkspace.Qd[60]; +acadoWorkspace.QDy[67] += acadoWorkspace.Qd[61]; +acadoWorkspace.QDy[68] += acadoWorkspace.Qd[62]; +acadoWorkspace.QDy[69] += acadoWorkspace.Qd[63]; +acadoWorkspace.QDy[70] += acadoWorkspace.Qd[64]; +acadoWorkspace.QDy[71] += acadoWorkspace.Qd[65]; +acadoWorkspace.QDy[72] += acadoWorkspace.Qd[66]; +acadoWorkspace.QDy[73] += acadoWorkspace.Qd[67]; +acadoWorkspace.QDy[74] += acadoWorkspace.Qd[68]; +acadoWorkspace.QDy[75] += acadoWorkspace.Qd[69]; +acadoWorkspace.QDy[76] += acadoWorkspace.Qd[70]; +acadoWorkspace.QDy[77] += acadoWorkspace.Qd[71]; +acadoWorkspace.QDy[78] += acadoWorkspace.Qd[72]; +acadoWorkspace.QDy[79] += acadoWorkspace.Qd[73]; +acadoWorkspace.QDy[80] += acadoWorkspace.Qd[74]; +acadoWorkspace.QDy[81] += acadoWorkspace.Qd[75]; +acadoWorkspace.QDy[82] += acadoWorkspace.Qd[76]; +acadoWorkspace.QDy[83] += acadoWorkspace.Qd[77]; +acadoWorkspace.QDy[84] += acadoWorkspace.Qd[78]; +acadoWorkspace.QDy[85] += acadoWorkspace.Qd[79]; +acadoWorkspace.QDy[86] += acadoWorkspace.Qd[80]; +acadoWorkspace.QDy[87] += acadoWorkspace.Qd[81]; +acadoWorkspace.QDy[88] += acadoWorkspace.Qd[82]; +acadoWorkspace.QDy[89] += acadoWorkspace.Qd[83]; +acadoWorkspace.QDy[90] += acadoWorkspace.Qd[84]; +acadoWorkspace.QDy[91] += acadoWorkspace.Qd[85]; +acadoWorkspace.QDy[92] += acadoWorkspace.Qd[86]; +acadoWorkspace.QDy[93] += acadoWorkspace.Qd[87]; +acadoWorkspace.QDy[94] += acadoWorkspace.Qd[88]; +acadoWorkspace.QDy[95] += acadoWorkspace.Qd[89]; +acadoWorkspace.QDy[96] += acadoWorkspace.Qd[90]; +acadoWorkspace.QDy[97] += acadoWorkspace.Qd[91]; +acadoWorkspace.QDy[98] += acadoWorkspace.Qd[92]; +acadoWorkspace.QDy[99] += acadoWorkspace.Qd[93]; +acadoWorkspace.QDy[100] += acadoWorkspace.Qd[94]; +acadoWorkspace.QDy[101] += acadoWorkspace.Qd[95]; +acadoWorkspace.QDy[102] += acadoWorkspace.Qd[96]; +acadoWorkspace.QDy[103] += acadoWorkspace.Qd[97]; +acadoWorkspace.QDy[104] += acadoWorkspace.Qd[98]; +acadoWorkspace.QDy[105] += acadoWorkspace.Qd[99]; +acadoWorkspace.QDy[106] += acadoWorkspace.Qd[100]; +acadoWorkspace.QDy[107] += acadoWorkspace.Qd[101]; +acadoWorkspace.QDy[108] += acadoWorkspace.Qd[102]; +acadoWorkspace.QDy[109] += acadoWorkspace.Qd[103]; +acadoWorkspace.QDy[110] += acadoWorkspace.Qd[104]; +acadoWorkspace.QDy[111] += acadoWorkspace.Qd[105]; +acadoWorkspace.QDy[112] += acadoWorkspace.Qd[106]; +acadoWorkspace.QDy[113] += acadoWorkspace.Qd[107]; +acadoWorkspace.QDy[114] += acadoWorkspace.Qd[108]; +acadoWorkspace.QDy[115] += acadoWorkspace.Qd[109]; +acadoWorkspace.QDy[116] += acadoWorkspace.Qd[110]; +acadoWorkspace.QDy[117] += acadoWorkspace.Qd[111]; +acadoWorkspace.QDy[118] += acadoWorkspace.Qd[112]; +acadoWorkspace.QDy[119] += acadoWorkspace.Qd[113]; +acadoWorkspace.QDy[120] += acadoWorkspace.Qd[114]; +acadoWorkspace.QDy[121] += acadoWorkspace.Qd[115]; +acadoWorkspace.QDy[122] += acadoWorkspace.Qd[116]; +acadoWorkspace.QDy[123] += acadoWorkspace.Qd[117]; +acadoWorkspace.QDy[124] += acadoWorkspace.Qd[118]; +acadoWorkspace.QDy[125] += acadoWorkspace.Qd[119]; + +acadoWorkspace.g[0] = + acadoWorkspace.evGx[0]*acadoWorkspace.QDy[6] + acadoWorkspace.evGx[6]*acadoWorkspace.QDy[7] + acadoWorkspace.evGx[12]*acadoWorkspace.QDy[8] + acadoWorkspace.evGx[18]*acadoWorkspace.QDy[9] + acadoWorkspace.evGx[24]*acadoWorkspace.QDy[10] + acadoWorkspace.evGx[30]*acadoWorkspace.QDy[11] + acadoWorkspace.evGx[36]*acadoWorkspace.QDy[12] + acadoWorkspace.evGx[42]*acadoWorkspace.QDy[13] + acadoWorkspace.evGx[48]*acadoWorkspace.QDy[14] + acadoWorkspace.evGx[54]*acadoWorkspace.QDy[15] + acadoWorkspace.evGx[60]*acadoWorkspace.QDy[16] + acadoWorkspace.evGx[66]*acadoWorkspace.QDy[17] + acadoWorkspace.evGx[72]*acadoWorkspace.QDy[18] + acadoWorkspace.evGx[78]*acadoWorkspace.QDy[19] + acadoWorkspace.evGx[84]*acadoWorkspace.QDy[20] + acadoWorkspace.evGx[90]*acadoWorkspace.QDy[21] + acadoWorkspace.evGx[96]*acadoWorkspace.QDy[22] + acadoWorkspace.evGx[102]*acadoWorkspace.QDy[23] + acadoWorkspace.evGx[108]*acadoWorkspace.QDy[24] + acadoWorkspace.evGx[114]*acadoWorkspace.QDy[25] + acadoWorkspace.evGx[120]*acadoWorkspace.QDy[26] + acadoWorkspace.evGx[126]*acadoWorkspace.QDy[27] + acadoWorkspace.evGx[132]*acadoWorkspace.QDy[28] + acadoWorkspace.evGx[138]*acadoWorkspace.QDy[29] + acadoWorkspace.evGx[144]*acadoWorkspace.QDy[30] + acadoWorkspace.evGx[150]*acadoWorkspace.QDy[31] + acadoWorkspace.evGx[156]*acadoWorkspace.QDy[32] + acadoWorkspace.evGx[162]*acadoWorkspace.QDy[33] + acadoWorkspace.evGx[168]*acadoWorkspace.QDy[34] + acadoWorkspace.evGx[174]*acadoWorkspace.QDy[35] + acadoWorkspace.evGx[180]*acadoWorkspace.QDy[36] + acadoWorkspace.evGx[186]*acadoWorkspace.QDy[37] + acadoWorkspace.evGx[192]*acadoWorkspace.QDy[38] + acadoWorkspace.evGx[198]*acadoWorkspace.QDy[39] + acadoWorkspace.evGx[204]*acadoWorkspace.QDy[40] + acadoWorkspace.evGx[210]*acadoWorkspace.QDy[41] + acadoWorkspace.evGx[216]*acadoWorkspace.QDy[42] + acadoWorkspace.evGx[222]*acadoWorkspace.QDy[43] + acadoWorkspace.evGx[228]*acadoWorkspace.QDy[44] + acadoWorkspace.evGx[234]*acadoWorkspace.QDy[45] + acadoWorkspace.evGx[240]*acadoWorkspace.QDy[46] + acadoWorkspace.evGx[246]*acadoWorkspace.QDy[47] + acadoWorkspace.evGx[252]*acadoWorkspace.QDy[48] + acadoWorkspace.evGx[258]*acadoWorkspace.QDy[49] + acadoWorkspace.evGx[264]*acadoWorkspace.QDy[50] + acadoWorkspace.evGx[270]*acadoWorkspace.QDy[51] + acadoWorkspace.evGx[276]*acadoWorkspace.QDy[52] + acadoWorkspace.evGx[282]*acadoWorkspace.QDy[53] + acadoWorkspace.evGx[288]*acadoWorkspace.QDy[54] + acadoWorkspace.evGx[294]*acadoWorkspace.QDy[55] + acadoWorkspace.evGx[300]*acadoWorkspace.QDy[56] + acadoWorkspace.evGx[306]*acadoWorkspace.QDy[57] + acadoWorkspace.evGx[312]*acadoWorkspace.QDy[58] + acadoWorkspace.evGx[318]*acadoWorkspace.QDy[59] + acadoWorkspace.evGx[324]*acadoWorkspace.QDy[60] + acadoWorkspace.evGx[330]*acadoWorkspace.QDy[61] + acadoWorkspace.evGx[336]*acadoWorkspace.QDy[62] + acadoWorkspace.evGx[342]*acadoWorkspace.QDy[63] + acadoWorkspace.evGx[348]*acadoWorkspace.QDy[64] + acadoWorkspace.evGx[354]*acadoWorkspace.QDy[65] + acadoWorkspace.evGx[360]*acadoWorkspace.QDy[66] + acadoWorkspace.evGx[366]*acadoWorkspace.QDy[67] + acadoWorkspace.evGx[372]*acadoWorkspace.QDy[68] + acadoWorkspace.evGx[378]*acadoWorkspace.QDy[69] + acadoWorkspace.evGx[384]*acadoWorkspace.QDy[70] + acadoWorkspace.evGx[390]*acadoWorkspace.QDy[71] + acadoWorkspace.evGx[396]*acadoWorkspace.QDy[72] + acadoWorkspace.evGx[402]*acadoWorkspace.QDy[73] + acadoWorkspace.evGx[408]*acadoWorkspace.QDy[74] + acadoWorkspace.evGx[414]*acadoWorkspace.QDy[75] + acadoWorkspace.evGx[420]*acadoWorkspace.QDy[76] + acadoWorkspace.evGx[426]*acadoWorkspace.QDy[77] + acadoWorkspace.evGx[432]*acadoWorkspace.QDy[78] + acadoWorkspace.evGx[438]*acadoWorkspace.QDy[79] + acadoWorkspace.evGx[444]*acadoWorkspace.QDy[80] + acadoWorkspace.evGx[450]*acadoWorkspace.QDy[81] + acadoWorkspace.evGx[456]*acadoWorkspace.QDy[82] + acadoWorkspace.evGx[462]*acadoWorkspace.QDy[83] + acadoWorkspace.evGx[468]*acadoWorkspace.QDy[84] + acadoWorkspace.evGx[474]*acadoWorkspace.QDy[85] + acadoWorkspace.evGx[480]*acadoWorkspace.QDy[86] + acadoWorkspace.evGx[486]*acadoWorkspace.QDy[87] + acadoWorkspace.evGx[492]*acadoWorkspace.QDy[88] + acadoWorkspace.evGx[498]*acadoWorkspace.QDy[89] + acadoWorkspace.evGx[504]*acadoWorkspace.QDy[90] + acadoWorkspace.evGx[510]*acadoWorkspace.QDy[91] + acadoWorkspace.evGx[516]*acadoWorkspace.QDy[92] + acadoWorkspace.evGx[522]*acadoWorkspace.QDy[93] + acadoWorkspace.evGx[528]*acadoWorkspace.QDy[94] + acadoWorkspace.evGx[534]*acadoWorkspace.QDy[95] + acadoWorkspace.evGx[540]*acadoWorkspace.QDy[96] + acadoWorkspace.evGx[546]*acadoWorkspace.QDy[97] + acadoWorkspace.evGx[552]*acadoWorkspace.QDy[98] + acadoWorkspace.evGx[558]*acadoWorkspace.QDy[99] + acadoWorkspace.evGx[564]*acadoWorkspace.QDy[100] + acadoWorkspace.evGx[570]*acadoWorkspace.QDy[101] + acadoWorkspace.evGx[576]*acadoWorkspace.QDy[102] + acadoWorkspace.evGx[582]*acadoWorkspace.QDy[103] + acadoWorkspace.evGx[588]*acadoWorkspace.QDy[104] + acadoWorkspace.evGx[594]*acadoWorkspace.QDy[105] + acadoWorkspace.evGx[600]*acadoWorkspace.QDy[106] + acadoWorkspace.evGx[606]*acadoWorkspace.QDy[107] + acadoWorkspace.evGx[612]*acadoWorkspace.QDy[108] + acadoWorkspace.evGx[618]*acadoWorkspace.QDy[109] + acadoWorkspace.evGx[624]*acadoWorkspace.QDy[110] + acadoWorkspace.evGx[630]*acadoWorkspace.QDy[111] + acadoWorkspace.evGx[636]*acadoWorkspace.QDy[112] + acadoWorkspace.evGx[642]*acadoWorkspace.QDy[113] + acadoWorkspace.evGx[648]*acadoWorkspace.QDy[114] + acadoWorkspace.evGx[654]*acadoWorkspace.QDy[115] + acadoWorkspace.evGx[660]*acadoWorkspace.QDy[116] + acadoWorkspace.evGx[666]*acadoWorkspace.QDy[117] + acadoWorkspace.evGx[672]*acadoWorkspace.QDy[118] + acadoWorkspace.evGx[678]*acadoWorkspace.QDy[119] + acadoWorkspace.evGx[684]*acadoWorkspace.QDy[120] + acadoWorkspace.evGx[690]*acadoWorkspace.QDy[121] + acadoWorkspace.evGx[696]*acadoWorkspace.QDy[122] + acadoWorkspace.evGx[702]*acadoWorkspace.QDy[123] + acadoWorkspace.evGx[708]*acadoWorkspace.QDy[124] + acadoWorkspace.evGx[714]*acadoWorkspace.QDy[125]; +acadoWorkspace.g[1] = + acadoWorkspace.evGx[1]*acadoWorkspace.QDy[6] + acadoWorkspace.evGx[7]*acadoWorkspace.QDy[7] + acadoWorkspace.evGx[13]*acadoWorkspace.QDy[8] + acadoWorkspace.evGx[19]*acadoWorkspace.QDy[9] + acadoWorkspace.evGx[25]*acadoWorkspace.QDy[10] + acadoWorkspace.evGx[31]*acadoWorkspace.QDy[11] + acadoWorkspace.evGx[37]*acadoWorkspace.QDy[12] + acadoWorkspace.evGx[43]*acadoWorkspace.QDy[13] + acadoWorkspace.evGx[49]*acadoWorkspace.QDy[14] + acadoWorkspace.evGx[55]*acadoWorkspace.QDy[15] + acadoWorkspace.evGx[61]*acadoWorkspace.QDy[16] + acadoWorkspace.evGx[67]*acadoWorkspace.QDy[17] + acadoWorkspace.evGx[73]*acadoWorkspace.QDy[18] + acadoWorkspace.evGx[79]*acadoWorkspace.QDy[19] + acadoWorkspace.evGx[85]*acadoWorkspace.QDy[20] + acadoWorkspace.evGx[91]*acadoWorkspace.QDy[21] + acadoWorkspace.evGx[97]*acadoWorkspace.QDy[22] + acadoWorkspace.evGx[103]*acadoWorkspace.QDy[23] + acadoWorkspace.evGx[109]*acadoWorkspace.QDy[24] + acadoWorkspace.evGx[115]*acadoWorkspace.QDy[25] + acadoWorkspace.evGx[121]*acadoWorkspace.QDy[26] + acadoWorkspace.evGx[127]*acadoWorkspace.QDy[27] + acadoWorkspace.evGx[133]*acadoWorkspace.QDy[28] + acadoWorkspace.evGx[139]*acadoWorkspace.QDy[29] + acadoWorkspace.evGx[145]*acadoWorkspace.QDy[30] + acadoWorkspace.evGx[151]*acadoWorkspace.QDy[31] + acadoWorkspace.evGx[157]*acadoWorkspace.QDy[32] + acadoWorkspace.evGx[163]*acadoWorkspace.QDy[33] + acadoWorkspace.evGx[169]*acadoWorkspace.QDy[34] + acadoWorkspace.evGx[175]*acadoWorkspace.QDy[35] + acadoWorkspace.evGx[181]*acadoWorkspace.QDy[36] + acadoWorkspace.evGx[187]*acadoWorkspace.QDy[37] + acadoWorkspace.evGx[193]*acadoWorkspace.QDy[38] + acadoWorkspace.evGx[199]*acadoWorkspace.QDy[39] + acadoWorkspace.evGx[205]*acadoWorkspace.QDy[40] + acadoWorkspace.evGx[211]*acadoWorkspace.QDy[41] + acadoWorkspace.evGx[217]*acadoWorkspace.QDy[42] + acadoWorkspace.evGx[223]*acadoWorkspace.QDy[43] + acadoWorkspace.evGx[229]*acadoWorkspace.QDy[44] + acadoWorkspace.evGx[235]*acadoWorkspace.QDy[45] + acadoWorkspace.evGx[241]*acadoWorkspace.QDy[46] + acadoWorkspace.evGx[247]*acadoWorkspace.QDy[47] + acadoWorkspace.evGx[253]*acadoWorkspace.QDy[48] + acadoWorkspace.evGx[259]*acadoWorkspace.QDy[49] + acadoWorkspace.evGx[265]*acadoWorkspace.QDy[50] + acadoWorkspace.evGx[271]*acadoWorkspace.QDy[51] + acadoWorkspace.evGx[277]*acadoWorkspace.QDy[52] + acadoWorkspace.evGx[283]*acadoWorkspace.QDy[53] + acadoWorkspace.evGx[289]*acadoWorkspace.QDy[54] + acadoWorkspace.evGx[295]*acadoWorkspace.QDy[55] + acadoWorkspace.evGx[301]*acadoWorkspace.QDy[56] + acadoWorkspace.evGx[307]*acadoWorkspace.QDy[57] + acadoWorkspace.evGx[313]*acadoWorkspace.QDy[58] + acadoWorkspace.evGx[319]*acadoWorkspace.QDy[59] + acadoWorkspace.evGx[325]*acadoWorkspace.QDy[60] + acadoWorkspace.evGx[331]*acadoWorkspace.QDy[61] + acadoWorkspace.evGx[337]*acadoWorkspace.QDy[62] + acadoWorkspace.evGx[343]*acadoWorkspace.QDy[63] + acadoWorkspace.evGx[349]*acadoWorkspace.QDy[64] + acadoWorkspace.evGx[355]*acadoWorkspace.QDy[65] + acadoWorkspace.evGx[361]*acadoWorkspace.QDy[66] + acadoWorkspace.evGx[367]*acadoWorkspace.QDy[67] + acadoWorkspace.evGx[373]*acadoWorkspace.QDy[68] + acadoWorkspace.evGx[379]*acadoWorkspace.QDy[69] + acadoWorkspace.evGx[385]*acadoWorkspace.QDy[70] + acadoWorkspace.evGx[391]*acadoWorkspace.QDy[71] + acadoWorkspace.evGx[397]*acadoWorkspace.QDy[72] + acadoWorkspace.evGx[403]*acadoWorkspace.QDy[73] + acadoWorkspace.evGx[409]*acadoWorkspace.QDy[74] + acadoWorkspace.evGx[415]*acadoWorkspace.QDy[75] + acadoWorkspace.evGx[421]*acadoWorkspace.QDy[76] + acadoWorkspace.evGx[427]*acadoWorkspace.QDy[77] + acadoWorkspace.evGx[433]*acadoWorkspace.QDy[78] + acadoWorkspace.evGx[439]*acadoWorkspace.QDy[79] + acadoWorkspace.evGx[445]*acadoWorkspace.QDy[80] + acadoWorkspace.evGx[451]*acadoWorkspace.QDy[81] + acadoWorkspace.evGx[457]*acadoWorkspace.QDy[82] + acadoWorkspace.evGx[463]*acadoWorkspace.QDy[83] + acadoWorkspace.evGx[469]*acadoWorkspace.QDy[84] + acadoWorkspace.evGx[475]*acadoWorkspace.QDy[85] + acadoWorkspace.evGx[481]*acadoWorkspace.QDy[86] + acadoWorkspace.evGx[487]*acadoWorkspace.QDy[87] + acadoWorkspace.evGx[493]*acadoWorkspace.QDy[88] + acadoWorkspace.evGx[499]*acadoWorkspace.QDy[89] + acadoWorkspace.evGx[505]*acadoWorkspace.QDy[90] + acadoWorkspace.evGx[511]*acadoWorkspace.QDy[91] + acadoWorkspace.evGx[517]*acadoWorkspace.QDy[92] + acadoWorkspace.evGx[523]*acadoWorkspace.QDy[93] + acadoWorkspace.evGx[529]*acadoWorkspace.QDy[94] + acadoWorkspace.evGx[535]*acadoWorkspace.QDy[95] + acadoWorkspace.evGx[541]*acadoWorkspace.QDy[96] + acadoWorkspace.evGx[547]*acadoWorkspace.QDy[97] + acadoWorkspace.evGx[553]*acadoWorkspace.QDy[98] + acadoWorkspace.evGx[559]*acadoWorkspace.QDy[99] + acadoWorkspace.evGx[565]*acadoWorkspace.QDy[100] + acadoWorkspace.evGx[571]*acadoWorkspace.QDy[101] + acadoWorkspace.evGx[577]*acadoWorkspace.QDy[102] + acadoWorkspace.evGx[583]*acadoWorkspace.QDy[103] + acadoWorkspace.evGx[589]*acadoWorkspace.QDy[104] + acadoWorkspace.evGx[595]*acadoWorkspace.QDy[105] + acadoWorkspace.evGx[601]*acadoWorkspace.QDy[106] + acadoWorkspace.evGx[607]*acadoWorkspace.QDy[107] + acadoWorkspace.evGx[613]*acadoWorkspace.QDy[108] + acadoWorkspace.evGx[619]*acadoWorkspace.QDy[109] + acadoWorkspace.evGx[625]*acadoWorkspace.QDy[110] + acadoWorkspace.evGx[631]*acadoWorkspace.QDy[111] + acadoWorkspace.evGx[637]*acadoWorkspace.QDy[112] + acadoWorkspace.evGx[643]*acadoWorkspace.QDy[113] + acadoWorkspace.evGx[649]*acadoWorkspace.QDy[114] + acadoWorkspace.evGx[655]*acadoWorkspace.QDy[115] + acadoWorkspace.evGx[661]*acadoWorkspace.QDy[116] + acadoWorkspace.evGx[667]*acadoWorkspace.QDy[117] + acadoWorkspace.evGx[673]*acadoWorkspace.QDy[118] + acadoWorkspace.evGx[679]*acadoWorkspace.QDy[119] + acadoWorkspace.evGx[685]*acadoWorkspace.QDy[120] + acadoWorkspace.evGx[691]*acadoWorkspace.QDy[121] + acadoWorkspace.evGx[697]*acadoWorkspace.QDy[122] + acadoWorkspace.evGx[703]*acadoWorkspace.QDy[123] + acadoWorkspace.evGx[709]*acadoWorkspace.QDy[124] + acadoWorkspace.evGx[715]*acadoWorkspace.QDy[125]; +acadoWorkspace.g[2] = + acadoWorkspace.evGx[2]*acadoWorkspace.QDy[6] + acadoWorkspace.evGx[8]*acadoWorkspace.QDy[7] + acadoWorkspace.evGx[14]*acadoWorkspace.QDy[8] + acadoWorkspace.evGx[20]*acadoWorkspace.QDy[9] + acadoWorkspace.evGx[26]*acadoWorkspace.QDy[10] + acadoWorkspace.evGx[32]*acadoWorkspace.QDy[11] + acadoWorkspace.evGx[38]*acadoWorkspace.QDy[12] + acadoWorkspace.evGx[44]*acadoWorkspace.QDy[13] + acadoWorkspace.evGx[50]*acadoWorkspace.QDy[14] + acadoWorkspace.evGx[56]*acadoWorkspace.QDy[15] + acadoWorkspace.evGx[62]*acadoWorkspace.QDy[16] + acadoWorkspace.evGx[68]*acadoWorkspace.QDy[17] + acadoWorkspace.evGx[74]*acadoWorkspace.QDy[18] + acadoWorkspace.evGx[80]*acadoWorkspace.QDy[19] + acadoWorkspace.evGx[86]*acadoWorkspace.QDy[20] + acadoWorkspace.evGx[92]*acadoWorkspace.QDy[21] + acadoWorkspace.evGx[98]*acadoWorkspace.QDy[22] + acadoWorkspace.evGx[104]*acadoWorkspace.QDy[23] + acadoWorkspace.evGx[110]*acadoWorkspace.QDy[24] + acadoWorkspace.evGx[116]*acadoWorkspace.QDy[25] + acadoWorkspace.evGx[122]*acadoWorkspace.QDy[26] + acadoWorkspace.evGx[128]*acadoWorkspace.QDy[27] + acadoWorkspace.evGx[134]*acadoWorkspace.QDy[28] + acadoWorkspace.evGx[140]*acadoWorkspace.QDy[29] + acadoWorkspace.evGx[146]*acadoWorkspace.QDy[30] + acadoWorkspace.evGx[152]*acadoWorkspace.QDy[31] + acadoWorkspace.evGx[158]*acadoWorkspace.QDy[32] + acadoWorkspace.evGx[164]*acadoWorkspace.QDy[33] + acadoWorkspace.evGx[170]*acadoWorkspace.QDy[34] + acadoWorkspace.evGx[176]*acadoWorkspace.QDy[35] + acadoWorkspace.evGx[182]*acadoWorkspace.QDy[36] + acadoWorkspace.evGx[188]*acadoWorkspace.QDy[37] + acadoWorkspace.evGx[194]*acadoWorkspace.QDy[38] + acadoWorkspace.evGx[200]*acadoWorkspace.QDy[39] + acadoWorkspace.evGx[206]*acadoWorkspace.QDy[40] + acadoWorkspace.evGx[212]*acadoWorkspace.QDy[41] + acadoWorkspace.evGx[218]*acadoWorkspace.QDy[42] + acadoWorkspace.evGx[224]*acadoWorkspace.QDy[43] + acadoWorkspace.evGx[230]*acadoWorkspace.QDy[44] + acadoWorkspace.evGx[236]*acadoWorkspace.QDy[45] + acadoWorkspace.evGx[242]*acadoWorkspace.QDy[46] + acadoWorkspace.evGx[248]*acadoWorkspace.QDy[47] + acadoWorkspace.evGx[254]*acadoWorkspace.QDy[48] + acadoWorkspace.evGx[260]*acadoWorkspace.QDy[49] + acadoWorkspace.evGx[266]*acadoWorkspace.QDy[50] + acadoWorkspace.evGx[272]*acadoWorkspace.QDy[51] + acadoWorkspace.evGx[278]*acadoWorkspace.QDy[52] + acadoWorkspace.evGx[284]*acadoWorkspace.QDy[53] + acadoWorkspace.evGx[290]*acadoWorkspace.QDy[54] + acadoWorkspace.evGx[296]*acadoWorkspace.QDy[55] + acadoWorkspace.evGx[302]*acadoWorkspace.QDy[56] + acadoWorkspace.evGx[308]*acadoWorkspace.QDy[57] + acadoWorkspace.evGx[314]*acadoWorkspace.QDy[58] + acadoWorkspace.evGx[320]*acadoWorkspace.QDy[59] + acadoWorkspace.evGx[326]*acadoWorkspace.QDy[60] + acadoWorkspace.evGx[332]*acadoWorkspace.QDy[61] + acadoWorkspace.evGx[338]*acadoWorkspace.QDy[62] + acadoWorkspace.evGx[344]*acadoWorkspace.QDy[63] + acadoWorkspace.evGx[350]*acadoWorkspace.QDy[64] + acadoWorkspace.evGx[356]*acadoWorkspace.QDy[65] + acadoWorkspace.evGx[362]*acadoWorkspace.QDy[66] + acadoWorkspace.evGx[368]*acadoWorkspace.QDy[67] + acadoWorkspace.evGx[374]*acadoWorkspace.QDy[68] + acadoWorkspace.evGx[380]*acadoWorkspace.QDy[69] + acadoWorkspace.evGx[386]*acadoWorkspace.QDy[70] + acadoWorkspace.evGx[392]*acadoWorkspace.QDy[71] + acadoWorkspace.evGx[398]*acadoWorkspace.QDy[72] + acadoWorkspace.evGx[404]*acadoWorkspace.QDy[73] + acadoWorkspace.evGx[410]*acadoWorkspace.QDy[74] + acadoWorkspace.evGx[416]*acadoWorkspace.QDy[75] + acadoWorkspace.evGx[422]*acadoWorkspace.QDy[76] + acadoWorkspace.evGx[428]*acadoWorkspace.QDy[77] + acadoWorkspace.evGx[434]*acadoWorkspace.QDy[78] + acadoWorkspace.evGx[440]*acadoWorkspace.QDy[79] + acadoWorkspace.evGx[446]*acadoWorkspace.QDy[80] + acadoWorkspace.evGx[452]*acadoWorkspace.QDy[81] + acadoWorkspace.evGx[458]*acadoWorkspace.QDy[82] + acadoWorkspace.evGx[464]*acadoWorkspace.QDy[83] + acadoWorkspace.evGx[470]*acadoWorkspace.QDy[84] + acadoWorkspace.evGx[476]*acadoWorkspace.QDy[85] + acadoWorkspace.evGx[482]*acadoWorkspace.QDy[86] + acadoWorkspace.evGx[488]*acadoWorkspace.QDy[87] + acadoWorkspace.evGx[494]*acadoWorkspace.QDy[88] + acadoWorkspace.evGx[500]*acadoWorkspace.QDy[89] + acadoWorkspace.evGx[506]*acadoWorkspace.QDy[90] + acadoWorkspace.evGx[512]*acadoWorkspace.QDy[91] + acadoWorkspace.evGx[518]*acadoWorkspace.QDy[92] + acadoWorkspace.evGx[524]*acadoWorkspace.QDy[93] + acadoWorkspace.evGx[530]*acadoWorkspace.QDy[94] + acadoWorkspace.evGx[536]*acadoWorkspace.QDy[95] + acadoWorkspace.evGx[542]*acadoWorkspace.QDy[96] + acadoWorkspace.evGx[548]*acadoWorkspace.QDy[97] + acadoWorkspace.evGx[554]*acadoWorkspace.QDy[98] + acadoWorkspace.evGx[560]*acadoWorkspace.QDy[99] + acadoWorkspace.evGx[566]*acadoWorkspace.QDy[100] + acadoWorkspace.evGx[572]*acadoWorkspace.QDy[101] + acadoWorkspace.evGx[578]*acadoWorkspace.QDy[102] + acadoWorkspace.evGx[584]*acadoWorkspace.QDy[103] + acadoWorkspace.evGx[590]*acadoWorkspace.QDy[104] + acadoWorkspace.evGx[596]*acadoWorkspace.QDy[105] + acadoWorkspace.evGx[602]*acadoWorkspace.QDy[106] + acadoWorkspace.evGx[608]*acadoWorkspace.QDy[107] + acadoWorkspace.evGx[614]*acadoWorkspace.QDy[108] + acadoWorkspace.evGx[620]*acadoWorkspace.QDy[109] + acadoWorkspace.evGx[626]*acadoWorkspace.QDy[110] + acadoWorkspace.evGx[632]*acadoWorkspace.QDy[111] + acadoWorkspace.evGx[638]*acadoWorkspace.QDy[112] + acadoWorkspace.evGx[644]*acadoWorkspace.QDy[113] + acadoWorkspace.evGx[650]*acadoWorkspace.QDy[114] + acadoWorkspace.evGx[656]*acadoWorkspace.QDy[115] + acadoWorkspace.evGx[662]*acadoWorkspace.QDy[116] + acadoWorkspace.evGx[668]*acadoWorkspace.QDy[117] + acadoWorkspace.evGx[674]*acadoWorkspace.QDy[118] + acadoWorkspace.evGx[680]*acadoWorkspace.QDy[119] + acadoWorkspace.evGx[686]*acadoWorkspace.QDy[120] + acadoWorkspace.evGx[692]*acadoWorkspace.QDy[121] + acadoWorkspace.evGx[698]*acadoWorkspace.QDy[122] + acadoWorkspace.evGx[704]*acadoWorkspace.QDy[123] + acadoWorkspace.evGx[710]*acadoWorkspace.QDy[124] + acadoWorkspace.evGx[716]*acadoWorkspace.QDy[125]; +acadoWorkspace.g[3] = + acadoWorkspace.evGx[3]*acadoWorkspace.QDy[6] + acadoWorkspace.evGx[9]*acadoWorkspace.QDy[7] + acadoWorkspace.evGx[15]*acadoWorkspace.QDy[8] + acadoWorkspace.evGx[21]*acadoWorkspace.QDy[9] + acadoWorkspace.evGx[27]*acadoWorkspace.QDy[10] + acadoWorkspace.evGx[33]*acadoWorkspace.QDy[11] + acadoWorkspace.evGx[39]*acadoWorkspace.QDy[12] + acadoWorkspace.evGx[45]*acadoWorkspace.QDy[13] + acadoWorkspace.evGx[51]*acadoWorkspace.QDy[14] + acadoWorkspace.evGx[57]*acadoWorkspace.QDy[15] + acadoWorkspace.evGx[63]*acadoWorkspace.QDy[16] + acadoWorkspace.evGx[69]*acadoWorkspace.QDy[17] + acadoWorkspace.evGx[75]*acadoWorkspace.QDy[18] + acadoWorkspace.evGx[81]*acadoWorkspace.QDy[19] + acadoWorkspace.evGx[87]*acadoWorkspace.QDy[20] + acadoWorkspace.evGx[93]*acadoWorkspace.QDy[21] + acadoWorkspace.evGx[99]*acadoWorkspace.QDy[22] + acadoWorkspace.evGx[105]*acadoWorkspace.QDy[23] + acadoWorkspace.evGx[111]*acadoWorkspace.QDy[24] + acadoWorkspace.evGx[117]*acadoWorkspace.QDy[25] + acadoWorkspace.evGx[123]*acadoWorkspace.QDy[26] + acadoWorkspace.evGx[129]*acadoWorkspace.QDy[27] + acadoWorkspace.evGx[135]*acadoWorkspace.QDy[28] + acadoWorkspace.evGx[141]*acadoWorkspace.QDy[29] + acadoWorkspace.evGx[147]*acadoWorkspace.QDy[30] + acadoWorkspace.evGx[153]*acadoWorkspace.QDy[31] + acadoWorkspace.evGx[159]*acadoWorkspace.QDy[32] + acadoWorkspace.evGx[165]*acadoWorkspace.QDy[33] + acadoWorkspace.evGx[171]*acadoWorkspace.QDy[34] + acadoWorkspace.evGx[177]*acadoWorkspace.QDy[35] + acadoWorkspace.evGx[183]*acadoWorkspace.QDy[36] + acadoWorkspace.evGx[189]*acadoWorkspace.QDy[37] + acadoWorkspace.evGx[195]*acadoWorkspace.QDy[38] + acadoWorkspace.evGx[201]*acadoWorkspace.QDy[39] + acadoWorkspace.evGx[207]*acadoWorkspace.QDy[40] + acadoWorkspace.evGx[213]*acadoWorkspace.QDy[41] + acadoWorkspace.evGx[219]*acadoWorkspace.QDy[42] + acadoWorkspace.evGx[225]*acadoWorkspace.QDy[43] + acadoWorkspace.evGx[231]*acadoWorkspace.QDy[44] + acadoWorkspace.evGx[237]*acadoWorkspace.QDy[45] + acadoWorkspace.evGx[243]*acadoWorkspace.QDy[46] + acadoWorkspace.evGx[249]*acadoWorkspace.QDy[47] + acadoWorkspace.evGx[255]*acadoWorkspace.QDy[48] + acadoWorkspace.evGx[261]*acadoWorkspace.QDy[49] + acadoWorkspace.evGx[267]*acadoWorkspace.QDy[50] + acadoWorkspace.evGx[273]*acadoWorkspace.QDy[51] + acadoWorkspace.evGx[279]*acadoWorkspace.QDy[52] + acadoWorkspace.evGx[285]*acadoWorkspace.QDy[53] + acadoWorkspace.evGx[291]*acadoWorkspace.QDy[54] + acadoWorkspace.evGx[297]*acadoWorkspace.QDy[55] + acadoWorkspace.evGx[303]*acadoWorkspace.QDy[56] + acadoWorkspace.evGx[309]*acadoWorkspace.QDy[57] + acadoWorkspace.evGx[315]*acadoWorkspace.QDy[58] + acadoWorkspace.evGx[321]*acadoWorkspace.QDy[59] + acadoWorkspace.evGx[327]*acadoWorkspace.QDy[60] + acadoWorkspace.evGx[333]*acadoWorkspace.QDy[61] + acadoWorkspace.evGx[339]*acadoWorkspace.QDy[62] + acadoWorkspace.evGx[345]*acadoWorkspace.QDy[63] + acadoWorkspace.evGx[351]*acadoWorkspace.QDy[64] + acadoWorkspace.evGx[357]*acadoWorkspace.QDy[65] + acadoWorkspace.evGx[363]*acadoWorkspace.QDy[66] + acadoWorkspace.evGx[369]*acadoWorkspace.QDy[67] + acadoWorkspace.evGx[375]*acadoWorkspace.QDy[68] + acadoWorkspace.evGx[381]*acadoWorkspace.QDy[69] + acadoWorkspace.evGx[387]*acadoWorkspace.QDy[70] + acadoWorkspace.evGx[393]*acadoWorkspace.QDy[71] + acadoWorkspace.evGx[399]*acadoWorkspace.QDy[72] + acadoWorkspace.evGx[405]*acadoWorkspace.QDy[73] + acadoWorkspace.evGx[411]*acadoWorkspace.QDy[74] + acadoWorkspace.evGx[417]*acadoWorkspace.QDy[75] + acadoWorkspace.evGx[423]*acadoWorkspace.QDy[76] + acadoWorkspace.evGx[429]*acadoWorkspace.QDy[77] + acadoWorkspace.evGx[435]*acadoWorkspace.QDy[78] + acadoWorkspace.evGx[441]*acadoWorkspace.QDy[79] + acadoWorkspace.evGx[447]*acadoWorkspace.QDy[80] + acadoWorkspace.evGx[453]*acadoWorkspace.QDy[81] + acadoWorkspace.evGx[459]*acadoWorkspace.QDy[82] + acadoWorkspace.evGx[465]*acadoWorkspace.QDy[83] + acadoWorkspace.evGx[471]*acadoWorkspace.QDy[84] + acadoWorkspace.evGx[477]*acadoWorkspace.QDy[85] + acadoWorkspace.evGx[483]*acadoWorkspace.QDy[86] + acadoWorkspace.evGx[489]*acadoWorkspace.QDy[87] + acadoWorkspace.evGx[495]*acadoWorkspace.QDy[88] + acadoWorkspace.evGx[501]*acadoWorkspace.QDy[89] + acadoWorkspace.evGx[507]*acadoWorkspace.QDy[90] + acadoWorkspace.evGx[513]*acadoWorkspace.QDy[91] + acadoWorkspace.evGx[519]*acadoWorkspace.QDy[92] + acadoWorkspace.evGx[525]*acadoWorkspace.QDy[93] + acadoWorkspace.evGx[531]*acadoWorkspace.QDy[94] + acadoWorkspace.evGx[537]*acadoWorkspace.QDy[95] + acadoWorkspace.evGx[543]*acadoWorkspace.QDy[96] + acadoWorkspace.evGx[549]*acadoWorkspace.QDy[97] + acadoWorkspace.evGx[555]*acadoWorkspace.QDy[98] + acadoWorkspace.evGx[561]*acadoWorkspace.QDy[99] + acadoWorkspace.evGx[567]*acadoWorkspace.QDy[100] + acadoWorkspace.evGx[573]*acadoWorkspace.QDy[101] + acadoWorkspace.evGx[579]*acadoWorkspace.QDy[102] + acadoWorkspace.evGx[585]*acadoWorkspace.QDy[103] + acadoWorkspace.evGx[591]*acadoWorkspace.QDy[104] + acadoWorkspace.evGx[597]*acadoWorkspace.QDy[105] + acadoWorkspace.evGx[603]*acadoWorkspace.QDy[106] + acadoWorkspace.evGx[609]*acadoWorkspace.QDy[107] + acadoWorkspace.evGx[615]*acadoWorkspace.QDy[108] + acadoWorkspace.evGx[621]*acadoWorkspace.QDy[109] + acadoWorkspace.evGx[627]*acadoWorkspace.QDy[110] + acadoWorkspace.evGx[633]*acadoWorkspace.QDy[111] + acadoWorkspace.evGx[639]*acadoWorkspace.QDy[112] + acadoWorkspace.evGx[645]*acadoWorkspace.QDy[113] + acadoWorkspace.evGx[651]*acadoWorkspace.QDy[114] + acadoWorkspace.evGx[657]*acadoWorkspace.QDy[115] + acadoWorkspace.evGx[663]*acadoWorkspace.QDy[116] + acadoWorkspace.evGx[669]*acadoWorkspace.QDy[117] + acadoWorkspace.evGx[675]*acadoWorkspace.QDy[118] + acadoWorkspace.evGx[681]*acadoWorkspace.QDy[119] + acadoWorkspace.evGx[687]*acadoWorkspace.QDy[120] + acadoWorkspace.evGx[693]*acadoWorkspace.QDy[121] + acadoWorkspace.evGx[699]*acadoWorkspace.QDy[122] + acadoWorkspace.evGx[705]*acadoWorkspace.QDy[123] + acadoWorkspace.evGx[711]*acadoWorkspace.QDy[124] + acadoWorkspace.evGx[717]*acadoWorkspace.QDy[125]; +acadoWorkspace.g[4] = + acadoWorkspace.evGx[4]*acadoWorkspace.QDy[6] + acadoWorkspace.evGx[10]*acadoWorkspace.QDy[7] + acadoWorkspace.evGx[16]*acadoWorkspace.QDy[8] + acadoWorkspace.evGx[22]*acadoWorkspace.QDy[9] + acadoWorkspace.evGx[28]*acadoWorkspace.QDy[10] + acadoWorkspace.evGx[34]*acadoWorkspace.QDy[11] + acadoWorkspace.evGx[40]*acadoWorkspace.QDy[12] + acadoWorkspace.evGx[46]*acadoWorkspace.QDy[13] + acadoWorkspace.evGx[52]*acadoWorkspace.QDy[14] + acadoWorkspace.evGx[58]*acadoWorkspace.QDy[15] + acadoWorkspace.evGx[64]*acadoWorkspace.QDy[16] + acadoWorkspace.evGx[70]*acadoWorkspace.QDy[17] + acadoWorkspace.evGx[76]*acadoWorkspace.QDy[18] + acadoWorkspace.evGx[82]*acadoWorkspace.QDy[19] + acadoWorkspace.evGx[88]*acadoWorkspace.QDy[20] + acadoWorkspace.evGx[94]*acadoWorkspace.QDy[21] + acadoWorkspace.evGx[100]*acadoWorkspace.QDy[22] + acadoWorkspace.evGx[106]*acadoWorkspace.QDy[23] + acadoWorkspace.evGx[112]*acadoWorkspace.QDy[24] + acadoWorkspace.evGx[118]*acadoWorkspace.QDy[25] + acadoWorkspace.evGx[124]*acadoWorkspace.QDy[26] + acadoWorkspace.evGx[130]*acadoWorkspace.QDy[27] + acadoWorkspace.evGx[136]*acadoWorkspace.QDy[28] + acadoWorkspace.evGx[142]*acadoWorkspace.QDy[29] + acadoWorkspace.evGx[148]*acadoWorkspace.QDy[30] + acadoWorkspace.evGx[154]*acadoWorkspace.QDy[31] + acadoWorkspace.evGx[160]*acadoWorkspace.QDy[32] + acadoWorkspace.evGx[166]*acadoWorkspace.QDy[33] + acadoWorkspace.evGx[172]*acadoWorkspace.QDy[34] + acadoWorkspace.evGx[178]*acadoWorkspace.QDy[35] + acadoWorkspace.evGx[184]*acadoWorkspace.QDy[36] + acadoWorkspace.evGx[190]*acadoWorkspace.QDy[37] + acadoWorkspace.evGx[196]*acadoWorkspace.QDy[38] + acadoWorkspace.evGx[202]*acadoWorkspace.QDy[39] + acadoWorkspace.evGx[208]*acadoWorkspace.QDy[40] + acadoWorkspace.evGx[214]*acadoWorkspace.QDy[41] + acadoWorkspace.evGx[220]*acadoWorkspace.QDy[42] + acadoWorkspace.evGx[226]*acadoWorkspace.QDy[43] + acadoWorkspace.evGx[232]*acadoWorkspace.QDy[44] + acadoWorkspace.evGx[238]*acadoWorkspace.QDy[45] + acadoWorkspace.evGx[244]*acadoWorkspace.QDy[46] + acadoWorkspace.evGx[250]*acadoWorkspace.QDy[47] + acadoWorkspace.evGx[256]*acadoWorkspace.QDy[48] + acadoWorkspace.evGx[262]*acadoWorkspace.QDy[49] + acadoWorkspace.evGx[268]*acadoWorkspace.QDy[50] + acadoWorkspace.evGx[274]*acadoWorkspace.QDy[51] + acadoWorkspace.evGx[280]*acadoWorkspace.QDy[52] + acadoWorkspace.evGx[286]*acadoWorkspace.QDy[53] + acadoWorkspace.evGx[292]*acadoWorkspace.QDy[54] + acadoWorkspace.evGx[298]*acadoWorkspace.QDy[55] + acadoWorkspace.evGx[304]*acadoWorkspace.QDy[56] + acadoWorkspace.evGx[310]*acadoWorkspace.QDy[57] + acadoWorkspace.evGx[316]*acadoWorkspace.QDy[58] + acadoWorkspace.evGx[322]*acadoWorkspace.QDy[59] + acadoWorkspace.evGx[328]*acadoWorkspace.QDy[60] + acadoWorkspace.evGx[334]*acadoWorkspace.QDy[61] + acadoWorkspace.evGx[340]*acadoWorkspace.QDy[62] + acadoWorkspace.evGx[346]*acadoWorkspace.QDy[63] + acadoWorkspace.evGx[352]*acadoWorkspace.QDy[64] + acadoWorkspace.evGx[358]*acadoWorkspace.QDy[65] + acadoWorkspace.evGx[364]*acadoWorkspace.QDy[66] + acadoWorkspace.evGx[370]*acadoWorkspace.QDy[67] + acadoWorkspace.evGx[376]*acadoWorkspace.QDy[68] + acadoWorkspace.evGx[382]*acadoWorkspace.QDy[69] + acadoWorkspace.evGx[388]*acadoWorkspace.QDy[70] + acadoWorkspace.evGx[394]*acadoWorkspace.QDy[71] + acadoWorkspace.evGx[400]*acadoWorkspace.QDy[72] + acadoWorkspace.evGx[406]*acadoWorkspace.QDy[73] + acadoWorkspace.evGx[412]*acadoWorkspace.QDy[74] + acadoWorkspace.evGx[418]*acadoWorkspace.QDy[75] + acadoWorkspace.evGx[424]*acadoWorkspace.QDy[76] + acadoWorkspace.evGx[430]*acadoWorkspace.QDy[77] + acadoWorkspace.evGx[436]*acadoWorkspace.QDy[78] + acadoWorkspace.evGx[442]*acadoWorkspace.QDy[79] + acadoWorkspace.evGx[448]*acadoWorkspace.QDy[80] + acadoWorkspace.evGx[454]*acadoWorkspace.QDy[81] + acadoWorkspace.evGx[460]*acadoWorkspace.QDy[82] + acadoWorkspace.evGx[466]*acadoWorkspace.QDy[83] + acadoWorkspace.evGx[472]*acadoWorkspace.QDy[84] + acadoWorkspace.evGx[478]*acadoWorkspace.QDy[85] + acadoWorkspace.evGx[484]*acadoWorkspace.QDy[86] + acadoWorkspace.evGx[490]*acadoWorkspace.QDy[87] + acadoWorkspace.evGx[496]*acadoWorkspace.QDy[88] + acadoWorkspace.evGx[502]*acadoWorkspace.QDy[89] + acadoWorkspace.evGx[508]*acadoWorkspace.QDy[90] + acadoWorkspace.evGx[514]*acadoWorkspace.QDy[91] + acadoWorkspace.evGx[520]*acadoWorkspace.QDy[92] + acadoWorkspace.evGx[526]*acadoWorkspace.QDy[93] + acadoWorkspace.evGx[532]*acadoWorkspace.QDy[94] + acadoWorkspace.evGx[538]*acadoWorkspace.QDy[95] + acadoWorkspace.evGx[544]*acadoWorkspace.QDy[96] + acadoWorkspace.evGx[550]*acadoWorkspace.QDy[97] + acadoWorkspace.evGx[556]*acadoWorkspace.QDy[98] + acadoWorkspace.evGx[562]*acadoWorkspace.QDy[99] + acadoWorkspace.evGx[568]*acadoWorkspace.QDy[100] + acadoWorkspace.evGx[574]*acadoWorkspace.QDy[101] + acadoWorkspace.evGx[580]*acadoWorkspace.QDy[102] + acadoWorkspace.evGx[586]*acadoWorkspace.QDy[103] + acadoWorkspace.evGx[592]*acadoWorkspace.QDy[104] + acadoWorkspace.evGx[598]*acadoWorkspace.QDy[105] + acadoWorkspace.evGx[604]*acadoWorkspace.QDy[106] + acadoWorkspace.evGx[610]*acadoWorkspace.QDy[107] + acadoWorkspace.evGx[616]*acadoWorkspace.QDy[108] + acadoWorkspace.evGx[622]*acadoWorkspace.QDy[109] + acadoWorkspace.evGx[628]*acadoWorkspace.QDy[110] + acadoWorkspace.evGx[634]*acadoWorkspace.QDy[111] + acadoWorkspace.evGx[640]*acadoWorkspace.QDy[112] + acadoWorkspace.evGx[646]*acadoWorkspace.QDy[113] + acadoWorkspace.evGx[652]*acadoWorkspace.QDy[114] + acadoWorkspace.evGx[658]*acadoWorkspace.QDy[115] + acadoWorkspace.evGx[664]*acadoWorkspace.QDy[116] + acadoWorkspace.evGx[670]*acadoWorkspace.QDy[117] + acadoWorkspace.evGx[676]*acadoWorkspace.QDy[118] + acadoWorkspace.evGx[682]*acadoWorkspace.QDy[119] + acadoWorkspace.evGx[688]*acadoWorkspace.QDy[120] + acadoWorkspace.evGx[694]*acadoWorkspace.QDy[121] + acadoWorkspace.evGx[700]*acadoWorkspace.QDy[122] + acadoWorkspace.evGx[706]*acadoWorkspace.QDy[123] + acadoWorkspace.evGx[712]*acadoWorkspace.QDy[124] + acadoWorkspace.evGx[718]*acadoWorkspace.QDy[125]; +acadoWorkspace.g[5] = + acadoWorkspace.evGx[5]*acadoWorkspace.QDy[6] + acadoWorkspace.evGx[11]*acadoWorkspace.QDy[7] + acadoWorkspace.evGx[17]*acadoWorkspace.QDy[8] + acadoWorkspace.evGx[23]*acadoWorkspace.QDy[9] + acadoWorkspace.evGx[29]*acadoWorkspace.QDy[10] + acadoWorkspace.evGx[35]*acadoWorkspace.QDy[11] + acadoWorkspace.evGx[41]*acadoWorkspace.QDy[12] + acadoWorkspace.evGx[47]*acadoWorkspace.QDy[13] + acadoWorkspace.evGx[53]*acadoWorkspace.QDy[14] + acadoWorkspace.evGx[59]*acadoWorkspace.QDy[15] + acadoWorkspace.evGx[65]*acadoWorkspace.QDy[16] + acadoWorkspace.evGx[71]*acadoWorkspace.QDy[17] + acadoWorkspace.evGx[77]*acadoWorkspace.QDy[18] + acadoWorkspace.evGx[83]*acadoWorkspace.QDy[19] + acadoWorkspace.evGx[89]*acadoWorkspace.QDy[20] + acadoWorkspace.evGx[95]*acadoWorkspace.QDy[21] + acadoWorkspace.evGx[101]*acadoWorkspace.QDy[22] + acadoWorkspace.evGx[107]*acadoWorkspace.QDy[23] + acadoWorkspace.evGx[113]*acadoWorkspace.QDy[24] + acadoWorkspace.evGx[119]*acadoWorkspace.QDy[25] + acadoWorkspace.evGx[125]*acadoWorkspace.QDy[26] + acadoWorkspace.evGx[131]*acadoWorkspace.QDy[27] + acadoWorkspace.evGx[137]*acadoWorkspace.QDy[28] + acadoWorkspace.evGx[143]*acadoWorkspace.QDy[29] + acadoWorkspace.evGx[149]*acadoWorkspace.QDy[30] + acadoWorkspace.evGx[155]*acadoWorkspace.QDy[31] + acadoWorkspace.evGx[161]*acadoWorkspace.QDy[32] + acadoWorkspace.evGx[167]*acadoWorkspace.QDy[33] + acadoWorkspace.evGx[173]*acadoWorkspace.QDy[34] + acadoWorkspace.evGx[179]*acadoWorkspace.QDy[35] + acadoWorkspace.evGx[185]*acadoWorkspace.QDy[36] + acadoWorkspace.evGx[191]*acadoWorkspace.QDy[37] + acadoWorkspace.evGx[197]*acadoWorkspace.QDy[38] + acadoWorkspace.evGx[203]*acadoWorkspace.QDy[39] + acadoWorkspace.evGx[209]*acadoWorkspace.QDy[40] + acadoWorkspace.evGx[215]*acadoWorkspace.QDy[41] + acadoWorkspace.evGx[221]*acadoWorkspace.QDy[42] + acadoWorkspace.evGx[227]*acadoWorkspace.QDy[43] + acadoWorkspace.evGx[233]*acadoWorkspace.QDy[44] + acadoWorkspace.evGx[239]*acadoWorkspace.QDy[45] + acadoWorkspace.evGx[245]*acadoWorkspace.QDy[46] + acadoWorkspace.evGx[251]*acadoWorkspace.QDy[47] + acadoWorkspace.evGx[257]*acadoWorkspace.QDy[48] + acadoWorkspace.evGx[263]*acadoWorkspace.QDy[49] + acadoWorkspace.evGx[269]*acadoWorkspace.QDy[50] + acadoWorkspace.evGx[275]*acadoWorkspace.QDy[51] + acadoWorkspace.evGx[281]*acadoWorkspace.QDy[52] + acadoWorkspace.evGx[287]*acadoWorkspace.QDy[53] + acadoWorkspace.evGx[293]*acadoWorkspace.QDy[54] + acadoWorkspace.evGx[299]*acadoWorkspace.QDy[55] + acadoWorkspace.evGx[305]*acadoWorkspace.QDy[56] + acadoWorkspace.evGx[311]*acadoWorkspace.QDy[57] + acadoWorkspace.evGx[317]*acadoWorkspace.QDy[58] + acadoWorkspace.evGx[323]*acadoWorkspace.QDy[59] + acadoWorkspace.evGx[329]*acadoWorkspace.QDy[60] + acadoWorkspace.evGx[335]*acadoWorkspace.QDy[61] + acadoWorkspace.evGx[341]*acadoWorkspace.QDy[62] + acadoWorkspace.evGx[347]*acadoWorkspace.QDy[63] + acadoWorkspace.evGx[353]*acadoWorkspace.QDy[64] + acadoWorkspace.evGx[359]*acadoWorkspace.QDy[65] + acadoWorkspace.evGx[365]*acadoWorkspace.QDy[66] + acadoWorkspace.evGx[371]*acadoWorkspace.QDy[67] + acadoWorkspace.evGx[377]*acadoWorkspace.QDy[68] + acadoWorkspace.evGx[383]*acadoWorkspace.QDy[69] + acadoWorkspace.evGx[389]*acadoWorkspace.QDy[70] + acadoWorkspace.evGx[395]*acadoWorkspace.QDy[71] + acadoWorkspace.evGx[401]*acadoWorkspace.QDy[72] + acadoWorkspace.evGx[407]*acadoWorkspace.QDy[73] + acadoWorkspace.evGx[413]*acadoWorkspace.QDy[74] + acadoWorkspace.evGx[419]*acadoWorkspace.QDy[75] + acadoWorkspace.evGx[425]*acadoWorkspace.QDy[76] + acadoWorkspace.evGx[431]*acadoWorkspace.QDy[77] + acadoWorkspace.evGx[437]*acadoWorkspace.QDy[78] + acadoWorkspace.evGx[443]*acadoWorkspace.QDy[79] + acadoWorkspace.evGx[449]*acadoWorkspace.QDy[80] + acadoWorkspace.evGx[455]*acadoWorkspace.QDy[81] + acadoWorkspace.evGx[461]*acadoWorkspace.QDy[82] + acadoWorkspace.evGx[467]*acadoWorkspace.QDy[83] + acadoWorkspace.evGx[473]*acadoWorkspace.QDy[84] + acadoWorkspace.evGx[479]*acadoWorkspace.QDy[85] + acadoWorkspace.evGx[485]*acadoWorkspace.QDy[86] + acadoWorkspace.evGx[491]*acadoWorkspace.QDy[87] + acadoWorkspace.evGx[497]*acadoWorkspace.QDy[88] + acadoWorkspace.evGx[503]*acadoWorkspace.QDy[89] + acadoWorkspace.evGx[509]*acadoWorkspace.QDy[90] + acadoWorkspace.evGx[515]*acadoWorkspace.QDy[91] + acadoWorkspace.evGx[521]*acadoWorkspace.QDy[92] + acadoWorkspace.evGx[527]*acadoWorkspace.QDy[93] + acadoWorkspace.evGx[533]*acadoWorkspace.QDy[94] + acadoWorkspace.evGx[539]*acadoWorkspace.QDy[95] + acadoWorkspace.evGx[545]*acadoWorkspace.QDy[96] + acadoWorkspace.evGx[551]*acadoWorkspace.QDy[97] + acadoWorkspace.evGx[557]*acadoWorkspace.QDy[98] + acadoWorkspace.evGx[563]*acadoWorkspace.QDy[99] + acadoWorkspace.evGx[569]*acadoWorkspace.QDy[100] + acadoWorkspace.evGx[575]*acadoWorkspace.QDy[101] + acadoWorkspace.evGx[581]*acadoWorkspace.QDy[102] + acadoWorkspace.evGx[587]*acadoWorkspace.QDy[103] + acadoWorkspace.evGx[593]*acadoWorkspace.QDy[104] + acadoWorkspace.evGx[599]*acadoWorkspace.QDy[105] + acadoWorkspace.evGx[605]*acadoWorkspace.QDy[106] + acadoWorkspace.evGx[611]*acadoWorkspace.QDy[107] + acadoWorkspace.evGx[617]*acadoWorkspace.QDy[108] + acadoWorkspace.evGx[623]*acadoWorkspace.QDy[109] + acadoWorkspace.evGx[629]*acadoWorkspace.QDy[110] + acadoWorkspace.evGx[635]*acadoWorkspace.QDy[111] + acadoWorkspace.evGx[641]*acadoWorkspace.QDy[112] + acadoWorkspace.evGx[647]*acadoWorkspace.QDy[113] + acadoWorkspace.evGx[653]*acadoWorkspace.QDy[114] + acadoWorkspace.evGx[659]*acadoWorkspace.QDy[115] + acadoWorkspace.evGx[665]*acadoWorkspace.QDy[116] + acadoWorkspace.evGx[671]*acadoWorkspace.QDy[117] + acadoWorkspace.evGx[677]*acadoWorkspace.QDy[118] + acadoWorkspace.evGx[683]*acadoWorkspace.QDy[119] + acadoWorkspace.evGx[689]*acadoWorkspace.QDy[120] + acadoWorkspace.evGx[695]*acadoWorkspace.QDy[121] + acadoWorkspace.evGx[701]*acadoWorkspace.QDy[122] + acadoWorkspace.evGx[707]*acadoWorkspace.QDy[123] + acadoWorkspace.evGx[713]*acadoWorkspace.QDy[124] + acadoWorkspace.evGx[719]*acadoWorkspace.QDy[125]; + + +acado_multEQDy( acadoWorkspace.E, &(acadoWorkspace.QDy[ 6 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 6 ]), &(acadoWorkspace.QDy[ 12 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 18 ]), &(acadoWorkspace.QDy[ 18 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 36 ]), &(acadoWorkspace.QDy[ 24 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 60 ]), &(acadoWorkspace.QDy[ 30 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 90 ]), &(acadoWorkspace.QDy[ 36 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 126 ]), &(acadoWorkspace.QDy[ 42 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 168 ]), &(acadoWorkspace.QDy[ 48 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 216 ]), &(acadoWorkspace.QDy[ 54 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 270 ]), &(acadoWorkspace.QDy[ 60 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 330 ]), &(acadoWorkspace.QDy[ 66 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 396 ]), &(acadoWorkspace.QDy[ 72 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 468 ]), &(acadoWorkspace.QDy[ 78 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 546 ]), &(acadoWorkspace.QDy[ 84 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 630 ]), &(acadoWorkspace.QDy[ 90 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 720 ]), &(acadoWorkspace.QDy[ 96 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 816 ]), &(acadoWorkspace.QDy[ 102 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 918 ]), &(acadoWorkspace.QDy[ 108 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 1026 ]), &(acadoWorkspace.QDy[ 114 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 1140 ]), &(acadoWorkspace.QDy[ 120 ]), &(acadoWorkspace.g[ 6 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 12 ]), &(acadoWorkspace.QDy[ 12 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 24 ]), &(acadoWorkspace.QDy[ 18 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 42 ]), &(acadoWorkspace.QDy[ 24 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 66 ]), &(acadoWorkspace.QDy[ 30 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 96 ]), &(acadoWorkspace.QDy[ 36 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 132 ]), &(acadoWorkspace.QDy[ 42 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 174 ]), &(acadoWorkspace.QDy[ 48 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 222 ]), &(acadoWorkspace.QDy[ 54 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 276 ]), &(acadoWorkspace.QDy[ 60 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 336 ]), &(acadoWorkspace.QDy[ 66 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 402 ]), &(acadoWorkspace.QDy[ 72 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 474 ]), &(acadoWorkspace.QDy[ 78 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 552 ]), &(acadoWorkspace.QDy[ 84 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 636 ]), &(acadoWorkspace.QDy[ 90 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 726 ]), &(acadoWorkspace.QDy[ 96 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 822 ]), &(acadoWorkspace.QDy[ 102 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 924 ]), &(acadoWorkspace.QDy[ 108 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 1032 ]), &(acadoWorkspace.QDy[ 114 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 1146 ]), &(acadoWorkspace.QDy[ 120 ]), &(acadoWorkspace.g[ 7 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 30 ]), &(acadoWorkspace.QDy[ 18 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 48 ]), &(acadoWorkspace.QDy[ 24 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 72 ]), &(acadoWorkspace.QDy[ 30 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 102 ]), &(acadoWorkspace.QDy[ 36 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 138 ]), &(acadoWorkspace.QDy[ 42 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 180 ]), &(acadoWorkspace.QDy[ 48 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 228 ]), &(acadoWorkspace.QDy[ 54 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 282 ]), &(acadoWorkspace.QDy[ 60 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 342 ]), &(acadoWorkspace.QDy[ 66 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 408 ]), &(acadoWorkspace.QDy[ 72 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 480 ]), &(acadoWorkspace.QDy[ 78 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 558 ]), &(acadoWorkspace.QDy[ 84 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 642 ]), &(acadoWorkspace.QDy[ 90 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 732 ]), &(acadoWorkspace.QDy[ 96 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 828 ]), &(acadoWorkspace.QDy[ 102 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 930 ]), &(acadoWorkspace.QDy[ 108 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 1038 ]), &(acadoWorkspace.QDy[ 114 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 1152 ]), &(acadoWorkspace.QDy[ 120 ]), &(acadoWorkspace.g[ 8 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 54 ]), &(acadoWorkspace.QDy[ 24 ]), &(acadoWorkspace.g[ 9 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 78 ]), &(acadoWorkspace.QDy[ 30 ]), &(acadoWorkspace.g[ 9 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 108 ]), &(acadoWorkspace.QDy[ 36 ]), &(acadoWorkspace.g[ 9 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 144 ]), &(acadoWorkspace.QDy[ 42 ]), &(acadoWorkspace.g[ 9 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 186 ]), &(acadoWorkspace.QDy[ 48 ]), &(acadoWorkspace.g[ 9 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 234 ]), &(acadoWorkspace.QDy[ 54 ]), &(acadoWorkspace.g[ 9 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 288 ]), &(acadoWorkspace.QDy[ 60 ]), &(acadoWorkspace.g[ 9 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 348 ]), &(acadoWorkspace.QDy[ 66 ]), &(acadoWorkspace.g[ 9 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 414 ]), &(acadoWorkspace.QDy[ 72 ]), &(acadoWorkspace.g[ 9 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 486 ]), &(acadoWorkspace.QDy[ 78 ]), &(acadoWorkspace.g[ 9 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 564 ]), &(acadoWorkspace.QDy[ 84 ]), &(acadoWorkspace.g[ 9 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 648 ]), &(acadoWorkspace.QDy[ 90 ]), &(acadoWorkspace.g[ 9 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 738 ]), &(acadoWorkspace.QDy[ 96 ]), &(acadoWorkspace.g[ 9 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 834 ]), &(acadoWorkspace.QDy[ 102 ]), &(acadoWorkspace.g[ 9 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 936 ]), &(acadoWorkspace.QDy[ 108 ]), &(acadoWorkspace.g[ 9 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 1044 ]), &(acadoWorkspace.QDy[ 114 ]), &(acadoWorkspace.g[ 9 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 1158 ]), &(acadoWorkspace.QDy[ 120 ]), &(acadoWorkspace.g[ 9 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 84 ]), &(acadoWorkspace.QDy[ 30 ]), &(acadoWorkspace.g[ 10 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 114 ]), &(acadoWorkspace.QDy[ 36 ]), &(acadoWorkspace.g[ 10 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 150 ]), &(acadoWorkspace.QDy[ 42 ]), &(acadoWorkspace.g[ 10 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 192 ]), &(acadoWorkspace.QDy[ 48 ]), &(acadoWorkspace.g[ 10 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 240 ]), &(acadoWorkspace.QDy[ 54 ]), &(acadoWorkspace.g[ 10 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 294 ]), &(acadoWorkspace.QDy[ 60 ]), &(acadoWorkspace.g[ 10 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 354 ]), &(acadoWorkspace.QDy[ 66 ]), &(acadoWorkspace.g[ 10 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 420 ]), &(acadoWorkspace.QDy[ 72 ]), &(acadoWorkspace.g[ 10 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 492 ]), &(acadoWorkspace.QDy[ 78 ]), &(acadoWorkspace.g[ 10 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 570 ]), &(acadoWorkspace.QDy[ 84 ]), &(acadoWorkspace.g[ 10 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 654 ]), &(acadoWorkspace.QDy[ 90 ]), &(acadoWorkspace.g[ 10 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 744 ]), &(acadoWorkspace.QDy[ 96 ]), &(acadoWorkspace.g[ 10 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 840 ]), &(acadoWorkspace.QDy[ 102 ]), &(acadoWorkspace.g[ 10 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 942 ]), &(acadoWorkspace.QDy[ 108 ]), &(acadoWorkspace.g[ 10 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 1050 ]), &(acadoWorkspace.QDy[ 114 ]), &(acadoWorkspace.g[ 10 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 1164 ]), &(acadoWorkspace.QDy[ 120 ]), &(acadoWorkspace.g[ 10 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 120 ]), &(acadoWorkspace.QDy[ 36 ]), &(acadoWorkspace.g[ 11 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 156 ]), &(acadoWorkspace.QDy[ 42 ]), &(acadoWorkspace.g[ 11 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 198 ]), &(acadoWorkspace.QDy[ 48 ]), &(acadoWorkspace.g[ 11 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 246 ]), &(acadoWorkspace.QDy[ 54 ]), &(acadoWorkspace.g[ 11 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 300 ]), &(acadoWorkspace.QDy[ 60 ]), &(acadoWorkspace.g[ 11 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 360 ]), &(acadoWorkspace.QDy[ 66 ]), &(acadoWorkspace.g[ 11 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 426 ]), &(acadoWorkspace.QDy[ 72 ]), &(acadoWorkspace.g[ 11 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 498 ]), &(acadoWorkspace.QDy[ 78 ]), &(acadoWorkspace.g[ 11 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 576 ]), &(acadoWorkspace.QDy[ 84 ]), &(acadoWorkspace.g[ 11 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 660 ]), &(acadoWorkspace.QDy[ 90 ]), &(acadoWorkspace.g[ 11 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 750 ]), &(acadoWorkspace.QDy[ 96 ]), &(acadoWorkspace.g[ 11 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 846 ]), &(acadoWorkspace.QDy[ 102 ]), &(acadoWorkspace.g[ 11 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 948 ]), &(acadoWorkspace.QDy[ 108 ]), &(acadoWorkspace.g[ 11 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 1056 ]), &(acadoWorkspace.QDy[ 114 ]), &(acadoWorkspace.g[ 11 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 1170 ]), &(acadoWorkspace.QDy[ 120 ]), &(acadoWorkspace.g[ 11 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 162 ]), &(acadoWorkspace.QDy[ 42 ]), &(acadoWorkspace.g[ 12 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 204 ]), &(acadoWorkspace.QDy[ 48 ]), &(acadoWorkspace.g[ 12 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 252 ]), &(acadoWorkspace.QDy[ 54 ]), &(acadoWorkspace.g[ 12 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 306 ]), &(acadoWorkspace.QDy[ 60 ]), &(acadoWorkspace.g[ 12 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 366 ]), &(acadoWorkspace.QDy[ 66 ]), &(acadoWorkspace.g[ 12 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 432 ]), &(acadoWorkspace.QDy[ 72 ]), &(acadoWorkspace.g[ 12 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 504 ]), &(acadoWorkspace.QDy[ 78 ]), &(acadoWorkspace.g[ 12 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 582 ]), &(acadoWorkspace.QDy[ 84 ]), &(acadoWorkspace.g[ 12 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 666 ]), &(acadoWorkspace.QDy[ 90 ]), &(acadoWorkspace.g[ 12 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 756 ]), &(acadoWorkspace.QDy[ 96 ]), &(acadoWorkspace.g[ 12 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 852 ]), &(acadoWorkspace.QDy[ 102 ]), &(acadoWorkspace.g[ 12 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 954 ]), &(acadoWorkspace.QDy[ 108 ]), &(acadoWorkspace.g[ 12 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 1062 ]), &(acadoWorkspace.QDy[ 114 ]), &(acadoWorkspace.g[ 12 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 1176 ]), &(acadoWorkspace.QDy[ 120 ]), &(acadoWorkspace.g[ 12 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 210 ]), &(acadoWorkspace.QDy[ 48 ]), &(acadoWorkspace.g[ 13 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 258 ]), &(acadoWorkspace.QDy[ 54 ]), &(acadoWorkspace.g[ 13 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 312 ]), &(acadoWorkspace.QDy[ 60 ]), &(acadoWorkspace.g[ 13 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 372 ]), &(acadoWorkspace.QDy[ 66 ]), &(acadoWorkspace.g[ 13 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 438 ]), &(acadoWorkspace.QDy[ 72 ]), &(acadoWorkspace.g[ 13 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 510 ]), &(acadoWorkspace.QDy[ 78 ]), &(acadoWorkspace.g[ 13 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 588 ]), &(acadoWorkspace.QDy[ 84 ]), &(acadoWorkspace.g[ 13 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 672 ]), &(acadoWorkspace.QDy[ 90 ]), &(acadoWorkspace.g[ 13 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 762 ]), &(acadoWorkspace.QDy[ 96 ]), &(acadoWorkspace.g[ 13 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 858 ]), &(acadoWorkspace.QDy[ 102 ]), &(acadoWorkspace.g[ 13 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 960 ]), &(acadoWorkspace.QDy[ 108 ]), &(acadoWorkspace.g[ 13 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 1068 ]), &(acadoWorkspace.QDy[ 114 ]), &(acadoWorkspace.g[ 13 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 1182 ]), &(acadoWorkspace.QDy[ 120 ]), &(acadoWorkspace.g[ 13 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 264 ]), &(acadoWorkspace.QDy[ 54 ]), &(acadoWorkspace.g[ 14 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 318 ]), &(acadoWorkspace.QDy[ 60 ]), &(acadoWorkspace.g[ 14 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 378 ]), &(acadoWorkspace.QDy[ 66 ]), &(acadoWorkspace.g[ 14 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 444 ]), &(acadoWorkspace.QDy[ 72 ]), &(acadoWorkspace.g[ 14 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 516 ]), &(acadoWorkspace.QDy[ 78 ]), &(acadoWorkspace.g[ 14 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 594 ]), &(acadoWorkspace.QDy[ 84 ]), &(acadoWorkspace.g[ 14 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 678 ]), &(acadoWorkspace.QDy[ 90 ]), &(acadoWorkspace.g[ 14 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 768 ]), &(acadoWorkspace.QDy[ 96 ]), &(acadoWorkspace.g[ 14 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 864 ]), &(acadoWorkspace.QDy[ 102 ]), &(acadoWorkspace.g[ 14 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 966 ]), &(acadoWorkspace.QDy[ 108 ]), &(acadoWorkspace.g[ 14 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 1074 ]), &(acadoWorkspace.QDy[ 114 ]), &(acadoWorkspace.g[ 14 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 1188 ]), &(acadoWorkspace.QDy[ 120 ]), &(acadoWorkspace.g[ 14 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 324 ]), &(acadoWorkspace.QDy[ 60 ]), &(acadoWorkspace.g[ 15 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 384 ]), &(acadoWorkspace.QDy[ 66 ]), &(acadoWorkspace.g[ 15 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 450 ]), &(acadoWorkspace.QDy[ 72 ]), &(acadoWorkspace.g[ 15 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 522 ]), &(acadoWorkspace.QDy[ 78 ]), &(acadoWorkspace.g[ 15 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 600 ]), &(acadoWorkspace.QDy[ 84 ]), &(acadoWorkspace.g[ 15 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 684 ]), &(acadoWorkspace.QDy[ 90 ]), &(acadoWorkspace.g[ 15 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 774 ]), &(acadoWorkspace.QDy[ 96 ]), &(acadoWorkspace.g[ 15 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 870 ]), &(acadoWorkspace.QDy[ 102 ]), &(acadoWorkspace.g[ 15 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 972 ]), &(acadoWorkspace.QDy[ 108 ]), &(acadoWorkspace.g[ 15 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 1080 ]), &(acadoWorkspace.QDy[ 114 ]), &(acadoWorkspace.g[ 15 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 1194 ]), &(acadoWorkspace.QDy[ 120 ]), &(acadoWorkspace.g[ 15 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 390 ]), &(acadoWorkspace.QDy[ 66 ]), &(acadoWorkspace.g[ 16 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 456 ]), &(acadoWorkspace.QDy[ 72 ]), &(acadoWorkspace.g[ 16 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 528 ]), &(acadoWorkspace.QDy[ 78 ]), &(acadoWorkspace.g[ 16 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 606 ]), &(acadoWorkspace.QDy[ 84 ]), &(acadoWorkspace.g[ 16 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 690 ]), &(acadoWorkspace.QDy[ 90 ]), &(acadoWorkspace.g[ 16 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 780 ]), &(acadoWorkspace.QDy[ 96 ]), &(acadoWorkspace.g[ 16 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 876 ]), &(acadoWorkspace.QDy[ 102 ]), &(acadoWorkspace.g[ 16 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 978 ]), &(acadoWorkspace.QDy[ 108 ]), &(acadoWorkspace.g[ 16 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 1086 ]), &(acadoWorkspace.QDy[ 114 ]), &(acadoWorkspace.g[ 16 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 1200 ]), &(acadoWorkspace.QDy[ 120 ]), &(acadoWorkspace.g[ 16 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 462 ]), &(acadoWorkspace.QDy[ 72 ]), &(acadoWorkspace.g[ 17 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 534 ]), &(acadoWorkspace.QDy[ 78 ]), &(acadoWorkspace.g[ 17 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 612 ]), &(acadoWorkspace.QDy[ 84 ]), &(acadoWorkspace.g[ 17 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 696 ]), &(acadoWorkspace.QDy[ 90 ]), &(acadoWorkspace.g[ 17 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 786 ]), &(acadoWorkspace.QDy[ 96 ]), &(acadoWorkspace.g[ 17 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 882 ]), &(acadoWorkspace.QDy[ 102 ]), &(acadoWorkspace.g[ 17 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 984 ]), &(acadoWorkspace.QDy[ 108 ]), &(acadoWorkspace.g[ 17 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 1092 ]), &(acadoWorkspace.QDy[ 114 ]), &(acadoWorkspace.g[ 17 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 1206 ]), &(acadoWorkspace.QDy[ 120 ]), &(acadoWorkspace.g[ 17 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 540 ]), &(acadoWorkspace.QDy[ 78 ]), &(acadoWorkspace.g[ 18 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 618 ]), &(acadoWorkspace.QDy[ 84 ]), &(acadoWorkspace.g[ 18 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 702 ]), &(acadoWorkspace.QDy[ 90 ]), &(acadoWorkspace.g[ 18 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 792 ]), &(acadoWorkspace.QDy[ 96 ]), &(acadoWorkspace.g[ 18 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 888 ]), &(acadoWorkspace.QDy[ 102 ]), &(acadoWorkspace.g[ 18 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 990 ]), &(acadoWorkspace.QDy[ 108 ]), &(acadoWorkspace.g[ 18 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 1098 ]), &(acadoWorkspace.QDy[ 114 ]), &(acadoWorkspace.g[ 18 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 1212 ]), &(acadoWorkspace.QDy[ 120 ]), &(acadoWorkspace.g[ 18 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 624 ]), &(acadoWorkspace.QDy[ 84 ]), &(acadoWorkspace.g[ 19 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 708 ]), &(acadoWorkspace.QDy[ 90 ]), &(acadoWorkspace.g[ 19 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 798 ]), &(acadoWorkspace.QDy[ 96 ]), &(acadoWorkspace.g[ 19 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 894 ]), &(acadoWorkspace.QDy[ 102 ]), &(acadoWorkspace.g[ 19 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 996 ]), &(acadoWorkspace.QDy[ 108 ]), &(acadoWorkspace.g[ 19 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 1104 ]), &(acadoWorkspace.QDy[ 114 ]), &(acadoWorkspace.g[ 19 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 1218 ]), &(acadoWorkspace.QDy[ 120 ]), &(acadoWorkspace.g[ 19 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 714 ]), &(acadoWorkspace.QDy[ 90 ]), &(acadoWorkspace.g[ 20 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 804 ]), &(acadoWorkspace.QDy[ 96 ]), &(acadoWorkspace.g[ 20 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 900 ]), &(acadoWorkspace.QDy[ 102 ]), &(acadoWorkspace.g[ 20 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 1002 ]), &(acadoWorkspace.QDy[ 108 ]), &(acadoWorkspace.g[ 20 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 1110 ]), &(acadoWorkspace.QDy[ 114 ]), &(acadoWorkspace.g[ 20 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 1224 ]), &(acadoWorkspace.QDy[ 120 ]), &(acadoWorkspace.g[ 20 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 810 ]), &(acadoWorkspace.QDy[ 96 ]), &(acadoWorkspace.g[ 21 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 906 ]), &(acadoWorkspace.QDy[ 102 ]), &(acadoWorkspace.g[ 21 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 1008 ]), &(acadoWorkspace.QDy[ 108 ]), &(acadoWorkspace.g[ 21 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 1116 ]), &(acadoWorkspace.QDy[ 114 ]), &(acadoWorkspace.g[ 21 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 1230 ]), &(acadoWorkspace.QDy[ 120 ]), &(acadoWorkspace.g[ 21 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 912 ]), &(acadoWorkspace.QDy[ 102 ]), &(acadoWorkspace.g[ 22 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 1014 ]), &(acadoWorkspace.QDy[ 108 ]), &(acadoWorkspace.g[ 22 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 1122 ]), &(acadoWorkspace.QDy[ 114 ]), &(acadoWorkspace.g[ 22 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 1236 ]), &(acadoWorkspace.QDy[ 120 ]), &(acadoWorkspace.g[ 22 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 1020 ]), &(acadoWorkspace.QDy[ 108 ]), &(acadoWorkspace.g[ 23 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 1128 ]), &(acadoWorkspace.QDy[ 114 ]), &(acadoWorkspace.g[ 23 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 1242 ]), &(acadoWorkspace.QDy[ 120 ]), &(acadoWorkspace.g[ 23 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 1134 ]), &(acadoWorkspace.QDy[ 114 ]), &(acadoWorkspace.g[ 24 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 1248 ]), &(acadoWorkspace.QDy[ 120 ]), &(acadoWorkspace.g[ 24 ]) ); +acado_multEQDy( &(acadoWorkspace.E[ 1254 ]), &(acadoWorkspace.QDy[ 120 ]), &(acadoWorkspace.g[ 25 ]) ); + +acadoWorkspace.lb[0] = acadoWorkspace.Dx0[0]; +acadoWorkspace.lb[1] = acadoWorkspace.Dx0[1]; +acadoWorkspace.lb[2] = acadoWorkspace.Dx0[2]; +acadoWorkspace.lb[3] = acadoWorkspace.Dx0[3]; +acadoWorkspace.lb[4] = acadoWorkspace.Dx0[4]; +acadoWorkspace.lb[5] = acadoWorkspace.Dx0[5]; +acadoWorkspace.ub[0] = acadoWorkspace.Dx0[0]; +acadoWorkspace.ub[1] = acadoWorkspace.Dx0[1]; +acadoWorkspace.ub[2] = acadoWorkspace.Dx0[2]; +acadoWorkspace.ub[3] = acadoWorkspace.Dx0[3]; +acadoWorkspace.ub[4] = acadoWorkspace.Dx0[4]; +acadoWorkspace.ub[5] = acadoWorkspace.Dx0[5]; +tmp = acadoVariables.x[7] + acadoWorkspace.d[1]; +acadoWorkspace.lbA[0] = - tmp; +acadoWorkspace.ubA[0] = (real_t)1.0000000000000000e+12 - tmp; +tmp = acadoVariables.x[13] + acadoWorkspace.d[7]; +acadoWorkspace.lbA[1] = - tmp; +acadoWorkspace.ubA[1] = (real_t)1.0000000000000000e+12 - tmp; +tmp = acadoVariables.x[19] + acadoWorkspace.d[13]; +acadoWorkspace.lbA[2] = - tmp; +acadoWorkspace.ubA[2] = (real_t)1.0000000000000000e+12 - tmp; +tmp = acadoVariables.x[25] + acadoWorkspace.d[19]; +acadoWorkspace.lbA[3] = - tmp; +acadoWorkspace.ubA[3] = (real_t)1.0000000000000000e+12 - tmp; +tmp = acadoVariables.x[31] + acadoWorkspace.d[25]; +acadoWorkspace.lbA[4] = - tmp; +acadoWorkspace.ubA[4] = (real_t)1.0000000000000000e+12 - tmp; +tmp = acadoVariables.x[37] + acadoWorkspace.d[31]; +acadoWorkspace.lbA[5] = - tmp; +acadoWorkspace.ubA[5] = (real_t)1.0000000000000000e+12 - tmp; +tmp = acadoVariables.x[43] + acadoWorkspace.d[37]; +acadoWorkspace.lbA[6] = - tmp; +acadoWorkspace.ubA[6] = (real_t)1.0000000000000000e+12 - tmp; +tmp = acadoVariables.x[49] + acadoWorkspace.d[43]; +acadoWorkspace.lbA[7] = - tmp; +acadoWorkspace.ubA[7] = (real_t)1.0000000000000000e+12 - tmp; +tmp = acadoVariables.x[55] + acadoWorkspace.d[49]; +acadoWorkspace.lbA[8] = - tmp; +acadoWorkspace.ubA[8] = (real_t)1.0000000000000000e+12 - tmp; +tmp = acadoVariables.x[61] + acadoWorkspace.d[55]; +acadoWorkspace.lbA[9] = - tmp; +acadoWorkspace.ubA[9] = (real_t)1.0000000000000000e+12 - tmp; +tmp = acadoVariables.x[67] + acadoWorkspace.d[61]; +acadoWorkspace.lbA[10] = - tmp; +acadoWorkspace.ubA[10] = (real_t)1.0000000000000000e+12 - tmp; +tmp = acadoVariables.x[73] + acadoWorkspace.d[67]; +acadoWorkspace.lbA[11] = - tmp; +acadoWorkspace.ubA[11] = (real_t)1.0000000000000000e+12 - tmp; +tmp = acadoVariables.x[79] + acadoWorkspace.d[73]; +acadoWorkspace.lbA[12] = - tmp; +acadoWorkspace.ubA[12] = (real_t)1.0000000000000000e+12 - tmp; +tmp = acadoVariables.x[85] + acadoWorkspace.d[79]; +acadoWorkspace.lbA[13] = - tmp; +acadoWorkspace.ubA[13] = (real_t)1.0000000000000000e+12 - tmp; +tmp = acadoVariables.x[91] + acadoWorkspace.d[85]; +acadoWorkspace.lbA[14] = - tmp; +acadoWorkspace.ubA[14] = (real_t)1.0000000000000000e+12 - tmp; +tmp = acadoVariables.x[97] + acadoWorkspace.d[91]; +acadoWorkspace.lbA[15] = - tmp; +acadoWorkspace.ubA[15] = (real_t)1.0000000000000000e+12 - tmp; +tmp = acadoVariables.x[103] + acadoWorkspace.d[97]; +acadoWorkspace.lbA[16] = - tmp; +acadoWorkspace.ubA[16] = (real_t)1.0000000000000000e+12 - tmp; +tmp = acadoVariables.x[109] + acadoWorkspace.d[103]; +acadoWorkspace.lbA[17] = - tmp; +acadoWorkspace.ubA[17] = (real_t)1.0000000000000000e+12 - tmp; +tmp = acadoVariables.x[115] + acadoWorkspace.d[109]; +acadoWorkspace.lbA[18] = - tmp; +acadoWorkspace.ubA[18] = (real_t)1.0000000000000000e+12 - tmp; +tmp = acadoVariables.x[121] + acadoWorkspace.d[115]; +acadoWorkspace.lbA[19] = - tmp; +acadoWorkspace.ubA[19] = (real_t)1.0000000000000000e+12 - tmp; + +} + +void acado_expand( ) +{ +acadoVariables.x[0] += acadoWorkspace.x[0]; +acadoVariables.x[1] += acadoWorkspace.x[1]; +acadoVariables.x[2] += acadoWorkspace.x[2]; +acadoVariables.x[3] += acadoWorkspace.x[3]; +acadoVariables.x[4] += acadoWorkspace.x[4]; +acadoVariables.x[5] += acadoWorkspace.x[5]; + +acadoVariables.u[0] += acadoWorkspace.x[6]; +acadoVariables.u[1] += acadoWorkspace.x[7]; +acadoVariables.u[2] += acadoWorkspace.x[8]; +acadoVariables.u[3] += acadoWorkspace.x[9]; +acadoVariables.u[4] += acadoWorkspace.x[10]; +acadoVariables.u[5] += acadoWorkspace.x[11]; +acadoVariables.u[6] += acadoWorkspace.x[12]; +acadoVariables.u[7] += acadoWorkspace.x[13]; +acadoVariables.u[8] += acadoWorkspace.x[14]; +acadoVariables.u[9] += acadoWorkspace.x[15]; +acadoVariables.u[10] += acadoWorkspace.x[16]; +acadoVariables.u[11] += acadoWorkspace.x[17]; +acadoVariables.u[12] += acadoWorkspace.x[18]; +acadoVariables.u[13] += acadoWorkspace.x[19]; +acadoVariables.u[14] += acadoWorkspace.x[20]; +acadoVariables.u[15] += acadoWorkspace.x[21]; +acadoVariables.u[16] += acadoWorkspace.x[22]; +acadoVariables.u[17] += acadoWorkspace.x[23]; +acadoVariables.u[18] += acadoWorkspace.x[24]; +acadoVariables.u[19] += acadoWorkspace.x[25]; + +acadoVariables.x[6] += + acadoWorkspace.evGx[0]*acadoWorkspace.x[0] + acadoWorkspace.evGx[1]*acadoWorkspace.x[1] + acadoWorkspace.evGx[2]*acadoWorkspace.x[2] + acadoWorkspace.evGx[3]*acadoWorkspace.x[3] + acadoWorkspace.evGx[4]*acadoWorkspace.x[4] + acadoWorkspace.evGx[5]*acadoWorkspace.x[5] + acadoWorkspace.d[0]; +acadoVariables.x[7] += + acadoWorkspace.evGx[6]*acadoWorkspace.x[0] + acadoWorkspace.evGx[7]*acadoWorkspace.x[1] + acadoWorkspace.evGx[8]*acadoWorkspace.x[2] + acadoWorkspace.evGx[9]*acadoWorkspace.x[3] + acadoWorkspace.evGx[10]*acadoWorkspace.x[4] + acadoWorkspace.evGx[11]*acadoWorkspace.x[5] + acadoWorkspace.d[1]; +acadoVariables.x[8] += + acadoWorkspace.evGx[12]*acadoWorkspace.x[0] + acadoWorkspace.evGx[13]*acadoWorkspace.x[1] + acadoWorkspace.evGx[14]*acadoWorkspace.x[2] + acadoWorkspace.evGx[15]*acadoWorkspace.x[3] + acadoWorkspace.evGx[16]*acadoWorkspace.x[4] + acadoWorkspace.evGx[17]*acadoWorkspace.x[5] + acadoWorkspace.d[2]; +acadoVariables.x[9] += + acadoWorkspace.evGx[18]*acadoWorkspace.x[0] + acadoWorkspace.evGx[19]*acadoWorkspace.x[1] + acadoWorkspace.evGx[20]*acadoWorkspace.x[2] + acadoWorkspace.evGx[21]*acadoWorkspace.x[3] + acadoWorkspace.evGx[22]*acadoWorkspace.x[4] + acadoWorkspace.evGx[23]*acadoWorkspace.x[5] + acadoWorkspace.d[3]; +acadoVariables.x[10] += + acadoWorkspace.evGx[24]*acadoWorkspace.x[0] + acadoWorkspace.evGx[25]*acadoWorkspace.x[1] + acadoWorkspace.evGx[26]*acadoWorkspace.x[2] + acadoWorkspace.evGx[27]*acadoWorkspace.x[3] + acadoWorkspace.evGx[28]*acadoWorkspace.x[4] + acadoWorkspace.evGx[29]*acadoWorkspace.x[5] + acadoWorkspace.d[4]; +acadoVariables.x[11] += + acadoWorkspace.evGx[30]*acadoWorkspace.x[0] + acadoWorkspace.evGx[31]*acadoWorkspace.x[1] + acadoWorkspace.evGx[32]*acadoWorkspace.x[2] + acadoWorkspace.evGx[33]*acadoWorkspace.x[3] + acadoWorkspace.evGx[34]*acadoWorkspace.x[4] + acadoWorkspace.evGx[35]*acadoWorkspace.x[5] + acadoWorkspace.d[5]; +acadoVariables.x[12] += + acadoWorkspace.evGx[36]*acadoWorkspace.x[0] + acadoWorkspace.evGx[37]*acadoWorkspace.x[1] + acadoWorkspace.evGx[38]*acadoWorkspace.x[2] + acadoWorkspace.evGx[39]*acadoWorkspace.x[3] + acadoWorkspace.evGx[40]*acadoWorkspace.x[4] + acadoWorkspace.evGx[41]*acadoWorkspace.x[5] + acadoWorkspace.d[6]; +acadoVariables.x[13] += + acadoWorkspace.evGx[42]*acadoWorkspace.x[0] + acadoWorkspace.evGx[43]*acadoWorkspace.x[1] + acadoWorkspace.evGx[44]*acadoWorkspace.x[2] + acadoWorkspace.evGx[45]*acadoWorkspace.x[3] + acadoWorkspace.evGx[46]*acadoWorkspace.x[4] + acadoWorkspace.evGx[47]*acadoWorkspace.x[5] + acadoWorkspace.d[7]; +acadoVariables.x[14] += + acadoWorkspace.evGx[48]*acadoWorkspace.x[0] + acadoWorkspace.evGx[49]*acadoWorkspace.x[1] + acadoWorkspace.evGx[50]*acadoWorkspace.x[2] + acadoWorkspace.evGx[51]*acadoWorkspace.x[3] + acadoWorkspace.evGx[52]*acadoWorkspace.x[4] + acadoWorkspace.evGx[53]*acadoWorkspace.x[5] + acadoWorkspace.d[8]; +acadoVariables.x[15] += + acadoWorkspace.evGx[54]*acadoWorkspace.x[0] + acadoWorkspace.evGx[55]*acadoWorkspace.x[1] + acadoWorkspace.evGx[56]*acadoWorkspace.x[2] + acadoWorkspace.evGx[57]*acadoWorkspace.x[3] + acadoWorkspace.evGx[58]*acadoWorkspace.x[4] + acadoWorkspace.evGx[59]*acadoWorkspace.x[5] + acadoWorkspace.d[9]; +acadoVariables.x[16] += + acadoWorkspace.evGx[60]*acadoWorkspace.x[0] + acadoWorkspace.evGx[61]*acadoWorkspace.x[1] + acadoWorkspace.evGx[62]*acadoWorkspace.x[2] + acadoWorkspace.evGx[63]*acadoWorkspace.x[3] + acadoWorkspace.evGx[64]*acadoWorkspace.x[4] + acadoWorkspace.evGx[65]*acadoWorkspace.x[5] + acadoWorkspace.d[10]; +acadoVariables.x[17] += + acadoWorkspace.evGx[66]*acadoWorkspace.x[0] + acadoWorkspace.evGx[67]*acadoWorkspace.x[1] + acadoWorkspace.evGx[68]*acadoWorkspace.x[2] + acadoWorkspace.evGx[69]*acadoWorkspace.x[3] + acadoWorkspace.evGx[70]*acadoWorkspace.x[4] + acadoWorkspace.evGx[71]*acadoWorkspace.x[5] + acadoWorkspace.d[11]; +acadoVariables.x[18] += + acadoWorkspace.evGx[72]*acadoWorkspace.x[0] + acadoWorkspace.evGx[73]*acadoWorkspace.x[1] + acadoWorkspace.evGx[74]*acadoWorkspace.x[2] + acadoWorkspace.evGx[75]*acadoWorkspace.x[3] + acadoWorkspace.evGx[76]*acadoWorkspace.x[4] + acadoWorkspace.evGx[77]*acadoWorkspace.x[5] + acadoWorkspace.d[12]; +acadoVariables.x[19] += + acadoWorkspace.evGx[78]*acadoWorkspace.x[0] + acadoWorkspace.evGx[79]*acadoWorkspace.x[1] + acadoWorkspace.evGx[80]*acadoWorkspace.x[2] + acadoWorkspace.evGx[81]*acadoWorkspace.x[3] + acadoWorkspace.evGx[82]*acadoWorkspace.x[4] + acadoWorkspace.evGx[83]*acadoWorkspace.x[5] + acadoWorkspace.d[13]; +acadoVariables.x[20] += + acadoWorkspace.evGx[84]*acadoWorkspace.x[0] + acadoWorkspace.evGx[85]*acadoWorkspace.x[1] + acadoWorkspace.evGx[86]*acadoWorkspace.x[2] + acadoWorkspace.evGx[87]*acadoWorkspace.x[3] + acadoWorkspace.evGx[88]*acadoWorkspace.x[4] + acadoWorkspace.evGx[89]*acadoWorkspace.x[5] + acadoWorkspace.d[14]; +acadoVariables.x[21] += + acadoWorkspace.evGx[90]*acadoWorkspace.x[0] + acadoWorkspace.evGx[91]*acadoWorkspace.x[1] + acadoWorkspace.evGx[92]*acadoWorkspace.x[2] + acadoWorkspace.evGx[93]*acadoWorkspace.x[3] + acadoWorkspace.evGx[94]*acadoWorkspace.x[4] + acadoWorkspace.evGx[95]*acadoWorkspace.x[5] + acadoWorkspace.d[15]; +acadoVariables.x[22] += + acadoWorkspace.evGx[96]*acadoWorkspace.x[0] + acadoWorkspace.evGx[97]*acadoWorkspace.x[1] + acadoWorkspace.evGx[98]*acadoWorkspace.x[2] + acadoWorkspace.evGx[99]*acadoWorkspace.x[3] + acadoWorkspace.evGx[100]*acadoWorkspace.x[4] + acadoWorkspace.evGx[101]*acadoWorkspace.x[5] + acadoWorkspace.d[16]; +acadoVariables.x[23] += + acadoWorkspace.evGx[102]*acadoWorkspace.x[0] + acadoWorkspace.evGx[103]*acadoWorkspace.x[1] + acadoWorkspace.evGx[104]*acadoWorkspace.x[2] + acadoWorkspace.evGx[105]*acadoWorkspace.x[3] + acadoWorkspace.evGx[106]*acadoWorkspace.x[4] + acadoWorkspace.evGx[107]*acadoWorkspace.x[5] + acadoWorkspace.d[17]; +acadoVariables.x[24] += + acadoWorkspace.evGx[108]*acadoWorkspace.x[0] + acadoWorkspace.evGx[109]*acadoWorkspace.x[1] + acadoWorkspace.evGx[110]*acadoWorkspace.x[2] + acadoWorkspace.evGx[111]*acadoWorkspace.x[3] + acadoWorkspace.evGx[112]*acadoWorkspace.x[4] + acadoWorkspace.evGx[113]*acadoWorkspace.x[5] + acadoWorkspace.d[18]; +acadoVariables.x[25] += + acadoWorkspace.evGx[114]*acadoWorkspace.x[0] + acadoWorkspace.evGx[115]*acadoWorkspace.x[1] + acadoWorkspace.evGx[116]*acadoWorkspace.x[2] + acadoWorkspace.evGx[117]*acadoWorkspace.x[3] + acadoWorkspace.evGx[118]*acadoWorkspace.x[4] + acadoWorkspace.evGx[119]*acadoWorkspace.x[5] + acadoWorkspace.d[19]; +acadoVariables.x[26] += + acadoWorkspace.evGx[120]*acadoWorkspace.x[0] + acadoWorkspace.evGx[121]*acadoWorkspace.x[1] + acadoWorkspace.evGx[122]*acadoWorkspace.x[2] + acadoWorkspace.evGx[123]*acadoWorkspace.x[3] + acadoWorkspace.evGx[124]*acadoWorkspace.x[4] + acadoWorkspace.evGx[125]*acadoWorkspace.x[5] + acadoWorkspace.d[20]; +acadoVariables.x[27] += + acadoWorkspace.evGx[126]*acadoWorkspace.x[0] + acadoWorkspace.evGx[127]*acadoWorkspace.x[1] + acadoWorkspace.evGx[128]*acadoWorkspace.x[2] + acadoWorkspace.evGx[129]*acadoWorkspace.x[3] + acadoWorkspace.evGx[130]*acadoWorkspace.x[4] + acadoWorkspace.evGx[131]*acadoWorkspace.x[5] + acadoWorkspace.d[21]; +acadoVariables.x[28] += + acadoWorkspace.evGx[132]*acadoWorkspace.x[0] + acadoWorkspace.evGx[133]*acadoWorkspace.x[1] + acadoWorkspace.evGx[134]*acadoWorkspace.x[2] + acadoWorkspace.evGx[135]*acadoWorkspace.x[3] + acadoWorkspace.evGx[136]*acadoWorkspace.x[4] + acadoWorkspace.evGx[137]*acadoWorkspace.x[5] + acadoWorkspace.d[22]; +acadoVariables.x[29] += + acadoWorkspace.evGx[138]*acadoWorkspace.x[0] + acadoWorkspace.evGx[139]*acadoWorkspace.x[1] + acadoWorkspace.evGx[140]*acadoWorkspace.x[2] + acadoWorkspace.evGx[141]*acadoWorkspace.x[3] + acadoWorkspace.evGx[142]*acadoWorkspace.x[4] + acadoWorkspace.evGx[143]*acadoWorkspace.x[5] + acadoWorkspace.d[23]; +acadoVariables.x[30] += + acadoWorkspace.evGx[144]*acadoWorkspace.x[0] + acadoWorkspace.evGx[145]*acadoWorkspace.x[1] + acadoWorkspace.evGx[146]*acadoWorkspace.x[2] + acadoWorkspace.evGx[147]*acadoWorkspace.x[3] + acadoWorkspace.evGx[148]*acadoWorkspace.x[4] + acadoWorkspace.evGx[149]*acadoWorkspace.x[5] + acadoWorkspace.d[24]; +acadoVariables.x[31] += + acadoWorkspace.evGx[150]*acadoWorkspace.x[0] + acadoWorkspace.evGx[151]*acadoWorkspace.x[1] + acadoWorkspace.evGx[152]*acadoWorkspace.x[2] + acadoWorkspace.evGx[153]*acadoWorkspace.x[3] + acadoWorkspace.evGx[154]*acadoWorkspace.x[4] + acadoWorkspace.evGx[155]*acadoWorkspace.x[5] + acadoWorkspace.d[25]; +acadoVariables.x[32] += + acadoWorkspace.evGx[156]*acadoWorkspace.x[0] + acadoWorkspace.evGx[157]*acadoWorkspace.x[1] + acadoWorkspace.evGx[158]*acadoWorkspace.x[2] + acadoWorkspace.evGx[159]*acadoWorkspace.x[3] + acadoWorkspace.evGx[160]*acadoWorkspace.x[4] + acadoWorkspace.evGx[161]*acadoWorkspace.x[5] + acadoWorkspace.d[26]; +acadoVariables.x[33] += + acadoWorkspace.evGx[162]*acadoWorkspace.x[0] + acadoWorkspace.evGx[163]*acadoWorkspace.x[1] + acadoWorkspace.evGx[164]*acadoWorkspace.x[2] + acadoWorkspace.evGx[165]*acadoWorkspace.x[3] + acadoWorkspace.evGx[166]*acadoWorkspace.x[4] + acadoWorkspace.evGx[167]*acadoWorkspace.x[5] + acadoWorkspace.d[27]; +acadoVariables.x[34] += + acadoWorkspace.evGx[168]*acadoWorkspace.x[0] + acadoWorkspace.evGx[169]*acadoWorkspace.x[1] + acadoWorkspace.evGx[170]*acadoWorkspace.x[2] + acadoWorkspace.evGx[171]*acadoWorkspace.x[3] + acadoWorkspace.evGx[172]*acadoWorkspace.x[4] + acadoWorkspace.evGx[173]*acadoWorkspace.x[5] + acadoWorkspace.d[28]; +acadoVariables.x[35] += + acadoWorkspace.evGx[174]*acadoWorkspace.x[0] + acadoWorkspace.evGx[175]*acadoWorkspace.x[1] + acadoWorkspace.evGx[176]*acadoWorkspace.x[2] + acadoWorkspace.evGx[177]*acadoWorkspace.x[3] + acadoWorkspace.evGx[178]*acadoWorkspace.x[4] + acadoWorkspace.evGx[179]*acadoWorkspace.x[5] + acadoWorkspace.d[29]; +acadoVariables.x[36] += + acadoWorkspace.evGx[180]*acadoWorkspace.x[0] + acadoWorkspace.evGx[181]*acadoWorkspace.x[1] + acadoWorkspace.evGx[182]*acadoWorkspace.x[2] + acadoWorkspace.evGx[183]*acadoWorkspace.x[3] + acadoWorkspace.evGx[184]*acadoWorkspace.x[4] + acadoWorkspace.evGx[185]*acadoWorkspace.x[5] + acadoWorkspace.d[30]; +acadoVariables.x[37] += + acadoWorkspace.evGx[186]*acadoWorkspace.x[0] + acadoWorkspace.evGx[187]*acadoWorkspace.x[1] + acadoWorkspace.evGx[188]*acadoWorkspace.x[2] + acadoWorkspace.evGx[189]*acadoWorkspace.x[3] + acadoWorkspace.evGx[190]*acadoWorkspace.x[4] + acadoWorkspace.evGx[191]*acadoWorkspace.x[5] + acadoWorkspace.d[31]; +acadoVariables.x[38] += + acadoWorkspace.evGx[192]*acadoWorkspace.x[0] + acadoWorkspace.evGx[193]*acadoWorkspace.x[1] + acadoWorkspace.evGx[194]*acadoWorkspace.x[2] + acadoWorkspace.evGx[195]*acadoWorkspace.x[3] + acadoWorkspace.evGx[196]*acadoWorkspace.x[4] + acadoWorkspace.evGx[197]*acadoWorkspace.x[5] + acadoWorkspace.d[32]; +acadoVariables.x[39] += + acadoWorkspace.evGx[198]*acadoWorkspace.x[0] + acadoWorkspace.evGx[199]*acadoWorkspace.x[1] + acadoWorkspace.evGx[200]*acadoWorkspace.x[2] + acadoWorkspace.evGx[201]*acadoWorkspace.x[3] + acadoWorkspace.evGx[202]*acadoWorkspace.x[4] + acadoWorkspace.evGx[203]*acadoWorkspace.x[5] + acadoWorkspace.d[33]; +acadoVariables.x[40] += + acadoWorkspace.evGx[204]*acadoWorkspace.x[0] + acadoWorkspace.evGx[205]*acadoWorkspace.x[1] + acadoWorkspace.evGx[206]*acadoWorkspace.x[2] + acadoWorkspace.evGx[207]*acadoWorkspace.x[3] + acadoWorkspace.evGx[208]*acadoWorkspace.x[4] + acadoWorkspace.evGx[209]*acadoWorkspace.x[5] + acadoWorkspace.d[34]; +acadoVariables.x[41] += + acadoWorkspace.evGx[210]*acadoWorkspace.x[0] + acadoWorkspace.evGx[211]*acadoWorkspace.x[1] + acadoWorkspace.evGx[212]*acadoWorkspace.x[2] + acadoWorkspace.evGx[213]*acadoWorkspace.x[3] + acadoWorkspace.evGx[214]*acadoWorkspace.x[4] + acadoWorkspace.evGx[215]*acadoWorkspace.x[5] + acadoWorkspace.d[35]; +acadoVariables.x[42] += + acadoWorkspace.evGx[216]*acadoWorkspace.x[0] + acadoWorkspace.evGx[217]*acadoWorkspace.x[1] + acadoWorkspace.evGx[218]*acadoWorkspace.x[2] + acadoWorkspace.evGx[219]*acadoWorkspace.x[3] + acadoWorkspace.evGx[220]*acadoWorkspace.x[4] + acadoWorkspace.evGx[221]*acadoWorkspace.x[5] + acadoWorkspace.d[36]; +acadoVariables.x[43] += + acadoWorkspace.evGx[222]*acadoWorkspace.x[0] + acadoWorkspace.evGx[223]*acadoWorkspace.x[1] + acadoWorkspace.evGx[224]*acadoWorkspace.x[2] + acadoWorkspace.evGx[225]*acadoWorkspace.x[3] + acadoWorkspace.evGx[226]*acadoWorkspace.x[4] + acadoWorkspace.evGx[227]*acadoWorkspace.x[5] + acadoWorkspace.d[37]; +acadoVariables.x[44] += + acadoWorkspace.evGx[228]*acadoWorkspace.x[0] + acadoWorkspace.evGx[229]*acadoWorkspace.x[1] + acadoWorkspace.evGx[230]*acadoWorkspace.x[2] + acadoWorkspace.evGx[231]*acadoWorkspace.x[3] + acadoWorkspace.evGx[232]*acadoWorkspace.x[4] + acadoWorkspace.evGx[233]*acadoWorkspace.x[5] + acadoWorkspace.d[38]; +acadoVariables.x[45] += + acadoWorkspace.evGx[234]*acadoWorkspace.x[0] + acadoWorkspace.evGx[235]*acadoWorkspace.x[1] + acadoWorkspace.evGx[236]*acadoWorkspace.x[2] + acadoWorkspace.evGx[237]*acadoWorkspace.x[3] + acadoWorkspace.evGx[238]*acadoWorkspace.x[4] + acadoWorkspace.evGx[239]*acadoWorkspace.x[5] + acadoWorkspace.d[39]; +acadoVariables.x[46] += + acadoWorkspace.evGx[240]*acadoWorkspace.x[0] + acadoWorkspace.evGx[241]*acadoWorkspace.x[1] + acadoWorkspace.evGx[242]*acadoWorkspace.x[2] + acadoWorkspace.evGx[243]*acadoWorkspace.x[3] + acadoWorkspace.evGx[244]*acadoWorkspace.x[4] + acadoWorkspace.evGx[245]*acadoWorkspace.x[5] + acadoWorkspace.d[40]; +acadoVariables.x[47] += + acadoWorkspace.evGx[246]*acadoWorkspace.x[0] + acadoWorkspace.evGx[247]*acadoWorkspace.x[1] + acadoWorkspace.evGx[248]*acadoWorkspace.x[2] + acadoWorkspace.evGx[249]*acadoWorkspace.x[3] + acadoWorkspace.evGx[250]*acadoWorkspace.x[4] + acadoWorkspace.evGx[251]*acadoWorkspace.x[5] + acadoWorkspace.d[41]; +acadoVariables.x[48] += + acadoWorkspace.evGx[252]*acadoWorkspace.x[0] + acadoWorkspace.evGx[253]*acadoWorkspace.x[1] + acadoWorkspace.evGx[254]*acadoWorkspace.x[2] + acadoWorkspace.evGx[255]*acadoWorkspace.x[3] + acadoWorkspace.evGx[256]*acadoWorkspace.x[4] + acadoWorkspace.evGx[257]*acadoWorkspace.x[5] + acadoWorkspace.d[42]; +acadoVariables.x[49] += + acadoWorkspace.evGx[258]*acadoWorkspace.x[0] + acadoWorkspace.evGx[259]*acadoWorkspace.x[1] + acadoWorkspace.evGx[260]*acadoWorkspace.x[2] + acadoWorkspace.evGx[261]*acadoWorkspace.x[3] + acadoWorkspace.evGx[262]*acadoWorkspace.x[4] + acadoWorkspace.evGx[263]*acadoWorkspace.x[5] + acadoWorkspace.d[43]; +acadoVariables.x[50] += + acadoWorkspace.evGx[264]*acadoWorkspace.x[0] + acadoWorkspace.evGx[265]*acadoWorkspace.x[1] + acadoWorkspace.evGx[266]*acadoWorkspace.x[2] + acadoWorkspace.evGx[267]*acadoWorkspace.x[3] + acadoWorkspace.evGx[268]*acadoWorkspace.x[4] + acadoWorkspace.evGx[269]*acadoWorkspace.x[5] + acadoWorkspace.d[44]; +acadoVariables.x[51] += + acadoWorkspace.evGx[270]*acadoWorkspace.x[0] + acadoWorkspace.evGx[271]*acadoWorkspace.x[1] + acadoWorkspace.evGx[272]*acadoWorkspace.x[2] + acadoWorkspace.evGx[273]*acadoWorkspace.x[3] + acadoWorkspace.evGx[274]*acadoWorkspace.x[4] + acadoWorkspace.evGx[275]*acadoWorkspace.x[5] + acadoWorkspace.d[45]; +acadoVariables.x[52] += + acadoWorkspace.evGx[276]*acadoWorkspace.x[0] + acadoWorkspace.evGx[277]*acadoWorkspace.x[1] + acadoWorkspace.evGx[278]*acadoWorkspace.x[2] + acadoWorkspace.evGx[279]*acadoWorkspace.x[3] + acadoWorkspace.evGx[280]*acadoWorkspace.x[4] + acadoWorkspace.evGx[281]*acadoWorkspace.x[5] + acadoWorkspace.d[46]; +acadoVariables.x[53] += + acadoWorkspace.evGx[282]*acadoWorkspace.x[0] + acadoWorkspace.evGx[283]*acadoWorkspace.x[1] + acadoWorkspace.evGx[284]*acadoWorkspace.x[2] + acadoWorkspace.evGx[285]*acadoWorkspace.x[3] + acadoWorkspace.evGx[286]*acadoWorkspace.x[4] + acadoWorkspace.evGx[287]*acadoWorkspace.x[5] + acadoWorkspace.d[47]; +acadoVariables.x[54] += + acadoWorkspace.evGx[288]*acadoWorkspace.x[0] + acadoWorkspace.evGx[289]*acadoWorkspace.x[1] + acadoWorkspace.evGx[290]*acadoWorkspace.x[2] + acadoWorkspace.evGx[291]*acadoWorkspace.x[3] + acadoWorkspace.evGx[292]*acadoWorkspace.x[4] + acadoWorkspace.evGx[293]*acadoWorkspace.x[5] + acadoWorkspace.d[48]; +acadoVariables.x[55] += + acadoWorkspace.evGx[294]*acadoWorkspace.x[0] + acadoWorkspace.evGx[295]*acadoWorkspace.x[1] + acadoWorkspace.evGx[296]*acadoWorkspace.x[2] + acadoWorkspace.evGx[297]*acadoWorkspace.x[3] + acadoWorkspace.evGx[298]*acadoWorkspace.x[4] + acadoWorkspace.evGx[299]*acadoWorkspace.x[5] + acadoWorkspace.d[49]; +acadoVariables.x[56] += + acadoWorkspace.evGx[300]*acadoWorkspace.x[0] + acadoWorkspace.evGx[301]*acadoWorkspace.x[1] + acadoWorkspace.evGx[302]*acadoWorkspace.x[2] + acadoWorkspace.evGx[303]*acadoWorkspace.x[3] + acadoWorkspace.evGx[304]*acadoWorkspace.x[4] + acadoWorkspace.evGx[305]*acadoWorkspace.x[5] + acadoWorkspace.d[50]; +acadoVariables.x[57] += + acadoWorkspace.evGx[306]*acadoWorkspace.x[0] + acadoWorkspace.evGx[307]*acadoWorkspace.x[1] + acadoWorkspace.evGx[308]*acadoWorkspace.x[2] + acadoWorkspace.evGx[309]*acadoWorkspace.x[3] + acadoWorkspace.evGx[310]*acadoWorkspace.x[4] + acadoWorkspace.evGx[311]*acadoWorkspace.x[5] + acadoWorkspace.d[51]; +acadoVariables.x[58] += + acadoWorkspace.evGx[312]*acadoWorkspace.x[0] + acadoWorkspace.evGx[313]*acadoWorkspace.x[1] + acadoWorkspace.evGx[314]*acadoWorkspace.x[2] + acadoWorkspace.evGx[315]*acadoWorkspace.x[3] + acadoWorkspace.evGx[316]*acadoWorkspace.x[4] + acadoWorkspace.evGx[317]*acadoWorkspace.x[5] + acadoWorkspace.d[52]; +acadoVariables.x[59] += + acadoWorkspace.evGx[318]*acadoWorkspace.x[0] + acadoWorkspace.evGx[319]*acadoWorkspace.x[1] + acadoWorkspace.evGx[320]*acadoWorkspace.x[2] + acadoWorkspace.evGx[321]*acadoWorkspace.x[3] + acadoWorkspace.evGx[322]*acadoWorkspace.x[4] + acadoWorkspace.evGx[323]*acadoWorkspace.x[5] + acadoWorkspace.d[53]; +acadoVariables.x[60] += + acadoWorkspace.evGx[324]*acadoWorkspace.x[0] + acadoWorkspace.evGx[325]*acadoWorkspace.x[1] + acadoWorkspace.evGx[326]*acadoWorkspace.x[2] + acadoWorkspace.evGx[327]*acadoWorkspace.x[3] + acadoWorkspace.evGx[328]*acadoWorkspace.x[4] + acadoWorkspace.evGx[329]*acadoWorkspace.x[5] + acadoWorkspace.d[54]; +acadoVariables.x[61] += + acadoWorkspace.evGx[330]*acadoWorkspace.x[0] + acadoWorkspace.evGx[331]*acadoWorkspace.x[1] + acadoWorkspace.evGx[332]*acadoWorkspace.x[2] + acadoWorkspace.evGx[333]*acadoWorkspace.x[3] + acadoWorkspace.evGx[334]*acadoWorkspace.x[4] + acadoWorkspace.evGx[335]*acadoWorkspace.x[5] + acadoWorkspace.d[55]; +acadoVariables.x[62] += + acadoWorkspace.evGx[336]*acadoWorkspace.x[0] + acadoWorkspace.evGx[337]*acadoWorkspace.x[1] + acadoWorkspace.evGx[338]*acadoWorkspace.x[2] + acadoWorkspace.evGx[339]*acadoWorkspace.x[3] + acadoWorkspace.evGx[340]*acadoWorkspace.x[4] + acadoWorkspace.evGx[341]*acadoWorkspace.x[5] + acadoWorkspace.d[56]; +acadoVariables.x[63] += + acadoWorkspace.evGx[342]*acadoWorkspace.x[0] + acadoWorkspace.evGx[343]*acadoWorkspace.x[1] + acadoWorkspace.evGx[344]*acadoWorkspace.x[2] + acadoWorkspace.evGx[345]*acadoWorkspace.x[3] + acadoWorkspace.evGx[346]*acadoWorkspace.x[4] + acadoWorkspace.evGx[347]*acadoWorkspace.x[5] + acadoWorkspace.d[57]; +acadoVariables.x[64] += + acadoWorkspace.evGx[348]*acadoWorkspace.x[0] + acadoWorkspace.evGx[349]*acadoWorkspace.x[1] + acadoWorkspace.evGx[350]*acadoWorkspace.x[2] + acadoWorkspace.evGx[351]*acadoWorkspace.x[3] + acadoWorkspace.evGx[352]*acadoWorkspace.x[4] + acadoWorkspace.evGx[353]*acadoWorkspace.x[5] + acadoWorkspace.d[58]; +acadoVariables.x[65] += + acadoWorkspace.evGx[354]*acadoWorkspace.x[0] + acadoWorkspace.evGx[355]*acadoWorkspace.x[1] + acadoWorkspace.evGx[356]*acadoWorkspace.x[2] + acadoWorkspace.evGx[357]*acadoWorkspace.x[3] + acadoWorkspace.evGx[358]*acadoWorkspace.x[4] + acadoWorkspace.evGx[359]*acadoWorkspace.x[5] + acadoWorkspace.d[59]; +acadoVariables.x[66] += + acadoWorkspace.evGx[360]*acadoWorkspace.x[0] + acadoWorkspace.evGx[361]*acadoWorkspace.x[1] + acadoWorkspace.evGx[362]*acadoWorkspace.x[2] + acadoWorkspace.evGx[363]*acadoWorkspace.x[3] + acadoWorkspace.evGx[364]*acadoWorkspace.x[4] + acadoWorkspace.evGx[365]*acadoWorkspace.x[5] + acadoWorkspace.d[60]; +acadoVariables.x[67] += + acadoWorkspace.evGx[366]*acadoWorkspace.x[0] + acadoWorkspace.evGx[367]*acadoWorkspace.x[1] + acadoWorkspace.evGx[368]*acadoWorkspace.x[2] + acadoWorkspace.evGx[369]*acadoWorkspace.x[3] + acadoWorkspace.evGx[370]*acadoWorkspace.x[4] + acadoWorkspace.evGx[371]*acadoWorkspace.x[5] + acadoWorkspace.d[61]; +acadoVariables.x[68] += + acadoWorkspace.evGx[372]*acadoWorkspace.x[0] + acadoWorkspace.evGx[373]*acadoWorkspace.x[1] + acadoWorkspace.evGx[374]*acadoWorkspace.x[2] + acadoWorkspace.evGx[375]*acadoWorkspace.x[3] + acadoWorkspace.evGx[376]*acadoWorkspace.x[4] + acadoWorkspace.evGx[377]*acadoWorkspace.x[5] + acadoWorkspace.d[62]; +acadoVariables.x[69] += + acadoWorkspace.evGx[378]*acadoWorkspace.x[0] + acadoWorkspace.evGx[379]*acadoWorkspace.x[1] + acadoWorkspace.evGx[380]*acadoWorkspace.x[2] + acadoWorkspace.evGx[381]*acadoWorkspace.x[3] + acadoWorkspace.evGx[382]*acadoWorkspace.x[4] + acadoWorkspace.evGx[383]*acadoWorkspace.x[5] + acadoWorkspace.d[63]; +acadoVariables.x[70] += + acadoWorkspace.evGx[384]*acadoWorkspace.x[0] + acadoWorkspace.evGx[385]*acadoWorkspace.x[1] + acadoWorkspace.evGx[386]*acadoWorkspace.x[2] + acadoWorkspace.evGx[387]*acadoWorkspace.x[3] + acadoWorkspace.evGx[388]*acadoWorkspace.x[4] + acadoWorkspace.evGx[389]*acadoWorkspace.x[5] + acadoWorkspace.d[64]; +acadoVariables.x[71] += + acadoWorkspace.evGx[390]*acadoWorkspace.x[0] + acadoWorkspace.evGx[391]*acadoWorkspace.x[1] + acadoWorkspace.evGx[392]*acadoWorkspace.x[2] + acadoWorkspace.evGx[393]*acadoWorkspace.x[3] + acadoWorkspace.evGx[394]*acadoWorkspace.x[4] + acadoWorkspace.evGx[395]*acadoWorkspace.x[5] + acadoWorkspace.d[65]; +acadoVariables.x[72] += + acadoWorkspace.evGx[396]*acadoWorkspace.x[0] + acadoWorkspace.evGx[397]*acadoWorkspace.x[1] + acadoWorkspace.evGx[398]*acadoWorkspace.x[2] + acadoWorkspace.evGx[399]*acadoWorkspace.x[3] + acadoWorkspace.evGx[400]*acadoWorkspace.x[4] + acadoWorkspace.evGx[401]*acadoWorkspace.x[5] + acadoWorkspace.d[66]; +acadoVariables.x[73] += + acadoWorkspace.evGx[402]*acadoWorkspace.x[0] + acadoWorkspace.evGx[403]*acadoWorkspace.x[1] + acadoWorkspace.evGx[404]*acadoWorkspace.x[2] + acadoWorkspace.evGx[405]*acadoWorkspace.x[3] + acadoWorkspace.evGx[406]*acadoWorkspace.x[4] + acadoWorkspace.evGx[407]*acadoWorkspace.x[5] + acadoWorkspace.d[67]; +acadoVariables.x[74] += + acadoWorkspace.evGx[408]*acadoWorkspace.x[0] + acadoWorkspace.evGx[409]*acadoWorkspace.x[1] + acadoWorkspace.evGx[410]*acadoWorkspace.x[2] + acadoWorkspace.evGx[411]*acadoWorkspace.x[3] + acadoWorkspace.evGx[412]*acadoWorkspace.x[4] + acadoWorkspace.evGx[413]*acadoWorkspace.x[5] + acadoWorkspace.d[68]; +acadoVariables.x[75] += + acadoWorkspace.evGx[414]*acadoWorkspace.x[0] + acadoWorkspace.evGx[415]*acadoWorkspace.x[1] + acadoWorkspace.evGx[416]*acadoWorkspace.x[2] + acadoWorkspace.evGx[417]*acadoWorkspace.x[3] + acadoWorkspace.evGx[418]*acadoWorkspace.x[4] + acadoWorkspace.evGx[419]*acadoWorkspace.x[5] + acadoWorkspace.d[69]; +acadoVariables.x[76] += + acadoWorkspace.evGx[420]*acadoWorkspace.x[0] + acadoWorkspace.evGx[421]*acadoWorkspace.x[1] + acadoWorkspace.evGx[422]*acadoWorkspace.x[2] + acadoWorkspace.evGx[423]*acadoWorkspace.x[3] + acadoWorkspace.evGx[424]*acadoWorkspace.x[4] + acadoWorkspace.evGx[425]*acadoWorkspace.x[5] + acadoWorkspace.d[70]; +acadoVariables.x[77] += + acadoWorkspace.evGx[426]*acadoWorkspace.x[0] + acadoWorkspace.evGx[427]*acadoWorkspace.x[1] + acadoWorkspace.evGx[428]*acadoWorkspace.x[2] + acadoWorkspace.evGx[429]*acadoWorkspace.x[3] + acadoWorkspace.evGx[430]*acadoWorkspace.x[4] + acadoWorkspace.evGx[431]*acadoWorkspace.x[5] + acadoWorkspace.d[71]; +acadoVariables.x[78] += + acadoWorkspace.evGx[432]*acadoWorkspace.x[0] + acadoWorkspace.evGx[433]*acadoWorkspace.x[1] + acadoWorkspace.evGx[434]*acadoWorkspace.x[2] + acadoWorkspace.evGx[435]*acadoWorkspace.x[3] + acadoWorkspace.evGx[436]*acadoWorkspace.x[4] + acadoWorkspace.evGx[437]*acadoWorkspace.x[5] + acadoWorkspace.d[72]; +acadoVariables.x[79] += + acadoWorkspace.evGx[438]*acadoWorkspace.x[0] + acadoWorkspace.evGx[439]*acadoWorkspace.x[1] + acadoWorkspace.evGx[440]*acadoWorkspace.x[2] + acadoWorkspace.evGx[441]*acadoWorkspace.x[3] + acadoWorkspace.evGx[442]*acadoWorkspace.x[4] + acadoWorkspace.evGx[443]*acadoWorkspace.x[5] + acadoWorkspace.d[73]; +acadoVariables.x[80] += + acadoWorkspace.evGx[444]*acadoWorkspace.x[0] + acadoWorkspace.evGx[445]*acadoWorkspace.x[1] + acadoWorkspace.evGx[446]*acadoWorkspace.x[2] + acadoWorkspace.evGx[447]*acadoWorkspace.x[3] + acadoWorkspace.evGx[448]*acadoWorkspace.x[4] + acadoWorkspace.evGx[449]*acadoWorkspace.x[5] + acadoWorkspace.d[74]; +acadoVariables.x[81] += + acadoWorkspace.evGx[450]*acadoWorkspace.x[0] + acadoWorkspace.evGx[451]*acadoWorkspace.x[1] + acadoWorkspace.evGx[452]*acadoWorkspace.x[2] + acadoWorkspace.evGx[453]*acadoWorkspace.x[3] + acadoWorkspace.evGx[454]*acadoWorkspace.x[4] + acadoWorkspace.evGx[455]*acadoWorkspace.x[5] + acadoWorkspace.d[75]; +acadoVariables.x[82] += + acadoWorkspace.evGx[456]*acadoWorkspace.x[0] + acadoWorkspace.evGx[457]*acadoWorkspace.x[1] + acadoWorkspace.evGx[458]*acadoWorkspace.x[2] + acadoWorkspace.evGx[459]*acadoWorkspace.x[3] + acadoWorkspace.evGx[460]*acadoWorkspace.x[4] + acadoWorkspace.evGx[461]*acadoWorkspace.x[5] + acadoWorkspace.d[76]; +acadoVariables.x[83] += + acadoWorkspace.evGx[462]*acadoWorkspace.x[0] + acadoWorkspace.evGx[463]*acadoWorkspace.x[1] + acadoWorkspace.evGx[464]*acadoWorkspace.x[2] + acadoWorkspace.evGx[465]*acadoWorkspace.x[3] + acadoWorkspace.evGx[466]*acadoWorkspace.x[4] + acadoWorkspace.evGx[467]*acadoWorkspace.x[5] + acadoWorkspace.d[77]; +acadoVariables.x[84] += + acadoWorkspace.evGx[468]*acadoWorkspace.x[0] + acadoWorkspace.evGx[469]*acadoWorkspace.x[1] + acadoWorkspace.evGx[470]*acadoWorkspace.x[2] + acadoWorkspace.evGx[471]*acadoWorkspace.x[3] + acadoWorkspace.evGx[472]*acadoWorkspace.x[4] + acadoWorkspace.evGx[473]*acadoWorkspace.x[5] + acadoWorkspace.d[78]; +acadoVariables.x[85] += + acadoWorkspace.evGx[474]*acadoWorkspace.x[0] + acadoWorkspace.evGx[475]*acadoWorkspace.x[1] + acadoWorkspace.evGx[476]*acadoWorkspace.x[2] + acadoWorkspace.evGx[477]*acadoWorkspace.x[3] + acadoWorkspace.evGx[478]*acadoWorkspace.x[4] + acadoWorkspace.evGx[479]*acadoWorkspace.x[5] + acadoWorkspace.d[79]; +acadoVariables.x[86] += + acadoWorkspace.evGx[480]*acadoWorkspace.x[0] + acadoWorkspace.evGx[481]*acadoWorkspace.x[1] + acadoWorkspace.evGx[482]*acadoWorkspace.x[2] + acadoWorkspace.evGx[483]*acadoWorkspace.x[3] + acadoWorkspace.evGx[484]*acadoWorkspace.x[4] + acadoWorkspace.evGx[485]*acadoWorkspace.x[5] + acadoWorkspace.d[80]; +acadoVariables.x[87] += + acadoWorkspace.evGx[486]*acadoWorkspace.x[0] + acadoWorkspace.evGx[487]*acadoWorkspace.x[1] + acadoWorkspace.evGx[488]*acadoWorkspace.x[2] + acadoWorkspace.evGx[489]*acadoWorkspace.x[3] + acadoWorkspace.evGx[490]*acadoWorkspace.x[4] + acadoWorkspace.evGx[491]*acadoWorkspace.x[5] + acadoWorkspace.d[81]; +acadoVariables.x[88] += + acadoWorkspace.evGx[492]*acadoWorkspace.x[0] + acadoWorkspace.evGx[493]*acadoWorkspace.x[1] + acadoWorkspace.evGx[494]*acadoWorkspace.x[2] + acadoWorkspace.evGx[495]*acadoWorkspace.x[3] + acadoWorkspace.evGx[496]*acadoWorkspace.x[4] + acadoWorkspace.evGx[497]*acadoWorkspace.x[5] + acadoWorkspace.d[82]; +acadoVariables.x[89] += + acadoWorkspace.evGx[498]*acadoWorkspace.x[0] + acadoWorkspace.evGx[499]*acadoWorkspace.x[1] + acadoWorkspace.evGx[500]*acadoWorkspace.x[2] + acadoWorkspace.evGx[501]*acadoWorkspace.x[3] + acadoWorkspace.evGx[502]*acadoWorkspace.x[4] + acadoWorkspace.evGx[503]*acadoWorkspace.x[5] + acadoWorkspace.d[83]; +acadoVariables.x[90] += + acadoWorkspace.evGx[504]*acadoWorkspace.x[0] + acadoWorkspace.evGx[505]*acadoWorkspace.x[1] + acadoWorkspace.evGx[506]*acadoWorkspace.x[2] + acadoWorkspace.evGx[507]*acadoWorkspace.x[3] + acadoWorkspace.evGx[508]*acadoWorkspace.x[4] + acadoWorkspace.evGx[509]*acadoWorkspace.x[5] + acadoWorkspace.d[84]; +acadoVariables.x[91] += + acadoWorkspace.evGx[510]*acadoWorkspace.x[0] + acadoWorkspace.evGx[511]*acadoWorkspace.x[1] + acadoWorkspace.evGx[512]*acadoWorkspace.x[2] + acadoWorkspace.evGx[513]*acadoWorkspace.x[3] + acadoWorkspace.evGx[514]*acadoWorkspace.x[4] + acadoWorkspace.evGx[515]*acadoWorkspace.x[5] + acadoWorkspace.d[85]; +acadoVariables.x[92] += + acadoWorkspace.evGx[516]*acadoWorkspace.x[0] + acadoWorkspace.evGx[517]*acadoWorkspace.x[1] + acadoWorkspace.evGx[518]*acadoWorkspace.x[2] + acadoWorkspace.evGx[519]*acadoWorkspace.x[3] + acadoWorkspace.evGx[520]*acadoWorkspace.x[4] + acadoWorkspace.evGx[521]*acadoWorkspace.x[5] + acadoWorkspace.d[86]; +acadoVariables.x[93] += + acadoWorkspace.evGx[522]*acadoWorkspace.x[0] + acadoWorkspace.evGx[523]*acadoWorkspace.x[1] + acadoWorkspace.evGx[524]*acadoWorkspace.x[2] + acadoWorkspace.evGx[525]*acadoWorkspace.x[3] + acadoWorkspace.evGx[526]*acadoWorkspace.x[4] + acadoWorkspace.evGx[527]*acadoWorkspace.x[5] + acadoWorkspace.d[87]; +acadoVariables.x[94] += + acadoWorkspace.evGx[528]*acadoWorkspace.x[0] + acadoWorkspace.evGx[529]*acadoWorkspace.x[1] + acadoWorkspace.evGx[530]*acadoWorkspace.x[2] + acadoWorkspace.evGx[531]*acadoWorkspace.x[3] + acadoWorkspace.evGx[532]*acadoWorkspace.x[4] + acadoWorkspace.evGx[533]*acadoWorkspace.x[5] + acadoWorkspace.d[88]; +acadoVariables.x[95] += + acadoWorkspace.evGx[534]*acadoWorkspace.x[0] + acadoWorkspace.evGx[535]*acadoWorkspace.x[1] + acadoWorkspace.evGx[536]*acadoWorkspace.x[2] + acadoWorkspace.evGx[537]*acadoWorkspace.x[3] + acadoWorkspace.evGx[538]*acadoWorkspace.x[4] + acadoWorkspace.evGx[539]*acadoWorkspace.x[5] + acadoWorkspace.d[89]; +acadoVariables.x[96] += + acadoWorkspace.evGx[540]*acadoWorkspace.x[0] + acadoWorkspace.evGx[541]*acadoWorkspace.x[1] + acadoWorkspace.evGx[542]*acadoWorkspace.x[2] + acadoWorkspace.evGx[543]*acadoWorkspace.x[3] + acadoWorkspace.evGx[544]*acadoWorkspace.x[4] + acadoWorkspace.evGx[545]*acadoWorkspace.x[5] + acadoWorkspace.d[90]; +acadoVariables.x[97] += + acadoWorkspace.evGx[546]*acadoWorkspace.x[0] + acadoWorkspace.evGx[547]*acadoWorkspace.x[1] + acadoWorkspace.evGx[548]*acadoWorkspace.x[2] + acadoWorkspace.evGx[549]*acadoWorkspace.x[3] + acadoWorkspace.evGx[550]*acadoWorkspace.x[4] + acadoWorkspace.evGx[551]*acadoWorkspace.x[5] + acadoWorkspace.d[91]; +acadoVariables.x[98] += + acadoWorkspace.evGx[552]*acadoWorkspace.x[0] + acadoWorkspace.evGx[553]*acadoWorkspace.x[1] + acadoWorkspace.evGx[554]*acadoWorkspace.x[2] + acadoWorkspace.evGx[555]*acadoWorkspace.x[3] + acadoWorkspace.evGx[556]*acadoWorkspace.x[4] + acadoWorkspace.evGx[557]*acadoWorkspace.x[5] + acadoWorkspace.d[92]; +acadoVariables.x[99] += + acadoWorkspace.evGx[558]*acadoWorkspace.x[0] + acadoWorkspace.evGx[559]*acadoWorkspace.x[1] + acadoWorkspace.evGx[560]*acadoWorkspace.x[2] + acadoWorkspace.evGx[561]*acadoWorkspace.x[3] + acadoWorkspace.evGx[562]*acadoWorkspace.x[4] + acadoWorkspace.evGx[563]*acadoWorkspace.x[5] + acadoWorkspace.d[93]; +acadoVariables.x[100] += + acadoWorkspace.evGx[564]*acadoWorkspace.x[0] + acadoWorkspace.evGx[565]*acadoWorkspace.x[1] + acadoWorkspace.evGx[566]*acadoWorkspace.x[2] + acadoWorkspace.evGx[567]*acadoWorkspace.x[3] + acadoWorkspace.evGx[568]*acadoWorkspace.x[4] + acadoWorkspace.evGx[569]*acadoWorkspace.x[5] + acadoWorkspace.d[94]; +acadoVariables.x[101] += + acadoWorkspace.evGx[570]*acadoWorkspace.x[0] + acadoWorkspace.evGx[571]*acadoWorkspace.x[1] + acadoWorkspace.evGx[572]*acadoWorkspace.x[2] + acadoWorkspace.evGx[573]*acadoWorkspace.x[3] + acadoWorkspace.evGx[574]*acadoWorkspace.x[4] + acadoWorkspace.evGx[575]*acadoWorkspace.x[5] + acadoWorkspace.d[95]; +acadoVariables.x[102] += + acadoWorkspace.evGx[576]*acadoWorkspace.x[0] + acadoWorkspace.evGx[577]*acadoWorkspace.x[1] + acadoWorkspace.evGx[578]*acadoWorkspace.x[2] + acadoWorkspace.evGx[579]*acadoWorkspace.x[3] + acadoWorkspace.evGx[580]*acadoWorkspace.x[4] + acadoWorkspace.evGx[581]*acadoWorkspace.x[5] + acadoWorkspace.d[96]; +acadoVariables.x[103] += + acadoWorkspace.evGx[582]*acadoWorkspace.x[0] + acadoWorkspace.evGx[583]*acadoWorkspace.x[1] + acadoWorkspace.evGx[584]*acadoWorkspace.x[2] + acadoWorkspace.evGx[585]*acadoWorkspace.x[3] + acadoWorkspace.evGx[586]*acadoWorkspace.x[4] + acadoWorkspace.evGx[587]*acadoWorkspace.x[5] + acadoWorkspace.d[97]; +acadoVariables.x[104] += + acadoWorkspace.evGx[588]*acadoWorkspace.x[0] + acadoWorkspace.evGx[589]*acadoWorkspace.x[1] + acadoWorkspace.evGx[590]*acadoWorkspace.x[2] + acadoWorkspace.evGx[591]*acadoWorkspace.x[3] + acadoWorkspace.evGx[592]*acadoWorkspace.x[4] + acadoWorkspace.evGx[593]*acadoWorkspace.x[5] + acadoWorkspace.d[98]; +acadoVariables.x[105] += + acadoWorkspace.evGx[594]*acadoWorkspace.x[0] + acadoWorkspace.evGx[595]*acadoWorkspace.x[1] + acadoWorkspace.evGx[596]*acadoWorkspace.x[2] + acadoWorkspace.evGx[597]*acadoWorkspace.x[3] + acadoWorkspace.evGx[598]*acadoWorkspace.x[4] + acadoWorkspace.evGx[599]*acadoWorkspace.x[5] + acadoWorkspace.d[99]; +acadoVariables.x[106] += + acadoWorkspace.evGx[600]*acadoWorkspace.x[0] + acadoWorkspace.evGx[601]*acadoWorkspace.x[1] + acadoWorkspace.evGx[602]*acadoWorkspace.x[2] + acadoWorkspace.evGx[603]*acadoWorkspace.x[3] + acadoWorkspace.evGx[604]*acadoWorkspace.x[4] + acadoWorkspace.evGx[605]*acadoWorkspace.x[5] + acadoWorkspace.d[100]; +acadoVariables.x[107] += + acadoWorkspace.evGx[606]*acadoWorkspace.x[0] + acadoWorkspace.evGx[607]*acadoWorkspace.x[1] + acadoWorkspace.evGx[608]*acadoWorkspace.x[2] + acadoWorkspace.evGx[609]*acadoWorkspace.x[3] + acadoWorkspace.evGx[610]*acadoWorkspace.x[4] + acadoWorkspace.evGx[611]*acadoWorkspace.x[5] + acadoWorkspace.d[101]; +acadoVariables.x[108] += + acadoWorkspace.evGx[612]*acadoWorkspace.x[0] + acadoWorkspace.evGx[613]*acadoWorkspace.x[1] + acadoWorkspace.evGx[614]*acadoWorkspace.x[2] + acadoWorkspace.evGx[615]*acadoWorkspace.x[3] + acadoWorkspace.evGx[616]*acadoWorkspace.x[4] + acadoWorkspace.evGx[617]*acadoWorkspace.x[5] + acadoWorkspace.d[102]; +acadoVariables.x[109] += + acadoWorkspace.evGx[618]*acadoWorkspace.x[0] + acadoWorkspace.evGx[619]*acadoWorkspace.x[1] + acadoWorkspace.evGx[620]*acadoWorkspace.x[2] + acadoWorkspace.evGx[621]*acadoWorkspace.x[3] + acadoWorkspace.evGx[622]*acadoWorkspace.x[4] + acadoWorkspace.evGx[623]*acadoWorkspace.x[5] + acadoWorkspace.d[103]; +acadoVariables.x[110] += + acadoWorkspace.evGx[624]*acadoWorkspace.x[0] + acadoWorkspace.evGx[625]*acadoWorkspace.x[1] + acadoWorkspace.evGx[626]*acadoWorkspace.x[2] + acadoWorkspace.evGx[627]*acadoWorkspace.x[3] + acadoWorkspace.evGx[628]*acadoWorkspace.x[4] + acadoWorkspace.evGx[629]*acadoWorkspace.x[5] + acadoWorkspace.d[104]; +acadoVariables.x[111] += + acadoWorkspace.evGx[630]*acadoWorkspace.x[0] + acadoWorkspace.evGx[631]*acadoWorkspace.x[1] + acadoWorkspace.evGx[632]*acadoWorkspace.x[2] + acadoWorkspace.evGx[633]*acadoWorkspace.x[3] + acadoWorkspace.evGx[634]*acadoWorkspace.x[4] + acadoWorkspace.evGx[635]*acadoWorkspace.x[5] + acadoWorkspace.d[105]; +acadoVariables.x[112] += + acadoWorkspace.evGx[636]*acadoWorkspace.x[0] + acadoWorkspace.evGx[637]*acadoWorkspace.x[1] + acadoWorkspace.evGx[638]*acadoWorkspace.x[2] + acadoWorkspace.evGx[639]*acadoWorkspace.x[3] + acadoWorkspace.evGx[640]*acadoWorkspace.x[4] + acadoWorkspace.evGx[641]*acadoWorkspace.x[5] + acadoWorkspace.d[106]; +acadoVariables.x[113] += + acadoWorkspace.evGx[642]*acadoWorkspace.x[0] + acadoWorkspace.evGx[643]*acadoWorkspace.x[1] + acadoWorkspace.evGx[644]*acadoWorkspace.x[2] + acadoWorkspace.evGx[645]*acadoWorkspace.x[3] + acadoWorkspace.evGx[646]*acadoWorkspace.x[4] + acadoWorkspace.evGx[647]*acadoWorkspace.x[5] + acadoWorkspace.d[107]; +acadoVariables.x[114] += + acadoWorkspace.evGx[648]*acadoWorkspace.x[0] + acadoWorkspace.evGx[649]*acadoWorkspace.x[1] + acadoWorkspace.evGx[650]*acadoWorkspace.x[2] + acadoWorkspace.evGx[651]*acadoWorkspace.x[3] + acadoWorkspace.evGx[652]*acadoWorkspace.x[4] + acadoWorkspace.evGx[653]*acadoWorkspace.x[5] + acadoWorkspace.d[108]; +acadoVariables.x[115] += + acadoWorkspace.evGx[654]*acadoWorkspace.x[0] + acadoWorkspace.evGx[655]*acadoWorkspace.x[1] + acadoWorkspace.evGx[656]*acadoWorkspace.x[2] + acadoWorkspace.evGx[657]*acadoWorkspace.x[3] + acadoWorkspace.evGx[658]*acadoWorkspace.x[4] + acadoWorkspace.evGx[659]*acadoWorkspace.x[5] + acadoWorkspace.d[109]; +acadoVariables.x[116] += + acadoWorkspace.evGx[660]*acadoWorkspace.x[0] + acadoWorkspace.evGx[661]*acadoWorkspace.x[1] + acadoWorkspace.evGx[662]*acadoWorkspace.x[2] + acadoWorkspace.evGx[663]*acadoWorkspace.x[3] + acadoWorkspace.evGx[664]*acadoWorkspace.x[4] + acadoWorkspace.evGx[665]*acadoWorkspace.x[5] + acadoWorkspace.d[110]; +acadoVariables.x[117] += + acadoWorkspace.evGx[666]*acadoWorkspace.x[0] + acadoWorkspace.evGx[667]*acadoWorkspace.x[1] + acadoWorkspace.evGx[668]*acadoWorkspace.x[2] + acadoWorkspace.evGx[669]*acadoWorkspace.x[3] + acadoWorkspace.evGx[670]*acadoWorkspace.x[4] + acadoWorkspace.evGx[671]*acadoWorkspace.x[5] + acadoWorkspace.d[111]; +acadoVariables.x[118] += + acadoWorkspace.evGx[672]*acadoWorkspace.x[0] + acadoWorkspace.evGx[673]*acadoWorkspace.x[1] + acadoWorkspace.evGx[674]*acadoWorkspace.x[2] + acadoWorkspace.evGx[675]*acadoWorkspace.x[3] + acadoWorkspace.evGx[676]*acadoWorkspace.x[4] + acadoWorkspace.evGx[677]*acadoWorkspace.x[5] + acadoWorkspace.d[112]; +acadoVariables.x[119] += + acadoWorkspace.evGx[678]*acadoWorkspace.x[0] + acadoWorkspace.evGx[679]*acadoWorkspace.x[1] + acadoWorkspace.evGx[680]*acadoWorkspace.x[2] + acadoWorkspace.evGx[681]*acadoWorkspace.x[3] + acadoWorkspace.evGx[682]*acadoWorkspace.x[4] + acadoWorkspace.evGx[683]*acadoWorkspace.x[5] + acadoWorkspace.d[113]; +acadoVariables.x[120] += + acadoWorkspace.evGx[684]*acadoWorkspace.x[0] + acadoWorkspace.evGx[685]*acadoWorkspace.x[1] + acadoWorkspace.evGx[686]*acadoWorkspace.x[2] + acadoWorkspace.evGx[687]*acadoWorkspace.x[3] + acadoWorkspace.evGx[688]*acadoWorkspace.x[4] + acadoWorkspace.evGx[689]*acadoWorkspace.x[5] + acadoWorkspace.d[114]; +acadoVariables.x[121] += + acadoWorkspace.evGx[690]*acadoWorkspace.x[0] + acadoWorkspace.evGx[691]*acadoWorkspace.x[1] + acadoWorkspace.evGx[692]*acadoWorkspace.x[2] + acadoWorkspace.evGx[693]*acadoWorkspace.x[3] + acadoWorkspace.evGx[694]*acadoWorkspace.x[4] + acadoWorkspace.evGx[695]*acadoWorkspace.x[5] + acadoWorkspace.d[115]; +acadoVariables.x[122] += + acadoWorkspace.evGx[696]*acadoWorkspace.x[0] + acadoWorkspace.evGx[697]*acadoWorkspace.x[1] + acadoWorkspace.evGx[698]*acadoWorkspace.x[2] + acadoWorkspace.evGx[699]*acadoWorkspace.x[3] + acadoWorkspace.evGx[700]*acadoWorkspace.x[4] + acadoWorkspace.evGx[701]*acadoWorkspace.x[5] + acadoWorkspace.d[116]; +acadoVariables.x[123] += + acadoWorkspace.evGx[702]*acadoWorkspace.x[0] + acadoWorkspace.evGx[703]*acadoWorkspace.x[1] + acadoWorkspace.evGx[704]*acadoWorkspace.x[2] + acadoWorkspace.evGx[705]*acadoWorkspace.x[3] + acadoWorkspace.evGx[706]*acadoWorkspace.x[4] + acadoWorkspace.evGx[707]*acadoWorkspace.x[5] + acadoWorkspace.d[117]; +acadoVariables.x[124] += + acadoWorkspace.evGx[708]*acadoWorkspace.x[0] + acadoWorkspace.evGx[709]*acadoWorkspace.x[1] + acadoWorkspace.evGx[710]*acadoWorkspace.x[2] + acadoWorkspace.evGx[711]*acadoWorkspace.x[3] + acadoWorkspace.evGx[712]*acadoWorkspace.x[4] + acadoWorkspace.evGx[713]*acadoWorkspace.x[5] + acadoWorkspace.d[118]; +acadoVariables.x[125] += + acadoWorkspace.evGx[714]*acadoWorkspace.x[0] + acadoWorkspace.evGx[715]*acadoWorkspace.x[1] + acadoWorkspace.evGx[716]*acadoWorkspace.x[2] + acadoWorkspace.evGx[717]*acadoWorkspace.x[3] + acadoWorkspace.evGx[718]*acadoWorkspace.x[4] + acadoWorkspace.evGx[719]*acadoWorkspace.x[5] + acadoWorkspace.d[119]; + +acado_multEDu( acadoWorkspace.E, &(acadoWorkspace.x[ 6 ]), &(acadoVariables.x[ 6 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 6 ]), &(acadoWorkspace.x[ 6 ]), &(acadoVariables.x[ 12 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 12 ]), &(acadoWorkspace.x[ 7 ]), &(acadoVariables.x[ 12 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 18 ]), &(acadoWorkspace.x[ 6 ]), &(acadoVariables.x[ 18 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 24 ]), &(acadoWorkspace.x[ 7 ]), &(acadoVariables.x[ 18 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 30 ]), &(acadoWorkspace.x[ 8 ]), &(acadoVariables.x[ 18 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 36 ]), &(acadoWorkspace.x[ 6 ]), &(acadoVariables.x[ 24 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 42 ]), &(acadoWorkspace.x[ 7 ]), &(acadoVariables.x[ 24 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 48 ]), &(acadoWorkspace.x[ 8 ]), &(acadoVariables.x[ 24 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 54 ]), &(acadoWorkspace.x[ 9 ]), &(acadoVariables.x[ 24 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 60 ]), &(acadoWorkspace.x[ 6 ]), &(acadoVariables.x[ 30 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 66 ]), &(acadoWorkspace.x[ 7 ]), &(acadoVariables.x[ 30 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 72 ]), &(acadoWorkspace.x[ 8 ]), &(acadoVariables.x[ 30 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 78 ]), &(acadoWorkspace.x[ 9 ]), &(acadoVariables.x[ 30 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 84 ]), &(acadoWorkspace.x[ 10 ]), &(acadoVariables.x[ 30 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 90 ]), &(acadoWorkspace.x[ 6 ]), &(acadoVariables.x[ 36 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 96 ]), &(acadoWorkspace.x[ 7 ]), &(acadoVariables.x[ 36 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 102 ]), &(acadoWorkspace.x[ 8 ]), &(acadoVariables.x[ 36 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 108 ]), &(acadoWorkspace.x[ 9 ]), &(acadoVariables.x[ 36 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 114 ]), &(acadoWorkspace.x[ 10 ]), &(acadoVariables.x[ 36 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 120 ]), &(acadoWorkspace.x[ 11 ]), &(acadoVariables.x[ 36 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 126 ]), &(acadoWorkspace.x[ 6 ]), &(acadoVariables.x[ 42 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 132 ]), &(acadoWorkspace.x[ 7 ]), &(acadoVariables.x[ 42 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 138 ]), &(acadoWorkspace.x[ 8 ]), &(acadoVariables.x[ 42 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 144 ]), &(acadoWorkspace.x[ 9 ]), &(acadoVariables.x[ 42 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 150 ]), &(acadoWorkspace.x[ 10 ]), &(acadoVariables.x[ 42 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 156 ]), &(acadoWorkspace.x[ 11 ]), &(acadoVariables.x[ 42 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 162 ]), &(acadoWorkspace.x[ 12 ]), &(acadoVariables.x[ 42 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 168 ]), &(acadoWorkspace.x[ 6 ]), &(acadoVariables.x[ 48 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 174 ]), &(acadoWorkspace.x[ 7 ]), &(acadoVariables.x[ 48 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 180 ]), &(acadoWorkspace.x[ 8 ]), &(acadoVariables.x[ 48 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 186 ]), &(acadoWorkspace.x[ 9 ]), &(acadoVariables.x[ 48 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 192 ]), &(acadoWorkspace.x[ 10 ]), &(acadoVariables.x[ 48 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 198 ]), &(acadoWorkspace.x[ 11 ]), &(acadoVariables.x[ 48 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 204 ]), &(acadoWorkspace.x[ 12 ]), &(acadoVariables.x[ 48 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 210 ]), &(acadoWorkspace.x[ 13 ]), &(acadoVariables.x[ 48 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 216 ]), &(acadoWorkspace.x[ 6 ]), &(acadoVariables.x[ 54 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 222 ]), &(acadoWorkspace.x[ 7 ]), &(acadoVariables.x[ 54 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 228 ]), &(acadoWorkspace.x[ 8 ]), &(acadoVariables.x[ 54 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 234 ]), &(acadoWorkspace.x[ 9 ]), &(acadoVariables.x[ 54 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 240 ]), &(acadoWorkspace.x[ 10 ]), &(acadoVariables.x[ 54 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 246 ]), &(acadoWorkspace.x[ 11 ]), &(acadoVariables.x[ 54 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 252 ]), &(acadoWorkspace.x[ 12 ]), &(acadoVariables.x[ 54 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 258 ]), &(acadoWorkspace.x[ 13 ]), &(acadoVariables.x[ 54 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 264 ]), &(acadoWorkspace.x[ 14 ]), &(acadoVariables.x[ 54 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 270 ]), &(acadoWorkspace.x[ 6 ]), &(acadoVariables.x[ 60 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 276 ]), &(acadoWorkspace.x[ 7 ]), &(acadoVariables.x[ 60 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 282 ]), &(acadoWorkspace.x[ 8 ]), &(acadoVariables.x[ 60 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 288 ]), &(acadoWorkspace.x[ 9 ]), &(acadoVariables.x[ 60 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 294 ]), &(acadoWorkspace.x[ 10 ]), &(acadoVariables.x[ 60 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 300 ]), &(acadoWorkspace.x[ 11 ]), &(acadoVariables.x[ 60 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 306 ]), &(acadoWorkspace.x[ 12 ]), &(acadoVariables.x[ 60 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 312 ]), &(acadoWorkspace.x[ 13 ]), &(acadoVariables.x[ 60 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 318 ]), &(acadoWorkspace.x[ 14 ]), &(acadoVariables.x[ 60 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 324 ]), &(acadoWorkspace.x[ 15 ]), &(acadoVariables.x[ 60 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 330 ]), &(acadoWorkspace.x[ 6 ]), &(acadoVariables.x[ 66 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 336 ]), &(acadoWorkspace.x[ 7 ]), &(acadoVariables.x[ 66 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 342 ]), &(acadoWorkspace.x[ 8 ]), &(acadoVariables.x[ 66 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 348 ]), &(acadoWorkspace.x[ 9 ]), &(acadoVariables.x[ 66 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 354 ]), &(acadoWorkspace.x[ 10 ]), &(acadoVariables.x[ 66 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 360 ]), &(acadoWorkspace.x[ 11 ]), &(acadoVariables.x[ 66 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 366 ]), &(acadoWorkspace.x[ 12 ]), &(acadoVariables.x[ 66 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 372 ]), &(acadoWorkspace.x[ 13 ]), &(acadoVariables.x[ 66 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 378 ]), &(acadoWorkspace.x[ 14 ]), &(acadoVariables.x[ 66 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 384 ]), &(acadoWorkspace.x[ 15 ]), &(acadoVariables.x[ 66 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 390 ]), &(acadoWorkspace.x[ 16 ]), &(acadoVariables.x[ 66 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 396 ]), &(acadoWorkspace.x[ 6 ]), &(acadoVariables.x[ 72 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 402 ]), &(acadoWorkspace.x[ 7 ]), &(acadoVariables.x[ 72 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 408 ]), &(acadoWorkspace.x[ 8 ]), &(acadoVariables.x[ 72 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 414 ]), &(acadoWorkspace.x[ 9 ]), &(acadoVariables.x[ 72 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 420 ]), &(acadoWorkspace.x[ 10 ]), &(acadoVariables.x[ 72 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 426 ]), &(acadoWorkspace.x[ 11 ]), &(acadoVariables.x[ 72 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 432 ]), &(acadoWorkspace.x[ 12 ]), &(acadoVariables.x[ 72 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 438 ]), &(acadoWorkspace.x[ 13 ]), &(acadoVariables.x[ 72 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 444 ]), &(acadoWorkspace.x[ 14 ]), &(acadoVariables.x[ 72 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 450 ]), &(acadoWorkspace.x[ 15 ]), &(acadoVariables.x[ 72 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 456 ]), &(acadoWorkspace.x[ 16 ]), &(acadoVariables.x[ 72 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 462 ]), &(acadoWorkspace.x[ 17 ]), &(acadoVariables.x[ 72 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 468 ]), &(acadoWorkspace.x[ 6 ]), &(acadoVariables.x[ 78 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 474 ]), &(acadoWorkspace.x[ 7 ]), &(acadoVariables.x[ 78 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 480 ]), &(acadoWorkspace.x[ 8 ]), &(acadoVariables.x[ 78 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 486 ]), &(acadoWorkspace.x[ 9 ]), &(acadoVariables.x[ 78 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 492 ]), &(acadoWorkspace.x[ 10 ]), &(acadoVariables.x[ 78 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 498 ]), &(acadoWorkspace.x[ 11 ]), &(acadoVariables.x[ 78 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 504 ]), &(acadoWorkspace.x[ 12 ]), &(acadoVariables.x[ 78 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 510 ]), &(acadoWorkspace.x[ 13 ]), &(acadoVariables.x[ 78 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 516 ]), &(acadoWorkspace.x[ 14 ]), &(acadoVariables.x[ 78 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 522 ]), &(acadoWorkspace.x[ 15 ]), &(acadoVariables.x[ 78 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 528 ]), &(acadoWorkspace.x[ 16 ]), &(acadoVariables.x[ 78 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 534 ]), &(acadoWorkspace.x[ 17 ]), &(acadoVariables.x[ 78 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 540 ]), &(acadoWorkspace.x[ 18 ]), &(acadoVariables.x[ 78 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 546 ]), &(acadoWorkspace.x[ 6 ]), &(acadoVariables.x[ 84 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 552 ]), &(acadoWorkspace.x[ 7 ]), &(acadoVariables.x[ 84 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 558 ]), &(acadoWorkspace.x[ 8 ]), &(acadoVariables.x[ 84 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 564 ]), &(acadoWorkspace.x[ 9 ]), &(acadoVariables.x[ 84 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 570 ]), &(acadoWorkspace.x[ 10 ]), &(acadoVariables.x[ 84 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 576 ]), &(acadoWorkspace.x[ 11 ]), &(acadoVariables.x[ 84 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 582 ]), &(acadoWorkspace.x[ 12 ]), &(acadoVariables.x[ 84 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 588 ]), &(acadoWorkspace.x[ 13 ]), &(acadoVariables.x[ 84 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 594 ]), &(acadoWorkspace.x[ 14 ]), &(acadoVariables.x[ 84 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 600 ]), &(acadoWorkspace.x[ 15 ]), &(acadoVariables.x[ 84 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 606 ]), &(acadoWorkspace.x[ 16 ]), &(acadoVariables.x[ 84 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 612 ]), &(acadoWorkspace.x[ 17 ]), &(acadoVariables.x[ 84 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 618 ]), &(acadoWorkspace.x[ 18 ]), &(acadoVariables.x[ 84 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 624 ]), &(acadoWorkspace.x[ 19 ]), &(acadoVariables.x[ 84 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 630 ]), &(acadoWorkspace.x[ 6 ]), &(acadoVariables.x[ 90 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 636 ]), &(acadoWorkspace.x[ 7 ]), &(acadoVariables.x[ 90 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 642 ]), &(acadoWorkspace.x[ 8 ]), &(acadoVariables.x[ 90 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 648 ]), &(acadoWorkspace.x[ 9 ]), &(acadoVariables.x[ 90 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 654 ]), &(acadoWorkspace.x[ 10 ]), &(acadoVariables.x[ 90 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 660 ]), &(acadoWorkspace.x[ 11 ]), &(acadoVariables.x[ 90 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 666 ]), &(acadoWorkspace.x[ 12 ]), &(acadoVariables.x[ 90 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 672 ]), &(acadoWorkspace.x[ 13 ]), &(acadoVariables.x[ 90 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 678 ]), &(acadoWorkspace.x[ 14 ]), &(acadoVariables.x[ 90 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 684 ]), &(acadoWorkspace.x[ 15 ]), &(acadoVariables.x[ 90 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 690 ]), &(acadoWorkspace.x[ 16 ]), &(acadoVariables.x[ 90 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 696 ]), &(acadoWorkspace.x[ 17 ]), &(acadoVariables.x[ 90 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 702 ]), &(acadoWorkspace.x[ 18 ]), &(acadoVariables.x[ 90 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 708 ]), &(acadoWorkspace.x[ 19 ]), &(acadoVariables.x[ 90 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 714 ]), &(acadoWorkspace.x[ 20 ]), &(acadoVariables.x[ 90 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 720 ]), &(acadoWorkspace.x[ 6 ]), &(acadoVariables.x[ 96 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 726 ]), &(acadoWorkspace.x[ 7 ]), &(acadoVariables.x[ 96 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 732 ]), &(acadoWorkspace.x[ 8 ]), &(acadoVariables.x[ 96 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 738 ]), &(acadoWorkspace.x[ 9 ]), &(acadoVariables.x[ 96 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 744 ]), &(acadoWorkspace.x[ 10 ]), &(acadoVariables.x[ 96 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 750 ]), &(acadoWorkspace.x[ 11 ]), &(acadoVariables.x[ 96 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 756 ]), &(acadoWorkspace.x[ 12 ]), &(acadoVariables.x[ 96 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 762 ]), &(acadoWorkspace.x[ 13 ]), &(acadoVariables.x[ 96 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 768 ]), &(acadoWorkspace.x[ 14 ]), &(acadoVariables.x[ 96 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 774 ]), &(acadoWorkspace.x[ 15 ]), &(acadoVariables.x[ 96 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 780 ]), &(acadoWorkspace.x[ 16 ]), &(acadoVariables.x[ 96 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 786 ]), &(acadoWorkspace.x[ 17 ]), &(acadoVariables.x[ 96 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 792 ]), &(acadoWorkspace.x[ 18 ]), &(acadoVariables.x[ 96 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 798 ]), &(acadoWorkspace.x[ 19 ]), &(acadoVariables.x[ 96 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 804 ]), &(acadoWorkspace.x[ 20 ]), &(acadoVariables.x[ 96 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 810 ]), &(acadoWorkspace.x[ 21 ]), &(acadoVariables.x[ 96 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 816 ]), &(acadoWorkspace.x[ 6 ]), &(acadoVariables.x[ 102 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 822 ]), &(acadoWorkspace.x[ 7 ]), &(acadoVariables.x[ 102 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 828 ]), &(acadoWorkspace.x[ 8 ]), &(acadoVariables.x[ 102 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 834 ]), &(acadoWorkspace.x[ 9 ]), &(acadoVariables.x[ 102 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 840 ]), &(acadoWorkspace.x[ 10 ]), &(acadoVariables.x[ 102 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 846 ]), &(acadoWorkspace.x[ 11 ]), &(acadoVariables.x[ 102 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 852 ]), &(acadoWorkspace.x[ 12 ]), &(acadoVariables.x[ 102 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 858 ]), &(acadoWorkspace.x[ 13 ]), &(acadoVariables.x[ 102 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 864 ]), &(acadoWorkspace.x[ 14 ]), &(acadoVariables.x[ 102 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 870 ]), &(acadoWorkspace.x[ 15 ]), &(acadoVariables.x[ 102 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 876 ]), &(acadoWorkspace.x[ 16 ]), &(acadoVariables.x[ 102 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 882 ]), &(acadoWorkspace.x[ 17 ]), &(acadoVariables.x[ 102 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 888 ]), &(acadoWorkspace.x[ 18 ]), &(acadoVariables.x[ 102 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 894 ]), &(acadoWorkspace.x[ 19 ]), &(acadoVariables.x[ 102 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 900 ]), &(acadoWorkspace.x[ 20 ]), &(acadoVariables.x[ 102 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 906 ]), &(acadoWorkspace.x[ 21 ]), &(acadoVariables.x[ 102 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 912 ]), &(acadoWorkspace.x[ 22 ]), &(acadoVariables.x[ 102 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 918 ]), &(acadoWorkspace.x[ 6 ]), &(acadoVariables.x[ 108 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 924 ]), &(acadoWorkspace.x[ 7 ]), &(acadoVariables.x[ 108 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 930 ]), &(acadoWorkspace.x[ 8 ]), &(acadoVariables.x[ 108 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 936 ]), &(acadoWorkspace.x[ 9 ]), &(acadoVariables.x[ 108 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 942 ]), &(acadoWorkspace.x[ 10 ]), &(acadoVariables.x[ 108 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 948 ]), &(acadoWorkspace.x[ 11 ]), &(acadoVariables.x[ 108 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 954 ]), &(acadoWorkspace.x[ 12 ]), &(acadoVariables.x[ 108 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 960 ]), &(acadoWorkspace.x[ 13 ]), &(acadoVariables.x[ 108 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 966 ]), &(acadoWorkspace.x[ 14 ]), &(acadoVariables.x[ 108 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 972 ]), &(acadoWorkspace.x[ 15 ]), &(acadoVariables.x[ 108 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 978 ]), &(acadoWorkspace.x[ 16 ]), &(acadoVariables.x[ 108 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 984 ]), &(acadoWorkspace.x[ 17 ]), &(acadoVariables.x[ 108 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 990 ]), &(acadoWorkspace.x[ 18 ]), &(acadoVariables.x[ 108 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 996 ]), &(acadoWorkspace.x[ 19 ]), &(acadoVariables.x[ 108 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 1002 ]), &(acadoWorkspace.x[ 20 ]), &(acadoVariables.x[ 108 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 1008 ]), &(acadoWorkspace.x[ 21 ]), &(acadoVariables.x[ 108 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 1014 ]), &(acadoWorkspace.x[ 22 ]), &(acadoVariables.x[ 108 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 1020 ]), &(acadoWorkspace.x[ 23 ]), &(acadoVariables.x[ 108 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 1026 ]), &(acadoWorkspace.x[ 6 ]), &(acadoVariables.x[ 114 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 1032 ]), &(acadoWorkspace.x[ 7 ]), &(acadoVariables.x[ 114 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 1038 ]), &(acadoWorkspace.x[ 8 ]), &(acadoVariables.x[ 114 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 1044 ]), &(acadoWorkspace.x[ 9 ]), &(acadoVariables.x[ 114 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 1050 ]), &(acadoWorkspace.x[ 10 ]), &(acadoVariables.x[ 114 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 1056 ]), &(acadoWorkspace.x[ 11 ]), &(acadoVariables.x[ 114 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 1062 ]), &(acadoWorkspace.x[ 12 ]), &(acadoVariables.x[ 114 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 1068 ]), &(acadoWorkspace.x[ 13 ]), &(acadoVariables.x[ 114 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 1074 ]), &(acadoWorkspace.x[ 14 ]), &(acadoVariables.x[ 114 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 1080 ]), &(acadoWorkspace.x[ 15 ]), &(acadoVariables.x[ 114 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 1086 ]), &(acadoWorkspace.x[ 16 ]), &(acadoVariables.x[ 114 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 1092 ]), &(acadoWorkspace.x[ 17 ]), &(acadoVariables.x[ 114 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 1098 ]), &(acadoWorkspace.x[ 18 ]), &(acadoVariables.x[ 114 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 1104 ]), &(acadoWorkspace.x[ 19 ]), &(acadoVariables.x[ 114 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 1110 ]), &(acadoWorkspace.x[ 20 ]), &(acadoVariables.x[ 114 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 1116 ]), &(acadoWorkspace.x[ 21 ]), &(acadoVariables.x[ 114 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 1122 ]), &(acadoWorkspace.x[ 22 ]), &(acadoVariables.x[ 114 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 1128 ]), &(acadoWorkspace.x[ 23 ]), &(acadoVariables.x[ 114 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 1134 ]), &(acadoWorkspace.x[ 24 ]), &(acadoVariables.x[ 114 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 1140 ]), &(acadoWorkspace.x[ 6 ]), &(acadoVariables.x[ 120 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 1146 ]), &(acadoWorkspace.x[ 7 ]), &(acadoVariables.x[ 120 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 1152 ]), &(acadoWorkspace.x[ 8 ]), &(acadoVariables.x[ 120 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 1158 ]), &(acadoWorkspace.x[ 9 ]), &(acadoVariables.x[ 120 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 1164 ]), &(acadoWorkspace.x[ 10 ]), &(acadoVariables.x[ 120 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 1170 ]), &(acadoWorkspace.x[ 11 ]), &(acadoVariables.x[ 120 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 1176 ]), &(acadoWorkspace.x[ 12 ]), &(acadoVariables.x[ 120 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 1182 ]), &(acadoWorkspace.x[ 13 ]), &(acadoVariables.x[ 120 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 1188 ]), &(acadoWorkspace.x[ 14 ]), &(acadoVariables.x[ 120 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 1194 ]), &(acadoWorkspace.x[ 15 ]), &(acadoVariables.x[ 120 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 1200 ]), &(acadoWorkspace.x[ 16 ]), &(acadoVariables.x[ 120 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 1206 ]), &(acadoWorkspace.x[ 17 ]), &(acadoVariables.x[ 120 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 1212 ]), &(acadoWorkspace.x[ 18 ]), &(acadoVariables.x[ 120 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 1218 ]), &(acadoWorkspace.x[ 19 ]), &(acadoVariables.x[ 120 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 1224 ]), &(acadoWorkspace.x[ 20 ]), &(acadoVariables.x[ 120 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 1230 ]), &(acadoWorkspace.x[ 21 ]), &(acadoVariables.x[ 120 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 1236 ]), &(acadoWorkspace.x[ 22 ]), &(acadoVariables.x[ 120 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 1242 ]), &(acadoWorkspace.x[ 23 ]), &(acadoVariables.x[ 120 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 1248 ]), &(acadoWorkspace.x[ 24 ]), &(acadoVariables.x[ 120 ]) ); +acado_multEDu( &(acadoWorkspace.E[ 1254 ]), &(acadoWorkspace.x[ 25 ]), &(acadoVariables.x[ 120 ]) ); +} + +int acado_preparationStep(double TR) +{ +int ret; + +ret = acado_modelSimulation(); +acado_evaluateObjective(TR); +acado_condensePrep( ); +return ret; +} + +int acado_feedbackStep( ) +{ +int tmp; + +acado_condenseFdb( ); + +tmp = acado_solve( ); + +acado_expand( ); +return tmp; +} + +int acado_initializeSolver( ) +{ +int ret; + +/* This is a function which must be called once before any other function call! */ + + +ret = 0; + +memset(&acadoWorkspace, 0, sizeof( acadoWorkspace )); +return ret; +} + +void acado_initializeNodesByForwardSimulation( ) +{ +int index; +for (index = 0; index < 20; ++index) +{ +acadoWorkspace.state[0] = acadoVariables.x[index * 6]; +acadoWorkspace.state[1] = acadoVariables.x[index * 6 + 1]; +acadoWorkspace.state[2] = acadoVariables.x[index * 6 + 2]; +acadoWorkspace.state[3] = acadoVariables.x[index * 6 + 3]; +acadoWorkspace.state[4] = acadoVariables.x[index * 6 + 4]; +acadoWorkspace.state[5] = acadoVariables.x[index * 6 + 5]; +acadoWorkspace.state[48] = acadoVariables.u[index]; +acadoWorkspace.state[49] = acadoVariables.od[index * 2]; +acadoWorkspace.state[50] = acadoVariables.od[index * 2 + 1]; + +acado_integrate(acadoWorkspace.state, index == 0, index); + +acadoVariables.x[index * 6 + 6] = acadoWorkspace.state[0]; +acadoVariables.x[index * 6 + 7] = acadoWorkspace.state[1]; +acadoVariables.x[index * 6 + 8] = acadoWorkspace.state[2]; +acadoVariables.x[index * 6 + 9] = acadoWorkspace.state[3]; +acadoVariables.x[index * 6 + 10] = acadoWorkspace.state[4]; +acadoVariables.x[index * 6 + 11] = acadoWorkspace.state[5]; +} +} + +void acado_shiftStates( int strategy, real_t* const xEnd, real_t* const uEnd ) +{ +int index; +for (index = 0; index < 20; ++index) +{ +acadoVariables.x[index * 6] = acadoVariables.x[index * 6 + 6]; +acadoVariables.x[index * 6 + 1] = acadoVariables.x[index * 6 + 7]; +acadoVariables.x[index * 6 + 2] = acadoVariables.x[index * 6 + 8]; +acadoVariables.x[index * 6 + 3] = acadoVariables.x[index * 6 + 9]; +acadoVariables.x[index * 6 + 4] = acadoVariables.x[index * 6 + 10]; +acadoVariables.x[index * 6 + 5] = acadoVariables.x[index * 6 + 11]; +} + +if (strategy == 1 && xEnd != 0) +{ +acadoVariables.x[120] = xEnd[0]; +acadoVariables.x[121] = xEnd[1]; +acadoVariables.x[122] = xEnd[2]; +acadoVariables.x[123] = xEnd[3]; +acadoVariables.x[124] = xEnd[4]; +acadoVariables.x[125] = xEnd[5]; +} +else if (strategy == 2) +{ +acadoWorkspace.state[0] = acadoVariables.x[120]; +acadoWorkspace.state[1] = acadoVariables.x[121]; +acadoWorkspace.state[2] = acadoVariables.x[122]; +acadoWorkspace.state[3] = acadoVariables.x[123]; +acadoWorkspace.state[4] = acadoVariables.x[124]; +acadoWorkspace.state[5] = acadoVariables.x[125]; +if (uEnd != 0) +{ +acadoWorkspace.state[48] = uEnd[0]; +} +else +{ +acadoWorkspace.state[48] = acadoVariables.u[19]; +} +acadoWorkspace.state[49] = acadoVariables.od[40]; +acadoWorkspace.state[50] = acadoVariables.od[41]; + +acado_integrate(acadoWorkspace.state, 1, 19); + +acadoVariables.x[120] = acadoWorkspace.state[0]; +acadoVariables.x[121] = acadoWorkspace.state[1]; +acadoVariables.x[122] = acadoWorkspace.state[2]; +acadoVariables.x[123] = acadoWorkspace.state[3]; +acadoVariables.x[124] = acadoWorkspace.state[4]; +acadoVariables.x[125] = acadoWorkspace.state[5]; +} +} + +void acado_shiftControls( real_t* const uEnd ) +{ +int index; +for (index = 0; index < 19; ++index) +{ +acadoVariables.u[index] = acadoVariables.u[index + 1]; +} + +if (uEnd != 0) +{ +acadoVariables.u[19] = uEnd[0]; +} +} + +real_t acado_getKKT( ) +{ +real_t kkt; + +int index; +real_t prd; + +kkt = + acadoWorkspace.g[0]*acadoWorkspace.x[0] + acadoWorkspace.g[1]*acadoWorkspace.x[1] + acadoWorkspace.g[2]*acadoWorkspace.x[2] + acadoWorkspace.g[3]*acadoWorkspace.x[3] + acadoWorkspace.g[4]*acadoWorkspace.x[4] + acadoWorkspace.g[5]*acadoWorkspace.x[5] + acadoWorkspace.g[6]*acadoWorkspace.x[6] + acadoWorkspace.g[7]*acadoWorkspace.x[7] + acadoWorkspace.g[8]*acadoWorkspace.x[8] + acadoWorkspace.g[9]*acadoWorkspace.x[9] + acadoWorkspace.g[10]*acadoWorkspace.x[10] + acadoWorkspace.g[11]*acadoWorkspace.x[11] + acadoWorkspace.g[12]*acadoWorkspace.x[12] + acadoWorkspace.g[13]*acadoWorkspace.x[13] + acadoWorkspace.g[14]*acadoWorkspace.x[14] + acadoWorkspace.g[15]*acadoWorkspace.x[15] + acadoWorkspace.g[16]*acadoWorkspace.x[16] + acadoWorkspace.g[17]*acadoWorkspace.x[17] + acadoWorkspace.g[18]*acadoWorkspace.x[18] + acadoWorkspace.g[19]*acadoWorkspace.x[19] + acadoWorkspace.g[20]*acadoWorkspace.x[20] + acadoWorkspace.g[21]*acadoWorkspace.x[21] + acadoWorkspace.g[22]*acadoWorkspace.x[22] + acadoWorkspace.g[23]*acadoWorkspace.x[23] + acadoWorkspace.g[24]*acadoWorkspace.x[24] + acadoWorkspace.g[25]*acadoWorkspace.x[25]; +kkt = fabs( kkt ); +for (index = 0; index < 26; ++index) +{ +prd = acadoWorkspace.y[index]; +if (prd > 1e-12) +kkt += fabs(acadoWorkspace.lb[index] * prd); +else if (prd < -1e-12) +kkt += fabs(acadoWorkspace.ub[index] * prd); +} +for (index = 0; index < 20; ++index) +{ +prd = acadoWorkspace.y[index + 26]; +if (prd > 1e-12) +kkt += fabs(acadoWorkspace.lbA[index] * prd); +else if (prd < -1e-12) +kkt += fabs(acadoWorkspace.ubA[index] * prd); +} +return kkt; +} + +real_t acado_getObjective(double TR) +{ +real_t objVal; + +int lRun1; +/** Row vector of size: 4 */ +real_t tmpDy[ 4 ]; + +/** Row vector of size: 3 */ +real_t tmpDyN[ 3 ]; + +for (lRun1 = 0; lRun1 < 20; ++lRun1) +{ +acadoWorkspace.objValueIn[0] = acadoVariables.x[lRun1 * 6]; +acadoWorkspace.objValueIn[1] = acadoVariables.x[lRun1 * 6 + 1]; +acadoWorkspace.objValueIn[2] = acadoVariables.x[lRun1 * 6 + 2]; +acadoWorkspace.objValueIn[3] = acadoVariables.x[lRun1 * 6 + 3]; +acadoWorkspace.objValueIn[4] = acadoVariables.x[lRun1 * 6 + 4]; +acadoWorkspace.objValueIn[5] = acadoVariables.x[lRun1 * 6 + 5]; +acadoWorkspace.objValueIn[6] = acadoVariables.u[lRun1]; +acadoWorkspace.objValueIn[7] = acadoVariables.od[lRun1 * 2]; +acadoWorkspace.objValueIn[8] = acadoVariables.od[lRun1 * 2 + 1]; + +acado_evaluateLSQ( acadoWorkspace.objValueIn, acadoWorkspace.objValueOut, TR ); +acadoWorkspace.Dy[lRun1 * 4] = acadoWorkspace.objValueOut[0] - acadoVariables.y[lRun1 * 4]; +acadoWorkspace.Dy[lRun1 * 4 + 1] = acadoWorkspace.objValueOut[1] - acadoVariables.y[lRun1 * 4 + 1]; +acadoWorkspace.Dy[lRun1 * 4 + 2] = acadoWorkspace.objValueOut[2] - acadoVariables.y[lRun1 * 4 + 2]; +acadoWorkspace.Dy[lRun1 * 4 + 3] = acadoWorkspace.objValueOut[3] - acadoVariables.y[lRun1 * 4 + 3]; +} +acadoWorkspace.objValueIn[0] = acadoVariables.x[120]; +acadoWorkspace.objValueIn[1] = acadoVariables.x[121]; +acadoWorkspace.objValueIn[2] = acadoVariables.x[122]; +acadoWorkspace.objValueIn[3] = acadoVariables.x[123]; +acadoWorkspace.objValueIn[4] = acadoVariables.x[124]; +acadoWorkspace.objValueIn[5] = acadoVariables.x[125]; +acadoWorkspace.objValueIn[6] = acadoVariables.od[40]; +acadoWorkspace.objValueIn[7] = acadoVariables.od[41]; +acado_evaluateLSQEndTerm( acadoWorkspace.objValueIn, acadoWorkspace.objValueOut, TR ); +acadoWorkspace.DyN[0] = acadoWorkspace.objValueOut[0] - acadoVariables.yN[0]; +acadoWorkspace.DyN[1] = acadoWorkspace.objValueOut[1] - acadoVariables.yN[1]; +acadoWorkspace.DyN[2] = acadoWorkspace.objValueOut[2] - acadoVariables.yN[2]; +objVal = 0.0000000000000000e+00; +for (lRun1 = 0; lRun1 < 20; ++lRun1) +{ +tmpDy[0] = + acadoWorkspace.Dy[lRun1 * 4]*acadoVariables.W[lRun1 * 16] + acadoWorkspace.Dy[lRun1 * 4 + 1]*acadoVariables.W[lRun1 * 16 + 4] + acadoWorkspace.Dy[lRun1 * 4 + 2]*acadoVariables.W[lRun1 * 16 + 8] + acadoWorkspace.Dy[lRun1 * 4 + 3]*acadoVariables.W[lRun1 * 16 + 12]; +tmpDy[1] = + acadoWorkspace.Dy[lRun1 * 4]*acadoVariables.W[lRun1 * 16 + 1] + acadoWorkspace.Dy[lRun1 * 4 + 1]*acadoVariables.W[lRun1 * 16 + 5] + acadoWorkspace.Dy[lRun1 * 4 + 2]*acadoVariables.W[lRun1 * 16 + 9] + acadoWorkspace.Dy[lRun1 * 4 + 3]*acadoVariables.W[lRun1 * 16 + 13]; +tmpDy[2] = + acadoWorkspace.Dy[lRun1 * 4]*acadoVariables.W[lRun1 * 16 + 2] + acadoWorkspace.Dy[lRun1 * 4 + 1]*acadoVariables.W[lRun1 * 16 + 6] + acadoWorkspace.Dy[lRun1 * 4 + 2]*acadoVariables.W[lRun1 * 16 + 10] + acadoWorkspace.Dy[lRun1 * 4 + 3]*acadoVariables.W[lRun1 * 16 + 14]; +tmpDy[3] = + acadoWorkspace.Dy[lRun1 * 4]*acadoVariables.W[lRun1 * 16 + 3] + acadoWorkspace.Dy[lRun1 * 4 + 1]*acadoVariables.W[lRun1 * 16 + 7] + acadoWorkspace.Dy[lRun1 * 4 + 2]*acadoVariables.W[lRun1 * 16 + 11] + acadoWorkspace.Dy[lRun1 * 4 + 3]*acadoVariables.W[lRun1 * 16 + 15]; +objVal += + acadoWorkspace.Dy[lRun1 * 4]*tmpDy[0] + acadoWorkspace.Dy[lRun1 * 4 + 1]*tmpDy[1] + acadoWorkspace.Dy[lRun1 * 4 + 2]*tmpDy[2] + acadoWorkspace.Dy[lRun1 * 4 + 3]*tmpDy[3]; +} + +tmpDyN[0] = + acadoWorkspace.DyN[0]*acadoVariables.WN[0] + acadoWorkspace.DyN[1]*acadoVariables.WN[3] + acadoWorkspace.DyN[2]*acadoVariables.WN[6]; +tmpDyN[1] = + acadoWorkspace.DyN[0]*acadoVariables.WN[1] + acadoWorkspace.DyN[1]*acadoVariables.WN[4] + acadoWorkspace.DyN[2]*acadoVariables.WN[7]; +tmpDyN[2] = + acadoWorkspace.DyN[0]*acadoVariables.WN[2] + acadoWorkspace.DyN[1]*acadoVariables.WN[5] + acadoWorkspace.DyN[2]*acadoVariables.WN[8]; +objVal += + acadoWorkspace.DyN[0]*tmpDyN[0] + acadoWorkspace.DyN[1]*tmpDyN[1] + acadoWorkspace.DyN[2]*tmpDyN[2]; + +objVal *= 0.5; +return objVal; +} + diff --git a/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_solver.d b/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_solver.d new file mode 100644 index 00000000000000..2dae4b94389e48 --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_solver.d @@ -0,0 +1,3 @@ +lib_mpc_export/acado_solver.o: lib_mpc_export/acado_solver.c \ + lib_mpc_export/acado_common.h \ + lib_mpc_export/acado_qpoases_interface.hpp diff --git a/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_solver.o b/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_solver.o new file mode 100644 index 00000000000000..b53d2fe76f5a64 Binary files /dev/null and b/selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/acado_solver.o differ diff --git a/selfdrive/controls/lib/longitudinal_mpc/lib_qp/Bounds.d b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/Bounds.d new file mode 100644 index 00000000000000..752ec5e9f3c686 --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/Bounds.d @@ -0,0 +1,14 @@ +lib_qp/Bounds.o: ../../../../phonelibs/qpoases/SRC/Bounds.cpp \ + ../../../../phonelibs/qpoases/INCLUDE/Bounds.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/SubjectTo.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Indexlist.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Utils.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/MessageHandling.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Types.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Constants.hpp \ + lib_mpc_export/acado_qpoases_interface.hpp \ + ../../../../phonelibs/qpoases/SRC/MessageHandling.ipp \ + ../../../../phonelibs/qpoases/SRC/Utils.ipp \ + ../../../../phonelibs/qpoases/SRC/Indexlist.ipp \ + ../../../../phonelibs/qpoases/SRC/SubjectTo.ipp \ + ../../../../phonelibs/qpoases/SRC/Bounds.ipp diff --git a/selfdrive/controls/lib/longitudinal_mpc/lib_qp/Bounds.o b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/Bounds.o new file mode 100644 index 00000000000000..b770e3240eec05 Binary files /dev/null and b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/Bounds.o differ diff --git a/selfdrive/controls/lib/longitudinal_mpc/lib_qp/Constraints.d b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/Constraints.d new file mode 100644 index 00000000000000..60295bc07b3dc9 --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/Constraints.d @@ -0,0 +1,14 @@ +lib_qp/Constraints.o: ../../../../phonelibs/qpoases/SRC/Constraints.cpp \ + ../../../../phonelibs/qpoases/INCLUDE/Constraints.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/SubjectTo.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Indexlist.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Utils.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/MessageHandling.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Types.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Constants.hpp \ + lib_mpc_export/acado_qpoases_interface.hpp \ + ../../../../phonelibs/qpoases/SRC/MessageHandling.ipp \ + ../../../../phonelibs/qpoases/SRC/Utils.ipp \ + ../../../../phonelibs/qpoases/SRC/Indexlist.ipp \ + ../../../../phonelibs/qpoases/SRC/SubjectTo.ipp \ + ../../../../phonelibs/qpoases/SRC/Constraints.ipp diff --git a/selfdrive/controls/lib/longitudinal_mpc/lib_qp/Constraints.o b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/Constraints.o new file mode 100644 index 00000000000000..4d47fe901918b4 Binary files /dev/null and b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/Constraints.o differ diff --git a/selfdrive/controls/lib/longitudinal_mpc/lib_qp/CyclingManager.d b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/CyclingManager.d new file mode 100644 index 00000000000000..24145d8ed318e1 --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/CyclingManager.d @@ -0,0 +1,11 @@ +lib_qp/CyclingManager.o: \ + ../../../../phonelibs/qpoases/SRC/CyclingManager.cpp \ + ../../../../phonelibs/qpoases/INCLUDE/CyclingManager.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Utils.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/MessageHandling.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Types.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Constants.hpp \ + lib_mpc_export/acado_qpoases_interface.hpp \ + ../../../../phonelibs/qpoases/SRC/MessageHandling.ipp \ + ../../../../phonelibs/qpoases/SRC/Utils.ipp \ + ../../../../phonelibs/qpoases/SRC/CyclingManager.ipp diff --git a/selfdrive/controls/lib/longitudinal_mpc/lib_qp/CyclingManager.o b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/CyclingManager.o new file mode 100644 index 00000000000000..ec3e83d112b8c5 Binary files /dev/null and b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/CyclingManager.o differ diff --git a/selfdrive/controls/lib/longitudinal_mpc/lib_qp/EXTRAS/SolutionAnalysis.d b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/EXTRAS/SolutionAnalysis.d new file mode 100644 index 00000000000000..77c09376eef96e --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/EXTRAS/SolutionAnalysis.d @@ -0,0 +1,24 @@ +lib_qp/EXTRAS/SolutionAnalysis.o: \ + ../../../../phonelibs/qpoases/SRC/EXTRAS/SolutionAnalysis.cpp \ + ../../../../phonelibs/qpoases/INCLUDE/EXTRAS/SolutionAnalysis.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/QProblem.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/QProblemB.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Bounds.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/SubjectTo.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Indexlist.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Utils.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/MessageHandling.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Types.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Constants.hpp \ + lib_mpc_export/acado_qpoases_interface.hpp \ + ../../../../phonelibs/qpoases/SRC/MessageHandling.ipp \ + ../../../../phonelibs/qpoases/SRC/Utils.ipp \ + ../../../../phonelibs/qpoases/SRC/Indexlist.ipp \ + ../../../../phonelibs/qpoases/SRC/SubjectTo.ipp \ + ../../../../phonelibs/qpoases/SRC/Bounds.ipp \ + ../../../../phonelibs/qpoases/SRC/QProblemB.ipp \ + ../../../../phonelibs/qpoases/INCLUDE/Constraints.hpp \ + ../../../../phonelibs/qpoases/SRC/Constraints.ipp \ + ../../../../phonelibs/qpoases/INCLUDE/CyclingManager.hpp \ + ../../../../phonelibs/qpoases/SRC/CyclingManager.ipp \ + ../../../../phonelibs/qpoases/SRC/QProblem.ipp diff --git a/selfdrive/controls/lib/longitudinal_mpc/lib_qp/EXTRAS/SolutionAnalysis.o b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/EXTRAS/SolutionAnalysis.o new file mode 100644 index 00000000000000..71cbd4ce3aa5af Binary files /dev/null and b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/EXTRAS/SolutionAnalysis.o differ diff --git a/selfdrive/controls/lib/longitudinal_mpc/lib_qp/Indexlist.d b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/Indexlist.d new file mode 100644 index 00000000000000..6ead64cb9d8ee6 --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/Indexlist.d @@ -0,0 +1,10 @@ +lib_qp/Indexlist.o: ../../../../phonelibs/qpoases/SRC/Indexlist.cpp \ + ../../../../phonelibs/qpoases/INCLUDE/Indexlist.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Utils.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/MessageHandling.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Types.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Constants.hpp \ + lib_mpc_export/acado_qpoases_interface.hpp \ + ../../../../phonelibs/qpoases/SRC/MessageHandling.ipp \ + ../../../../phonelibs/qpoases/SRC/Utils.ipp \ + ../../../../phonelibs/qpoases/SRC/Indexlist.ipp diff --git a/selfdrive/controls/lib/longitudinal_mpc/lib_qp/Indexlist.o b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/Indexlist.o new file mode 100644 index 00000000000000..9ef68d5bfa7d38 Binary files /dev/null and b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/Indexlist.o differ diff --git a/selfdrive/controls/lib/longitudinal_mpc/lib_qp/MessageHandling.d b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/MessageHandling.d new file mode 100644 index 00000000000000..b5c6166aba1f64 --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/MessageHandling.d @@ -0,0 +1,9 @@ +lib_qp/MessageHandling.o: \ + ../../../../phonelibs/qpoases/SRC/MessageHandling.cpp \ + ../../../../phonelibs/qpoases/INCLUDE/MessageHandling.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Types.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Constants.hpp \ + lib_mpc_export/acado_qpoases_interface.hpp \ + ../../../../phonelibs/qpoases/SRC/MessageHandling.ipp \ + ../../../../phonelibs/qpoases/INCLUDE/Utils.hpp \ + ../../../../phonelibs/qpoases/SRC/Utils.ipp diff --git a/selfdrive/controls/lib/longitudinal_mpc/lib_qp/MessageHandling.o b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/MessageHandling.o new file mode 100644 index 00000000000000..87b200d0475adb Binary files /dev/null and b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/MessageHandling.o differ diff --git a/selfdrive/controls/lib/longitudinal_mpc/lib_qp/QProblem.d b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/QProblem.d new file mode 100644 index 00000000000000..1f6e188af55c17 --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/QProblem.d @@ -0,0 +1,22 @@ +lib_qp/QProblem.o: ../../../../phonelibs/qpoases/SRC/QProblem.cpp \ + ../../../../phonelibs/qpoases/INCLUDE/QProblem.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/QProblemB.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Bounds.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/SubjectTo.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Indexlist.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Utils.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/MessageHandling.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Types.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Constants.hpp \ + lib_mpc_export/acado_qpoases_interface.hpp \ + ../../../../phonelibs/qpoases/SRC/MessageHandling.ipp \ + ../../../../phonelibs/qpoases/SRC/Utils.ipp \ + ../../../../phonelibs/qpoases/SRC/Indexlist.ipp \ + ../../../../phonelibs/qpoases/SRC/SubjectTo.ipp \ + ../../../../phonelibs/qpoases/SRC/Bounds.ipp \ + ../../../../phonelibs/qpoases/SRC/QProblemB.ipp \ + ../../../../phonelibs/qpoases/INCLUDE/Constraints.hpp \ + ../../../../phonelibs/qpoases/SRC/Constraints.ipp \ + ../../../../phonelibs/qpoases/INCLUDE/CyclingManager.hpp \ + ../../../../phonelibs/qpoases/SRC/CyclingManager.ipp \ + ../../../../phonelibs/qpoases/SRC/QProblem.ipp diff --git a/selfdrive/controls/lib/longitudinal_mpc/lib_qp/QProblem.o b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/QProblem.o new file mode 100644 index 00000000000000..81a50555553aa0 Binary files /dev/null and b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/QProblem.o differ diff --git a/selfdrive/controls/lib/longitudinal_mpc/lib_qp/QProblemB.d b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/QProblemB.d new file mode 100644 index 00000000000000..7878a825ce5749 --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/QProblemB.d @@ -0,0 +1,16 @@ +lib_qp/QProblemB.o: ../../../../phonelibs/qpoases/SRC/QProblemB.cpp \ + ../../../../phonelibs/qpoases/INCLUDE/QProblemB.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Bounds.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/SubjectTo.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Indexlist.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Utils.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/MessageHandling.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Types.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Constants.hpp \ + lib_mpc_export/acado_qpoases_interface.hpp \ + ../../../../phonelibs/qpoases/SRC/MessageHandling.ipp \ + ../../../../phonelibs/qpoases/SRC/Utils.ipp \ + ../../../../phonelibs/qpoases/SRC/Indexlist.ipp \ + ../../../../phonelibs/qpoases/SRC/SubjectTo.ipp \ + ../../../../phonelibs/qpoases/SRC/Bounds.ipp \ + ../../../../phonelibs/qpoases/SRC/QProblemB.ipp diff --git a/selfdrive/controls/lib/longitudinal_mpc/lib_qp/QProblemB.o b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/QProblemB.o new file mode 100644 index 00000000000000..a850439245f58e Binary files /dev/null and b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/QProblemB.o differ diff --git a/selfdrive/controls/lib/longitudinal_mpc/lib_qp/SubjectTo.d b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/SubjectTo.d new file mode 100644 index 00000000000000..c896d9a9faf58d --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/SubjectTo.d @@ -0,0 +1,12 @@ +lib_qp/SubjectTo.o: ../../../../phonelibs/qpoases/SRC/SubjectTo.cpp \ + ../../../../phonelibs/qpoases/INCLUDE/SubjectTo.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Indexlist.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Utils.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/MessageHandling.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Types.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Constants.hpp \ + lib_mpc_export/acado_qpoases_interface.hpp \ + ../../../../phonelibs/qpoases/SRC/MessageHandling.ipp \ + ../../../../phonelibs/qpoases/SRC/Utils.ipp \ + ../../../../phonelibs/qpoases/SRC/Indexlist.ipp \ + ../../../../phonelibs/qpoases/SRC/SubjectTo.ipp diff --git a/selfdrive/controls/lib/longitudinal_mpc/lib_qp/SubjectTo.o b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/SubjectTo.o new file mode 100644 index 00000000000000..827237a682079f Binary files /dev/null and b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/SubjectTo.o differ diff --git a/selfdrive/controls/lib/longitudinal_mpc/lib_qp/Utils.d b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/Utils.d new file mode 100644 index 00000000000000..58f35a065397a3 --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/Utils.d @@ -0,0 +1,8 @@ +lib_qp/Utils.o: ../../../../phonelibs/qpoases/SRC/Utils.cpp \ + ../../../../phonelibs/qpoases/INCLUDE/Utils.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/MessageHandling.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Types.hpp \ + ../../../../phonelibs/qpoases/INCLUDE/Constants.hpp \ + lib_mpc_export/acado_qpoases_interface.hpp \ + ../../../../phonelibs/qpoases/SRC/MessageHandling.ipp \ + ../../../../phonelibs/qpoases/SRC/Utils.ipp diff --git a/selfdrive/controls/lib/longitudinal_mpc/lib_qp/Utils.o b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/Utils.o new file mode 100644 index 00000000000000..ef645ef188049f Binary files /dev/null and b/selfdrive/controls/lib/longitudinal_mpc/lib_qp/Utils.o differ diff --git a/selfdrive/controls/lib/longitudinal_mpc/libmpc1.so b/selfdrive/controls/lib/longitudinal_mpc/libmpc1.so new file mode 100755 index 00000000000000..a5baf2163eb1df Binary files /dev/null and b/selfdrive/controls/lib/longitudinal_mpc/libmpc1.so differ diff --git a/selfdrive/controls/lib/longitudinal_mpc/libmpc_py.py b/selfdrive/controls/lib/longitudinal_mpc/libmpc_py.py new file mode 100644 index 00000000000000..02d7600a35791c --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc/libmpc_py.py @@ -0,0 +1,50 @@ +import os +import platform +import subprocess + +from cffi import FFI + +mpc_dir = os.path.join(os.path.dirname(os.path.abspath(__file__))) + +if platform.machine() == "x86_64": + try: + FFI().dlopen(os.path.join(mpc_dir, "libmpc1.so")) + except OSError: + # libmpc1.so is likely built for aarch64. cleaning... + subprocess.check_call(["make", "clean"], cwd=mpc_dir) + +subprocess.check_call(["make", "-j4"], cwd=mpc_dir) + +def _get_libmpc(mpc_id): + libmpc_fn = os.path.join(mpc_dir, "libmpc%d.so" % mpc_id) + + ffi = FFI() + ffi.cdef(""" + typedef struct { + double x_ego, v_ego, a_ego, x_l, v_l, a_l; + } state_t; + + + typedef struct { + double x_ego[21]; + double v_ego[21]; + double a_ego[21]; + double j_ego[21]; + double x_l[21]; + double v_l[21]; + double t[21]; + double cost; + } log_t; + + void init(double ttcCost, double distanceCost, double accelerationCost, double jerkCost); + void init_with_simulation(double v_ego, double x_l, double v_l, double a_l, double l); + int run_mpc(state_t * x0, log_t * solution, + double l, double a_l_0, double TR); + """) + + return (ffi, ffi.dlopen(libmpc_fn)) + +mpcs = [_get_libmpc(1), _get_libmpc(2)] + +def get_libmpc(mpc_id): + return mpcs[mpc_id - 1] diff --git a/selfdrive/controls/lib/longitudinal_mpc/longitudinal_mpc.c b/selfdrive/controls/lib/longitudinal_mpc/longitudinal_mpc.c new file mode 100644 index 00000000000000..9e05bfa9e01ada --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc/longitudinal_mpc.c @@ -0,0 +1,155 @@ +#include "acado_common.h" +#include "acado_auxiliary_functions.h" + +#include +#include + +#define NX ACADO_NX /* Number of differential state variables. */ +#define NXA ACADO_NXA /* Number of algebraic variables. */ +#define NU ACADO_NU /* Number of control inputs. */ +#define NOD ACADO_NOD /* Number of online data values. */ + +#define NY ACADO_NY /* Number of measurements/references on nodes 0..N - 1. */ +#define NYN ACADO_NYN /* Number of measurements/references on node N. */ + +#define N ACADO_N /* Number of intervals in the horizon. */ + +ACADOvariables acadoVariables; +ACADOworkspace acadoWorkspace; + +typedef struct { + double x_ego, v_ego, a_ego, x_l, v_l, a_l; +} state_t; + + +typedef struct { + double x_ego[N+1]; + double v_ego[N+1]; + double a_ego[N+1]; + double j_ego[N+1]; + double x_l[N+1]; + double v_l[N+1]; + double t[N+1]; + double cost; +} log_t; + +void init(double ttcCost, double distanceCost, double accelerationCost, double jerkCost){ + acado_initializeSolver(); + int i; + const int STEP_MULTIPLIER = 3; + + /* Initialize the states and controls. */ + for (i = 0; i < NX * (N + 1); ++i) acadoVariables.x[ i ] = 0.0; + for (i = 0; i < NU * N; ++i) acadoVariables.u[ i ] = 0.0; + + /* Initialize the measurements/reference. */ + for (i = 0; i < NY * N; ++i) acadoVariables.y[ i ] = 0.0; + for (i = 0; i < NYN; ++i) acadoVariables.yN[ i ] = 0.0; + + /* MPC: initialize the current state feedback. */ + for (i = 0; i < NX; ++i) acadoVariables.x0[ i ] = 0.0; + // Set weights + + for (i = 0; i < N; i++) { + int f = 1; + if (i > 4){ + f = STEP_MULTIPLIER; + } + acadoVariables.W[16 * i + 0] = ttcCost * f; // exponential cost for time-to-collision (ttc) + acadoVariables.W[16 * i + 5] = distanceCost * f; // desired distance + acadoVariables.W[16 * i + 10] = accelerationCost * f; // acceleration + acadoVariables.W[16 * i + 15] = jerkCost * f; // jerk + } + acadoVariables.WN[0] = ttcCost * STEP_MULTIPLIER; // exponential cost for danger zone + acadoVariables.WN[4] = distanceCost * STEP_MULTIPLIER; // desired distance + acadoVariables.WN[8] = accelerationCost * STEP_MULTIPLIER; // acceleration + +} + +void init_with_simulation(double v_ego, double x_l_0, double v_l_0, double a_l_0, double l){ + int i; + double x_ego = 0.0; + double a_ego = 0.0; + + double x_l = x_l_0; + double v_l = v_l_0; + double a_l = a_l_0; + + + if (v_ego > v_l){ + a_ego = -(v_ego - v_l) * (v_ego - v_l) / (2.0 * x_l + 0.01) + a_l; + } + double dt = 0.2; + double t = 0.; + + for (i = 0; i < N + 1; ++i){ + if (i > 4){ + dt = 0.6; + } + + // Directly calculate a_l to prevent instabilites due to discretization + a_l = a_l_0 * exp(-l * t * t / 2); + + /* printf("x_e: %.2f\t v_e: %.2f\t a_e: %.2f\t", x_ego, v_ego, a_ego); */ + /* printf("x_l: %.2f\t v_l: %.2f\t a_l: %.2f\n", x_l, v_l, a_l); */ + + acadoVariables.x[i*NX] = x_ego; + acadoVariables.x[i*NX+1] = v_ego; + acadoVariables.x[i*NX+2] = a_ego; + + acadoVariables.x[i*NX+3] = x_l; + acadoVariables.x[i*NX+4] = v_l; + acadoVariables.x[i*NX+5] = t; + + x_ego += v_ego * dt; + v_ego += a_ego * dt; + + x_l += v_l * dt; + v_l += a_l * dt; + t += dt; + + if (v_ego <= 0.0) { + v_ego = 0.0; + a_ego = 0.0; + } + } + for (i = 0; i < NU * N; ++i) acadoVariables.u[ i ] = 0.0; + for (i = 0; i < NY * N; ++i) acadoVariables.y[ i ] = 0.0; + for (i = 0; i < NYN; ++i) acadoVariables.yN[ i ] = 0.0; +} + +int run_mpc(state_t * x0, log_t * solution, double l, double a_l_0, double TR){ + int i; + + for (i = 0; i <= NOD * N; i+= NOD){ + acadoVariables.od[i] = l; + acadoVariables.od[i+1] = a_l_0; + } + + acadoVariables.x[0] = acadoVariables.x0[0] = x0->x_ego; + acadoVariables.x[1] = acadoVariables.x0[1] = x0->v_ego; + acadoVariables.x[2] = acadoVariables.x0[2] = x0->a_ego; + acadoVariables.x[3] = acadoVariables.x0[3] = x0->x_l; + acadoVariables.x[4] = acadoVariables.x0[4] = x0->v_l; + acadoVariables.x[5] = acadoVariables.x0[5] = 0.0; + + acado_preparationStep(TR); + acado_feedbackStep(); + + for (i = 0; i <= N; i++){ + solution->x_ego[i] = acadoVariables.x[i*NX]; + solution->v_ego[i] = acadoVariables.x[i*NX+1]; + solution->a_ego[i] = acadoVariables.x[i*NX+2]; + solution->x_l[i] = acadoVariables.x[i*NX+3]; + solution->v_l[i] = acadoVariables.x[i*NX+4]; + solution->t[i] = acadoVariables.x[i*NX+5]; + + solution->j_ego[i] = acadoVariables.u[i]; + } + solution->cost = acado_getObjective(TR); + + // Dont shift states here. Current solution is closer to next timestep than if + // we shift by 0.2 seconds. + + return acado_getNWSR(); +} diff --git a/selfdrive/controls/lib/longitudinal_mpc/longitudinal_mpc.d b/selfdrive/controls/lib/longitudinal_mpc/longitudinal_mpc.d new file mode 100644 index 00000000000000..34a2a0d20ce304 --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc/longitudinal_mpc.d @@ -0,0 +1,3 @@ +longitudinal_mpc.o: longitudinal_mpc.c lib_mpc_export/acado_common.h \ + lib_mpc_export/acado_qpoases_interface.hpp \ + lib_mpc_export/acado_auxiliary_functions.h diff --git a/selfdrive/controls/lib/longitudinal_mpc/longitudinal_mpc.o b/selfdrive/controls/lib/longitudinal_mpc/longitudinal_mpc.o new file mode 100644 index 00000000000000..479d21492ac8fd Binary files /dev/null and b/selfdrive/controls/lib/longitudinal_mpc/longitudinal_mpc.o differ diff --git a/selfdrive/controls/lib/pathplanner.py b/selfdrive/controls/lib/pathplanner.py new file mode 100644 index 00000000000000..692f8574e5595c --- /dev/null +++ b/selfdrive/controls/lib/pathplanner.py @@ -0,0 +1,66 @@ +from common.numpy_fast import interp +from selfdrive.controls.lib.latcontrol_helpers import model_polyfit, calc_desired_path, compute_path_pinv +from selfdrive.kegman_conf import kegman_conf + +k = kegman_conf() +CAMERA_OFFSET = float(k.conf['cameraOffset']) # m from center car to camera + +class PathPlanner(object): + def __init__(self): + self.d_poly = [0., 0., 0., 0.] + self.c_poly = [0., 0., 0., 0.] + self.c_prob = 0. + self.last_model = 0. + self.lead_dist, self.lead_prob, self.lead_var = 0, 0, 1 + self._path_pinv = compute_path_pinv() + + self.lane_width_estimate = 2.85 + self.lane_width_certainty = 1.0 + self.lane_width = 2.85 + self.l_prob = 0. + self.r_prob = 0. + + def update(self, v_ego, md): + if md is not None: + p_poly = model_polyfit(md.model.path.points, self._path_pinv) # predicted path + l_poly = model_polyfit(md.model.leftLane.points, self._path_pinv) # left line + r_poly = model_polyfit(md.model.rightLane.points, self._path_pinv) # right line + + # only offset left and right lane lines; offsetting p_poly does not make sense + l_poly[3] += CAMERA_OFFSET + r_poly[3] += CAMERA_OFFSET + + p_prob = 1. # model does not tell this probability yet, so set to 1 for now + l_prob = md.model.leftLane.prob # left line prob + r_prob = md.model.rightLane.prob # right line prob + + # Find current lanewidth + lr_prob = l_prob * r_prob + self.lane_width_certainty += 0.05 * (lr_prob - self.lane_width_certainty) + current_lane_width = abs(l_poly[3] - r_poly[3]) + self.lane_width_estimate += 0.005 * (current_lane_width - self.lane_width_estimate) + speed_lane_width = interp(v_ego, [0., 31.], [2.85, 3.5]) + self.lane_width = self.lane_width_certainty * self.lane_width_estimate + \ + (1 - self.lane_width_certainty) * speed_lane_width + + lane_width_diff = abs(self.lane_width - current_lane_width) + lane_r_prob = interp(lane_width_diff, [0.3, 1.0], [1.0, 0.0]) + + r_prob *= lane_r_prob + + self.lead_dist = md.model.lead.dist + self.lead_prob = md.model.lead.prob + self.lead_var = md.model.lead.std**2 + + # compute target path + self.d_poly, self.c_poly, self.c_prob = calc_desired_path( + l_poly, r_poly, p_poly, l_prob, r_prob, p_prob, v_ego, self.lane_width) + + self.r_poly = r_poly + self.r_prob = r_prob + + self.l_poly = l_poly + self.l_prob = l_prob + + self.p_poly = p_poly + self.p_prob = p_prob diff --git a/selfdrive/controls/lib/pid.py b/selfdrive/controls/lib/pid.py new file mode 100644 index 00000000000000..b68dc3810eef4b --- /dev/null +++ b/selfdrive/controls/lib/pid.py @@ -0,0 +1,91 @@ +import numpy as np +from common.numpy_fast import clip, interp + +def apply_deadzone(error, deadzone): + if error > deadzone: + error -= deadzone + elif error < - deadzone: + error += deadzone + else: + error = 0. + return error + +class PIController(object): + def __init__(self, k_p, k_i, k_f=1., pos_limit=None, neg_limit=None, rate=100, sat_limit=0.8, convert=None): + self._k_p = k_p # proportional gain + self._k_i = k_i # integral gain + self.k_f = k_f # feedforward gain + + self.pos_limit = pos_limit + self.neg_limit = neg_limit + + self.sat_count_rate = 1.0 / rate + self.i_unwind_rate = 0.3 / rate + self.i_rate = 1.0 / rate + self.sat_limit = sat_limit + self.convert = convert + + self.reset() + + @property + def k_p(self): + return interp(self.speed, self._k_p[0], self._k_p[1]) + + @property + def k_i(self): + return interp(self.speed, self._k_i[0], self._k_i[1]) + + def _check_saturation(self, control, override, error): + saturated = (control < self.neg_limit) or (control > self.pos_limit) + + if saturated and not override and abs(error) > 0.1: + self.sat_count += self.sat_count_rate + else: + self.sat_count -= self.sat_count_rate + + self.sat_count = clip(self.sat_count, 0.0, 1.0) + + return self.sat_count > self.sat_limit + + def reset(self): + self.p = 0.0 + self.i = 0.0 + self.f = 0.0 + self.sat_count = 0.0 + self.saturated = False + self.control = 0 + + def update(self, setpoint, measurement, speed=0.0, check_saturation=True, override=False, feedforward=0., deadzone=0., freeze_integrator=False): + self.speed = speed + + error = float(apply_deadzone(setpoint - measurement, deadzone)) + self.p = error * self.k_p + self.f = feedforward * self.k_f + + if override: + self.i -= self.i_unwind_rate * float(np.sign(self.i)) + else: + i = self.i + error * self.k_i * self.i_rate + control = self.p + self.f + i + + if self.convert is not None: + control = self.convert(control, speed=self.speed) + + # Update when changing i will move the control away from the limits + # or when i will move towards the sign of the error + if ((error >= 0 and (control <= self.pos_limit or i < 0.0)) or \ + (error <= 0 and (control >= self.neg_limit or i > 0.0))) and \ + not freeze_integrator: + self.i = i + + control = self.p + self.f + self.i + if self.convert is not None: + control = self.convert(control, speed=self.speed) + + if check_saturation: + self.saturated = self._check_saturation(control, override, error) + else: + self.saturated = False + + self.control = clip(control, self.neg_limit, self.pos_limit) + return self.control diff --git a/selfdrive/controls/lib/planner.py b/selfdrive/controls/lib/planner.py new file mode 100755 index 00000000000000..d4f2eff741db5d --- /dev/null +++ b/selfdrive/controls/lib/planner.py @@ -0,0 +1,649 @@ +#!/usr/bin/env python +import os +import zmq +import math +import numpy as np +from copy import copy +from cereal import log +from collections import defaultdict +from common.params import Params +from common.realtime import sec_since_boot +from common.numpy_fast import interp +import selfdrive.messaging as messaging +from selfdrive.swaglog import cloudlog +from selfdrive.config import Conversions as CV +from selfdrive.services import service_list +from selfdrive.controls.lib.drive_helpers import create_event, MPC_COST_LONG, EventTypes as ET +from selfdrive.controls.lib.pathplanner import PathPlanner +from selfdrive.controls.lib.longitudinal_mpc import libmpc_py +from selfdrive.controls.lib.speed_smoother import speed_smoother +from selfdrive.controls.lib.longcontrol import LongCtrlState, MIN_CAN_SPEED +from selfdrive.controls.lib.radar_helpers import _LEAD_ACCEL_TAU + +# One, two and three bar distances (in s) +ONE_BAR_DISTANCE = 0.9 # in seconds +TWO_BAR_DISTANCE = 1.3 # in seconds +THREE_BAR_DISTANCE = 1.8 # in seconds +FOUR_BAR_DISTANCE = 2.5 # in seconds + +# Variables that change braking profiles +CITY_SPEED = 19.44 # braking profile changes when below this speed based on following dynamics below [m/s] +GAP_CLOSURE_SPEED = -1 # relative velocity between you and lead car which activates braking profile change [m/s] +TAILGATE_DISTANCE = 17.5 # when below this distance between you and lead car, braking profile change is active based on PULLAWAY_REL_V [m] +PULLAWAY_REL_V = 0.25 # within TAILGATE_DISTANCE, if the car is pulling away w/ rel velocity that exceeds this value, then change BACK to set bar distance [m/s] +MIN_DISTANCE = 7 # keep a minimum distance between you and lead car (when below this, activates braking profile change) [m] +STOPPING_DISTANCE = 2 # increase distance from lead car when stopped + +# Braking profile changes (makes the car brake harder because it wants to be farther from the lead car - increase to brake harder) +ONE_BAR_PROFILE = [ONE_BAR_DISTANCE, FOUR_BAR_DISTANCE] +ONE_BAR_PROFILE_BP = [-GAP_CLOSURE_SPEED, 5.0] + +TWO_BAR_PROFILE = [TWO_BAR_DISTANCE, FOUR_BAR_DISTANCE] +TWO_BAR_PROFILE_BP = [-GAP_CLOSURE_SPEED, 5.0] + +THREE_BAR_PROFILE = [THREE_BAR_DISTANCE, FOUR_BAR_DISTANCE] +THREE_BAR_PROFILE_BP = [-GAP_CLOSURE_SPEED, 5.0] + + +# Max lateral acceleration, used to caclulate how much to slow down in turns +A_Y_MAX = 1.85 # m/s^2 +NO_CURVATURE_SPEED = 200. * CV.MPH_TO_MS + +_DT = 0.01 # 100Hz +_DT_MPC = 0.2 # 5Hz +MAX_SPEED_ERROR = 2.0 +AWARENESS_DECEL = -0.2 # car smoothly decel at .2m/s^2 when user is distracted +TR = TWO_BAR_DISTANCE # CS.readdistancelines + +GPS_PLANNER_ADDR = "192.168.5.1" + +# lookup tables VS speed to determine min and max accels in cruise +# make sure these accelerations are smaller than mpc limits +_A_CRUISE_MIN_V = [-1.0, -.8, -.67, -.5, -.30] +_A_CRUISE_MIN_BP = [ 0., 5., 10., 20., 40.] + +# need fast accel at very low speed for stop and go +# make sure these accelerations are smaller than mpc limits +#_A_CRUISE_MAX_V = [1.1, 1.1, .8, .5, .3] +_A_CRUISE_MAX_V = [1.6, 1.6, 1.2, .7, .3] +_A_CRUISE_MAX_V_FOLLOWING = [1.6, 1.6, 1.2, .7, .3] +_A_CRUISE_MAX_BP = [0., 5., 10., 20., 40.] + +# Lookup table for turns +_A_TOTAL_MAX_V = [1.5, 1.9, 3.2] +_A_TOTAL_MAX_BP = [0., 20., 40.] + +_FCW_A_ACT_V = [-3., -2.] +_FCW_A_ACT_BP = [0., 30.] + + +def calc_cruise_accel_limits(v_ego, following): + a_cruise_min = interp(v_ego, _A_CRUISE_MIN_BP, _A_CRUISE_MIN_V) + + if following: + a_cruise_max = interp(v_ego, _A_CRUISE_MAX_BP, _A_CRUISE_MAX_V_FOLLOWING) + else: + a_cruise_max = interp(v_ego, _A_CRUISE_MAX_BP, _A_CRUISE_MAX_V) + return np.vstack([a_cruise_min, a_cruise_max]) + + +def limit_accel_in_turns(v_ego, angle_steers, a_target, CP): + """ + This function returns a limited long acceleration allowed, depending on the existing lateral acceleration + this should avoid accelerating when losing the target in turns + """ + + a_total_max = interp(v_ego, _A_TOTAL_MAX_BP, _A_TOTAL_MAX_V) + a_y = v_ego**2 * angle_steers * CV.DEG_TO_RAD / (CP.steerRatio * CP.wheelbase) + a_x_allowed = math.sqrt(max(a_total_max**2 - a_y**2, 0.)) + + a_target[1] = min(a_target[1], a_x_allowed) + return a_target + + +class FCWChecker(object): + def __init__(self): + self.reset_lead(0.0) + + def reset_lead(self, cur_time): + self.last_fcw_a = 0.0 + self.v_lead_max = 0.0 + self.lead_seen_t = cur_time + self.last_fcw_time = 0.0 + self.last_min_a = 0.0 + + self.counters = defaultdict(lambda: 0) + + @staticmethod + def calc_ttc(v_ego, a_ego, x_lead, v_lead, a_lead): + max_ttc = 5.0 + + v_rel = v_ego - v_lead + a_rel = a_ego - a_lead + + # assuming that closing gap ARel comes from lead vehicle decel, + # then limit ARel so that v_lead will get to zero in no sooner than t_decel. + # This helps underweighting ARel when v_lead is close to zero. + t_decel = 2. + a_rel = np.minimum(a_rel, v_lead/t_decel) + + # delta of the quadratic equation to solve for ttc + delta = v_rel**2 + 2 * x_lead * a_rel + + # assign an arbitrary high ttc value if there is no solution to ttc + if delta < 0.1 or (np.sqrt(delta) + v_rel < 0.1): + ttc = max_ttc + else: + ttc = np.minimum(2 * x_lead / (np.sqrt(delta) + v_rel), max_ttc) + return ttc + + def update(self, mpc_solution, cur_time, v_ego, a_ego, x_lead, v_lead, a_lead, y_lead, vlat_lead, fcw_lead, blinkers): + mpc_solution_a = list(mpc_solution[0].a_ego) + self.last_min_a = min(mpc_solution_a) + self.v_lead_max = max(self.v_lead_max, v_lead) + + if (fcw_lead > 0.99): + ttc = self.calc_ttc(v_ego, a_ego, x_lead, v_lead, a_lead) + self.counters['v_ego'] = self.counters['v_ego'] + 1 if v_ego > 5.0 else 0 + self.counters['ttc'] = self.counters['ttc'] + 1 if ttc < 2.5 else 0 + self.counters['v_lead_max'] = self.counters['v_lead_max'] + 1 if self.v_lead_max > 2.5 else 0 + self.counters['v_ego_lead'] = self.counters['v_ego_lead'] + 1 if v_ego > v_lead else 0 + self.counters['lead_seen'] = self.counters['lead_seen'] + 0.33 + self.counters['y_lead'] = self.counters['y_lead'] + 1 if abs(y_lead) < 1.0 else 0 + self.counters['vlat_lead'] = self.counters['vlat_lead'] + 1 if abs(vlat_lead) < 0.4 else 0 + self.counters['blinkers'] = self.counters['blinkers'] + 10.0 / (20 * 3.0) if not blinkers else 0 + + a_thr = interp(v_lead, _FCW_A_ACT_BP, _FCW_A_ACT_V) + a_delta = min(mpc_solution_a[:15]) - min(0.0, a_ego) + + fcw_allowed = all(c >= 10 for c in self.counters.values()) + if (self.last_min_a < -3.0 or a_delta < a_thr) and fcw_allowed and self.last_fcw_time + 5.0 < cur_time: + self.last_fcw_time = cur_time + self.last_fcw_a = self.last_min_a + return True + + return False + + +class LongitudinalMpc(object): + def __init__(self, mpc_id, live_longitudinal_mpc): + self.live_longitudinal_mpc = live_longitudinal_mpc + self.mpc_id = mpc_id + + self.setup_mpc() + self.v_mpc = 0.0 + self.v_mpc_future = 0.0 + self.a_mpc = 0.0 + self.v_cruise = 0.0 + self.prev_lead_status = False + self.prev_lead_x = 0.0 + self.new_lead = False + + self.override = False # for one bar distance at low speeds - introduce early braking and hysteresis for resume follow + self.lastTR = 2 + self.last_cloudlog_t = 0.0 + self.v_rel = 10 + self.tailgating = 0 + self.street_speed = 0 + self.lead_car_gap_shrinking = 0 + self.lead_car_rapid_gap_shrinking = 0 + + def send_mpc_solution(self, qp_iterations, calculation_time): + qp_iterations = max(0, qp_iterations) + dat = messaging.new_message() + dat.init('liveLongitudinalMpc') + dat.liveLongitudinalMpc.xEgo = list(self.mpc_solution[0].x_ego) + dat.liveLongitudinalMpc.vEgo = list(self.mpc_solution[0].v_ego) + dat.liveLongitudinalMpc.aEgo = list(self.mpc_solution[0].a_ego) + dat.liveLongitudinalMpc.xLead = list(self.mpc_solution[0].x_l) + dat.liveLongitudinalMpc.vLead = list(self.mpc_solution[0].v_l) + dat.liveLongitudinalMpc.cost = self.mpc_solution[0].cost + dat.liveLongitudinalMpc.aLeadTau = self.a_lead_tau + dat.liveLongitudinalMpc.qpIterations = qp_iterations + dat.liveLongitudinalMpc.mpcId = self.mpc_id + dat.liveLongitudinalMpc.calculationTime = calculation_time + self.live_longitudinal_mpc.send(dat.to_bytes()) + + def setup_mpc(self): + ffi, self.libmpc = libmpc_py.get_libmpc(self.mpc_id) + self.libmpc.init(MPC_COST_LONG.TTC, MPC_COST_LONG.DISTANCE, + MPC_COST_LONG.ACCELERATION, MPC_COST_LONG.JERK) + + self.mpc_solution = ffi.new("log_t *") + self.cur_state = ffi.new("state_t *") + self.cur_state[0].v_ego = 0 + self.cur_state[0].a_ego = 0 + self.a_lead_tau = _LEAD_ACCEL_TAU + + def set_cur_state(self, v, a): + self.cur_state[0].v_ego = v + self.cur_state[0].a_ego = a + + def update(self, CS, lead, v_cruise_setpoint): + # Setup current mpc state + self.cur_state[0].x_ego = 0.0 + + if lead is not None and lead.status: + #x_lead = lead.dRel + x_lead = max(0, lead.dRel - STOPPING_DISTANCE) # increase stopping distance to car by X [m] + v_lead = max(0.0, lead.vLead) + a_lead = lead.aLeadK + + + if (v_lead < 0.1 or -a_lead / 2.0 > v_lead): + v_lead = 0.0 + a_lead = 0.0 + + self.a_lead_tau = max(lead.aLeadTau, (a_lead**2 * math.pi) / (2 * (v_lead + 0.01)**2)) + self.new_lead = False + if not self.prev_lead_status or abs(x_lead - self.prev_lead_x) > 2.5: + self.libmpc.init_with_simulation(self.v_mpc, x_lead, v_lead, a_lead, self.a_lead_tau) + self.new_lead = True + + self.prev_lead_status = True + self.prev_lead_x = x_lead + self.cur_state[0].x_l = x_lead + self.cur_state[0].v_l = v_lead + else: + self.prev_lead_status = False + # Fake a fast lead car, so mpc keeps running + self.cur_state[0].x_l = 50.0 + self.cur_state[0].v_l = CS.vEgo + 10.0 + a_lead = 0.0 + v_lead = CS.vEgo + 10.0 + x_lead = 50.0 + self.a_lead_tau = _LEAD_ACCEL_TAU + + # Calculate mpc + t = sec_since_boot() + + # Calculate conditions + self.v_rel = v_lead - CS.vEgo # calculate relative velocity vs lead car + + # Defining some variables to make the logic more human readable for auto distance override below + + # Is the car running surface street speeds? + if CS.vEgo < CITY_SPEED: + self.street_speed = 1 + else: + self.street_speed = 0 + + # Is the gap from the lead car shrinking? + if self.v_rel < GAP_CLOSURE_SPEED: + self.lead_car_gap_shrinking = 1 + else: + self.lead_car_gap_shrinking = 0 + + # Is the car tailgating the lead car? + if x_lead < MIN_DISTANCE or (x_lead < TAILGATE_DISTANCE and self.v_rel < PULLAWAY_REL_V): + self.tailgating = 1 + else: + self.tailgating = 0 + + + # Adjust distance from lead car when distance button pressed + if CS.readdistancelines == 1: + if self.street_speed and (self.lead_car_gap_shrinking or self.tailgating): + TR = interp(-self.v_rel, ONE_BAR_PROFILE_BP, ONE_BAR_PROFILE) + #if self.lastTR != -CS.readdistancelines: + # self.libmpc.init(MPC_COST_LONG.TTC, 0.0850, MPC_COST_LONG.ACCELERATION, MPC_COST_LONG.JERK) + # self.lastTR = -CS.readdistancelines + else: + TR = ONE_BAR_DISTANCE + if CS.readdistancelines != self.lastTR: + self.libmpc.init(MPC_COST_LONG.TTC, 1.0, MPC_COST_LONG.ACCELERATION, MPC_COST_LONG.JERK) + self.lastTR = CS.readdistancelines + + elif CS.readdistancelines == 2: + if self.street_speed and (self.lead_car_gap_shrinking or self.tailgating): + TR = interp(-self.v_rel, TWO_BAR_PROFILE_BP, TWO_BAR_PROFILE) + #if self.lastTR != -CS.readdistancelines: + # self.libmpc.init(MPC_COST_LONG.TTC, 0.0875, MPC_COST_LONG.ACCELERATION, MPC_COST_LONG.JERK) + # self.lastTR = -CS.readdistancelines + else: + TR = TWO_BAR_DISTANCE + if CS.readdistancelines != self.lastTR: + self.libmpc.init(MPC_COST_LONG.TTC, MPC_COST_LONG.DISTANCE, MPC_COST_LONG.ACCELERATION, MPC_COST_LONG.JERK) + self.lastTR = CS.readdistancelines + + elif CS.readdistancelines == 3: + if self.street_speed and (self.lead_car_gap_shrinking or self.tailgating): + TR = interp(-self.v_rel, THREE_BAR_PROFILE_BP, THREE_BAR_PROFILE) + #if self.lastTR != -CS.readdistancelines: + # self.libmpc.init(MPC_COST_LONG.TTC, MPC_COST_LONG.DISTANCE, MPC_COST_LONG.ACCELERATION, MPC_COST_LONG.JERK) + # self.lastTR = -CS.readdistancelines + else: + TR = THREE_BAR_DISTANCE + if CS.readdistancelines != self.lastTR: + self.libmpc.init(MPC_COST_LONG.TTC, MPC_COST_LONG.DISTANCE, MPC_COST_LONG.ACCELERATION, MPC_COST_LONG.JERK) + self.lastTR = CS.readdistancelines + + elif CS.readdistancelines == 4: + TR = FOUR_BAR_DISTANCE + if CS.readdistancelines != self.lastTR: + self.libmpc.init(MPC_COST_LONG.TTC, 0.05, MPC_COST_LONG.ACCELERATION, MPC_COST_LONG.JERK) + self.lastTR = CS.readdistancelines + + else: + TR = TWO_BAR_DISTANCE # if readdistancelines != 1,2,3,4 + self.libmpc.init(MPC_COST_LONG.TTC, MPC_COST_LONG.DISTANCE, MPC_COST_LONG.ACCELERATION, MPC_COST_LONG.JERK) + + n_its = self.libmpc.run_mpc(self.cur_state, self.mpc_solution, self.a_lead_tau, a_lead, TR) + duration = int((sec_since_boot() - t) * 1e9) + self.send_mpc_solution(n_its, duration) + + # Get solution. MPC timestep is 0.2 s, so interpolation to 0.05 s is needed + self.v_mpc = self.mpc_solution[0].v_ego[1] + self.a_mpc = self.mpc_solution[0].a_ego[1] + self.v_mpc_future = self.mpc_solution[0].v_ego[10] + + # Reset if NaN or goes through lead car + dls = np.array(list(self.mpc_solution[0].x_l)) - np.array(list(self.mpc_solution[0].x_ego)) + crashing = min(dls) < -50.0 + nans = np.any(np.isnan(list(self.mpc_solution[0].v_ego))) + backwards = min(list(self.mpc_solution[0].v_ego)) < -0.01 + + if ((backwards or crashing) and self.prev_lead_status) or nans: + if t > self.last_cloudlog_t + 5.0: + self.last_cloudlog_t = t + cloudlog.warning("Longitudinal mpc %d reset - backwards: %s crashing: %s nan: %s" % ( + self.mpc_id, backwards, crashing, nans)) + + self.libmpc.init(MPC_COST_LONG.TTC, MPC_COST_LONG.DISTANCE, + MPC_COST_LONG.ACCELERATION, MPC_COST_LONG.JERK) + self.cur_state[0].v_ego = CS.vEgo + self.cur_state[0].a_ego = 0.0 + self.v_mpc = CS.vEgo + self.a_mpc = CS.aEgo + self.prev_lead_status = False + + +class Planner(object): + def __init__(self, CP, fcw_enabled): + context = zmq.Context() + self.CP = CP + self.poller = zmq.Poller() + + self.live20 = messaging.sub_sock(context, service_list['live20'].port, conflate=True, poller=self.poller) + self.model = messaging.sub_sock(context, service_list['model'].port, conflate=True, poller=self.poller) + self.live_map_data = messaging.sub_sock(context, service_list['liveMapData'].port, conflate=True, poller=self.poller) + + if os.environ.get('GPS_PLANNER_ACTIVE', False): + self.gps_planner_plan = messaging.sub_sock(context, service_list['gpsPlannerPlan'].port, conflate=True, poller=self.poller, addr=GPS_PLANNER_ADDR) + else: + self.gps_planner_plan = None + + self.plan = messaging.pub_sock(context, service_list['plan'].port) + self.live_longitudinal_mpc = messaging.pub_sock(context, service_list['liveLongitudinalMpc'].port) + + self.last_md_ts = 0 + self.last_l20_ts = 0 + self.last_model = 0. + self.last_l20 = 0. + self.model_dead = True + self.radar_dead = True + self.radar_errors = [] + + self.PP = PathPlanner() + self.mpc1 = LongitudinalMpc(1, self.live_longitudinal_mpc) + self.mpc2 = LongitudinalMpc(2, self.live_longitudinal_mpc) + + self.v_acc_start = 0.0 + self.a_acc_start = 0.0 + self.acc_start_time = sec_since_boot() + self.v_acc = 0.0 + self.v_acc_sol = 0.0 + self.v_acc_future = 0.0 + self.a_acc = 0.0 + self.a_acc_sol = 0.0 + self.v_cruise = 0.0 + self.a_cruise = 0.0 + + self.lead_1 = None + self.lead_2 = None + + self.longitudinalPlanSource = 'cruise' + self.fcw = False + self.fcw_checker = FCWChecker() + self.fcw_enabled = fcw_enabled + + self.last_gps_planner_plan = None + self.gps_planner_active = False + self.last_live_map_data = None + self.perception_state = log.Live20Data.new_message() + + self.params = Params() + self.v_curvature = NO_CURVATURE_SPEED + self.v_speedlimit = NO_CURVATURE_SPEED + self.decel_for_turn = False + self.map_valid = False + + def choose_solution(self, v_cruise_setpoint, enabled): + if enabled: + solutions = {'cruise': self.v_cruise} + if self.mpc1.prev_lead_status: + solutions['mpc1'] = self.mpc1.v_mpc + if self.mpc2.prev_lead_status: + solutions['mpc2'] = self.mpc2.v_mpc + + slowest = min(solutions, key=solutions.get) + + """ + print "D_SOL", solutions, slowest, self.v_acc_sol, self.a_acc_sol + print "D_V", self.mpc1.v_mpc, self.mpc2.v_mpc, self.v_cruise + print "D_A", self.mpc1.a_mpc, self.mpc2.a_mpc, self.a_cruise + """ + + self.longitudinalPlanSource = slowest + + # Choose lowest of MPC and cruise + if slowest == 'mpc1': + self.v_acc = self.mpc1.v_mpc + self.a_acc = self.mpc1.a_mpc + elif slowest == 'mpc2': + self.v_acc = self.mpc2.v_mpc + self.a_acc = self.mpc2.a_mpc + elif slowest == 'cruise': + self.v_acc = self.v_cruise + self.a_acc = self.a_cruise + + self.v_acc_future = min([self.mpc1.v_mpc_future, self.mpc2.v_mpc_future, v_cruise_setpoint]) + + # this runs whenever we get a packet that can change the plan + def update(self, CS, CP, VM, LaC, LoC, v_cruise_kph, force_slow_decel): + cur_time = sec_since_boot() + v_cruise_setpoint = v_cruise_kph * CV.KPH_TO_MS + + md = None + l20 = None + gps_planner_plan = None + + for socket, event in self.poller.poll(0): + if socket is self.model: + md = messaging.recv_one(socket) + elif socket is self.live20: + l20 = messaging.recv_one(socket) + elif socket is self.gps_planner_plan: + gps_planner_plan = messaging.recv_one(socket) + elif socket is self.live_map_data: + self.last_live_map_data = messaging.recv_one(socket).liveMapData + + if gps_planner_plan is not None: + self.last_gps_planner_plan = gps_planner_plan + + if md is not None: + self.last_md_ts = md.logMonoTime + self.last_model = cur_time + self.model_dead = False + + self.PP.update(CS.vEgo, md) + + if self.last_gps_planner_plan is not None: + plan = self.last_gps_planner_plan.gpsPlannerPlan + self.gps_planner_active = plan.valid + if plan.valid: + self.PP.d_poly = plan.poly + self.PP.p_poly = plan.poly + self.PP.c_poly = plan.poly + self.PP.l_prob = 0.0 + self.PP.r_prob = 0.0 + self.PP.c_prob = 1.0 + + if l20 is not None: + self.perception_state = copy(l20.live20) + self.last_l20_ts = l20.logMonoTime + self.last_l20 = cur_time + self.radar_dead = False + self.radar_errors = list(l20.live20.radarErrors) + + self.v_acc_start = self.v_acc_sol + self.a_acc_start = self.a_acc_sol + self.acc_start_time = cur_time + + self.lead_1 = l20.live20.leadOne + self.lead_2 = l20.live20.leadTwo + + enabled = (LoC.long_control_state == LongCtrlState.pid) or (LoC.long_control_state == LongCtrlState.stopping) + following = self.lead_1.status and self.lead_1.dRel < 45.0 and self.lead_1.vLeadK > CS.vEgo and self.lead_1.aLeadK > 0.0 + + if self.last_live_map_data: + self.v_speedlimit = NO_CURVATURE_SPEED + self.v_curvature = NO_CURVATURE_SPEED + self.map_valid = self.last_live_map_data.mapValid + + # Speed limit + if self.last_live_map_data.speedLimitValid: + speed_limit = self.last_live_map_data.speedLimit + set_speed_limit_active = self.params.get("LimitSetSpeed") == "1" and self.params.get("SpeedLimitOffset") is not None + + if set_speed_limit_active: + offset = float(self.params.get("SpeedLimitOffset")) + self.v_speedlimit = speed_limit + offset + + # Curvature + if self.last_live_map_data.curvatureValid: + curvature = abs(self.last_live_map_data.curvature) + v_curvature = math.sqrt(A_Y_MAX / max(1e-4, curvature)) + self.v_curvature = min(NO_CURVATURE_SPEED, v_curvature) + + # leave 1m/s margin on vEgo to asses if turn is limiting our speed. + self.decel_for_turn = bool(self.v_curvature < min([v_cruise_setpoint, self.v_speedlimit, CS.vEgo + 1.])) + v_cruise_setpoint = min([v_cruise_setpoint, self.v_curvature, self.v_speedlimit]) + + # Calculate speed for normal cruise control + if enabled: + accel_limits = map(float, calc_cruise_accel_limits(CS.vEgo, following)) + # TODO: make a separate lookup for jerk tuning + jerk_limits = [min(-0.1, accel_limits[0]), max(0.1, accel_limits[1])] + accel_limits = limit_accel_in_turns(CS.vEgo, CS.steeringAngle, accel_limits, self.CP) + + if force_slow_decel: + # if required so, force a smooth deceleration + accel_limits[1] = min(accel_limits[1], AWARENESS_DECEL) + accel_limits[0] = min(accel_limits[0], accel_limits[1]) + + # Change accel limits based on time remaining to turn + if self.decel_for_turn: + time_to_turn = max(1.0, self.last_live_map_data.distToTurn / max(self.v_cruise, 1.)) + required_decel = min(0, (self.v_curvature - self.v_cruise) / time_to_turn) + accel_limits[0] = max(accel_limits[0], required_decel) + + self.v_cruise, self.a_cruise = speed_smoother(self.v_acc_start, self.a_acc_start, + v_cruise_setpoint, + accel_limits[1], accel_limits[0], + jerk_limits[1], jerk_limits[0], + _DT_MPC) + # cruise speed can't be negative even is user is distracted + self.v_cruise = max(self.v_cruise, 0.) + else: + starting = LoC.long_control_state == LongCtrlState.starting + a_ego = min(CS.aEgo, 0.0) + reset_speed = MIN_CAN_SPEED if starting else CS.vEgo + reset_accel = self.CP.startAccel if starting else a_ego + self.v_acc = reset_speed + self.a_acc = reset_accel + self.v_acc_start = reset_speed + self.a_acc_start = reset_accel + self.v_cruise = reset_speed + self.a_cruise = reset_accel + self.v_acc_sol = reset_speed + self.a_acc_sol = reset_accel + + self.mpc1.set_cur_state(self.v_acc_start, self.a_acc_start) + self.mpc2.set_cur_state(self.v_acc_start, self.a_acc_start) + + self.mpc1.update(CS, self.lead_1, v_cruise_setpoint) + self.mpc2.update(CS, self.lead_2, v_cruise_setpoint) + + self.choose_solution(v_cruise_setpoint, enabled) + + # determine fcw + if self.mpc1.new_lead: + self.fcw_checker.reset_lead(cur_time) + + blinkers = CS.leftBlinker or CS.rightBlinker + self.fcw = self.fcw_checker.update(self.mpc1.mpc_solution, cur_time, CS.vEgo, CS.aEgo, + self.lead_1.dRel, self.lead_1.vLead, self.lead_1.aLeadK, + self.lead_1.yRel, self.lead_1.vLat, + self.lead_1.fcw, blinkers) \ + and not CS.brakePressed + if self.fcw: + cloudlog.info("FCW triggered %s", self.fcw_checker.counters) + + if cur_time - self.last_model > 0.5: + self.model_dead = True + + if cur_time - self.last_l20 > 0.5: + self.radar_dead = True + # **** send the plan **** + plan_send = messaging.new_message() + plan_send.init('plan') + + events = [] + if self.model_dead: + events.append(create_event('modelCommIssue', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE])) + if self.radar_dead or 'commIssue' in self.radar_errors: + events.append(create_event('radarCommIssue', [ET.NO_ENTRY, ET.SOFT_DISABLE])) + if 'fault' in self.radar_errors: + events.append(create_event('radarFault', [ET.NO_ENTRY, ET.SOFT_DISABLE])) + if LaC.mpc_solution[0].cost > 10000. or LaC.mpc_nans: # TODO: find a better way to detect when MPC did not converge + events.append(create_event('plannerError', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE])) + + # Interpolation of trajectory + dt = min(cur_time - self.acc_start_time, _DT_MPC + _DT) + _DT # no greater than dt mpc + dt, to prevent too high extraps + self.a_acc_sol = self.a_acc_start + (dt / _DT_MPC) * (self.a_acc - self.a_acc_start) + self.v_acc_sol = self.v_acc_start + dt * (self.a_acc_sol + self.a_acc_start) / 2.0 + + plan_send.plan.events = events + plan_send.plan.mdMonoTime = self.last_md_ts + plan_send.plan.l20MonoTime = self.last_l20_ts + + # lateral plan + plan_send.plan.lateralValid = not self.model_dead + plan_send.plan.dPoly = map(float, self.PP.d_poly) + plan_send.plan.laneWidth = float(self.PP.lane_width) + + # longitudal plan + plan_send.plan.longitudinalValid = not self.radar_dead + plan_send.plan.vCruise = self.v_cruise + plan_send.plan.aCruise = self.a_cruise + plan_send.plan.vTarget = self.v_acc_sol + plan_send.plan.aTarget = self.a_acc_sol + plan_send.plan.vTargetFuture = self.v_acc_future + plan_send.plan.hasLead = self.mpc1.prev_lead_status + plan_send.plan.hasLeftLane = bool(self.PP.l_prob > 0.5) + plan_send.plan.hasRightLane = bool(self.PP.r_prob > 0.5) + plan_send.plan.longitudinalPlanSource = self.longitudinalPlanSource + + plan_send.plan.gpsPlannerActive = self.gps_planner_active + + plan_send.plan.vCurvature = self.v_curvature + plan_send.plan.decelForTurn = self.decel_for_turn + plan_send.plan.mapValid = self.map_valid + + # Send out fcw + fcw = self.fcw and (self.fcw_enabled or LoC.long_control_state != LongCtrlState.off) + plan_send.plan.fcw = fcw + + self.plan.send(plan_send.to_bytes()) + return plan_send diff --git a/selfdrive/controls/lib/radar_helpers.py b/selfdrive/controls/lib/radar_helpers.py new file mode 100644 index 00000000000000..da7d3f71ba0c4d --- /dev/null +++ b/selfdrive/controls/lib/radar_helpers.py @@ -0,0 +1,283 @@ +import os +import sys +import platform +import numpy as np + +from common.numpy_fast import clip, interp +from common.kalman.simple_kalman import KF1D + +_LEAD_ACCEL_TAU = 1.5 +NO_FUSION_SCORE = 100 # bad default fusion score + +# radar tracks +SPEED, ACCEL = 0, 1 # Kalman filter states enum + +rate, ratev = 20., 20. # model and radar are both at 20Hz +ts = 1./rate +freq_v_lat = 0.2 # Hz +k_v_lat = 2*np.pi*freq_v_lat*ts / (1 + 2*np.pi*freq_v_lat*ts) + +freq_a_lead = .5 # Hz +k_a_lead = 2*np.pi*freq_a_lead*ts / (1 + 2*np.pi*freq_a_lead*ts) + +# stationary qualification parameters +v_stationary_thr = 4. # objects moving below this speed are classified as stationary +v_oncoming_thr = -3.9 # needs to be a bit lower in abs value than v_stationary_thr to not leave "holes" +v_ego_stationary = 4. # no stationary object flag below this speed + +# Lead Kalman Filter params +_VLEAD_A = [[1.0, ts], [0.0, 1.0]] +_VLEAD_C = [[1.0, 0.0]] +#_VLEAD_Q = np.matrix([[10., 0.0], [0.0, 100.]]) +#_VLEAD_R = 1e3 +#_VLEAD_K = np.matrix([[ 0.05705578], [ 0.03073241]]) +_VLEAD_K = [[ 0.1988689 ], [ 0.28555364]] + +RDR_TO_LDR = 2.7 + + +class Track(object): + def __init__(self): + self.ekf = None + self.stationary = True + self.initted = False + + def update(self, d_rel, y_rel, v_rel, d_path, v_ego_t_aligned, measured, steer_override): + if self.initted: + # pylint: disable=access-member-before-definition + self.dPathPrev = self.dPath + self.vLeadPrev = self.vLead + self.vRelPrev = self.vRel + + # relative values, copy + self.dRel = d_rel # LONG_DIST + self.yRel = y_rel # -LAT_DIST + self.vRel = v_rel # REL_SPEED + self.measured = measured # measured or estimate + + # compute distance to path + self.dPath = d_path + + # computed velocity and accelerations + self.vLead = self.vRel + v_ego_t_aligned + + if not self.initted: + self.initted = True + self.aLeadTau = _LEAD_ACCEL_TAU + self.cnt = 1 + self.vision_cnt = 0 + self.vision = False + self.aRel = 0. # nidec gives no information about this + self.vLat = 0. + self.kf = KF1D([[self.vLead], [0.0]], _VLEAD_A, _VLEAD_C, _VLEAD_K) + else: + # estimate acceleration + # TODO: use Kalman filter + a_rel_unfilt = (self.vRel - self.vRelPrev) / ts + a_rel_unfilt = clip(a_rel_unfilt, -10., 10.) + self.aRel = k_a_lead * a_rel_unfilt + (1 - k_a_lead) * self.aRel + + # TODO: use Kalman filter + # neglect steer override cases as dPath is too noisy + v_lat_unfilt = 0. if steer_override else (self.dPath - self.dPathPrev) / ts + self.vLat = k_v_lat * v_lat_unfilt + (1 - k_v_lat) * self.vLat + + self.kf.update(self.vLead) + + self.cnt += 1 + + self.vLeadK = float(self.kf.x[SPEED][0]) + self.aLeadK = float(self.kf.x[ACCEL][0]) + + if self.stationary: + # stationary objects can become non stationary, but not the other way around + self.stationary = v_ego_t_aligned > v_ego_stationary and abs(self.vLead) < v_stationary_thr + self.oncoming = self.vLead < v_oncoming_thr + + self.vision_score = NO_FUSION_SCORE + + # Learn if constant acceleration + if abs(self.aLeadK) < 0.5: + self.aLeadTau = _LEAD_ACCEL_TAU + else: + self.aLeadTau *= 0.9 + + def update_vision_score(self, dist_to_vision, rel_speed_diff): + # rel speed is very hard to estimate from vision + if dist_to_vision < 4.0 and rel_speed_diff < 10.: + self.vision_score = dist_to_vision + rel_speed_diff + else: + self.vision_score = NO_FUSION_SCORE + + def update_vision_fusion(self): + # vision point is never stationary + # don't trust 1 or 2 fusions until model quality is much better + if self.vision_cnt >= 3: + self.vision = True + self.stationary = False + + def get_key_for_cluster(self): + # Weigh y higher since radar is inaccurate in this dimension + return [self.dRel, self.yRel*2, self.vRel] + + +# ******************* Cluster ******************* +if platform.machine() == 'aarch64': + for x in sys.path: + pp = os.path.join(x, "phonelibs/hierarchy/lib") + if os.path.isfile(os.path.join(pp, "_hierarchy.so")): + sys.path.append(pp) + break + import _hierarchy #pylint: disable=import-error +else: + from scipy.cluster import _hierarchy + + +def fcluster(Z, t, criterion='inconsistent', depth=2, R=None, monocrit=None): + # supersimplified function to get fast clustering. Got it from scipy + Z = np.asarray(Z, order='c') + n = Z.shape[0] + 1 + T = np.zeros((n,), dtype='i') + _hierarchy.cluster_dist(Z, T, float(t), int(n)) + return T + + +def mean(l): + return sum(l) / len(l) + + +class Cluster(object): + def __init__(self): + self.tracks = set() + + def add(self, t): + # add the first track + self.tracks.add(t) + + # TODO: make generic + @property + def dRel(self): + return mean([t.dRel for t in self.tracks]) + + @property + def yRel(self): + return mean([t.yRel for t in self.tracks]) + + @property + def vRel(self): + return mean([t.vRel for t in self.tracks]) + + @property + def aRel(self): + return mean([t.aRel for t in self.tracks]) + + @property + def vLead(self): + return mean([t.vLead for t in self.tracks]) + + @property + def dPath(self): + return mean([t.dPath for t in self.tracks]) + + @property + def vLat(self): + return mean([t.vLat for t in self.tracks]) + + @property + def vLeadK(self): + return mean([t.vLeadK for t in self.tracks]) + + @property + def aLeadK(self): + return mean([t.aLeadK for t in self.tracks]) + + @property + def aLeadTau(self): + return mean([t.aLeadTau for t in self.tracks]) + + @property + def vision(self): + return any([t.vision for t in self.tracks]) + + @property + def measured(self): + return any([t.measured for t in self.tracks]) + + @property + def vision_cnt(self): + return max([t.vision_cnt for t in self.tracks]) + + @property + def stationary(self): + return all([t.stationary for t in self.tracks]) + + @property + def oncoming(self): + return all([t.oncoming for t in self.tracks]) + + def toLive20(self): + return { + "dRel": float(self.dRel) - RDR_TO_LDR, + "yRel": float(self.yRel), + "vRel": float(self.vRel), + "aRel": float(self.aRel), + "vLead": float(self.vLead), + "dPath": float(self.dPath), + "vLat": float(self.vLat), + "vLeadK": float(self.vLeadK), + "aLeadK": float(self.aLeadK), + "status": True, + "fcw": self.is_potential_fcw(), + "aLeadTau": float(self.aLeadTau) + } + + def __str__(self): + ret = "x: %4.1f y: %4.1f v: %4.1f a: %4.1f d: %4.2f" % (self.dRel, self.yRel, self.vRel, self.aLeadK, self.dPath) + if self.stationary: + ret += " stationary" + if self.vision: + ret += " vision" + if self.oncoming: + ret += " oncoming" + if self.vision_cnt > 0: + ret += " vision_cnt: %6.0f" % self.vision_cnt + return ret + + def is_potential_lead(self, v_ego): + # predict cut-ins by extrapolating lateral speed by a lookahead time + # lookahead time depends on cut-in distance. more attentive for close cut-ins + # also, above 50 meters the predicted path isn't very reliable + + # the distance at which v_lat matters is higher at higher speed + lookahead_dist = 40. + v_ego/1.2 #40m at 0mph, ~70m at 80mph + + t_lookahead_v = [1., 0.] + t_lookahead_bp = [10., lookahead_dist] + + # average dist + d_path = self.dPath + + # lat_corr used to be gated on enabled, now always running + t_lookahead = interp(self.dRel, t_lookahead_bp, t_lookahead_v) + + # correct d_path for lookahead time, considering only cut-ins and no more than 1m impact. + lat_corr = clip(t_lookahead * self.vLat, -1., 1.) if self.measured else 0. + + # consider only cut-ins + d_path = clip(d_path + lat_corr, min(0., d_path), max(0.,d_path)) + + return abs(d_path) < 1.5 and not self.stationary and not self.oncoming + + def is_potential_lead2(self, lead_clusters): + if len(lead_clusters) > 0: + lead_cluster = lead_clusters[0] + # check if the new lead is too close and roughly at the same speed of the first lead: + # it might just be the second axle of the same vehicle + return (self.dRel - lead_cluster.dRel) > 8. or abs(self.vRel - lead_cluster.vRel) > 1. + else: + return False + + def is_potential_fcw(self): + # is this cluster trustrable enough for triggering fcw? + # fcw can trigger only on clusters that have been fused vision model for at least 20 frames + return self.vision_cnt >= 20 diff --git a/selfdrive/controls/lib/speed_smoother.py b/selfdrive/controls/lib/speed_smoother.py new file mode 100644 index 00000000000000..1ee7ec6b18cb5d --- /dev/null +++ b/selfdrive/controls/lib/speed_smoother.py @@ -0,0 +1,99 @@ +import numpy as np + + +def get_delta_out_limits(aEgo, aMax, aMin, jMax, jMin): + + tDelta = 0. + if aEgo > aMax: + tDelta = (aMax - aEgo) / jMin + elif aEgo < aMin: + tDelta = (aMin - aEgo) / jMax + + return tDelta + + +def speed_smoother(vEgo, aEgo, vT, aMax, aMin, jMax, jMin, ts): + + dV = vT - vEgo + + # recover quickly if dV is positive and aEgo is negative or viceversa + if dV > 0. and aEgo < 0.: + jMax *= 3. + elif dV < 0. and aEgo > 0.: + jMin *= 3. + + tDelta = get_delta_out_limits(aEgo, aMax, aMin, jMax, jMin) + + if (ts <= tDelta): + if (aEgo < aMin): + vEgo += ts * aEgo + 0.5 * ts**2 * jMax + aEgo += ts * jMax + return vEgo, aEgo + elif (aEgo > aMax): + vEgo += ts * aEgo + 0.5 * ts**2 * jMin + aEgo += ts * jMin + return vEgo, aEgo + + if aEgo > aMax: + dV -= 0.5 * (aMax**2 - aEgo**2) / jMin + vEgo += 0.5 * (aMax**2 - aEgo**2) / jMin + aEgo += tDelta * jMin + elif aEgo < aMin: + dV -= 0.5 * (aMin**2 - aEgo**2) / jMax + vEgo += 0.5 * (aMin**2 - aEgo**2) / jMax + aEgo += tDelta * jMax + + ts -= tDelta + + jLim = jMin if aEgo >= 0 else jMax + # if we reduce the accel to zero immediately, how much delta speed we generate? + dv_min_shift = - 0.5 * aEgo**2 / jLim + + # flip signs so we can consider only one case + flipped = False + if dV < dv_min_shift: + flipped = True + dV *= -1 + vEgo *= -1 + aEgo *= -1 + aMax = -aMin + jMaxcopy = -jMin + jMin = -jMax + jMax = jMaxcopy + + # small addition needed to avoid numerical issues with sqrt of ~zero + aPeak = np.sqrt((0.5 * aEgo**2 / jMax + dV + 1e-9) / (0.5 / jMax - 0.5 / jMin)) + + if aPeak > aMax: + aPeak = aMax + t1 = (aPeak - aEgo) / jMax + if aPeak <= 0: # there is no solution, so stop after t1 + t2 = t1 + ts + 1e-9 + t3 = t2 + else: + vChange = dV - 0.5 * (aPeak**2 - aEgo**2) / jMax + 0.5 * aPeak**2 / jMin + if vChange < aPeak * ts: + t2 = t1 + vChange / aPeak + else: + t2 = t1 + ts + t3 = t2 - aPeak / jMin + else: + t1 = (aPeak - aEgo) / jMax + t2 = t1 + t3 = t2 - aPeak / jMin + + dt1 = min(ts, t1) + dt2 = max(min(ts, t2) - t1, 0.) + dt3 = max(min(ts, t3) - t2, 0.) + + if ts > t3: + vEgo += dV + aEgo = 0. + else: + vEgo += aEgo * dt1 + 0.5 * dt1**2 * jMax + aPeak * dt2 + aPeak * dt3 + 0.5 * dt3**2 * jMin + aEgo += jMax * dt1 + dt3 * jMin + + vEgo *= -1 if flipped else 1 + aEgo *= -1 if flipped else 1 + + return float(vEgo), float(aEgo) diff --git a/selfdrive/controls/lib/vehicle_model.py b/selfdrive/controls/lib/vehicle_model.py new file mode 100755 index 00000000000000..95e3ef37832d87 --- /dev/null +++ b/selfdrive/controls/lib/vehicle_model.py @@ -0,0 +1,186 @@ +#!/usr/bin/env python +import numpy as np +from numpy.linalg import solve + +""" +Dynamic bycicle model from "The Science of Vehicle Dynamics (2014), M. Guiggiani" + +The state is x = [v, r]^T +with v lateral speed [m/s], and r rotational speed [rad/s] + +The input u is the steering angle [rad] + +The system is defined by +x_dot = A*x + B*u + +A depends on longitudinal speed, u [m/s], and vehicle parameters CP +""" + + +def create_dyn_state_matrices(u, VM): + """Returns the A and B matrix for the dynamics system + + Args: + u: Vehicle speed [m/s] + VM: Vehicle model + + Returns: + A tuple with the 2x2 A matrix, and 2x1 B matrix + + Parameters in the vehicle model: + cF: Tire stiffnes Front [N/rad] + cR: Tire stiffnes Front [N/rad] + aF: Distance from CG to front wheels [m] + aR: Distance from CG to rear wheels [m] + m: Mass [kg] + j: Rotational inertia [kg m^2] + sR: Steering ratio [-] + chi: Steer ratio rear [-] + """ + A = np.zeros((2, 2)) + B = np.zeros((2, 1)) + A[0, 0] = - (VM.cF + VM.cR) / (VM.m * u) + A[0, 1] = - (VM.cF * VM.aF - VM.cR * VM.aR) / (VM.m * u) - u + A[1, 0] = - (VM.cF * VM.aF - VM.cR * VM.aR) / (VM.j * u) + A[1, 1] = - (VM.cF * VM.aF**2 + VM.cR * VM.aR**2) / (VM.j * u) + B[0, 0] = (VM.cF + VM.chi * VM.cR) / VM.m / VM.sR + B[1, 0] = (VM.cF * VM.aF - VM.chi * VM.cR * VM.aR) / VM.j / VM.sR + return A, B + + +def kin_ss_sol(sa, u, VM): + """Calculate the steady state solution at low speeds + At low speeds the tire slip is undefined, so a kinematic + model is used. + + Args: + sa: Steering angle [rad] + u: Speed [m/s] + VM: Vehicle model + + Returns: + 2x1 matrix with steady state solution + """ + K = np.zeros((2, 1)) + K[0, 0] = VM.aR / VM.sR / VM.l * u + K[1, 0] = 1. / VM.sR / VM.l * u + return K * sa + + +def dyn_ss_sol(sa, u, VM): + """Calculate the steady state solution when x_dot = 0, + Ax + Bu = 0 => x = A^{-1} B u + + Args: + sa: Steering angle [rad] + u: Speed [m/s] + VM: Vehicle model + + Returns: + 2x1 matrix with steady state solution + """ + A, B = create_dyn_state_matrices(u, VM) + return -solve(A, B) * sa + + +def calc_slip_factor(VM): + """The slip factor is a measure of how the curvature changes with speed + it's positive for Oversteering vehicle, negative (usual case) otherwise. + """ + return VM.m * (VM.cF * VM.aF - VM.cR * VM.aR) / (VM.l**2 * VM.cF * VM.cR) + + +class VehicleModel(object): + def __init__(self, CP): + """ + Args: + CP: Car Parameters + """ + # for math readability, convert long names car params into short names + self.m = CP.mass + self.j = CP.rotationalInertia + self.l = CP.wheelbase + self.aF = CP.centerToFront + self.aR = CP.wheelbase - CP.centerToFront + self.cF = CP.tireStiffnessFront + self.cR = CP.tireStiffnessRear + self.sR = CP.steerRatio + self.chi = CP.steerRatioRear + + def steady_state_sol(self, sa, u): + """Returns the steady state solution. + + If the speed is too small we can't use the dynamic model (tire slip is undefined), + we then have to use the kinematic model + + Args: + sa: Steering wheel angle [rad] + u: Speed [m/s] + + Returns: + 2x1 matrix with steady state solution (lateral speed, rotational speed) + """ + if u > 0.1: + return dyn_ss_sol(sa, u, self) + else: + return kin_ss_sol(sa, u, self) + + def calc_curvature(self, sa, u): + """Returns the curvature. Multiplied by the speed this will give the yaw rate. + + Args: + sa: Steering wheel angle [rad] + u: Speed [m/s] + + Returns: + Curvature factor [rad/m] + """ + return self.curvature_factor(u) * sa / self.sR + + def curvature_factor(self, u): + """Returns the curvature factor. + Multiplied by wheel angle (not steering wheel angle) this will give the curvature. + + Args: + u: Speed [m/s] + + Returns: + Curvature factor [1/m] + """ + sf = calc_slip_factor(self) + return (1. - self.chi) / (1. - sf * u**2) / self.l + + def get_steer_from_curvature(self, curv, u): + """Calculates the required steering wheel angle for a given curvature + + Args: + curv: Desired curvature [rad/s] + u: Speed [m/s] + + Returns: + Steering wheel angle [rad] + """ + + return curv * self.sR * 1.0 / self.curvature_factor(u) + + def yaw_rate(self, sa, u): + """Calculate yaw rate + + Args: + sa: Steering wheel angle [rad] + u: Speed [m/s] + + Returns: + Yaw rate [rad/s] + """ + return self.calc_curvature(sa, u) * u + + +if __name__ == '__main__': + import math + from selfdrive.car.honda.interface import CarInterface + from selfdrive.car.honda.values import CAR + + CP = CarInterface.get_params(CAR.CIVIC, {}) + VM = VehicleModel(CP) + print(VM.yaw_rate(math.radians(20), 10.)) diff --git a/selfdrive/controls/radard.py b/selfdrive/controls/radard.py new file mode 100755 index 00000000000000..c157ba908402da --- /dev/null +++ b/selfdrive/controls/radard.py @@ -0,0 +1,301 @@ +#!/usr/bin/env python +import zmq +import numpy as np +import numpy.matlib +import importlib +from collections import defaultdict +from fastcluster import linkage_vector +import selfdrive.messaging as messaging +from selfdrive.services import service_list +from selfdrive.controls.lib.latcontrol_helpers import calc_lookahead_offset +from selfdrive.controls.lib.pathplanner import PathPlanner +from selfdrive.controls.lib.radar_helpers import Track, Cluster, fcluster, \ + RDR_TO_LDR, NO_FUSION_SCORE +from selfdrive.controls.lib.vehicle_model import VehicleModel +from selfdrive.swaglog import cloudlog +from cereal import car +from common.params import Params +from common.realtime import set_realtime_priority, Ratekeeper +from common.kalman.ekf import EKF, SimpleSensor + +DEBUG = False + +#vision point +DIMSV = 2 +XV, SPEEDV = 0, 1 +VISION_POINT = -1 + + +class EKFV1D(EKF): + def __init__(self): + super(EKFV1D, self).__init__(False) + self.identity = numpy.matlib.identity(DIMSV) + self.state = np.matlib.zeros((DIMSV, 1)) + self.var_init = 1e2 # ~ model variance when probability is 70%, so good starting point + self.covar = self.identity * self.var_init + + self.process_noise = np.matlib.diag([0.5, 1]) + + def calc_transfer_fun(self, dt): + tf = np.matlib.identity(DIMSV) + tf[XV, SPEEDV] = dt + tfj = tf + return tf, tfj + + +## fuses camera and radar data for best lead detection +# FIXME: radard has a memory leak of about 50MB/hr +# BOUNTY: $100 coupon on shop.comma.ai +def radard_thread(gctx=None): + set_realtime_priority(2) + + # wait for stats about the car to come in from controls + cloudlog.info("radard is waiting for CarParams") + CP = car.CarParams.from_bytes(Params().get("CarParams", block=True)) + mocked = CP.carName == "mock" + VM = VehicleModel(CP) + cloudlog.info("radard got CarParams") + + # import the radar from the fingerprint + cloudlog.info("radard is importing %s", CP.carName) + RadarInterface = importlib.import_module('selfdrive.car.%s.radar_interface' % CP.carName).RadarInterface + context = zmq.Context() + + # *** subscribe to features and model from visiond + poller = zmq.Poller() + model = messaging.sub_sock(context, service_list['model'].port, conflate=True, poller=poller) + live100 = messaging.sub_sock(context, service_list['live100'].port, conflate=True, poller=poller) + + PP = PathPlanner() + RI = RadarInterface(CP) + + last_md_ts = 0 + last_l100_ts = 0 + + # *** publish live20 and liveTracks + live20 = messaging.pub_sock(context, service_list['live20'].port) + liveTracks = messaging.pub_sock(context, service_list['liveTracks'].port) + + path_x = np.arange(0.0, 140.0, 0.1) # 140 meters is max + + # Time-alignment + rate = 20. # model and radar are both at 20Hz + tsv = 1./rate + v_len = 20 # how many speed data points to remember for t alignment with rdr data + + active = 0 + steer_angle = 0. + steer_override = False + + tracks = defaultdict(dict) + + # Kalman filter stuff: + ekfv = EKFV1D() + speedSensorV = SimpleSensor(XV, 1, 2) + + # v_ego + v_ego = None + v_ego_array = np.zeros([2, v_len]) + v_ego_t_aligned = 0. + + rk = Ratekeeper(rate, print_delay_threshold=np.inf) + while 1: + rr = RI.update() + + ar_pts = {} + for pt in rr.points: + ar_pts[pt.trackId] = [pt.dRel + RDR_TO_LDR, pt.yRel, pt.vRel, pt.measured] + + # receive the live100s + l100 = None + md = None + + for socket, event in poller.poll(0): + if socket is live100: + l100 = messaging.recv_one(socket) + elif socket is model: + md = messaging.recv_one(socket) + + if l100 is not None: + active = l100.live100.active + v_ego = l100.live100.vEgo + steer_angle = l100.live100.angleSteers + steer_override = l100.live100.steerOverride + + v_ego_array = np.append(v_ego_array, [[v_ego], [float(rk.frame)/rate]], 1) + v_ego_array = v_ego_array[:, 1:] + + last_l100_ts = l100.logMonoTime + + if v_ego is None: + continue + + if md is not None: + last_md_ts = md.logMonoTime + + # *** get path prediction from the model *** + PP.update(v_ego, md) + + # run kalman filter only if prob is high enough + if PP.lead_prob > 0.7: + reading = speedSensorV.read(PP.lead_dist, covar=np.matrix(PP.lead_var)) + ekfv.update_scalar(reading) + ekfv.predict(tsv) + + # When changing lanes the distance to the lead car can suddenly change, + # which makes the Kalman filter output large relative acceleration + if mocked and abs(PP.lead_dist - ekfv.state[XV]) > 2.0: + ekfv.state[XV] = PP.lead_dist + ekfv.covar = (np.diag([PP.lead_var, ekfv.var_init])) + ekfv.state[SPEEDV] = 0. + + ar_pts[VISION_POINT] = (float(ekfv.state[XV]), np.polyval(PP.d_poly, float(ekfv.state[XV])), + float(ekfv.state[SPEEDV]), False) + else: + ekfv.state[XV] = PP.lead_dist + ekfv.covar = (np.diag([PP.lead_var, ekfv.var_init])) + ekfv.state[SPEEDV] = 0. + + if VISION_POINT in ar_pts: + del ar_pts[VISION_POINT] + + # *** compute the likely path_y *** + if (active and not steer_override) or mocked: + # use path from model (always when mocking as steering is too noisy) + path_y = np.polyval(PP.d_poly, path_x) + else: + # use path from steer, set angle_offset to 0 it does not only report the physical offset + path_y = calc_lookahead_offset(v_ego, steer_angle, path_x, VM, angle_offset=0)[0] + + # *** remove missing points from meta data *** + for ids in tracks.keys(): + if ids not in ar_pts: + tracks.pop(ids, None) + + # *** compute the tracks *** + for ids in ar_pts: + # ignore standalone vision point, unless we are mocking the radar + if ids == VISION_POINT and not mocked: + continue + rpt = ar_pts[ids] + + # align v_ego by a fixed time to align it with the radar measurement + cur_time = float(rk.frame)/rate + v_ego_t_aligned = np.interp(cur_time - RI.delay, v_ego_array[1], v_ego_array[0]) + d_path = np.sqrt(np.amin((path_x - rpt[0]) ** 2 + (path_y - rpt[1]) ** 2)) + # add sign + d_path *= np.sign(rpt[1] - np.interp(rpt[0], path_x, path_y)) + + # create the track if it doesn't exist or it's a new track + if ids not in tracks: + tracks[ids] = Track() + tracks[ids].update(rpt[0], rpt[1], rpt[2], d_path, v_ego_t_aligned, rpt[3], steer_override) + + # allow the vision model to remove the stationary flag if distance and rel speed roughly match + if VISION_POINT in ar_pts: + fused_id = None + best_score = NO_FUSION_SCORE + for ids in tracks: + dist_to_vision = np.sqrt((0.5*(ar_pts[VISION_POINT][0] - tracks[ids].dRel)) ** 2 + (2*(ar_pts[VISION_POINT][1] - tracks[ids].yRel)) ** 2) + rel_speed_diff = abs(ar_pts[VISION_POINT][2] - tracks[ids].vRel) + tracks[ids].update_vision_score(dist_to_vision, rel_speed_diff) + if best_score > tracks[ids].vision_score: + fused_id = ids + best_score = tracks[ids].vision_score + + if fused_id is not None: + tracks[fused_id].vision_cnt += 1 + tracks[fused_id].update_vision_fusion() + + if DEBUG: + print("NEW CYCLE") + if VISION_POINT in ar_pts: + print("vision", ar_pts[VISION_POINT]) + + idens = tracks.keys() + track_pts = np.array([tracks[iden].get_key_for_cluster() for iden in idens]) + + # If we have multiple points, cluster them + if len(track_pts) > 1: + link = linkage_vector(track_pts, method='centroid') + cluster_idxs = fcluster(link, 2.5, criterion='distance') + clusters = [None]*max(cluster_idxs) + + for idx in xrange(len(track_pts)): + cluster_i = cluster_idxs[idx]-1 + + if clusters[cluster_i] == None: + clusters[cluster_i] = Cluster() + clusters[cluster_i].add(tracks[idens[idx]]) + elif len(track_pts) == 1: + # TODO: why do we need this? + clusters = [Cluster()] + clusters[0].add(tracks[idens[0]]) + else: + clusters = [] + + if DEBUG: + for i in clusters: + print(i) + # *** extract the lead car *** + lead_clusters = [c for c in clusters + if c.is_potential_lead(v_ego)] + lead_clusters.sort(key=lambda x: x.dRel) + lead_len = len(lead_clusters) + + # *** extract the second lead from the whole set of leads *** + lead2_clusters = [c for c in lead_clusters + if c.is_potential_lead2(lead_clusters)] + lead2_clusters.sort(key=lambda x: x.dRel) + lead2_len = len(lead2_clusters) + + # *** publish live20 *** + dat = messaging.new_message() + dat.init('live20') + dat.live20.mdMonoTime = last_md_ts + dat.live20.canMonoTimes = list(rr.canMonoTimes) + dat.live20.radarErrors = list(rr.errors) + dat.live20.l100MonoTime = last_l100_ts + if lead_len > 0: + dat.live20.leadOne = lead_clusters[0].toLive20() + if lead2_len > 0: + dat.live20.leadTwo = lead2_clusters[0].toLive20() + else: + dat.live20.leadTwo.status = False + else: + dat.live20.leadOne.status = False + + dat.live20.cumLagMs = -rk.remaining*1000. + live20.send(dat.to_bytes()) + + # *** publish tracks for UI debugging (keep last) *** + dat = messaging.new_message() + dat.init('liveTracks', len(tracks)) + + for cnt, ids in enumerate(tracks.keys()): + if DEBUG: + print("id: %4.0f x: %4.1f y: %4.1f vr: %4.1f d: %4.1f va: %4.1f vl: %4.1f vlk: %4.1f alk: %4.1f s: %1.0f v: %1.0f" % \ + (ids, tracks[ids].dRel, tracks[ids].yRel, tracks[ids].vRel, + tracks[ids].dPath, tracks[ids].vLat, + tracks[ids].vLead, tracks[ids].vLeadK, + tracks[ids].aLeadK, + tracks[ids].stationary, + tracks[ids].measured)) + dat.liveTracks[cnt] = { + "trackId": ids, + "dRel": float(tracks[ids].dRel), + "yRel": float(tracks[ids].yRel), + "vRel": float(tracks[ids].vRel), + "aRel": float(tracks[ids].aRel), + "stationary": bool(tracks[ids].stationary), + "oncoming": bool(tracks[ids].oncoming), + } + liveTracks.send(dat.to_bytes()) + + rk.monitor_time() + +def main(gctx=None): + radard_thread(gctx) + +if __name__ == "__main__": + main() diff --git a/selfdrive/crash.py b/selfdrive/crash.py new file mode 100644 index 00000000000000..20003ee9faff57 --- /dev/null +++ b/selfdrive/crash.py @@ -0,0 +1,40 @@ +"""Install exception handler for process crash.""" +import os +import sys +from selfdrive.version import version, dirty + +from selfdrive.swaglog import cloudlog + +if os.getenv("NOLOG") or os.getenv("NOCRASH"): + def capture_exception(*exc_info): + pass + def bind_user(**kwargs): + pass + def bind_extra(**kwargs): + pass + def install(): + pass +else: + from raven import Client + from raven.transport.http import HTTPTransport + client = Client('https://1994756b5e6f41cf939a4c65de45f4f2:cefebaf3a8aa40d182609785f7189bd7@app.getsentry.com/77924', + install_sys_hook=False, transport=HTTPTransport, release=version, tags={'dirty': dirty}) + + def capture_exception(*args, **kwargs): + client.captureException(*args, **kwargs) + cloudlog.error("crash", exc_info=kwargs.get('exc_info', 1)) + + def bind_user(**kwargs): + client.user_context(kwargs) + + def bind_extra(**kwargs): + client.extra_context(kwargs) + + def install(): + # installs a sys.excepthook + __excepthook__ = sys.excepthook + def handle_exception(*exc_info): + if exc_info[0] not in (KeyboardInterrupt, SystemExit): + capture_exception(exc_info=exc_info) + __excepthook__(*exc_info) + sys.excepthook = handle_exception diff --git a/selfdrive/debug/can_printer.py b/selfdrive/debug/can_printer.py new file mode 100755 index 00000000000000..d7cbabe63ac139 --- /dev/null +++ b/selfdrive/debug/can_printer.py @@ -0,0 +1,44 @@ +#!/usr/bin/env python +import os +import sys +from collections import defaultdict +from common.realtime import sec_since_boot +import zmq +import selfdrive.messaging as messaging +from selfdrive.services import service_list + + +def can_printer(bus=0, max_msg=None, addr="127.0.0.1"): + context = zmq.Context() + logcan = messaging.sub_sock(context, service_list['can'].port, addr=addr) + + start = sec_since_boot() + lp = sec_since_boot() + msgs = defaultdict(list) + canbus = int(os.getenv("CAN", bus)) + while 1: + can_recv = messaging.drain_sock(logcan, wait_for_one=True) + for x in can_recv: + for y in x.can: + if y.src == canbus: + msgs[y.address].append(y.dat) + + if sec_since_boot() - lp > 0.1: + dd = chr(27) + "[2J" + dd += "%5.2f\n" % (sec_since_boot() - start) + for k,v in sorted(zip(msgs.keys(), map(lambda x: x[-1].encode("hex"), msgs.values()))): + if max_msg is None or k < max_msg: + dd += "%s(%6d) %s\n" % ("%04X(%4d)" % (k,k),len(msgs[k]), v) + print dd + lp = sec_since_boot() + +if __name__ == "__main__": + if len(sys.argv) > 3: + can_printer(int(sys.argv[1]), int(sys.argv[2]), sys.argv[3]) + elif len(sys.argv) > 2: + can_printer(int(sys.argv[1]), int(sys.argv[2])) + elif len(sys.argv) > 1: + can_printer(int(sys.argv[1])) + else: + can_printer() + diff --git a/selfdrive/debug/dump.py b/selfdrive/debug/dump.py new file mode 100755 index 00000000000000..80ac6e4b50859a --- /dev/null +++ b/selfdrive/debug/dump.py @@ -0,0 +1,83 @@ +#!/usr/bin/env python +import sys +import argparse +import zmq +import json +from hexdump import hexdump +from threading import Thread + +from cereal import log +import selfdrive.messaging as messaging +from selfdrive.services import service_list + +def run_server(socketio): + socketio.run(app, host='0.0.0.0', port=4000) + +if __name__ == "__main__": + context = zmq.Context() + poller = zmq.Poller() + + parser = argparse.ArgumentParser(description='Sniff a communcation socket') + parser.add_argument('--pipe', action='store_true') + parser.add_argument('--raw', action='store_true') + parser.add_argument('--json', action='store_true') + parser.add_argument('--dump-json', action='store_true') + parser.add_argument('--no-print', action='store_true') + parser.add_argument('--proxy', action='store_true', help='republish on localhost') + parser.add_argument('--map', action='store_true') + parser.add_argument('--addr', default='127.0.0.1') + parser.add_argument("socket", type=str, nargs='*', help="socket name") + args = parser.parse_args() + + republish_socks = {} + + for m in args.socket if len(args.socket) > 0 else service_list: + if m in service_list: + port = service_list[m].port + elif m.isdigit(): + port = int(m) + else: + print("service not found") + exit(-1) + sock = messaging.sub_sock(context, port, poller, addr=args.addr) + if args.proxy: + republish_socks[sock] = messaging.pub_sock(context, port) + + if args.map: + from flask.ext.socketio import SocketIO #pylint: disable=no-name-in-module, import-error + from flask import Flask + app = Flask(__name__) + socketio = SocketIO(app, async_mode='threading') + server_thread = Thread(target=run_server, args=(socketio,)) + server_thread.daemon = True + server_thread.start() + print 'server running' + + while 1: + polld = poller.poll(timeout=1000) + for sock, mode in polld: + if mode != zmq.POLLIN: + continue + msg = sock.recv() + evt = log.Event.from_bytes(msg) + if sock in republish_socks: + republish_socks[sock].send(msg) + if args.map and evt.which() == 'liveLocation': + print 'send loc' + socketio.emit('location', { + 'lat': evt.liveLocation.lat, + 'lon': evt.liveLocation.lon, + 'alt': evt.liveLocation.alt, + }) + if not args.no_print: + if args.pipe: + sys.stdout.write(msg) + sys.stdout.flush() + elif args.raw: + hexdump(msg) + elif args.json: + print(json.loads(msg)) + elif args.dump_json: + print json.dumps(evt.to_dict()) + else: + print evt diff --git a/selfdrive/debug/get_fingerprint.py b/selfdrive/debug/get_fingerprint.py new file mode 100755 index 00000000000000..dd8eb4d8088dd4 --- /dev/null +++ b/selfdrive/debug/get_fingerprint.py @@ -0,0 +1,30 @@ +#!/usr/bin/env python + +# simple script to get a vehicle fingerprint. + +# Instructions: +# - connect to a Panda +# - run selfdrive/boardd/boardd +# - launching this script +# - since some messages are published at low frequency, keep this script running for few +# seconds, until all messages are received at least once + +import zmq +import selfdrive.messaging as messaging +from selfdrive.services import service_list + +context = zmq.Context() +logcan = messaging.sub_sock(context, service_list['can'].port) +msgs = {} +while True: + lc = messaging.recv_sock(logcan, True) + for c in lc.can: + # read also msgs sent by EON on CAN bus 0x80 and filter out the + # addr with more than 11 bits + if c.src%0x80 == 0 and c.address < 0x800: + msgs[c.address] = len(c.dat) + + fingerprint = ', '.join("%d: %d" % v for v in sorted(msgs.items())) + + print "number of messages:", len(msgs) + print "fingerprint", fingerprint diff --git a/selfdrive/debug/getframes/Makefile b/selfdrive/debug/getframes/Makefile new file mode 100644 index 00000000000000..932673e208d116 --- /dev/null +++ b/selfdrive/debug/getframes/Makefile @@ -0,0 +1,26 @@ +CC = clang +CXX = clang++ + +WARN_FLAGS = -Werror=implicit-function-declaration \ + -Werror=incompatible-pointer-types \ + -Werror=int-conversion \ + -Werror=return-type \ + -Werror=format-extra-args + +CFLAGS = -std=gnu11 -g -fPIC -O2 $(WARN_FLAGS) + +.PHONY: all +all: libvisionipc.so + +visionipc.o: ../../common/visionipc.c ../../common/visionipc.h + @echo "[ CC ] $@" + $(CC) $(CFLAGS) -MMD \ + -I../.. -I../../.. \ + -c -o '$@' ../../common/visionipc.c + +libvisionipc.so: visionipc.o + $(CC) -shared -fPIC -o '$@' visionipc.o + +.PHONY: clean +clean: + rm visionipc.o libvisionipc.so diff --git a/selfdrive/debug/getframes/__init__.py b/selfdrive/debug/getframes/__init__.py new file mode 100644 index 00000000000000..e69de29bb2d1d6 diff --git a/selfdrive/debug/getframes/getframes.py b/selfdrive/debug/getframes/getframes.py new file mode 100755 index 00000000000000..292368d6a97ea6 --- /dev/null +++ b/selfdrive/debug/getframes/getframes.py @@ -0,0 +1,101 @@ +#!/usr/bin/env python +import os +import subprocess +from cffi import FFI + +import numpy as np + +gf_dir = os.path.dirname(os.path.abspath(__file__)) + +subprocess.check_call(["make"], cwd=gf_dir) + + +ffi = FFI() +ffi.cdef(""" + +typedef enum VisionStreamType { + VISION_STREAM_RGB_BACK, + VISION_STREAM_RGB_FRONT, + VISION_STREAM_YUV, + VISION_STREAM_YUV_FRONT, + VISION_STREAM_MAX, +} VisionStreamType; + +typedef struct VisionUIInfo { + int big_box_x, big_box_y; + int big_box_width, big_box_height; + int transformed_width, transformed_height; + + int front_box_x, front_box_y; + int front_box_width, front_box_height; +} VisionUIInfo; + +typedef struct VisionStreamBufs { + VisionStreamType type; + + int width, height, stride; + size_t buf_len; + + union { + VisionUIInfo ui_info; + } buf_info; +} VisionStreamBufs; + +typedef struct VIPCBuf { + int fd; + size_t len; + void* addr; +} VIPCBuf; + +typedef struct VIPCBufExtra { + // only for yuv + uint32_t frame_id; + uint64_t timestamp_eof; +} VIPCBufExtra; + +typedef struct VisionStream { + int ipc_fd; + int last_idx; + int last_type; + int num_bufs; + VisionStreamBufs bufs_info; + VIPCBuf *bufs; +} VisionStream; + +int visionstream_init(VisionStream *s, VisionStreamType type, bool tbuffer, VisionStreamBufs *out_bufs_info); +VIPCBuf* visionstream_get(VisionStream *s, VIPCBufExtra *out_extra); +void visionstream_destroy(VisionStream *s); + +""" +) + +clib = ffi.dlopen(os.path.join(gf_dir, "libvisionipc.so")) + + +def getframes(front=False): + s = ffi.new("VisionStream*") + buf_info = ffi.new("VisionStreamBufs*") + + if front: + stream_type = clib.VISION_STREAM_RGB_FRONT + else: + stream_type = clib.VISION_STREAM_RGB_BACK + + err = clib.visionstream_init(s, stream_type, True, buf_info) + assert err == 0 + + w = buf_info.width + h = buf_info.height + assert buf_info.stride == w*3 + assert buf_info.buf_len == w*h*3 + + while True: + buf = clib.visionstream_get(s, ffi.NULL) + + pbuf = ffi.buffer(buf.addr, buf.len) + yield np.frombuffer(pbuf, dtype=np.uint8).reshape((h, w, 3)) + + +if __name__ == "__main__": + for buf in getframes(): + print buf.shape, buf[101, 101] diff --git a/selfdrive/kegman_conf.py b/selfdrive/kegman_conf.py new file mode 100644 index 00000000000000..6e3a43c8cd5191 --- /dev/null +++ b/selfdrive/kegman_conf.py @@ -0,0 +1,21 @@ +import json +import os + +class kegman_conf(): + def __init__(self): + self.conf = self.read_config() + + def read_config(self): + if os.path.isfile('/data/kegman.json'): + with open('/data/kegman.json', 'r') as f: + self.config = json.load(f) + else: + self.config = {"cameraOffset":"0.06", "lastTrMode":"1", "battChargeMin":"60", "battChargeMax":"70", "wheelTouchSeconds":"180" } + self.write_config(self.config) + return self.config + + def write_config(self, config): + with open('/data/kegman.json', 'w') as f: + json.dump(self.config, f, indent=2, sort_keys=True) + os.chmod("/data/kegman.json", 0o764) + diff --git a/selfdrive/locationd/__init__.py b/selfdrive/locationd/__init__.py new file mode 100644 index 00000000000000..e69de29bb2d1d6 diff --git a/selfdrive/locationd/calibration_helpers.py b/selfdrive/locationd/calibration_helpers.py new file mode 100644 index 00000000000000..f2909007594924 --- /dev/null +++ b/selfdrive/locationd/calibration_helpers.py @@ -0,0 +1,11 @@ +import math + +class Filter: + MIN_SPEED = 7 # m/s (~15.5mph) + MAX_YAW_RATE = math.radians(3) # per second + +class Calibration: + UNCALIBRATED = 0 + CALIBRATED = 1 + INVALID = 2 + diff --git a/selfdrive/locationd/calibrationd.py b/selfdrive/locationd/calibrationd.py new file mode 100755 index 00000000000000..6c395efed20dc8 --- /dev/null +++ b/selfdrive/locationd/calibrationd.py @@ -0,0 +1,255 @@ +#!/usr/bin/env python +import os +import zmq +import cv2 +import copy +import json +import numpy as np +import selfdrive.messaging as messaging +from selfdrive.locationd.calibration_helpers import Calibration, Filter +from selfdrive.swaglog import cloudlog +from selfdrive.services import service_list +from common.params import Params +from common.ffi_wrapper import ffi_wrap +import common.transformations.orientation as orient +from common.transformations.model import model_height, get_camera_frame_from_model_frame, get_camera_frame_from_bigmodel_frame +from common.transformations.camera import view_frame_from_device_frame, get_view_frame_from_road_frame, \ + eon_intrinsics, get_calib_from_vp, normalize, denormalize, H, W + + +FRAMES_NEEDED = 120 # allow to update VP every so many frames +VP_CYCLES_NEEDED = 2 +CALIBRATION_CYCLES_NEEDED = FRAMES_NEEDED * VP_CYCLES_NEEDED +DT = 0.1 # nominal time step of 10Hz (orbd_live runs slower on pc) +VP_RATE_LIM = 2. * DT # 2 px/s +VP_INIT = np.array([W/2., H/2.]) +EXTERNAL_PATH = os.path.dirname(os.path.abspath(__file__)) +# big model is 864x288 +VP_VALIDITY_CORNERS = np.array([[-150., -200.], [150., 200.]]) + VP_INIT +GRID_WEIGHT_INIT = 2e6 +MAX_LINES = 500 # max lines to avoid over computation +HOOD_HEIGHT = H*3/4 # the part of image usually free from the car's hood + +DEBUG = os.getenv("DEBUG") is not None + +# Wrap c code for slow grid incrementation +c_header = "\nvoid increment_grid(double *grid, double *lines, long long n);" +c_code = "#define H %d\n" % H +c_code += "#define W %d\n" % W +c_code += "\n" + open(os.path.join(EXTERNAL_PATH, "get_vp.c")).read() +ffi, lib = ffi_wrap('get_vp', c_code, c_header) + + +def increment_grid_c(grid, lines, n): + lib.increment_grid(ffi.cast("double *", grid.ctypes.data), + ffi.cast("double *", lines.ctypes.data), + ffi.cast("long long", n)) + +def get_lines(p): + A = (p[:,0,1] - p[:,1,1]) + B = (p[:,1,0] - p[:,0,0]) + C = (p[:,0,0]*p[:,1,1] - p[:,1,0]*p[:,0,1]) + return np.column_stack((A, B, -C)) + +def correct_pts(pts, rot_speeds, dt): + pts = np.hstack((pts, np.ones((pts.shape[0],1)))) + cam_rot = dt * view_frame_from_device_frame.dot(rot_speeds) + rot = orient.rot_matrix(*cam_rot.T).T + pts_corrected = rot.dot(pts.T).T + pts_corrected[:,0] /= pts_corrected[:,2] + pts_corrected[:,1] /= pts_corrected[:,2] + return pts_corrected[:,:2] + +def gaussian_kernel(sizex, sizey, stdx, stdy, dx, dy): + y, x = np.mgrid[-sizey:sizey+1, -sizex:sizex+1] + g = np.exp(-((x - dx)**2 / (2. * stdx**2) + (y - dy)**2 / (2. * stdy**2))) + return g / g.sum() + +def gaussian_kernel_1d(kernel): + #creates separable gaussian filter + u,s,v = np.linalg.svd(kernel) + x = u[:,0]*np.sqrt(s[0]) + y = np.sqrt(s[0])*v[0,:] + return x, y + +def blur_image(img, kernel_x, kernel_y): + return cv2.sepFilter2D(img.astype(np.uint16), -1, kernel_x, kernel_y) + +def is_calibration_valid(vp): + return vp[0] > VP_VALIDITY_CORNERS[0,0] and vp[0] < VP_VALIDITY_CORNERS[1,0] and \ + vp[1] > VP_VALIDITY_CORNERS[0,1] and vp[1] < VP_VALIDITY_CORNERS[1,1] + +class Calibrator(object): + def __init__(self, param_put=False): + self.param_put = param_put + self.speed = 0 + self.vp_cycles = 0 + self.angle_offset = 0. + self.yaw_rate = 0. + self.l100_last_updated = 0 + self.prev_orbs = None + self.kernel = gaussian_kernel(11, 11, 2.35, 2.35, 0, 0) + self.kernel_x, self.kernel_y = gaussian_kernel_1d(self.kernel) + + self.vp = copy.copy(VP_INIT) + self.cal_status = Calibration.UNCALIBRATED + self.frame_counter = 0 + self.params = Params() + calibration_params = self.params.get("CalibrationParams") + if calibration_params: + try: + calibration_params = json.loads(calibration_params) + self.vp = np.array(calibration_params["vanishing_point"]) + self.cal_status = Calibration.CALIBRATED if is_calibration_valid(self.vp) else Calibration.INVALID + self.vp_cycles = VP_CYCLES_NEEDED + self.frame_counter = CALIBRATION_CYCLES_NEEDED + except Exception: + cloudlog.exception("CalibrationParams file found but error encountered") + + self.vp_unfilt = self.vp + self.orb_last_updated = 0. + self.reset_grid() + + def reset_grid(self): + if self.cal_status == Calibration.UNCALIBRATED: + # empty grid + self.grid = np.zeros((H+1, W+1), dtype=np.float) + else: + # gaussian grid, centered at vp + self.grid = gaussian_kernel(W/2., H/2., 16, 16, self.vp[0] - W/2., self.vp[1] - H/2.) * GRID_WEIGHT_INIT + + def rescale_grid(self): + self.grid *= 0.9 + + def update(self, uvs, yaw_rate, speed): + if len(uvs) < 10 or \ + abs(yaw_rate) > Filter.MAX_YAW_RATE or \ + speed < Filter.MIN_SPEED: + return + rot_speeds = np.array([0.,0.,-yaw_rate]) + uvs[:,1,:] = denormalize(correct_pts(normalize(uvs[:,1,:]), rot_speeds, self.dt)) + # exclude tracks where: + # - pixel movement was less than 10 pixels + # - tracks are in the "hood region" + good_tracks = np.all([np.linalg.norm(uvs[:,1,:] - uvs[:,0,:], axis=1) > 10, + uvs[:,0,1] < HOOD_HEIGHT, + uvs[:,1,1] < HOOD_HEIGHT], axis = 0) + uvs = uvs[good_tracks] + if uvs.shape[0] > MAX_LINES: + uvs = uvs[np.random.choice(uvs.shape[0], MAX_LINES, replace=False), :] + lines = get_lines(uvs) + + increment_grid_c(self.grid, lines, len(lines)) + self.frame_counter += 1 + if (self.frame_counter % FRAMES_NEEDED) == 0: + grid = blur_image(self.grid, self.kernel_x, self.kernel_y) + argmax_vp = np.unravel_index(np.argmax(grid), grid.shape)[::-1] + self.rescale_grid() + self.vp_unfilt = np.array(argmax_vp) + self.vp_cycles += 1 + if (self.vp_cycles - VP_CYCLES_NEEDED) % 10 == 0: # update file every 10 + # skip rate_lim before writing the file to avoid writing a lagged vp + if self.cal_status != Calibration.CALIBRATED: + self.vp = self.vp_unfilt + if self.param_put: + cal_params = {"vanishing_point": list(self.vp), "angle_offset2": self.angle_offset} + self.params.put("CalibrationParams", json.dumps(cal_params)) + return self.vp_unfilt + + def parse_orb_features(self, log): + matches = np.array(log.orbFeatures.matches) + n = len(log.orbFeatures.matches) + t = float(log.orbFeatures.timestampLastEof)*1e-9 + if t == 0 or n == 0: + return t, np.zeros((0,2,2)) + orbs = denormalize(np.column_stack((log.orbFeatures.xs, + log.orbFeatures.ys))) + if self.prev_orbs is not None: + valid_matches = (matches > -1) & (matches < len(self.prev_orbs)) + tracks = np.hstack((orbs[valid_matches], self.prev_orbs[matches[valid_matches]])).reshape((-1,2,2)) + else: + tracks = np.zeros((0,2,2)) + self.prev_orbs = orbs + return t, tracks + + def update_vp(self): + # rate limit to not move VP too fast + self.vp = np.clip(self.vp_unfilt, self.vp - VP_RATE_LIM, self.vp + VP_RATE_LIM) + if self.vp_cycles < VP_CYCLES_NEEDED: + self.cal_status = Calibration.UNCALIBRATED + else: + self.cal_status = Calibration.CALIBRATED if is_calibration_valid(self.vp) else Calibration.INVALID + + def handle_orb_features(self, log): + self.update_vp() + self.time_orb, frame_raw = self.parse_orb_features(log) + self.dt = min(self.time_orb - self.orb_last_updated, 1.) + self.orb_last_updated = self.time_orb + if self.time_orb - self.l100_last_updated < 1: + return self.update(frame_raw, self.yaw_rate, self.speed) + + def handle_live100(self, log): + self.l100_last_updated = self.time_orb + self.speed = log.live100.vEgo + self.angle_offset = log.live100.angleOffset + self.yaw_rate = log.live100.curvature * self.speed + + def handle_debug(self): + grid_blurred = blur_image(self.grid, self.kernel_x, self.kernel_y) + grid_grey = np.clip(grid_blurred/(0.1 + np.max(grid_blurred))*255, 0, 255) + grid_color = np.repeat(grid_grey[:,:,np.newaxis], 3, axis=2) + grid_color[:,:,0] = 0 + cv2.circle(grid_color, tuple(self.vp.astype(np.int64)), 2, (255, 255, 0), -1) + cv2.imshow("debug", grid_color.astype(np.uint8)) + + cv2.waitKey(1) + + def send_data(self, livecalibration): + calib = get_calib_from_vp(self.vp) + extrinsic_matrix = get_view_frame_from_road_frame(0, calib[1], calib[2], model_height) + ke = eon_intrinsics.dot(extrinsic_matrix) + warp_matrix = get_camera_frame_from_model_frame(ke) + warp_matrix_big = get_camera_frame_from_bigmodel_frame(ke) + + cal_send = messaging.new_message() + cal_send.init('liveCalibration') + cal_send.liveCalibration.calStatus = self.cal_status + cal_send.liveCalibration.calPerc = min(self.frame_counter * 100 / CALIBRATION_CYCLES_NEEDED, 100) + cal_send.liveCalibration.warpMatrix2 = map(float, warp_matrix.flatten()) + cal_send.liveCalibration.warpMatrixBig = map(float, warp_matrix_big.flatten()) + cal_send.liveCalibration.extrinsicMatrix = map(float, extrinsic_matrix.flatten()) + + livecalibration.send(cal_send.to_bytes()) + + +def calibrationd_thread(gctx=None, addr="127.0.0.1"): + context = zmq.Context() + + live100 = messaging.sub_sock(context, service_list['live100'].port, addr=addr, conflate=True) + orbfeatures = messaging.sub_sock(context, service_list['orbFeatures'].port, addr=addr, conflate=True) + livecalibration = messaging.pub_sock(context, service_list['liveCalibration'].port) + + calibrator = Calibrator(param_put = True) + + # buffer with all the messages that still need to be input into the kalman + while 1: + of = messaging.recv_one(orbfeatures) + l100 = messaging.recv_one_or_none(live100) + + new_vp = calibrator.handle_orb_features(of) + if DEBUG and new_vp is not None: + print 'got new vp', new_vp + if l100 is not None: + calibrator.handle_live100(l100) + if DEBUG: + calibrator.handle_debug() + + calibrator.send_data(livecalibration) + + +def main(gctx=None, addr="127.0.0.1"): + calibrationd_thread(gctx, addr) + +if __name__ == "__main__": + main() + diff --git a/selfdrive/locationd/ephemeris.py b/selfdrive/locationd/ephemeris.py new file mode 100644 index 00000000000000..dd8155e19a4507 --- /dev/null +++ b/selfdrive/locationd/ephemeris.py @@ -0,0 +1,137 @@ +def GET_FIELD_U(w, nb, pos): + return (((w) >> (pos)) & ((1 << (nb)) - 1)) + + +def twos_complement(v, nb): + sign = v >> (nb - 1) + value = v + if sign != 0: + value = value - (1 << nb) + return value + + +def GET_FIELD_S(w, nb, pos): + v = GET_FIELD_U(w, nb, pos) + return twos_complement(v, nb) + + +def extract_uint8(v, b): + return (v >> (8 * (3 - b))) & 255 + +def extract_int8(v, b): + value = extract_uint8(v, b) + if value > 127: + value -= 256 + return value + +class EphemerisData: + '''container for parsing a AID_EPH message + Thanks to Sylvain Munaut + http://cgit.osmocom.org/cgit/osmocom-lcs/tree/gps.c +on of this parser + + See IS-GPS-200F.pdf Table 20-III for the field meanings, scaling factors and + field widths + ''' + + def __init__(self, svId, subframes): + from math import pow + self.svId = svId + week_no = GET_FIELD_U(subframes[1][2+0], 10, 20) + # code_on_l2 = GET_FIELD_U(subframes[1][0], 2, 12) + # sv_ura = GET_FIELD_U(subframes[1][0], 4, 8) + # sv_health = GET_FIELD_U(subframes[1][0], 6, 2) + # l2_p_flag = GET_FIELD_U(subframes[1][1], 1, 23) + t_gd = GET_FIELD_S(subframes[1][2+4], 8, 6) + iodc = (GET_FIELD_U(subframes[1][2+0], 2, 6) << 8) | GET_FIELD_U( + subframes[1][2+5], 8, 22) + + t_oc = GET_FIELD_U(subframes[1][2+5], 16, 6) + a_f2 = GET_FIELD_S(subframes[1][2+6], 8, 22) + a_f1 = GET_FIELD_S(subframes[1][2+6], 16, 6) + a_f0 = GET_FIELD_S(subframes[1][2+7], 22, 8) + + c_rs = GET_FIELD_S(subframes[2][2+0], 16, 6) + delta_n = GET_FIELD_S(subframes[2][2+1], 16, 14) + m_0 = (GET_FIELD_S(subframes[2][2+1], 8, 6) << 24) | GET_FIELD_U( + subframes[2][2+2], 24, 6) + c_uc = GET_FIELD_S(subframes[2][2+3], 16, 14) + e = (GET_FIELD_U(subframes[2][2+3], 8, 6) << 24) | GET_FIELD_U(subframes[2][2+4], 24, 6) + c_us = GET_FIELD_S(subframes[2][2+5], 16, 14) + a_powhalf = (GET_FIELD_U(subframes[2][2+5], 8, 6) << 24) | GET_FIELD_U( + subframes[2][2+6], 24, 6) + t_oe = GET_FIELD_U(subframes[2][2+7], 16, 14) + # fit_flag = GET_FIELD_U(subframes[2][7], 1, 7) + + c_ic = GET_FIELD_S(subframes[3][2+0], 16, 14) + omega_0 = (GET_FIELD_S(subframes[3][2+0], 8, 6) << 24) | GET_FIELD_U( + subframes[3][2+1], 24, 6) + c_is = GET_FIELD_S(subframes[3][2+2], 16, 14) + i_0 = (GET_FIELD_S(subframes[3][2+2], 8, 6) << 24) | GET_FIELD_U( + subframes[3][2+3], 24, 6) + c_rc = GET_FIELD_S(subframes[3][2+4], 16, 14) + w = (GET_FIELD_S(subframes[3][2+4], 8, 6) << 24) | GET_FIELD_U(subframes[3][5], 24, 6) + omega_dot = GET_FIELD_S(subframes[3][2+6], 24, 6) + idot = GET_FIELD_S(subframes[3][2+7], 14, 8) + + self._rsvd1 = GET_FIELD_U(subframes[1][2+1], 23, 6) + self._rsvd2 = GET_FIELD_U(subframes[1][2+2], 24, 6) + self._rsvd3 = GET_FIELD_U(subframes[1][2+3], 24, 6) + self._rsvd4 = GET_FIELD_U(subframes[1][2+4], 16, 14) + self.aodo = GET_FIELD_U(subframes[2][2+7], 5, 8) + + # Definition of Pi used in the GPS coordinate system + gpsPi = 3.1415926535898 + + # now form variables in radians, meters and seconds etc + self.Tgd = t_gd * pow(2, -31) + self.A = pow(a_powhalf * pow(2, -19), 2.0) + self.cic = c_ic * pow(2, -29) + self.cis = c_is * pow(2, -29) + self.crc = c_rc * pow(2, -5) + self.crs = c_rs * pow(2, -5) + self.cuc = c_uc * pow(2, -29) + self.cus = c_us * pow(2, -29) + self.deltaN = delta_n * pow(2, -43) * gpsPi + self.ecc = e * pow(2, -33) + self.i0 = i_0 * pow(2, -31) * gpsPi + self.idot = idot * pow(2, -43) * gpsPi + self.M0 = m_0 * pow(2, -31) * gpsPi + self.omega = w * pow(2, -31) * gpsPi + self.omega_dot = omega_dot * pow(2, -43) * gpsPi + self.omega0 = omega_0 * pow(2, -31) * gpsPi + self.toe = t_oe * pow(2, 4) + + # clock correction information + self.toc = t_oc * pow(2, 4) + self.gpsWeek = week_no + self.af0 = a_f0 * pow(2, -31) + self.af1 = a_f1 * pow(2, -43) + self.af2 = a_f2 * pow(2, -55) + + iode1 = GET_FIELD_U(subframes[2][2+0], 8, 22) + iode2 = GET_FIELD_U(subframes[3][2+7], 8, 22) + self.valid = (iode1 == iode2) and (iode1 == (iodc & 0xff)) + self.iode = iode1 + + if GET_FIELD_U(subframes[4][2+0], 6, 22) == 56 and \ + GET_FIELD_U(subframes[4][2+0], 2, 28) == 1 and \ + GET_FIELD_U(subframes[5][2+0], 2, 28) == 1: + a0 = GET_FIELD_S(subframes[4][2], 8, 14) * pow(2, -30) + a1 = GET_FIELD_S(subframes[4][2], 8, 6) * pow(2, -27) + a2 = GET_FIELD_S(subframes[4][3], 8, 22) * pow(2, -24) + a3 = GET_FIELD_S(subframes[4][3], 8, 14) * pow(2, -24) + b0 = GET_FIELD_S(subframes[4][3], 8, 6) * pow(2, 11) + b1 = GET_FIELD_S(subframes[4][4], 8, 22) * pow(2, 14) + b2 = GET_FIELD_S(subframes[4][4], 8, 14) * pow(2, 16) + b3 = GET_FIELD_S(subframes[4][4], 8, 6) * pow(2, 16) + + self.ionoAlpha = [a0, a1, a2, a3] + self.ionoBeta = [b0, b1, b2, b3] + self.ionoCoeffsValid = True + else: + self.ionoAlpha = [] + self.ionoBeta = [] + self.ionoCoeffsValid = False + + diff --git a/selfdrive/locationd/get_vp.c b/selfdrive/locationd/get_vp.c new file mode 100644 index 00000000000000..8a48c88150b4cb --- /dev/null +++ b/selfdrive/locationd/get_vp.c @@ -0,0 +1,41 @@ +int get_intersections(double *lines, double *intersections, long long n) { + double D, Dx, Dy; + double x, y; + double *L1, *L2; + int k = 0; + for (int i=0; i < n; i++) { + for (int j=0; j < n; j++) { + L1 = lines + i*3; + L2 = lines + j*3; + D = L1[0] * L2[1] - L1[1] * L2[0]; + Dx = L1[2] * L2[1] - L1[1] * L2[2]; + Dy = L1[0] * L2[2] - L1[2] * L2[0]; + // only intersect lines from different quadrants and only left-right crossing + if ((D != 0) && (L1[0]*L2[0]*L1[1]*L2[1] < 0) && (L1[1]*L2[1] < 0)){ + x = Dx / D; + y = Dy / D; + if ((0 < x) && + (x < W) && + (0 < y) && + (y < H)){ + intersections[k*2 + 0] = x; + intersections[k*2 + 1] = y; + k++; + } + } + } + } + return k; +} + +void increment_grid(double *grid, double *lines, long long n) { + double *intersections = (double*) malloc(n*n*2*sizeof(double)); + int y, x, k; + k = get_intersections(lines, intersections, n); + for (int i=0; i < k; i++) { + x = (int) (intersections[i*2 + 0] + 0.5); + y = (int) (intersections[i*2 + 1] + 0.5); + grid[y*(W+1) + x] += 1.; + } + free(intersections); +} diff --git a/selfdrive/locationd/ublox.py b/selfdrive/locationd/ublox.py new file mode 100644 index 00000000000000..228dfc8433e9c1 --- /dev/null +++ b/selfdrive/locationd/ublox.py @@ -0,0 +1,995 @@ +#!/usr/bin/env python +''' +UBlox binary protocol handling + +Copyright Andrew Tridgell, October 2012 +Released under GNU GPL version 3 or later + +WARNING: This code has originally intended for +ublox version 7, it has been adapted to work +for ublox version 8, not all functions may work. +''' + +import struct +import time, os + +# protocol constants +PREAMBLE1 = 0xb5 +PREAMBLE2 = 0x62 + +# message classes +CLASS_NAV = 0x01 +CLASS_RXM = 0x02 +CLASS_INF = 0x04 +CLASS_ACK = 0x05 +CLASS_CFG = 0x06 +CLASS_MON = 0x0A +CLASS_AID = 0x0B +CLASS_TIM = 0x0D +CLASS_ESF = 0x10 + +# ACK messages +MSG_ACK_NACK = 0x00 +MSG_ACK_ACK = 0x01 + +# NAV messages +MSG_NAV_POSECEF = 0x1 +MSG_NAV_POSLLH = 0x2 +MSG_NAV_STATUS = 0x3 +MSG_NAV_DOP = 0x4 +MSG_NAV_SOL = 0x6 +MSG_NAV_PVT = 0x7 +MSG_NAV_POSUTM = 0x8 +MSG_NAV_VELNED = 0x12 +MSG_NAV_VELECEF = 0x11 +MSG_NAV_TIMEGPS = 0x20 +MSG_NAV_TIMEUTC = 0x21 +MSG_NAV_CLOCK = 0x22 +MSG_NAV_SVINFO = 0x30 +MSG_NAV_AOPSTATUS = 0x60 +MSG_NAV_DGPS = 0x31 +MSG_NAV_DOP = 0x04 +MSG_NAV_EKFSTATUS = 0x40 +MSG_NAV_SBAS = 0x32 +MSG_NAV_SOL = 0x06 + +# RXM messages +MSG_RXM_RAW = 0x15 +MSG_RXM_SFRB = 0x11 +MSG_RXM_SFRBX = 0x13 +MSG_RXM_SVSI = 0x20 +MSG_RXM_EPH = 0x31 +MSG_RXM_ALM = 0x30 +MSG_RXM_PMREQ = 0x41 + +# AID messages +MSG_AID_ALM = 0x30 +MSG_AID_EPH = 0x31 +MSG_AID_ALPSRV = 0x32 +MSG_AID_AOP = 0x33 +MSG_AID_DATA = 0x10 +MSG_AID_ALP = 0x50 +MSG_AID_DATA = 0x10 +MSG_AID_HUI = 0x02 +MSG_AID_INI = 0x01 +MSG_AID_REQ = 0x00 + +# CFG messages +MSG_CFG_PRT = 0x00 +MSG_CFG_ANT = 0x13 +MSG_CFG_DAT = 0x06 +MSG_CFG_EKF = 0x12 +MSG_CFG_ESFGWT = 0x29 +MSG_CFG_CFG = 0x09 +MSG_CFG_USB = 0x1b +MSG_CFG_RATE = 0x08 +MSG_CFG_SET_RATE = 0x01 +MSG_CFG_NAV5 = 0x24 +MSG_CFG_FXN = 0x0E +MSG_CFG_INF = 0x02 +MSG_CFG_ITFM = 0x39 +MSG_CFG_MSG = 0x01 +MSG_CFG_NAVX5 = 0x23 +MSG_CFG_NMEA = 0x17 +MSG_CFG_NVS = 0x22 +MSG_CFG_PM2 = 0x3B +MSG_CFG_PM = 0x32 +MSG_CFG_RINV = 0x34 +MSG_CFG_RST = 0x04 +MSG_CFG_RXM = 0x11 +MSG_CFG_SBAS = 0x16 +MSG_CFG_TMODE2 = 0x3D +MSG_CFG_TMODE = 0x1D +MSG_CFG_TPS = 0x31 +MSG_CFG_TP = 0x07 +MSG_CFG_GNSS = 0x3E +MSG_CFG_ODO = 0x1E + +# ESF messages +MSG_ESF_MEAS = 0x02 +MSG_ESF_STATUS = 0x10 + +# INF messages +MSG_INF_DEBUG = 0x04 +MSG_INF_ERROR = 0x00 +MSG_INF_NOTICE = 0x02 +MSG_INF_TEST = 0x03 +MSG_INF_WARNING = 0x01 + +# MON messages +MSG_MON_SCHD = 0x01 +MSG_MON_HW = 0x09 +MSG_MON_HW2 = 0x0B +MSG_MON_IO = 0x02 +MSG_MON_MSGPP = 0x06 +MSG_MON_RXBUF = 0x07 +MSG_MON_RXR = 0x21 +MSG_MON_TXBUF = 0x08 +MSG_MON_VER = 0x04 + +# TIM messages +MSG_TIM_TP = 0x01 +MSG_TIM_TM2 = 0x03 +MSG_TIM_SVIN = 0x04 +MSG_TIM_VRFY = 0x06 + +# port IDs +PORT_DDC = 0 +PORT_SERIAL1 = 1 +PORT_SERIAL2 = 2 +PORT_USB = 3 +PORT_SPI = 4 + +# dynamic models +DYNAMIC_MODEL_PORTABLE = 0 +DYNAMIC_MODEL_STATIONARY = 2 +DYNAMIC_MODEL_PEDESTRIAN = 3 +DYNAMIC_MODEL_AUTOMOTIVE = 4 +DYNAMIC_MODEL_SEA = 5 +DYNAMIC_MODEL_AIRBORNE1G = 6 +DYNAMIC_MODEL_AIRBORNE2G = 7 +DYNAMIC_MODEL_AIRBORNE4G = 8 + +#reset items +RESET_HOT = 0 +RESET_WARM = 1 +RESET_COLD = 0xFFFF + +RESET_HW = 0 +RESET_SW = 1 +RESET_SW_GPS = 2 +RESET_HW_GRACEFUL = 4 +RESET_GPS_STOP = 8 +RESET_GPS_START = 9 + + +class UBloxError(Exception): + '''Ublox error class''' + + def __init__(self, msg): + Exception.__init__(self, msg) + self.message = msg + + +class UBloxAttrDict(dict): + '''allow dictionary members as attributes''' + + def __init__(self): + dict.__init__(self) + + def __getattr__(self, name): + try: + return self.__getitem__(name) + except KeyError: + raise AttributeError(name) + + def __setattr__(self, name, value): + if self.__dict__.has_key(name): + # allow set on normal attributes + dict.__setattr__(self, name, value) + else: + self.__setitem__(name, value) + + +def ArrayParse(field): + '''parse an array descriptor''' + arridx = field.find('[') + if arridx == -1: + return (field, -1) + alen = int(field[arridx + 1:-1]) + fieldname = field[:arridx] + return (fieldname, alen) + + +class UBloxDescriptor: + '''class used to describe the layout of a UBlox message''' + + def __init__(self, + name, + msg_format, + fields=[], + count_field=None, + format2=None, + fields2=None): + self.name = name + self.msg_format = msg_format + self.fields = fields + self.count_field = count_field + self.format2 = format2 + self.fields2 = fields2 + + def unpack(self, msg): + '''unpack a UBloxMessage, creating the .fields and ._recs attributes in msg''' + msg._fields = {} + + # unpack main message blocks. A comm + formats = self.msg_format.split(',') + buf = msg._buf[6:-2] + count = 0 + msg._recs = [] + fields = self.fields[:] + + for fmt in formats: + size1 = struct.calcsize(fmt) + if size1 > len(buf): + raise UBloxError("%s INVALID_SIZE1=%u" % (self.name, len(buf))) + f1 = list(struct.unpack(fmt, buf[:size1])) + i = 0 + while i < len(f1): + field = fields.pop(0) + (fieldname, alen) = ArrayParse(field) + if alen == -1: + msg._fields[fieldname] = f1[i] + if self.count_field == fieldname: + count = int(f1[i]) + i += 1 + else: + msg._fields[fieldname] = [0] * alen + for a in range(alen): + msg._fields[fieldname][a] = f1[i] + i += 1 + buf = buf[size1:] + if len(buf) == 0: + break + + if self.count_field == '_remaining': + count = len(buf) / struct.calcsize(self.format2) + + if count == 0: + msg._unpacked = True + if len(buf) != 0: + raise UBloxError("EXTRA_BYTES=%u" % len(buf)) + return + + size2 = struct.calcsize(self.format2) + for c in range(count): + r = UBloxAttrDict() + if size2 > len(buf): + raise UBloxError("INVALID_SIZE=%u, " % len(buf)) + f2 = list(struct.unpack(self.format2, buf[:size2])) + for i in range(len(self.fields2)): + r[self.fields2[i]] = f2[i] + buf = buf[size2:] + msg._recs.append(r) + if len(buf) != 0: + raise UBloxError("EXTRA_BYTES=%u" % len(buf)) + msg._unpacked = True + + def pack(self, msg, msg_class=None, msg_id=None): + '''pack a UBloxMessage from the .fields and ._recs attributes in msg''' + f1 = [] + if msg_class is None: + msg_class = msg.msg_class() + if msg_id is None: + msg_id = msg.msg_id() + msg._buf = '' + + fields = self.fields[:] + for f in fields: + (fieldname, alen) = ArrayParse(f) + if not fieldname in msg._fields: + break + if alen == -1: + f1.append(msg._fields[fieldname]) + else: + for a in range(alen): + f1.append(msg._fields[fieldname][a]) + try: + # try full length message + fmt = self.msg_format.replace(',', '') + msg._buf = struct.pack(fmt, *tuple(f1)) + except Exception: + # try without optional part + fmt = self.msg_format.split(',')[0] + msg._buf = struct.pack(fmt, *tuple(f1)) + + length = len(msg._buf) + if msg._recs: + length += len(msg._recs) * struct.calcsize(self.format2) + header = struct.pack('= level: + print(msg) + + def unpack(self): + '''unpack a message''' + if not self.valid(): + raise UBloxError('INVALID MESSAGE') + type = self.msg_type() + if not type in msg_types: + raise UBloxError('Unknown message %s length=%u' % (str(type), len(self._buf))) + msg_types[type].unpack(self) + return self._fields, self._recs + + def pack(self): + '''pack a message''' + if not self.valid(): + raise UBloxError('INVALID MESSAGE') + type = self.msg_type() + if not type in msg_types: + raise UBloxError('Unknown message %s' % str(type)) + msg_types[type].pack(self) + + def name(self): + '''return the short string name for a message''' + if not self.valid(): + raise UBloxError('INVALID MESSAGE') + type = self.msg_type() + if not type in msg_types: + raise UBloxError('Unknown message %s length=%u' % (str(type), len(self._buf))) + return msg_types[type].name + + def msg_class(self): + '''return the message class''' + return ord(self._buf[2]) + + def msg_id(self): + '''return the message id within the class''' + return ord(self._buf[3]) + + def msg_type(self): + '''return the message type tuple (class, id)''' + return (self.msg_class(), self.msg_id()) + + def msg_length(self): + '''return the payload length''' + (payload_length, ) = struct.unpack(' 0 and ord(self._buf[0]) != PREAMBLE1: + return False + if len(self._buf) > 1 and ord(self._buf[1]) != PREAMBLE2: + self.debug(1, "bad pre2") + return False + if self.needed_bytes() == 0 and not self.valid(): + if len(self._buf) > 8: + self.debug(1, "bad checksum len=%u needed=%u" % (len(self._buf), + self.needed_bytes())) + else: + self.debug(1, "bad len len=%u needed=%u" % (len(self._buf), self.needed_bytes())) + return False + return True + + def add(self, bytes): + '''add some bytes to a message''' + self._buf += bytes + while not self.valid_so_far() and len(self._buf) > 0: + '''handle corrupted streams''' + self._buf = self._buf[1:] + if self.needed_bytes() < 0: + self._buf = "" + + def checksum(self, data=None): + '''return a checksum tuple for a message''' + if data is None: + data = self._buf[2:-2] + #cs = 0 + ck_a = 0 + ck_b = 0 + for i in data: + ck_a = (ck_a + ord(i)) & 0xFF + ck_b = (ck_b + ck_a) & 0xFF + return (ck_a, ck_b) + + def valid_checksum(self): + '''check if the checksum is OK''' + (ck_a, ck_b) = self.checksum() + #d = self._buf[2:-2] + (ck_a2, ck_b2) = struct.unpack('= 8 and self.needed_bytes() == 0 and self.valid_checksum() + + +class UBlox: + '''main UBlox control class. + + port can be a file (for reading only) or a serial device + ''' + + def __init__(self, port, baudrate=115200, timeout=0, panda=False, grey=False): + + self.serial_device = port + self.baudrate = baudrate + self.use_sendrecv = False + self.read_only = False + self.debug_level = 0 + + if panda: + from panda import Panda, PandaSerial + + self.panda = Panda() + + # resetting U-Blox module + self.panda.set_esp_power(0) + time.sleep(0.1) + self.panda.set_esp_power(1) + time.sleep(0.5) + + # can't set above 9600 now... + self.baudrate = 9600 + self.dev = PandaSerial(self.panda, 1, self.baudrate) + + self.baudrate = 460800 + print "upping baud:",self.baudrate + self.send_nmea("$PUBX,41,1,0007,0003,%u,0" % self.baudrate) + time.sleep(0.1) + + self.dev = PandaSerial(self.panda, 1, self.baudrate) + elif grey: + import zmq + from selfdrive.services import service_list + import selfdrive.messaging as messaging + + class BoarddSerial(object): + def __init__(self): + context = zmq.Context() + self.ubloxRaw = messaging.sub_sock(context, service_list['ubloxRaw'].port) + self.buf = "" + + def read(self, n): + for msg in messaging.drain_sock(self.ubloxRaw, len(self.buf) < n): + self.buf += msg.ubloxRaw + ret = self.buf[:n] + self.buf = self.buf[n:] + return ret + + + def write(self, dat): + pass + + self.dev = BoarddSerial() + else: + if self.serial_device.startswith("tcp:"): + import socket + a = self.serial_device.split(':') + destination_addr = (a[1], int(a[2])) + self.dev = socket.socket(socket.AF_INET, socket.SOCK_STREAM) + self.dev.connect(destination_addr) + self.dev.setblocking(1) + self.dev.setsockopt(socket.SOL_TCP, socket.TCP_NODELAY, 1) + self.use_sendrecv = True + elif os.path.isfile(self.serial_device): + self.read_only = True + self.dev = open(self.serial_device, mode='rb') + else: + import serial + self.dev = serial.Serial( + self.serial_device, + baudrate=self.baudrate, + dsrdtr=False, + rtscts=False, + xonxoff=False, + timeout=timeout) + + self.logfile = None + self.log = None + self.preferred_dynamic_model = None + self.preferred_usePPP = None + self.preferred_dgps_timeout = None + + def close(self): + '''close the device''' + self.dev.close() + self.dev = None + + def set_debug(self, debug_level): + '''set debug level''' + self.debug_level = debug_level + + def debug(self, level, msg): + '''write a debug message''' + if self.debug_level >= level: + print(msg) + + def set_logfile(self, logfile, append=False): + '''setup logging to a file''' + if self.log is not None: + self.log.close() + self.log = None + self.logfile = logfile + if self.logfile is not None: + if append: + mode = 'ab' + else: + mode = 'wb' + self.log = open(self.logfile, mode=mode) + + def set_preferred_dynamic_model(self, model): + '''set the preferred dynamic model for receiver''' + self.preferred_dynamic_model = model + if model is not None: + self.configure_poll(CLASS_CFG, MSG_CFG_NAV5) + + def set_preferred_dgps_timeout(self, timeout): + '''set the preferred DGPS timeout for receiver''' + self.preferred_dgps_timeout = timeout + if timeout is not None: + self.configure_poll(CLASS_CFG, MSG_CFG_NAV5) + + def set_preferred_usePPP(self, usePPP): + '''set the preferred usePPP setting for the receiver''' + if usePPP is None: + self.preferred_usePPP = None + return + self.preferred_usePPP = int(usePPP) + self.configure_poll(CLASS_CFG, MSG_CFG_NAVX5) + + def nmea_checksum(self, msg): + d = msg[1:] + cs = 0 + for i in d: + cs ^= ord(i) + return cs + + def write(self, buf): + '''write some bytes''' + if not self.read_only: + if self.use_sendrecv: + return self.dev.send(buf) + return self.dev.write(buf) + + def read(self, n): + '''read some bytes''' + if self.use_sendrecv: + import socket + try: + return self.dev.recv(n) + except socket.error: + return '' + return self.dev.read(n) + + def send_nmea(self, msg): + if not self.read_only: + s = msg + "*%02X" % self.nmea_checksum(msg) + "\r\n" + self.write(s) + + def set_binary(self): + '''put a UBlox into binary mode using a NMEA string''' + if not self.read_only: + print("try set binary at %u" % self.baudrate) + self.send_nmea("$PUBX,41,0,0007,0001,%u,0" % self.baudrate) + self.send_nmea("$PUBX,41,1,0007,0001,%u,0" % self.baudrate) + self.send_nmea("$PUBX,41,2,0007,0001,%u,0" % self.baudrate) + self.send_nmea("$PUBX,41,3,0007,0001,%u,0" % self.baudrate) + self.send_nmea("$PUBX,41,4,0007,0001,%u,0" % self.baudrate) + self.send_nmea("$PUBX,41,5,0007,0001,%u,0" % self.baudrate) + + def disable_nmea(self): + ''' stop sending all types of nmea messages ''' + self.send_nmea("$PUBX,40,GSV,1,1,1,1,1,0") + self.send_nmea("$PUBX,40,GGA,0,0,0,0,0,0") + self.send_nmea("$PUBX,40,GSA,0,0,0,0,0,0") + self.send_nmea("$PUBX,40,VTG,0,0,0,0,0,0") + self.send_nmea("$PUBX,40,TXT,0,0,0,0,0,0") + self.send_nmea("$PUBX,40,RMC,0,0,0,0,0,0") + + def seek_percent(self, pct): + '''seek to the given percentage of a file''' + self.dev.seek(0, 2) + filesize = self.dev.tell() + self.dev.seek(pct * 0.01 * filesize) + + def special_handling(self, msg): + '''handle automatic configuration changes''' + if msg.name() == 'CFG_NAV5': + msg.unpack() + sendit = False + pollit = False + if self.preferred_dynamic_model is not None and msg.dynModel != self.preferred_dynamic_model: + msg.dynModel = self.preferred_dynamic_model + sendit = True + pollit = True + if self.preferred_dgps_timeout is not None and msg.dgpsTimeOut != self.preferred_dgps_timeout: + msg.dgpsTimeOut = self.preferred_dgps_timeout + self.debug(2, "Setting dgpsTimeOut=%u" % msg.dgpsTimeOut) + sendit = True + # we don't re-poll for this one, as some receivers refuse to set it + if sendit: + msg.pack() + self.send(msg) + if pollit: + self.configure_poll(CLASS_CFG, MSG_CFG_NAV5) + if msg.name() == 'CFG_NAVX5' and self.preferred_usePPP is not None: + msg.unpack() + if msg.usePPP != self.preferred_usePPP: + msg.usePPP = self.preferred_usePPP + msg.mask = 1 << 13 + msg.pack() + self.send(msg) + self.configure_poll(CLASS_CFG, MSG_CFG_NAVX5) + + def receive_message(self, ignore_eof=False): + '''blocking receive of one ublox message''' + msg = UBloxMessage() + while True: + n = msg.needed_bytes() + b = self.read(n) + if not b: + if ignore_eof: + time.sleep(0.01) + continue + if len(msg._buf) > 0: + self.debug(1, "dropping %d bytes" % len(msg._buf)) + return None + msg.add(b) + if self.log is not None: + self.log.write(b) + self.log.flush() + if msg.valid(): + self.special_handling(msg) + return msg + + def receive_message_noerror(self, ignore_eof=False): + '''blocking receive of one ublox message, ignoring errors''' + try: + return self.receive_message(ignore_eof=ignore_eof) + except UBloxError as e: + print(e) + return None + except OSError as e: + # Occasionally we get hit with 'resource temporarily unavailable' + # messages here on the serial device, catch them too. + print(e) + return None + + def send(self, msg): + '''send a preformatted ublox message''' + if not msg.valid(): + self.debug(1, "invalid send") + return + if not self.read_only: + self.write(msg._buf) + + def send_message(self, msg_class, msg_id, payload): + '''send a ublox message with class, id and payload''' + msg = UBloxMessage() + msg._buf = struct.pack(' +#include +#include + +#include +#include +#include + +#include +#include +#include "common/timing.h" +#include "cereal/gen/cpp/log.capnp.h" + +int main() { + int err; + + struct logger_list *logger_list = android_logger_list_alloc(ANDROID_LOG_RDONLY, 0, 0); + assert(logger_list); + struct logger *main_logger = android_logger_open(logger_list, LOG_ID_MAIN); + assert(main_logger); + struct logger *radio_logger = android_logger_open(logger_list, LOG_ID_RADIO); + assert(radio_logger); + struct logger *system_logger = android_logger_open(logger_list, LOG_ID_SYSTEM); + assert(system_logger); + struct logger *crash_logger = android_logger_open(logger_list, LOG_ID_CRASH); + assert(crash_logger); + struct logger *kernel_logger = android_logger_open(logger_list, LOG_ID_KERNEL); + assert(kernel_logger); + + void *context = zmq_ctx_new(); + void *publisher = zmq_socket(context, ZMQ_PUB); + err = zmq_bind(publisher, "tcp://*:8020"); + assert(err == 0); + + while (1) { + log_msg log_msg; + err = android_logger_list_read(logger_list, &log_msg); + if (err <= 0) { + break; + } + + AndroidLogEntry entry; + err = android_log_processLogBuffer(&log_msg.entry_v1, &entry); + if (err < 0) { + continue; + } + + capnp::MallocMessageBuilder msg; + cereal::Event::Builder event = msg.initRoot(); + event.setLogMonoTime(nanos_since_boot()); + auto androidEntry = event.initAndroidLogEntry(); + androidEntry.setId(log_msg.id()); + androidEntry.setTs(entry.tv_sec * 1000000000ULL + entry.tv_nsec); + androidEntry.setPriority(entry.priority); + androidEntry.setPid(entry.pid); + androidEntry.setTid(entry.tid); + androidEntry.setTag(entry.tag); + androidEntry.setMessage(entry.message); + + auto words = capnp::messageToFlatArray(msg); + auto bytes = words.asBytes(); + zmq_send(publisher, bytes.begin(), bytes.size(), 0); + } + + android_logger_list_close(logger_list); + + return 0; +} \ No newline at end of file diff --git a/selfdrive/loggerd/Makefile b/selfdrive/loggerd/Makefile new file mode 100644 index 00000000000000..bd3038ad7a84c5 --- /dev/null +++ b/selfdrive/loggerd/Makefile @@ -0,0 +1,4 @@ +-include build_from_src.mk + +release: + @echo "loggerd: this is a release" diff --git a/selfdrive/loggerd/__init__.py b/selfdrive/loggerd/__init__.py new file mode 100644 index 00000000000000..e69de29bb2d1d6 diff --git a/selfdrive/loggerd/config.py b/selfdrive/loggerd/config.py new file mode 100644 index 00000000000000..9d1c3120fbaec5 --- /dev/null +++ b/selfdrive/loggerd/config.py @@ -0,0 +1,9 @@ +import os + +if os.environ.get('LOGGERD_ROOT', False): + ROOT = os.environ['LOGGERD_ROOT'] + print("Custom loggerd root: ", ROOT) +else: + ROOT = '/data/media/0/realdata/' + +SEGMENT_LENGTH = 60 diff --git a/selfdrive/loggerd/loggerd b/selfdrive/loggerd/loggerd new file mode 100755 index 00000000000000..ea4a99849b27c4 Binary files /dev/null and b/selfdrive/loggerd/loggerd differ diff --git a/selfdrive/loggerd/uploader.py b/selfdrive/loggerd/uploader.py new file mode 100644 index 00000000000000..6b35776ce011f0 --- /dev/null +++ b/selfdrive/loggerd/uploader.py @@ -0,0 +1,304 @@ +#!/usr/bin/env python +import os +import re +import time +import stat +import json +import random +import ctypes +import inspect +import requests +import traceback +import threading +import subprocess + +from collections import Counter +from selfdrive.swaglog import cloudlog +from selfdrive.loggerd.config import ROOT + +from common.params import Params +from common.api import api_get + +fake_upload = os.getenv("FAKEUPLOAD") is not None + +def raise_on_thread(t, exctype): + for ctid, tobj in threading._active.items(): + if tobj is t: + tid = ctid + break + else: + raise Exception("Could not find thread") + + '''Raises an exception in the threads with id tid''' + if not inspect.isclass(exctype): + raise TypeError("Only types can be raised (not instances)") + + res = ctypes.pythonapi.PyThreadState_SetAsyncExc(ctypes.c_long(tid), + ctypes.py_object(exctype)) + if res == 0: + raise ValueError("invalid thread id") + elif res != 1: + # "if it returns a number greater than one, you're in trouble, + # and you should call it again with exc=NULL to revert the effect" + ctypes.pythonapi.PyThreadState_SetAsyncExc(tid, 0) + raise SystemError("PyThreadState_SetAsyncExc failed") + +def listdir_with_creation_date(d): + lst = os.listdir(d) + for fn in lst: + try: + st = os.stat(os.path.join(d, fn)) + ctime = st[stat.ST_CTIME] + yield (ctime, fn) + except OSError: + cloudlog.exception("listdir_with_creation_date: stat failed?") + yield (None, fn) + +def listdir_by_creation_date(d): + times_and_paths = list(listdir_with_creation_date(d)) + return [path for _, path in sorted(times_and_paths)] + +def clear_locks(root): + for logname in os.listdir(root): + path = os.path.join(root, logname) + try: + for fname in os.listdir(path): + if fname.endswith(".lock"): + os.unlink(os.path.join(path, fname)) + except OSError: + cloudlog.exception("clear_locks failed") + +def is_on_wifi(): + # ConnectivityManager.getActiveNetworkInfo() + try: + result = subprocess.check_output(["service", "call", "connectivity", "2"]).strip().split("\n") + except subprocess.CalledProcessError: + return False + + data = ''.join(''.join(w.decode("hex")[::-1] for w in l[14:49].split()) for l in result[1:]) + + return "\x00".join("WIFI") in data + +def is_on_hotspot(): + try: + result = subprocess.check_output(["ifconfig", "wlan0"]) + result = re.findall(r"inet addr:((\d+\.){3}\d+)", result)[0][0] + + is_android = result.startswith('192.168.43.') + is_ios = result.startswith('172.20.10.') + return (is_android or is_ios) + except: + return False + +class Uploader(object): + def __init__(self, dongle_id, access_token, root): + self.dongle_id = dongle_id + self.access_token = access_token + self.root = root + + self.upload_thread = None + + self.last_resp = None + self.last_exc = None + + def clean_dirs(self): + try: + for logname in os.listdir(self.root): + path = os.path.join(self.root, logname) + # remove empty directories + if not os.listdir(path): + os.rmdir(path) + except OSError: + cloudlog.exception("clean_dirs failed") + + def gen_upload_files(self): + if not os.path.isdir(self.root): + return + for logname in listdir_by_creation_date(self.root): + path = os.path.join(self.root, logname) + names = os.listdir(path) + if any(name.endswith(".lock") for name in names): + continue + + for name in names: + key = os.path.join(logname, name) + fn = os.path.join(path, name) + + yield (name, key, fn) + + def get_data_stats(self): + name_counts = Counter() + total_size = 0 + for name, key, fn in self.gen_upload_files(): + name_counts[name] += 1 + total_size += os.stat(fn).st_size + return dict(name_counts), total_size + + def next_file_to_upload(self, with_video): + # try to upload log files first + for name, key, fn in self.gen_upload_files(): + if name in ["rlog", "rlog.bz2"]: + return (key, fn, 0) + + if with_video: + # then upload compressed rear and front camera files + for name, key, fn in self.gen_upload_files(): + if name == "fcamera.hevc": + return (key, fn, 1) + elif name == "dcamera.hevc": + return (key, fn, 2) + + # then upload other files + for name, key, fn in self.gen_upload_files(): + if not name.endswith('.lock') and not name.endswith(".tmp"): + return (key, fn, 3) + + return None + + + def do_upload(self, key, fn): + try: + url_resp = api_get("v1.2/"+self.dongle_id+"/upload_url/", timeout=2, path=key, access_token=self.access_token) + url_resp_json = json.loads(url_resp.text) + url = url_resp_json['url'] + headers = url_resp_json['headers'] + cloudlog.info("upload_url v1.2 %s %s", url, str(headers)) + + if fake_upload: + cloudlog.info("*** WARNING, THIS IS A FAKE UPLOAD TO %s ***" % url) + class FakeResponse(object): + def __init__(self): + self.status_code = 200 + self.last_resp = FakeResponse() + else: + with open(fn, "rb") as f: + self.last_resp = requests.put(url, data=f, headers=headers, timeout=10) + except Exception as e: + self.last_exc = (e, traceback.format_exc()) + raise + + def normal_upload(self, key, fn): + self.last_resp = None + self.last_exc = None + + try: + self.do_upload(key, fn) + except Exception: + pass + + return self.last_resp + + def killable_upload(self, key, fn): + self.last_resp = None + self.last_exc = None + + self.upload_thread = threading.Thread(target=lambda: self.do_upload(key, fn)) + self.upload_thread.start() + self.upload_thread.join() + self.upload_thread = None + + return self.last_resp + + def abort_upload(self): + thread = self.upload_thread + if thread is None: + return + if not thread.is_alive(): + return + raise_on_thread(thread, SystemExit) + thread.join() + + def upload(self, key, fn): + # write out the bz2 compress + if fn.endswith("log"): + ext = ".bz2" + cloudlog.info("compressing %r to %r", fn, fn+ext) + if os.system("nice -n 19 bzip2 -c %s > %s.tmp && mv %s.tmp %s%s && rm %s" % (fn, fn, fn, fn, ext, fn)) != 0: + cloudlog.exception("upload: bzip2 compression failed") + return False + + # assuming file is named properly + key += ext + fn += ext + + try: + sz = os.path.getsize(fn) + except OSError: + cloudlog.exception("upload: getsize failed") + return False + + cloudlog.event("upload", key=key, fn=fn, sz=sz) + + cloudlog.info("checking %r with size %r", key, sz) + + if sz == 0: + # can't upload files of 0 size + os.unlink(fn) # delete the file + success = True + else: + cloudlog.info("uploading %r", fn) + # stat = self.killable_upload(key, fn) + stat = self.normal_upload(key, fn) + if stat is not None and stat.status_code in (200, 201): + cloudlog.event("upload_success", key=key, fn=fn, sz=sz) + os.unlink(fn) # delete the file + success = True + else: + cloudlog.event("upload_failed", stat=stat, exc=self.last_exc, key=key, fn=fn, sz=sz) + success = False + + self.clean_dirs() + + return success + + + +def uploader_fn(exit_event): + cloudlog.info("uploader_fn") + + params = Params() + dongle_id, access_token = params.get("DongleId"), params.get("AccessToken") + + if dongle_id is None or access_token is None: + cloudlog.info("uploader MISSING DONGLE_ID or ACCESS_TOKEN") + raise Exception("uploader can't start without dongle id and access token") + + uploader = Uploader(dongle_id, access_token, ROOT) + + backoff = 0.1 + while True: + allow_cellular = (params.get("IsUploadVideoOverCellularEnabled") != "0") + on_hotspot = is_on_hotspot() + on_wifi = is_on_wifi() + should_upload = allow_cellular or (on_wifi and not on_hotspot) + + if exit_event.is_set(): + return + + if not should_upload: + time.sleep(5) + continue + + d = uploader.next_file_to_upload(with_video=True) + if d is None: + time.sleep(5) + continue + + key, fn, _ = d + + cloudlog.event("uploader_netcheck", allow_cellular=allow_cellular, is_on_hotspot=on_hotspot, is_on_wifi=on_wifi) + cloudlog.info("to upload %r", d) + success = uploader.upload(key, fn) + if success: + backoff = 0.1 + else: + cloudlog.info("backoff %r", backoff) + time.sleep(backoff + random.uniform(0, backoff)) + backoff = min(backoff*2, 120) + cloudlog.info("upload done, success=%r", success) + +def main(gctx=None): + uploader_fn(threading.Event()) + +if __name__ == "__main__": + main() diff --git a/selfdrive/logmessaged.py b/selfdrive/logmessaged.py new file mode 100755 index 00000000000000..971db829335242 --- /dev/null +++ b/selfdrive/logmessaged.py @@ -0,0 +1,39 @@ +#!/usr/bin/env python +import zmq +from logentries import LogentriesHandler +from selfdrive.services import service_list +import selfdrive.messaging as messaging + +def main(gctx): + # setup logentries. we forward log messages to it + le_token = "e8549616-0798-4d7e-a2ca-2513ae81fa17" + le_handler = LogentriesHandler(le_token, use_tls=False, verbose=False) + + le_level = 20 #logging.INFO + + ctx = zmq.Context() + sock = ctx.socket(zmq.PULL) + sock.bind("ipc:///tmp/logmessage") + + # and we publish them + pub_sock = messaging.pub_sock(ctx, service_list['logMessage'].port) + + while True: + dat = ''.join(sock.recv_multipart()) + + # print "RECV", repr(dat) + + levelnum = ord(dat[0]) + dat = dat[1:] + + if levelnum >= le_level: + # push to logentries + le_handler.emit_raw(dat) + + # then we publish them + msg = messaging.new_message() + msg.logMessage = dat + pub_sock.send(msg.to_bytes()) + +if __name__ == "__main__": + main(None) diff --git a/selfdrive/manager.py b/selfdrive/manager.py new file mode 100755 index 00000000000000..68e09d1f985996 --- /dev/null +++ b/selfdrive/manager.py @@ -0,0 +1,532 @@ +#!/usr/bin/env python2.7 +import os +import sys +import fcntl +import errno +import signal +import subprocess + +from common.basedir import BASEDIR +sys.path.append(os.path.join(BASEDIR, "pyextra")) +os.environ['BASEDIR'] = BASEDIR + +def unblock_stdout(): + # get a non-blocking stdout + child_pid, child_pty = os.forkpty() + if child_pid != 0: # parent + + # child is in its own process group, manually pass kill signals + signal.signal(signal.SIGINT, lambda signum, frame: os.kill(child_pid, signal.SIGINT)) + signal.signal(signal.SIGTERM, lambda signum, frame: os.kill(child_pid, signal.SIGTERM)) + + fcntl.fcntl(sys.stdout, fcntl.F_SETFL, + fcntl.fcntl(sys.stdout, fcntl.F_GETFL) | os.O_NONBLOCK) + + while True: + try: + dat = os.read(child_pty, 4096) + except OSError as e: + if e.errno == errno.EIO: + break + continue + + if not dat: + break + + try: + sys.stdout.write(dat) + except (OSError, IOError): + pass + + os._exit(os.wait()[1]) + +if __name__ == "__main__": + neos_update_required = os.path.isfile("/init.qcom.rc") \ + and (not os.path.isfile("/VERSION") or int(open("/VERSION").read()) < 8) + if neos_update_required: + # update continue.sh before updating NEOS + if os.path.isfile(os.path.join(BASEDIR, "scripts", "continue.sh")): + from shutil import copyfile + copyfile(os.path.join(BASEDIR, "scripts", "continue.sh"), "/data/data/com.termux/files/continue.sh") + + # run the updater + print("Starting NEOS updater") + subprocess.check_call(["git", "clean", "-xdf"], cwd=BASEDIR) + os.system(os.path.join(BASEDIR, "installer", "updater", "updater")) + raise Exception("NEOS outdated") + elif os.path.isdir("/data/neoupdate"): + from shutil import rmtree + rmtree("/data/neoupdate") + + unblock_stdout() + +import glob +import shutil +import hashlib +import importlib +import subprocess +import traceback +from multiprocessing import Process + +import zmq +from setproctitle import setproctitle #pylint: disable=no-name-in-module + +from common.params import Params +import cereal +ThermalStatus = cereal.log.ThermalData.ThermalStatus + +from selfdrive.services import service_list +from selfdrive.swaglog import cloudlog +import selfdrive.messaging as messaging +from selfdrive.registration import register +from selfdrive.version import version, dirty +import selfdrive.crash as crash + +from selfdrive.loggerd.config import ROOT + +# comment out anything you don't want to run +managed_processes = { + "thermald": "selfdrive.thermald", + "uploader": "selfdrive.loggerd.uploader", + "controlsd": "selfdrive.controls.controlsd", + "radard": "selfdrive.controls.radard", + "ubloxd": "selfdrive.locationd.ubloxd", + "mapd": "selfdrive.mapd.mapd", + "loggerd": ("selfdrive/loggerd", ["./loggerd"]), + "logmessaged": "selfdrive.logmessaged", + "tombstoned": "selfdrive.tombstoned", + "logcatd": ("selfdrive/logcatd", ["./logcatd"]), + "proclogd": ("selfdrive/proclogd", ["./proclogd"]), + "boardd": ("selfdrive/boardd", ["./boardd"]), # not used directly + "pandad": "selfdrive.pandad", + "ui": ("selfdrive/ui", ["./start.sh"]), + "calibrationd": "selfdrive.locationd.calibrationd", + "visiond": ("selfdrive/visiond", ["./visiond"]), + "sensord": ("selfdrive/sensord", ["./sensord"]), + "gpsd": ("selfdrive/sensord", ["./gpsd"]), + "orbd": ("selfdrive/orbd", ["./orbd_wrapper.sh"]), + "updated": "selfdrive.updated", +} +android_packages = ("ai.comma.plus.offroad", "ai.comma.plus.frame") + +running = {} +def get_running(): + return running + +# due to qualcomm kernel bugs SIGKILLing visiond sometimes causes page table corruption +unkillable_processes = ['visiond'] + +# processes to end with SIGINT instead of SIGTERM +interrupt_processes = [] + +persistent_processes = [ + 'thermald', + 'logmessaged', + 'logcatd', + 'tombstoned', + 'uploader', + 'ui', + 'gpsd', + 'updated', +] + +car_started_processes = [ + 'controlsd', + 'loggerd', + 'sensord', + 'radard', + 'calibrationd', + 'visiond', + 'proclogd', + 'ubloxd', + 'orbd', + 'mapd', +] + +def register_managed_process(name, desc, car_started=False): + global managed_processes, car_started_processes, persistent_processes + print("registering %s" % name) + managed_processes[name] = desc + if car_started: + car_started_processes.append(name) + else: + persistent_processes.append(name) + +# ****************** process management functions ****************** +def launcher(proc, gctx): + try: + # import the process + mod = importlib.import_module(proc) + + # rename the process + setproctitle(proc) + + # exec the process + mod.main(gctx) + except KeyboardInterrupt: + cloudlog.warning("child %s got SIGINT" % proc) + except Exception: + # can't install the crash handler becuase sys.excepthook doesn't play nice + # with threads, so catch it here. + crash.capture_exception() + raise + +def nativelauncher(pargs, cwd): + # exec the process + os.chdir(cwd) + + # because when extracted from pex zips permissions get lost -_- + os.chmod(pargs[0], 0o700) + + os.execvp(pargs[0], pargs) + +def start_managed_process(name): + if name in running or name not in managed_processes: + return + proc = managed_processes[name] + if isinstance(proc, str): + cloudlog.info("starting python %s" % proc) + running[name] = Process(name=name, target=launcher, args=(proc, gctx)) + else: + pdir, pargs = proc + cwd = os.path.join(BASEDIR, pdir) + cloudlog.info("starting process %s" % name) + running[name] = Process(name=name, target=nativelauncher, args=(pargs, cwd)) + running[name].start() + +def prepare_managed_process(p): + proc = managed_processes[p] + if isinstance(proc, str): + # import this python + cloudlog.info("preimporting %s" % proc) + importlib.import_module(proc) + else: + # build this process + cloudlog.info("building %s" % (proc,)) + try: + subprocess.check_call(["make", "-j4"], cwd=os.path.join(BASEDIR, proc[0])) + except subprocess.CalledProcessError: + # make clean if the build failed + cloudlog.warning("building %s failed, make clean" % (proc, )) + subprocess.check_call(["make", "clean"], cwd=os.path.join(BASEDIR, proc[0])) + subprocess.check_call(["make", "-j4"], cwd=os.path.join(BASEDIR, proc[0])) + +def kill_managed_process(name): + if name not in running or name not in managed_processes: + return + cloudlog.info("killing %s" % name) + + if running[name].exitcode is None: + if name in interrupt_processes: + os.kill(running[name].pid, signal.SIGINT) + else: + running[name].terminate() + + # give it 5 seconds to die + running[name].join(5.0) + if running[name].exitcode is None: + if name in unkillable_processes: + cloudlog.critical("unkillable process %s failed to exit! rebooting in 15 if it doesn't die" % name) + running[name].join(15.0) + if running[name].exitcode is None: + cloudlog.critical("FORCE REBOOTING PHONE!") + os.system("date >> /sdcard/unkillable_reboot") + os.system("reboot") + raise RuntimeError + else: + cloudlog.info("killing %s with SIGKILL" % name) + os.kill(running[name].pid, signal.SIGKILL) + running[name].join() + + cloudlog.info("%s is dead with %d" % (name, running[name].exitcode)) + del running[name] + +def pm_apply_packages(cmd): + for p in android_packages: + system("pm %s %s" % (cmd, p)) + +def cleanup_all_processes(signal, frame): + cloudlog.info("caught ctrl-c %s %s" % (signal, frame)) + + pm_apply_packages('disable') + + for name in list(running.keys()): + kill_managed_process(name) + cloudlog.info("everything is dead") + + +# ****************** run loop ****************** + +def manager_init(should_register=True): + global gctx + + if should_register: + reg_res = register() + if reg_res: + dongle_id, dongle_secret = reg_res + else: + raise Exception("server registration failed") + else: + dongle_id = "c"*16 + + # set dongle id + cloudlog.info("dongle id is " + dongle_id) + os.environ['DONGLE_ID'] = dongle_id + + cloudlog.info("dirty is %d" % dirty) + if not dirty: + os.environ['CLEAN'] = '1' + + cloudlog.bind_global(dongle_id=dongle_id, version=version, dirty=dirty, is_eon=True) + crash.bind_user(id=dongle_id) + crash.bind_extra(version=version, dirty=dirty, is_eon=True) + + os.umask(0) + try: + os.mkdir(ROOT, 0o777) + except OSError: + pass + + # set gctx + gctx = {} + +def system(cmd): + try: + cloudlog.info("running %s" % cmd) + subprocess.check_output(cmd, stderr=subprocess.STDOUT, shell=True) + except subprocess.CalledProcessError as e: + cloudlog.event("running failed", + cmd=e.cmd, + output=e.output[-1024:], + returncode=e.returncode) + + +def manager_thread(): + # now loop + context = zmq.Context() + thermal_sock = messaging.sub_sock(context, service_list['thermal'].port) + + cloudlog.info("manager start") + cloudlog.info({"environ": os.environ}) + + # save boot log + subprocess.call(["./loggerd", "--bootlog"], cwd=os.path.join(BASEDIR, "selfdrive/loggerd")) + + for p in persistent_processes: + start_managed_process(p) + + # start frame + pm_apply_packages('enable') + system("am start -n ai.comma.plus.frame/.MainActivity") + + if os.getenv("NOBOARD") is None: + start_managed_process("pandad") + + params = Params() + logger_dead = False + + while 1: + # get health of board, log this in "thermal" + msg = messaging.recv_sock(thermal_sock, wait=True) + + # uploader is gated based on the phone temperature + if msg.thermal.thermalStatus >= ThermalStatus.yellow or msg.thermal.started: + kill_managed_process("uploader") + else: + start_managed_process("uploader") + + if msg.thermal.freeSpace < 0.05: + logger_dead = True + + if msg.thermal.started: + for p in car_started_processes: + if p == "loggerd" and logger_dead: + kill_managed_process(p) + else: + start_managed_process(p) + else: + logger_dead = False + for p in car_started_processes: + kill_managed_process(p) + + # check the status of all processes, did any of them die? + for p in running: + cloudlog.debug(" running %s %s" % (p, running[p])) + + # is this still needed? + if params.get("DoUninstall") == "1": + break + +def get_installed_apks(): + dat = subprocess.check_output(["pm", "list", "packages", "-f"]).strip().split("\n") + ret = {} + for x in dat: + if x.startswith("package:"): + v,k = x.split("package:")[1].split("=") + ret[k] = v + return ret + +def install_apk(path): + # can only install from world readable path + install_path = "/sdcard/%s" % os.path.basename(path) + shutil.copyfile(path, install_path) + + ret = subprocess.call(["pm", "install", "-r", install_path]) + os.remove(install_path) + return ret == 0 + +def update_apks(): + # install apks + installed = get_installed_apks() + + install_apks = glob.glob(os.path.join(BASEDIR, "apk/*.apk")) + for apk in install_apks: + app = os.path.basename(apk)[:-4] + if app not in installed: + installed[app] = None + + cloudlog.info("installed apks %s" % (str(installed), )) + + for app in installed.iterkeys(): + + apk_path = os.path.join(BASEDIR, "apk/"+app+".apk") + if not os.path.exists(apk_path): + continue + + h1 = hashlib.sha1(open(apk_path).read()).hexdigest() + h2 = None + if installed[app] is not None: + h2 = hashlib.sha1(open(installed[app]).read()).hexdigest() + cloudlog.info("comparing version of %s %s vs %s" % (app, h1, h2)) + + if h2 is None or h1 != h2: + cloudlog.info("installing %s" % app) + + success = install_apk(apk_path) + if not success: + cloudlog.info("needing to uninstall %s" % app) + system("pm uninstall %s" % app) + success = install_apk(apk_path) + + assert success + +def manager_update(): + if os.path.exists(os.path.join(BASEDIR, "vpn")): + cloudlog.info("installing vpn") + os.system(os.path.join(BASEDIR, "vpn", "install.sh")) + update_apks() + +def manager_prepare(): + # build cereal first + subprocess.check_call(["make", "-j4"], cwd=os.path.join(BASEDIR, "cereal")) + + # build all processes + os.chdir(os.path.dirname(os.path.abspath(__file__))) + for p in managed_processes: + prepare_managed_process(p) + +def uninstall(): + cloudlog.warning("uninstalling") + with open('/cache/recovery/command', 'w') as f: + f.write('--wipe_data\n') + # IPowerManager.reboot(confirm=false, reason="recovery", wait=true) + os.system("service call power 16 i32 0 s16 recovery i32 1") + +def main(): + # the flippening! + os.system('LD_LIBRARY_PATH="" content insert --uri content://settings/system --bind name:s:user_rotation --bind value:i:1') + + if os.getenv("NOLOG") is not None: + del managed_processes['loggerd'] + del managed_processes['tombstoned'] + if os.getenv("NOUPLOAD") is not None: + del managed_processes['uploader'] + if os.getenv("NOVISION") is not None: + del managed_processes['visiond'] + if os.getenv("LEAN") is not None: + del managed_processes['uploader'] + del managed_processes['loggerd'] + del managed_processes['logmessaged'] + del managed_processes['logcatd'] + del managed_processes['tombstoned'] + del managed_processes['proclogd'] + if os.getenv("NOCONTROL") is not None: + del managed_processes['controlsd'] + del managed_processes['radard'] + + # support additional internal only extensions + try: + import selfdrive.manager_extensions + selfdrive.manager_extensions.register(register_managed_process) + except ImportError: + pass + + params = Params() + params.manager_start() + + # set unset params + if params.get("IsMetric") is None: + params.put("IsMetric", "0") + if params.get("RecordFront") is None: + params.put("RecordFront", "0") + if params.get("IsFcwEnabled") is None: + params.put("IsFcwEnabled", "1") + if params.get("HasAcceptedTerms") is None: + params.put("HasAcceptedTerms", "0") + if params.get("IsUploadVideoOverCellularEnabled") is None: + params.put("IsUploadVideoOverCellularEnabled", "1") + if params.get("IsDriverMonitoringEnabled") is None: + params.put("IsDriverMonitoringEnabled", "1") + if params.get("IsGeofenceEnabled") is None: + params.put("IsGeofenceEnabled", "-1") + if params.get("SpeedLimitOffset") is None: + params.put("SpeedLimitOffset", "0") + if params.get("LongitudinalControl") is None: + params.put("LongitudinalControl", "0") + if params.get("LimitSetSpeed") is None: + params.put("LimitSetSpeed", "0") + + # is this chffrplus? + if os.getenv("PASSIVE") is not None: + params.put("Passive", str(int(os.getenv("PASSIVE")))) + + if params.get("Passive") is None: + raise Exception("Passive must be set to continue") + + # put something on screen while we set things up + if os.getenv("PREPAREONLY") is not None: + spinner_proc = None + else: + spinner_text = "chffrplus" if params.get("Passive")=="1" else "openpilot" + spinner_proc = subprocess.Popen(["./spinner", "loading %s"%spinner_text], + cwd=os.path.join(BASEDIR, "selfdrive", "ui", "spinner"), + close_fds=True) + try: + manager_update() + manager_init() + manager_prepare() + finally: + if spinner_proc: + spinner_proc.terminate() + + if os.getenv("PREPAREONLY") is not None: + return + + # SystemExit on sigterm + signal.signal(signal.SIGTERM, lambda signum, frame: sys.exit(1)) + + try: + manager_thread() + except Exception: + traceback.print_exc() + crash.capture_exception() + finally: + cleanup_all_processes(None, None) + + if params.get("DoUninstall") == "1": + uninstall() + +if __name__ == "__main__": + main() + # manual exit because we are forked + sys.exit(0) diff --git a/selfdrive/mapd/__init__.py b/selfdrive/mapd/__init__.py new file mode 100644 index 00000000000000..e69de29bb2d1d6 diff --git a/selfdrive/mapd/mapd.py b/selfdrive/mapd/mapd.py new file mode 100755 index 00000000000000..1ae7b6aabc82a4 --- /dev/null +++ b/selfdrive/mapd/mapd.py @@ -0,0 +1,294 @@ +#!/usr/bin/env python + +# Add phonelibs openblas to LD_LIBRARY_PATH if import fails +try: + from scipy import spatial +except ImportError as e: + import os + import sys + from common.basedir import BASEDIR + + openblas_path = os.path.join(BASEDIR, "phonelibs/openblas/") + os.environ['LD_LIBRARY_PATH'] += ':' + openblas_path + + args = [sys.executable] + args.extend(sys.argv) + os.execv(sys.executable, args) + +import os +import sys +import time +import zmq +import threading +import numpy as np +import overpy +from collections import defaultdict + +from common.params import Params +from common.transformations.coordinates import geodetic2ecef +from selfdrive.services import service_list +import selfdrive.messaging as messaging +from mapd_helpers import MAPS_LOOKAHEAD_DISTANCE, Way, circle_through_points +import selfdrive.crash as crash +from selfdrive.version import version, dirty + + +OVERPASS_API_URL = "https://overpass.kumi.systems/api/interpreter" +OVERPASS_HEADERS = { + 'User-Agent': 'NEOS (comma.ai)' +} + +last_gps = None +query_lock = threading.Lock() +last_query_result = None +last_query_pos = None +cache_valid = False + + +def setup_thread_excepthook(): + """ + Workaround for `sys.excepthook` thread bug from: + http://bugs.python.org/issue1230540 + Call once from the main thread before creating any threads. + Source: https://stackoverflow.com/a/31622038 + """ + init_original = threading.Thread.__init__ + + def init(self, *args, **kwargs): + init_original(self, *args, **kwargs) + run_original = self.run + + def run_with_except_hook(*args2, **kwargs2): + try: + run_original(*args2, **kwargs2) + except Exception: + sys.excepthook(*sys.exc_info()) + + self.run = run_with_except_hook + + threading.Thread.__init__ = init + + +def build_way_query(lat, lon, radius=50): + """Builds a query to find all highways within a given radius around a point""" + pos = " (around:%f,%f,%f)" % (radius, lat, lon) + q = """( + way + """ + pos + """ + [highway][highway!~"^(footway|path|bridleway|steps|cycleway|construction|bus_guideway|escape)$"]; + >;);out; + """ + return q + + +def query_thread(): + global last_query_result, last_query_pos, cache_valid + api = overpy.Overpass(url=OVERPASS_API_URL, headers=OVERPASS_HEADERS, timeout=10.) + + while True: + time.sleep(1) + if last_gps is not None: + fix_ok = last_gps.flags & 1 + if not fix_ok: + continue + + if last_query_pos is not None: + cur_ecef = geodetic2ecef((last_gps.latitude, last_gps.longitude, last_gps.altitude)) + prev_ecef = geodetic2ecef((last_query_pos.latitude, last_query_pos.longitude, last_query_pos.altitude)) + dist = np.linalg.norm(cur_ecef - prev_ecef) + if dist < 1000: + continue + + if dist > 3000: + cache_valid = False + + q = build_way_query(last_gps.latitude, last_gps.longitude, radius=3000) + try: + new_result = api.query(q) + + # Build kd-tree + nodes = [] + real_nodes = [] + node_to_way = defaultdict(list) + + for n in new_result.nodes: + nodes.append((float(n.lat), float(n.lon), 0)) + real_nodes.append(n) + + for way in new_result.ways: + for n in way.nodes: + node_to_way[n.id].append(way) + + nodes = np.asarray(nodes) + nodes = geodetic2ecef(nodes) + tree = spatial.cKDTree(nodes) + + query_lock.acquire() + last_query_result = new_result, tree, real_nodes, node_to_way + last_query_pos = last_gps + cache_valid = True + query_lock.release() + + except Exception as e: + print e + query_lock.acquire() + last_query_result = None + query_lock.release() + + +def mapsd_thread(): + global last_gps + + context = zmq.Context() + gps_sock = messaging.sub_sock(context, service_list['gpsLocation'].port, conflate=True) + gps_external_sock = messaging.sub_sock(context, service_list['gpsLocationExternal'].port, conflate=True) + map_data_sock = messaging.pub_sock(context, service_list['liveMapData'].port) + + cur_way = None + curvature_valid = False + curvature = None + upcoming_curvature = 0. + dist_to_turn = 0. + road_points = None + + while True: + gps = messaging.recv_one(gps_sock) + gps_ext = messaging.recv_one_or_none(gps_external_sock) + + if gps_ext is not None: + gps = gps_ext.gpsLocationExternal + else: + gps = gps.gpsLocation + + last_gps = gps + + fix_ok = gps.flags & 1 + if not fix_ok or last_query_result is None or not cache_valid: + cur_way = None + curvature = None + curvature_valid = False + upcoming_curvature = 0. + dist_to_turn = 0. + road_points = None + map_valid = False + else: + map_valid = True + lat = gps.latitude + lon = gps.longitude + heading = gps.bearing + speed = gps.speed + + query_lock.acquire() + cur_way = Way.closest(last_query_result, lat, lon, heading, cur_way) + if cur_way is not None: + pnts, curvature_valid = cur_way.get_lookahead(last_query_result, lat, lon, heading, MAPS_LOOKAHEAD_DISTANCE) + + xs = pnts[:, 0] + ys = pnts[:, 1] + road_points = map(float, xs), map(float, ys) + + if speed < 10: + curvature_valid = False + if curvature_valid and pnts.shape[0] <= 3: + curvature_valid = False + + # The curvature is valid when at least MAPS_LOOKAHEAD_DISTANCE of road is found + if curvature_valid: + # Compute the curvature for each point + with np.errstate(divide='ignore'): + circles = [circle_through_points(*p) for p in zip(pnts, pnts[1:], pnts[2:])] + circles = np.asarray(circles) + radii = np.nan_to_num(circles[:, 2]) + radii[radii < 10] = np.inf + curvature = 1. / radii + + # Index of closest point + closest = np.argmin(np.linalg.norm(pnts, axis=1)) + dist_to_closest = pnts[closest, 0] # We can use x distance here since it should be close + + # Compute distance along path + dists = list() + dists.append(0) + for p, p_prev in zip(pnts, pnts[1:, :]): + dists.append(dists[-1] + np.linalg.norm(p - p_prev)) + dists = np.asarray(dists) + dists = dists - dists[closest] + dist_to_closest + dists = dists[1:-1] + + close_idx = np.logical_and(dists > 0, dists < 500) + dists = dists[close_idx] + curvature = curvature[close_idx] + + if len(curvature): + # TODO: Determine left or right turn + curvature = np.nan_to_num(curvature) + + # Outlier rejection + new_curvature = np.percentile(curvature, 90, interpolation='lower') + + k = 0.6 + upcoming_curvature = k * upcoming_curvature + (1 - k) * new_curvature + in_turn_indices = curvature > 0.8 * new_curvature + + if np.any(in_turn_indices): + dist_to_turn = np.min(dists[in_turn_indices]) + else: + dist_to_turn = 999 + else: + upcoming_curvature = 0. + dist_to_turn = 999 + + query_lock.release() + + dat = messaging.new_message() + dat.init('liveMapData') + + if last_gps is not None: + dat.liveMapData.lastGps = last_gps + + if cur_way is not None: + dat.liveMapData.wayId = cur_way.id + + # Seed limit + max_speed = cur_way.max_speed + if max_speed is not None: + dat.liveMapData.speedLimitValid = True + dat.liveMapData.speedLimit = max_speed + + # Curvature + dat.liveMapData.curvatureValid = curvature_valid + dat.liveMapData.curvature = float(upcoming_curvature) + dat.liveMapData.distToTurn = float(dist_to_turn) + if road_points is not None: + dat.liveMapData.roadX, dat.liveMapData.roadY = road_points + if curvature is not None: + dat.liveMapData.roadCurvatureX = map(float, dists) + dat.liveMapData.roadCurvature = map(float, curvature) + + dat.liveMapData.mapValid = map_valid + + map_data_sock.send(dat.to_bytes()) + + +def main(gctx=None): + params = Params() + dongle_id = params.get("DongleId") + crash.bind_user(id=dongle_id) + crash.bind_extra(version=version, dirty=dirty, is_eon=True) + crash.install() + + setup_thread_excepthook() + main_thread = threading.Thread(target=mapsd_thread) + main_thread.daemon = True + main_thread.start() + + q_thread = threading.Thread(target=query_thread) + q_thread.daemon = True + q_thread.start() + + while True: + time.sleep(0.1) + + +if __name__ == "__main__": + main() diff --git a/selfdrive/mapd/mapd_helpers.py b/selfdrive/mapd/mapd_helpers.py new file mode 100644 index 00000000000000..09239f6a2f3d0b --- /dev/null +++ b/selfdrive/mapd/mapd_helpers.py @@ -0,0 +1,256 @@ +import math +import numpy as np +from datetime import datetime + +from selfdrive.config import Conversions as CV +from common.transformations.coordinates import LocalCoord, geodetic2ecef + +LOOKAHEAD_TIME = 10. +MAPS_LOOKAHEAD_DISTANCE = 50 * LOOKAHEAD_TIME + + +def circle_through_points(p1, p2, p3): + """Fits a circle through three points + Formulas from: http://www.ambrsoft.com/trigocalc/circle3d.htm""" + x1, y1, _ = p1 + x2, y2, _ = p2 + x3, y3, _ = p3 + + A = x1 * (y2 - y3) - y1 * (x2 - x3) + x2 * y3 - x3 * y2 + B = (x1**2 + y1**2) * (y3 - y2) + (x2**2 + y2**2) * (y1 - y3) + (x3**2 + y3**2) * (y2 - y1) + C = (x1**2 + y1**2) * (x2 - x3) + (x2**2 + y2**2) * (x3 - x1) + (x3**2 + y3**2) * (x1 - x2) + D = (x1**2 + y1**2) * (x3 * y2 - x2 * y3) + (x2**2 + y2**2) * (x1 * y3 - x3 * y1) + (x3**2 + y3**2) * (x2 * y1 - x1 * y2) + + return (-B / (2 * A), - C / (2 * A), np.sqrt((B**2 + C**2 - 4 * A * D) / (4 * A**2))) + + +def parse_speed_unit(max_speed): + """Converts a maxspeed string to m/s based on the unit present in the input. + OpenStreetMap defaults to kph if no unit is present. """ + + conversion = CV.KPH_TO_MS + if 'mph' in max_speed: + max_speed = max_speed.replace(' mph', '') + conversion = CV.MPH_TO_MS + + try: + max_speed = float(max_speed) * conversion + except ValueError: + max_speed = None + + return max_speed + + +class Way: + def __init__(self, way): + self.id = way.id + self.way = way + + points = list() + + for node in self.way.get_nodes(resolve_missing=False): + points.append((float(node.lat), float(node.lon), 0.)) + + self.points = np.asarray(points) + + @classmethod + def closest(cls, query_results, lat, lon, heading, prev_way=None): + results, tree, real_nodes, node_to_way = query_results + + cur_pos = geodetic2ecef((lat, lon, 0)) + nodes = tree.query_ball_point(cur_pos, 500) + + # If no nodes within 500m, choose closest one + if not nodes: + nodes = [tree.query(cur_pos)[1]] + + ways = [] + for n in nodes: + real_node = real_nodes[n] + ways += node_to_way[real_node.id] + ways = set(ways) + + closest_way = None + best_score = None + for way in ways: + way = Way(way) + points = way.points_in_car_frame(lat, lon, heading) + + on_way = way.on_way(lat, lon, heading, points) + if not on_way: + continue + + # Create mask of points in front and behind + x = points[:, 0] + y = points[:, 1] + angles = np.arctan2(y, x) + front = np.logical_and((-np.pi / 2) < angles, + angles < (np.pi / 2)) + behind = np.logical_not(front) + + dists = np.linalg.norm(points, axis=1) + + # Get closest point behind the car + dists_behind = np.copy(dists) + dists_behind[front] = np.NaN + closest_behind = points[np.nanargmin(dists_behind)] + + # Get closest point in front of the car + dists_front = np.copy(dists) + dists_front[behind] = np.NaN + closest_front = points[np.nanargmin(dists_front)] + + # fit line: y = a*x + b + x1, y1, _ = closest_behind + x2, y2, _ = closest_front + a = (y2 - y1) / max((x2 - x1), 1e-5) + b = y1 - a * x1 + + # With a factor of 60 a 20m offset causes the same error as a 20 degree heading error + # (A 20 degree heading offset results in an a of about 1/3) + score = abs(a) * 60. + abs(b) + + # Prefer same type of road + if prev_way is not None: + if way.way.tags.get('highway', '') == prev_way.way.tags.get('highway', ''): + score *= 0.5 + + if closest_way is None or score < best_score: + closest_way = way + best_score = score + + return closest_way + + def __str__(self): + return "%s %s" % (self.id, self.way.tags) + + @property + def max_speed(self): + """Extracts the (conditional) speed limit from a way""" + if not self.way: + return None + + tags = self.way.tags + max_speed = None + + if 'maxspeed' in tags: + max_speed = parse_speed_unit(tags['maxspeed']) + + try: + if 'maxspeed:conditional' in tags: + max_speed_cond, cond = tags['maxspeed:conditional'].split(' @ ') + cond = cond[1:-1] + + start, end = cond.split('-') + now = datetime.now() # TODO: Get time and timezone from gps fix so this will work correctly on replays + start = datetime.strptime(start, "%H:%M").replace(year=now.year, month=now.month, day=now.day) + end = datetime.strptime(end, "%H:%M").replace(year=now.year, month=now.month, day=now.day) + + if start <= now <= end: + max_speed = parse_speed_unit(max_speed_cond) + except ValueError: + pass + + return max_speed + + def on_way(self, lat, lon, heading, points=None): + if points is None: + points = self.points_in_car_frame(lat, lon, heading) + x = points[:, 0] + return np.min(x) < 0. and np.max(x) > 0. + + def closest_point(self, lat, lon, heading, points=None): + if points is None: + points = self.points_in_car_frame(lat, lon, heading) + i = np.argmin(np.linalg.norm(points, axis=1)) + return points[i] + + def distance_to_closest_node(self, lat, lon, heading, points=None): + if points is None: + points = self.points_in_car_frame(lat, lon, heading) + return np.min(np.linalg.norm(points, axis=1)) + + def points_in_car_frame(self, lat, lon, heading): + lc = LocalCoord.from_geodetic([lat, lon, 0.]) + + # Build rotation matrix + heading = math.radians(-heading + 90) + c, s = np.cos(heading), np.sin(heading) + rot = np.array([[c, s, 0.], [-s, c, 0.], [0., 0., 1.]]) + + # Convert to local coordinates + points_carframe = lc.geodetic2ned(self.points).T + + # Rotate with heading of car + points_carframe = np.dot(rot, points_carframe[(1, 0, 2), :]).T + + return points_carframe + + def next_way(self, query_results, lat, lon, heading, backwards=False): + results, tree, real_nodes, node_to_way = query_results + + if backwards: + node = self.way.nodes[0] + else: + node = self.way.nodes[-1] + + ways = node_to_way[node.id] + + way = None + try: + # Simple heuristic to find next way + ways = [w for w in ways if w.id != self.id] + ways = [w for w in ways if w.nodes[0] == node] + + # Filter on highway tag + acceptable_tags = list() + cur_tag = self.way.tags['highway'] + acceptable_tags.append(cur_tag) + if cur_tag == 'motorway_link': + acceptable_tags.append('motorway') + acceptable_tags.append('trunk') + acceptable_tags.append('primary') + ways = [w for w in ways if w.tags['highway'] in acceptable_tags] + + # Filter on number of lanes + cur_num_lanes = int(self.way.tags['lanes']) + if len(ways) > 1: + ways = [w for w in ways if int(w.tags['lanes']) == cur_num_lanes] + if len(ways) > 1: + ways = [w for w in ways if int(w.tags['lanes']) > cur_num_lanes] + if len(ways) == 1: + way = Way(ways[0]) + + except (KeyError, ValueError): + pass + + return way + + def get_lookahead(self, query_results, lat, lon, heading, lookahead): + pnts = None + way = self + valid = False + + for i in range(5): + # Get new points and append to list + new_pnts = way.points_in_car_frame(lat, lon, heading) + + if pnts is None: + pnts = new_pnts + else: + pnts = np.vstack([pnts, new_pnts]) + + # Check current lookahead distance + max_dist = np.linalg.norm(pnts[-1, :]) + if max_dist > lookahead: + valid = True + + if max_dist > 2 * lookahead: + break + + # Find next way + way = way.next_way(query_results, lat, lon, heading) + if not way: + break + + return pnts, valid diff --git a/selfdrive/messaging.py b/selfdrive/messaging.py new file mode 100644 index 00000000000000..4811f934548f19 --- /dev/null +++ b/selfdrive/messaging.py @@ -0,0 +1,63 @@ +import zmq + +from cereal import log +from common import realtime + +def new_message(): + dat = log.Event.new_message() + dat.logMonoTime = int(realtime.sec_since_boot() * 1e9) + return dat + +def pub_sock(context, port, addr="*"): + sock = context.socket(zmq.PUB) + sock.bind("tcp://%s:%d" % (addr, port)) + return sock + +def sub_sock(context, port, poller=None, addr="127.0.0.1", conflate=False): + sock = context.socket(zmq.SUB) + if conflate: + sock.setsockopt(zmq.CONFLATE, 1) + sock.connect("tcp://%s:%d" % (addr, port)) + sock.setsockopt(zmq.SUBSCRIBE, b"") + if poller is not None: + poller.register(sock, zmq.POLLIN) + return sock + +def drain_sock(sock, wait_for_one=False): + ret = [] + while 1: + try: + if wait_for_one and len(ret) == 0: + dat = sock.recv() + else: + dat = sock.recv(zmq.NOBLOCK) + dat = log.Event.from_bytes(dat) + ret.append(dat) + except zmq.error.Again: + break + return ret + + +# TODO: print when we drop packets? +def recv_sock(sock, wait=False): + dat = None + while 1: + try: + if wait and dat is None: + dat = sock.recv() + else: + dat = sock.recv(zmq.NOBLOCK) + except zmq.error.Again: + break + if dat is not None: + dat = log.Event.from_bytes(dat) + return dat + +def recv_one(sock): + return log.Event.from_bytes(sock.recv()) + +def recv_one_or_none(sock): + try: + return log.Event.from_bytes(sock.recv(zmq.NOBLOCK)) + except zmq.error.Again: + return None diff --git a/selfdrive/orbd/.gitignore b/selfdrive/orbd/.gitignore new file mode 100644 index 00000000000000..829780eb506383 --- /dev/null +++ b/selfdrive/orbd/.gitignore @@ -0,0 +1,8 @@ +orbd +orbd_cpu +test/turbocv_profile +test/turbocv_test +dspout/* +dumb_test +bilinear_lut.h +orb_lut.h diff --git a/selfdrive/orbd/Makefile b/selfdrive/orbd/Makefile new file mode 100644 index 00000000000000..32e9c6dfa549da --- /dev/null +++ b/selfdrive/orbd/Makefile @@ -0,0 +1,105 @@ +# CPU + +CC = clang +CXX = clang++ + +WARN_FLAGS = -Werror=implicit-function-declaration \ + -Werror=incompatible-pointer-types \ + -Werror=int-conversion \ + -Werror=return-type \ + -Werror=format-extra-args + +JSON_FLAGS = -I$(PHONELIBS)/json/src + +CFLAGS = -std=gnu11 -g -O2 -fPIC $(WARN_FLAGS) -Iinclude $(JSON_FLAGS) -I. +CXXFLAGS = -std=c++11 -g -O2 -fPIC $(WARN_FLAGS) -Iinclude $(JSON_FLAGS) -I. +LDFLAGS = + +# profile +# CXXFLAGS += -DTURBOCV_PROFILE=1 + +PHONELIBS = ../../phonelibs +BASEDIR = ../.. +EXTERNAL = ../../external +PYTHONLIBS = + +UNAME_M := $(shell uname -m) + +ifeq ($(UNAME_M),x86_64) +# computer + +ZMQ_FLAGS = -I$(PHONELIBS)/zmq/aarch64/include +ZMQ_LIBS = -L$(BASEDIR)/external/zmq/lib/ \ + -l:libczmq.a -l:libzmq.a -lpthread + +OPENCV_LIBS = -lopencv_core -lopencv_highgui -lopencv_features2d -lopencv_imgproc + +CXXFLAGS += -fopenmp +LDFLAGS += -lomp + +else +# phone +ZMQ_FLAGS = -I$(PHONELIBS)/zmq/aarch64/include +ZMQ_LIBS = -L$(PHONELIBS)/zmq/aarch64/lib \ + -l:libczmq.a -l:libzmq.a \ + -lgnustl_shared + +OPENCV_FLAGS = -I$(PHONELIBS)/opencv/include +OPENCV_LIBS = -Wl,--enable-new-dtags -Wl,-rpath,/usr/local/lib/python2.7/site-packages -L/usr/local/lib/python2.7/site-packages -l:cv2.so + +endif + +.PHONY: all +all: orbd + +include ../common/cereal.mk + +DEP_OBJS = ../common/visionipc.o ../common/ipc.o ../common/swaglog.o $(PHONELIBS)/json/src/json.o + +orbd: orbd_dsp.o $(DEP_OBJS) calculator_stub.o freethedsp.o + @echo "[ LINK ] $@" + $(CXX) -fPIC -o '$@' $^ \ + $(LDFLAGS) \ + $(ZMQ_LIBS) \ + $(CEREAL_LIBS) \ + -L/usr/lib \ + -L/system/vendor/lib64 \ + -ladsprpc \ + -lm -lz -llog + +%.o: %.c + @echo "[ CC ] $@" + $(CC) $(CFLAGS) \ + $(ZMQ_FLAGS) \ + -I../ \ + -I../../ \ + -c -o '$@' '$<' + +orbd_dsp.o: orbd.cc + @echo "[ CXX ] $@" + $(CXX) $(CXXFLAGS) \ + $(CEREAL_CXXFLAGS) \ + $(ZMQ_FLAGS) \ + $(OPENCV_FLAGS) \ + -DDSP \ + -I../ \ + -I../../ \ + -I../../../ \ + -I./include \ + -c -o '$@' '$<' + +freethedsp.o: dsp/freethedsp.c + @echo "[ CC ] $@" + $(CC) $(CFLAGS) \ + -c -o '$@' '$<' + +calculator_stub.o: dsp/gen/calculator_stub.c + @echo "[ CC ] $@" + $(CC) $(CFLAGS) -I./include -c -o '$@' '$<' + +-include internal.mk + +.PHONY: clean +clean: + rm -f *.o turbocv.so orbd test/turbocv_profile test/turbocv_test test/*.o *_lut.h + diff --git a/selfdrive/orbd/dsp/freethedsp.c b/selfdrive/orbd/dsp/freethedsp.c new file mode 100644 index 00000000000000..298f4fd83143b0 --- /dev/null +++ b/selfdrive/orbd/dsp/freethedsp.c @@ -0,0 +1,119 @@ +// freethedsp by geohot +// (because the DSP should be free) +// released under MIT License + +// usage instructions: +// 1. Compile an example from the Qualcomm Hexagon SDK +// 2. Try to run it on your phone +// 3. Be very sad when "adsprpc ... dlopen error: ... signature verify start failed for ..." appears in logcat +// ...here is where people would give up before freethedsp +// 4. Compile freethedsp with 'clang -shared freethedsp.c -o freethedsp.so' (or statically link it to your program) +// 5. Run your program with 'LD_PRELOAD=./freethedsp.so ./' +// 6. OMG THE DSP WORKS +// 7. Be happy. + +// *** patch may have to change for your phone *** + +// this is patching /dsp/fastrpc_shell_0 +// correct if sha hash of fastrpc_shell_0 is "fbadc96848aefad99a95aa4edb560929dcdf78f8" +// patch to return 0xFFFFFFFF from is_test_enabled instead of 0 +// your fastrpc_shell_0 may vary +#define PATCH_ADDR 0x5200c +#define PATCH_OLD "\x40\x3f\x20\x50" +#define PATCH_NEW "\x40\x3f\x00\x5a" +#define PATCH_LEN (sizeof(PATCH_OLD)-1) +#define _BITS_IOCTL_H_ + +// under 100 lines of code begins now +#include +#include +#include +#include +#include + +// ioctl stuff +#define IOC_OUT 0x40000000 /* copy out parameters */ +#define IOC_IN 0x80000000 /* copy in parameters */ +#define IOC_INOUT (IOC_IN|IOC_OUT) +#define IOCPARM_MASK 0x1fff /* parameter length, at most 13 bits */ + +#define _IOC(inout,group,num,len) \ + (inout | ((len & IOCPARM_MASK) << 16) | ((group) << 8) | (num)) +#define _IOWR(g,n,t) _IOC(IOC_INOUT, (g), (n), sizeof(t)) + +// ion ioctls +#include +#define ION_IOC_MSM_MAGIC 'M' +#define ION_IOC_CLEAN_INV_CACHES _IOWR(ION_IOC_MSM_MAGIC, 2, \ + struct ion_flush_data) + +struct ion_flush_data { + ion_user_handle_t handle; + int fd; + void *vaddr; + unsigned int offset; + unsigned int length; +}; + +// fastrpc ioctls +#define FASTRPC_IOCTL_INIT _IOWR('R', 6, struct fastrpc_ioctl_init) + +struct fastrpc_ioctl_init { + uint32_t flags; /* one of FASTRPC_INIT_* macros */ + uintptr_t __user file; /* pointer to elf file */ + int32_t filelen; /* elf file length */ + int32_t filefd; /* ION fd for the file */ + uintptr_t __user mem; /* mem for the PD */ + int32_t memlen; /* mem length */ + int32_t memfd; /* ION fd for the mem */ +}; + +int ioctl(int fd, unsigned long request, void *arg) { + static void *handle = NULL; + static int (*orig_ioctl)(int, int, void*); + + if (handle == NULL) { + handle = dlopen("/system/lib64/libc.so", RTLD_LAZY); + assert(handle != NULL); + orig_ioctl = dlsym(handle, "ioctl"); + } + + int ret = orig_ioctl(fd, request, arg); + + // carefully modify this one + if (request == FASTRPC_IOCTL_INIT) { + struct fastrpc_ioctl_init *init = (struct fastrpc_ioctl_init *)arg; + + // confirm patch is correct and do the patch + assert(memcmp((void*)(init->mem+PATCH_ADDR), PATCH_OLD, PATCH_LEN) == 0); + memcpy((void*)(init->mem+PATCH_ADDR), PATCH_NEW, PATCH_LEN); + + // flush cache + int ionfd = open("/dev/ion", O_RDONLY); + assert(ionfd > 0); + + struct ion_fd_data fd_data; + fd_data.fd = init->memfd; + int ret = ioctl(ionfd, ION_IOC_IMPORT, &fd_data); + assert(ret == 0); + + struct ion_flush_data flush_data; + flush_data.handle = fd_data.handle; + flush_data.vaddr = (void*)init->mem; + flush_data.offset = 0; + flush_data.length = init->memlen; + ret = ioctl(ionfd, ION_IOC_CLEAN_INV_CACHES, &flush_data); + assert(ret == 0); + + struct ion_handle_data handle_data; + handle_data.handle = fd_data.handle; + ret = ioctl(ionfd, ION_IOC_FREE, &handle_data); + assert(ret == 0); + + // cleanup + close(ionfd); + } + + return ret; +} + diff --git a/selfdrive/orbd/dsp/gen/calculator.h b/selfdrive/orbd/dsp/gen/calculator.h new file mode 100644 index 00000000000000..86a3de6717c833 --- /dev/null +++ b/selfdrive/orbd/dsp/gen/calculator.h @@ -0,0 +1,39 @@ +#ifndef _CALCULATOR_H +#define _CALCULATOR_H + +#include +typedef uint8_t uint8; +typedef uint32_t uint32; + +#ifndef __QAIC_HEADER +#define __QAIC_HEADER(ff) ff +#endif //__QAIC_HEADER + +#ifndef __QAIC_HEADER_EXPORT +#define __QAIC_HEADER_EXPORT +#endif // __QAIC_HEADER_EXPORT + +#ifndef __QAIC_HEADER_ATTRIBUTE +#define __QAIC_HEADER_ATTRIBUTE +#endif // __QAIC_HEADER_ATTRIBUTE + +#ifndef __QAIC_IMPL +#define __QAIC_IMPL(ff) ff +#endif //__QAIC_IMPL + +#ifndef __QAIC_IMPL_EXPORT +#define __QAIC_IMPL_EXPORT +#endif // __QAIC_IMPL_EXPORT + +#ifndef __QAIC_IMPL_ATTRIBUTE +#define __QAIC_IMPL_ATTRIBUTE +#endif // __QAIC_IMPL_ATTRIBUTE +#ifdef __cplusplus +extern "C" { +#endif +__QAIC_HEADER_EXPORT int __QAIC_HEADER(calculator_init)(uint32* leet) __QAIC_HEADER_ATTRIBUTE; +__QAIC_HEADER_EXPORT int __QAIC_HEADER(calculator_extract_and_match)(const uint8* img, int imgLen, uint8* features, int featuresLen) __QAIC_HEADER_ATTRIBUTE; +#ifdef __cplusplus +} +#endif +#endif //_CALCULATOR_H diff --git a/selfdrive/orbd/dsp/gen/calculator_stub.c b/selfdrive/orbd/dsp/gen/calculator_stub.c new file mode 100644 index 00000000000000..66e4a0f822158d --- /dev/null +++ b/selfdrive/orbd/dsp/gen/calculator_stub.c @@ -0,0 +1,613 @@ +#ifndef _CALCULATOR_STUB_H +#define _CALCULATOR_STUB_H +#include "calculator.h" + +// remote.h +#include +#include + +typedef uint32_t remote_handle; +typedef uint64_t remote_handle64; + +typedef struct { + void *pv; + size_t nLen; +} remote_buf; + +typedef struct { + int32_t fd; + uint32_t offset; +} remote_dma_handle; + +typedef union { + remote_buf buf; + remote_handle h; + remote_handle64 h64; + remote_dma_handle dma; +} remote_arg; + +int remote_handle_open(const char* name, remote_handle *ph); +int remote_handle_invoke(remote_handle h, uint32_t dwScalars, remote_arg *pra); +int remote_handle_close(remote_handle h); + +#define REMOTE_SCALARS_MAKEX(nAttr,nMethod,nIn,nOut,noIn,noOut) \ + ((((uint32_t) (nAttr) & 0x7) << 29) | \ + (((uint32_t) (nMethod) & 0x1f) << 24) | \ + (((uint32_t) (nIn) & 0xff) << 16) | \ + (((uint32_t) (nOut) & 0xff) << 8) | \ + (((uint32_t) (noIn) & 0x0f) << 4) | \ + ((uint32_t) (noOut) & 0x0f)) + +#ifndef _QAIC_ENV_H +#define _QAIC_ENV_H + +#ifdef __GNUC__ +#ifdef __clang__ +#pragma GCC diagnostic ignored "-Wunknown-pragmas" +#else +#pragma GCC diagnostic ignored "-Wpragmas" +#endif +#pragma GCC diagnostic ignored "-Wuninitialized" +#pragma GCC diagnostic ignored "-Wunused-parameter" +#pragma GCC diagnostic ignored "-Wunused-function" +#endif + +#ifndef _ATTRIBUTE_UNUSED + +#ifdef _WIN32 +#define _ATTRIBUTE_UNUSED +#else +#define _ATTRIBUTE_UNUSED __attribute__ ((unused)) +#endif + +#endif // _ATTRIBUTE_UNUSED + +#ifndef __QAIC_REMOTE +#define __QAIC_REMOTE(ff) ff +#endif //__QAIC_REMOTE + +#ifndef __QAIC_HEADER +#define __QAIC_HEADER(ff) ff +#endif //__QAIC_HEADER + +#ifndef __QAIC_HEADER_EXPORT +#define __QAIC_HEADER_EXPORT +#endif // __QAIC_HEADER_EXPORT + +#ifndef __QAIC_HEADER_ATTRIBUTE +#define __QAIC_HEADER_ATTRIBUTE +#endif // __QAIC_HEADER_ATTRIBUTE + +#ifndef __QAIC_IMPL +#define __QAIC_IMPL(ff) ff +#endif //__QAIC_IMPL + +#ifndef __QAIC_IMPL_EXPORT +#define __QAIC_IMPL_EXPORT +#endif // __QAIC_IMPL_EXPORT + +#ifndef __QAIC_IMPL_ATTRIBUTE +#define __QAIC_IMPL_ATTRIBUTE +#endif // __QAIC_IMPL_ATTRIBUTE + +#ifndef __QAIC_STUB +#define __QAIC_STUB(ff) ff +#endif //__QAIC_STUB + +#ifndef __QAIC_STUB_EXPORT +#define __QAIC_STUB_EXPORT +#endif // __QAIC_STUB_EXPORT + +#ifndef __QAIC_STUB_ATTRIBUTE +#define __QAIC_STUB_ATTRIBUTE +#endif // __QAIC_STUB_ATTRIBUTE + +#ifndef __QAIC_SKEL +#define __QAIC_SKEL(ff) ff +#endif //__QAIC_SKEL__ + +#ifndef __QAIC_SKEL_EXPORT +#define __QAIC_SKEL_EXPORT +#endif // __QAIC_SKEL_EXPORT + +#ifndef __QAIC_SKEL_ATTRIBUTE +#define __QAIC_SKEL_ATTRIBUTE +#endif // __QAIC_SKEL_ATTRIBUTE + +#ifdef __QAIC_DEBUG__ + #ifndef __QAIC_DBG_PRINTF__ + #include + #define __QAIC_DBG_PRINTF__( ee ) do { printf ee ; } while(0) + #endif +#else + #define __QAIC_DBG_PRINTF__( ee ) (void)0 +#endif + + +#define _OFFSET(src, sof) ((void*)(((char*)(src)) + (sof))) + +#define _COPY(dst, dof, src, sof, sz) \ + do {\ + struct __copy { \ + char ar[sz]; \ + };\ + *(struct __copy*)_OFFSET(dst, dof) = *(struct __copy*)_OFFSET(src, sof);\ + } while (0) + +#define _COPYIF(dst, dof, src, sof, sz) \ + do {\ + if(_OFFSET(dst, dof) != _OFFSET(src, sof)) {\ + _COPY(dst, dof, src, sof, sz); \ + } \ + } while (0) + +_ATTRIBUTE_UNUSED +static __inline void _qaic_memmove(void* dst, void* src, int size) { + int i; + for(i = 0; i < size; ++i) { + ((char*)dst)[i] = ((char*)src)[i]; + } +} + +#define _MEMMOVEIF(dst, src, sz) \ + do {\ + if(dst != src) {\ + _qaic_memmove(dst, src, sz);\ + } \ + } while (0) + + +#define _ASSIGN(dst, src, sof) \ + do {\ + dst = OFFSET(src, sof); \ + } while (0) + +#define _STD_STRLEN_IF(str) (str == 0 ? 0 : strlen(str)) + +#define AEE_SUCCESS 0 +#define AEE_EOFFSET 0x80000400 +#define AEE_EBADPARM (AEE_EOFFSET + 0x00E) + +#define _TRY(ee, func) \ + do { \ + if (AEE_SUCCESS != ((ee) = func)) {\ + __QAIC_DBG_PRINTF__((__FILE__ ":%d:error:%d:%s\n", __LINE__, (int)(ee),#func));\ + goto ee##bail;\ + } \ + } while (0) + +#define _CATCH(exception) exception##bail: if (exception != AEE_SUCCESS) + +#define _ASSERT(nErr, ff) _TRY(nErr, 0 == (ff) ? AEE_EBADPARM : AEE_SUCCESS) + +#ifdef __QAIC_DEBUG__ +#define _ALLOCATE(nErr, pal, size, alignment, pv) _TRY(nErr, _allocator_alloc(pal, __FILE_LINE__, size, alignment, (void**)&pv)) +#else +#define _ALLOCATE(nErr, pal, size, alignment, pv) _TRY(nErr, _allocator_alloc(pal, 0, size, alignment, (void**)&pv)) +#endif + + +#endif // _QAIC_ENV_H + +#ifndef _ALLOCATOR_H +#define _ALLOCATOR_H + +#include +#include + +typedef struct _heap _heap; +struct _heap { + _heap* pPrev; + const char* loc; + uint64_t buf; +}; + +typedef struct _allocator { + _heap* pheap; + uint8_t* stack; + uint8_t* stackEnd; + int nSize; +} _allocator; + +_ATTRIBUTE_UNUSED +static __inline int _heap_alloc(_heap** ppa, const char* loc, int size, void** ppbuf) { + _heap* pn = 0; + pn = malloc(size + sizeof(_heap) - sizeof(uint64_t)); + if(pn != 0) { + pn->pPrev = *ppa; + pn->loc = loc; + *ppa = pn; + *ppbuf = (void*)&(pn->buf); + return 0; + } else { + return -1; + } +} +#define _ALIGN_SIZE(x, y) (((x) + (y-1)) & ~(y-1)) + +_ATTRIBUTE_UNUSED +static __inline int _allocator_alloc(_allocator* me, + const char* loc, + int size, + unsigned int al, + void** ppbuf) { + if(size < 0) { + return -1; + } else if (size == 0) { + *ppbuf = 0; + return 0; + } + if((_ALIGN_SIZE((uintptr_t)me->stackEnd, al) + size) < (uintptr_t)me->stack + me->nSize) { + *ppbuf = (uint8_t*)_ALIGN_SIZE((uintptr_t)me->stackEnd, al); + me->stackEnd = (uint8_t*)_ALIGN_SIZE((uintptr_t)me->stackEnd, al) + size; + return 0; + } else { + return _heap_alloc(&me->pheap, loc, size, ppbuf); + } +} + +_ATTRIBUTE_UNUSED +static __inline void _allocator_deinit(_allocator* me) { + _heap* pa = me->pheap; + while(pa != 0) { + _heap* pn = pa; + const char* loc = pn->loc; + (void)loc; + pa = pn->pPrev; + free(pn); + } +} + +_ATTRIBUTE_UNUSED +static __inline void _allocator_init(_allocator* me, uint8_t* stack, int stackSize) { + me->stack = stack; + me->stackEnd = stack + stackSize; + me->nSize = stackSize; + me->pheap = 0; +} + + +#endif // _ALLOCATOR_H + +#ifndef SLIM_H +#define SLIM_H + +#include + +//a C data structure for the idl types that can be used to implement +//static and dynamic language bindings fairly efficiently. +// +//the goal is to have a minimal ROM and RAM footprint and without +//doing too many allocations. A good way to package these things seemed +//like the module boundary, so all the idls within one module can share +//all the type references. + + +#define PARAMETER_IN 0x0 +#define PARAMETER_OUT 0x1 +#define PARAMETER_INOUT 0x2 +#define PARAMETER_ROUT 0x3 +#define PARAMETER_INROUT 0x4 + +//the types that we get from idl +#define TYPE_OBJECT 0x0 +#define TYPE_INTERFACE 0x1 +#define TYPE_PRIMITIVE 0x2 +#define TYPE_ENUM 0x3 +#define TYPE_STRING 0x4 +#define TYPE_WSTRING 0x5 +#define TYPE_STRUCTURE 0x6 +#define TYPE_UNION 0x7 +#define TYPE_ARRAY 0x8 +#define TYPE_SEQUENCE 0x9 + +//these require the pack/unpack to recurse +//so it's a hint to those languages that can optimize in cases where +//recursion isn't necessary. +#define TYPE_COMPLEX_STRUCTURE (0x10 | TYPE_STRUCTURE) +#define TYPE_COMPLEX_UNION (0x10 | TYPE_UNION) +#define TYPE_COMPLEX_ARRAY (0x10 | TYPE_ARRAY) +#define TYPE_COMPLEX_SEQUENCE (0x10 | TYPE_SEQUENCE) + + +typedef struct Type Type; + +#define INHERIT_TYPE\ + int32_t nativeSize; /*in the simple case its the same as wire size and alignment*/\ + union {\ + struct {\ + const uintptr_t p1;\ + const uintptr_t p2;\ + } _cast;\ + struct {\ + uint32_t iid;\ + uint32_t bNotNil;\ + } object;\ + struct {\ + const Type *arrayType;\ + int32_t nItems;\ + } array;\ + struct {\ + const Type *seqType;\ + int32_t nMaxLen;\ + } seqSimple; \ + struct {\ + uint32_t bFloating;\ + uint32_t bSigned;\ + } prim; \ + const SequenceType* seqComplex;\ + const UnionType *unionType;\ + const StructType *structType;\ + int32_t stringMaxLen;\ + uint8_t bInterfaceNotNil;\ + } param;\ + uint8_t type;\ + uint8_t nativeAlignment\ + +typedef struct UnionType UnionType; +typedef struct StructType StructType; +typedef struct SequenceType SequenceType; +struct Type { + INHERIT_TYPE; +}; + +struct SequenceType { + const Type * seqType; + uint32_t nMaxLen; + uint32_t inSize; + uint32_t routSizePrimIn; + uint32_t routSizePrimROut; +}; + +//byte offset from the start of the case values for +//this unions case value array. it MUST be aligned +//at the alignment requrements for the descriptor +// +//if negative it means that the unions cases are +//simple enumerators, so the value read from the descriptor +//can be used directly to find the correct case +typedef union CaseValuePtr CaseValuePtr; +union CaseValuePtr { + const uint8_t* value8s; + const uint16_t* value16s; + const uint32_t* value32s; + const uint64_t* value64s; +}; + +//these are only used in complex cases +//so I pulled them out of the type definition as references to make +//the type smaller +struct UnionType { + const Type *descriptor; + uint32_t nCases; + const CaseValuePtr caseValues; + const Type * const *cases; + int32_t inSize; + int32_t routSizePrimIn; + int32_t routSizePrimROut; + uint8_t inAlignment; + uint8_t routAlignmentPrimIn; + uint8_t routAlignmentPrimROut; + uint8_t inCaseAlignment; + uint8_t routCaseAlignmentPrimIn; + uint8_t routCaseAlignmentPrimROut; + uint8_t nativeCaseAlignment; + uint8_t bDefaultCase; +}; + +struct StructType { + uint32_t nMembers; + const Type * const *members; + int32_t inSize; + int32_t routSizePrimIn; + int32_t routSizePrimROut; + uint8_t inAlignment; + uint8_t routAlignmentPrimIn; + uint8_t routAlignmentPrimROut; +}; + +typedef struct Parameter Parameter; +struct Parameter { + INHERIT_TYPE; + uint8_t mode; + uint8_t bNotNil; +}; + +#define SLIM_IFPTR32(is32,is64) (sizeof(uintptr_t) == 4 ? (is32) : (is64)) +#define SLIM_SCALARS_IS_DYNAMIC(u) (((u) & 0x00ffffff) == 0x00ffffff) + +typedef struct Method Method; +struct Method { + uint32_t uScalars; //no method index + int32_t primInSize; + int32_t primROutSize; + int maxArgs; + int numParams; + const Parameter * const *params; + uint8_t primInAlignment; + uint8_t primROutAlignment; +}; + +typedef struct Interface Interface; + +struct Interface { + int nMethods; + const Method * const *methodArray; + int nIIds; + const uint32_t *iids; + const uint16_t* methodStringArray; + const uint16_t* methodStrings; + const char* strings; +}; + + +#endif //SLIM_H + + +#ifndef _CALCULATOR_SLIM_H +#define _CALCULATOR_SLIM_H + +// remote.h + +#include + +#ifndef __QAIC_SLIM +#define __QAIC_SLIM(ff) ff +#endif +#ifndef __QAIC_SLIM_EXPORT +#define __QAIC_SLIM_EXPORT +#endif + +static const Type types[1]; +static const Type types[1] = {{0x1,{{(const uintptr_t)0,(const uintptr_t)0}}, 2,0x1}}; +static const Parameter parameters[3] = {{0x4,{{(const uintptr_t)0,(const uintptr_t)0}}, 2,0x4,3,0},{SLIM_IFPTR32(0x8,0x10),{{(const uintptr_t)&(types[0]),(const uintptr_t)0x0}}, 9,SLIM_IFPTR32(0x4,0x8),0,0},{SLIM_IFPTR32(0x8,0x10),{{(const uintptr_t)&(types[0]),(const uintptr_t)0x0}}, 9,SLIM_IFPTR32(0x4,0x8),3,0}}; +static const Parameter* const parameterArrays[3] = {(&(parameters[1])),(&(parameters[2])),(&(parameters[0]))}; +static const Method methods[2] = {{REMOTE_SCALARS_MAKEX(0,0,0x0,0x1,0x0,0x0),0x0,0x4,1,1,(&(parameterArrays[2])),0x1,0x4},{REMOTE_SCALARS_MAKEX(0,0,0x2,0x1,0x0,0x0),0x8,0x0,5,2,(&(parameterArrays[0])),0x4,0x1}}; +static const Method* const methodArrays[2] = {&(methods[0]),&(methods[1])}; +static const char strings[41] = "extract_and_match\0features\0leet\0init\0img\0"; +static const uint16_t methodStrings[5] = {0,37,18,32,27}; +static const uint16_t methodStringsArrays[2] = {3,0}; +__QAIC_SLIM_EXPORT const Interface __QAIC_SLIM(calculator_slim) = {2,&(methodArrays[0]),0,0,&(methodStringsArrays [0]),methodStrings,strings}; +#endif //_CALCULATOR_SLIM_H +#ifdef __cplusplus +extern "C" { +#endif + +#ifndef _const_calculator_handle +#define _const_calculator_handle ((remote_handle)-1) +#endif //_const_calculator_handle + +static void _calculator_pls_dtor(void* data) { + remote_handle* ph = (remote_handle*)data; + if(_const_calculator_handle != *ph) { + (void)__QAIC_REMOTE(remote_handle_close)(*ph); + *ph = _const_calculator_handle; + } +} + +static int _calculator_pls_ctor(void* ctx, void* data) { + remote_handle* ph = (remote_handle*)data; + *ph = _const_calculator_handle; + if(*ph == (remote_handle)-1) { + return __QAIC_REMOTE(remote_handle_open)((const char*)ctx, ph); + } + return 0; +} + +#if (defined __qdsp6__) || (defined __hexagon__) +#pragma weak adsp_pls_add_lookup +extern int adsp_pls_add_lookup(uint32_t type, uint32_t key, int size, int (*ctor)(void* ctx, void* data), void* ctx, void (*dtor)(void* ctx), void** ppo); +#pragma weak HAP_pls_add_lookup +extern int HAP_pls_add_lookup(uint32_t type, uint32_t key, int size, int (*ctor)(void* ctx, void* data), void* ctx, void (*dtor)(void* ctx), void** ppo); + +__QAIC_STUB_EXPORT remote_handle _calculator_handle(void) { + remote_handle* ph; + if(adsp_pls_add_lookup) { + if(0 == adsp_pls_add_lookup((uint32_t)_calculator_handle, 0, sizeof(*ph), _calculator_pls_ctor, "calculator", _calculator_pls_dtor, (void**)&ph)) { + return *ph; + } + return (remote_handle)-1; + } else if(HAP_pls_add_lookup) { + if(0 == HAP_pls_add_lookup((uint32_t)_calculator_handle, 0, sizeof(*ph), _calculator_pls_ctor, "calculator", _calculator_pls_dtor, (void**)&ph)) { + return *ph; + } + return (remote_handle)-1; + } + return(remote_handle)-1; +} + +#else //__qdsp6__ || __hexagon__ + +uint32_t _calculator_atomic_CompareAndExchange(uint32_t * volatile puDest, uint32_t uExchange, uint32_t uCompare); + +#ifdef _WIN32 +#include "Windows.h" +uint32_t _calculator_atomic_CompareAndExchange(uint32_t * volatile puDest, uint32_t uExchange, uint32_t uCompare) { + return (uint32_t)InterlockedCompareExchange((volatile LONG*)puDest, (LONG)uExchange, (LONG)uCompare); +} +#elif __GNUC__ +uint32_t _calculator_atomic_CompareAndExchange(uint32_t * volatile puDest, uint32_t uExchange, uint32_t uCompare) { + return __sync_val_compare_and_swap(puDest, uCompare, uExchange); +} +#endif //_WIN32 + + +__QAIC_STUB_EXPORT remote_handle _calculator_handle(void) { + static remote_handle handle = _const_calculator_handle; + if((remote_handle)-1 != handle) { + return handle; + } else { + remote_handle tmp; + int nErr = _calculator_pls_ctor("calculator", (void*)&tmp); + if(nErr) { + return (remote_handle)-1; + } + if(((remote_handle)-1 != handle) || ((remote_handle)-1 != (remote_handle)_calculator_atomic_CompareAndExchange((uint32_t*)&handle, (uint32_t)tmp, (uint32_t)-1))) { + _calculator_pls_dtor(&tmp); + } + return handle; + } +} + +#endif //__qdsp6__ + +__QAIC_STUB_EXPORT int __QAIC_STUB(calculator_skel_invoke)(uint32_t _sc, remote_arg* _pra) __QAIC_STUB_ATTRIBUTE { + return __QAIC_REMOTE(remote_handle_invoke)(_calculator_handle(), _sc, _pra); +} + +#ifdef __cplusplus +} +#endif + + +#ifdef __cplusplus +extern "C" { +#endif +extern int remote_register_dma_handle(int, uint32_t); +static __inline int _stub_method(remote_handle _handle, uint32_t _mid, uint32_t _rout0[1]) { + int _numIn[1]; + remote_arg _pra[1]; + uint32_t _primROut[1]; + int _nErr = 0; + _numIn[0] = 0; + _pra[(_numIn[0] + 0)].buf.pv = (void*)_primROut; + _pra[(_numIn[0] + 0)].buf.nLen = sizeof(_primROut); + _TRY(_nErr, __QAIC_REMOTE(remote_handle_invoke)(_handle, REMOTE_SCALARS_MAKEX(0, _mid, 0, 1, 0, 0), _pra)); + _COPY(_rout0, 0, _primROut, 0, 4); + _CATCH(_nErr) {} + return _nErr; +} +__QAIC_STUB_EXPORT int __QAIC_STUB(calculator_init)(uint32* leet) __QAIC_STUB_ATTRIBUTE { + uint32_t _mid = 0; + return _stub_method(_calculator_handle(), _mid, (uint32_t*)leet); +} +static __inline int _stub_method_1(remote_handle _handle, uint32_t _mid, char* _in0[1], uint32_t _in0Len[1], char* _rout1[1], uint32_t _rout1Len[1]) { + int _numIn[1]; + remote_arg _pra[3]; + uint32_t _primIn[2]; + remote_arg* _praIn; + remote_arg* _praROut; + int _nErr = 0; + _numIn[0] = 1; + _pra[0].buf.pv = (void*)_primIn; + _pra[0].buf.nLen = sizeof(_primIn); + _COPY(_primIn, 0, _in0Len, 0, 4); + _praIn = (_pra + 1); + _praIn[0].buf.pv = _in0[0]; + _praIn[0].buf.nLen = (1 * _in0Len[0]); + _COPY(_primIn, 4, _rout1Len, 0, 4); + _praROut = (_praIn + _numIn[0] + 0); + _praROut[0].buf.pv = _rout1[0]; + _praROut[0].buf.nLen = (1 * _rout1Len[0]); + _TRY(_nErr, __QAIC_REMOTE(remote_handle_invoke)(_handle, REMOTE_SCALARS_MAKEX(0, _mid, 2, 1, 0, 0), _pra)); + _CATCH(_nErr) {} + return _nErr; +} +__QAIC_STUB_EXPORT int __QAIC_STUB(calculator_extract_and_match)(const uint8* img, int imgLen, uint8* features, int featuresLen) __QAIC_STUB_ATTRIBUTE { + uint32_t _mid = 1; + return _stub_method_1(_calculator_handle(), _mid, (char**)&img, (uint32_t*)&imgLen, (char**)&features, (uint32_t*)&featuresLen); +} +#ifdef __cplusplus +} +#endif +#endif //_CALCULATOR_STUB_H diff --git a/selfdrive/orbd/dsp/gen/libcalculator_skel.so b/selfdrive/orbd/dsp/gen/libcalculator_skel.so new file mode 100755 index 00000000000000..e48cab48208b0f Binary files /dev/null and b/selfdrive/orbd/dsp/gen/libcalculator_skel.so differ diff --git a/selfdrive/orbd/extractor.h b/selfdrive/orbd/extractor.h new file mode 100644 index 00000000000000..f506cd3868a05d --- /dev/null +++ b/selfdrive/orbd/extractor.h @@ -0,0 +1,38 @@ +#ifndef EXTRACTOR_H +#define EXTRACTOR_H + +#ifdef __cplusplus +extern "C" { +#endif + +#include + +#define ORBD_KEYPOINTS 3000 +#define ORBD_DESCRIPTOR_LENGTH 32 +#define ORBD_HEIGHT 874 +#define ORBD_WIDTH 1164 +#define ORBD_FOCAL 910 + +// matches OrbFeatures from log.capnp +struct orb_features { + // align this + uint16_t n_corners; + uint16_t xy[ORBD_KEYPOINTS][2]; + uint8_t octave[ORBD_KEYPOINTS]; + uint8_t des[ORBD_KEYPOINTS][ORBD_DESCRIPTOR_LENGTH]; + int16_t matches[ORBD_KEYPOINTS]; +}; + +// forward declare this +struct pyramid; + +// manage the pyramids in extractor.c +void init_gpyrs(); +int extract_and_match_gpyrs(const uint8_t *img, struct orb_features *); +int extract_and_match(const uint8_t *img, struct pyramid *pyrs, struct pyramid *prev_pyrs, struct orb_features *); + +#ifdef __cplusplus +} +#endif + +#endif // EXTRACTOR_H diff --git a/selfdrive/orbd/orbd.cc b/selfdrive/orbd/orbd.cc new file mode 100644 index 00000000000000..ce0d47aec6efbd --- /dev/null +++ b/selfdrive/orbd/orbd.cc @@ -0,0 +1,191 @@ +#include +#include +#include +#include +#include +#include +#include + +#include "common/visionipc.h" +#include "common/swaglog.h" + +#include "extractor.h" + +#ifdef DSP +#include "dsp/gen/calculator.h" +#else +#include "turbocv.h" +#endif + +#include +#include +#include "cereal/gen/cpp/log.capnp.h" + +#ifndef PATH_MAX +#include +#endif + +volatile int do_exit = 0; + +static void set_do_exit(int sig) { + do_exit = 1; +} + +int main(int argc, char *argv[]) { + int err; + setpriority(PRIO_PROCESS, 0, -13); + printf("starting orbd\n"); + +#ifdef DSP + uint32_t test_leet = 0; + char my_path[PATH_MAX+1]; + memset(my_path, 0, sizeof(my_path)); + + ssize_t len = readlink("/proc/self/exe", my_path, sizeof(my_path)); + assert(len > 5); + my_path[len-5] = '\0'; + LOGW("running from %s with PATH_MAX %d", my_path, PATH_MAX); + + char adsp_path[PATH_MAX+1]; + snprintf(adsp_path, PATH_MAX, "ADSP_LIBRARY_PATH=%s/dsp/gen", my_path); + assert(putenv(adsp_path) == 0); + + assert(calculator_init(&test_leet) == 0); + assert(test_leet == 0x1337); + LOGW("orbd init complete"); +#else + init_gpyrs(); +#endif + + signal(SIGINT, (sighandler_t) set_do_exit); + signal(SIGTERM, (sighandler_t) set_do_exit); + + void *ctx = zmq_ctx_new(); + + void *orb_features_sock = zmq_socket(ctx, ZMQ_PUB); + assert(orb_features_sock); + zmq_bind(orb_features_sock, "tcp://*:8058"); + + void *orb_features_summary_sock = zmq_socket(ctx, ZMQ_PUB); + assert(orb_features_summary_sock); + zmq_bind(orb_features_summary_sock, "tcp://*:8062"); + + struct orb_features *features = (struct orb_features *)malloc(sizeof(struct orb_features)); + int last_frame_id = 0; + uint64_t frame_count = 0; + + // every other frame + const int RATE = 2; + + VisionStream stream; + while (!do_exit) { + VisionStreamBufs buf_info; + err = visionstream_init(&stream, VISION_STREAM_YUV, true, &buf_info); + if (err) { + printf("visionstream connect fail\n"); + usleep(100000); + continue; + } + uint64_t timestamp_last_eof = 0; + while (!do_exit) { + VIPCBuf *buf; + VIPCBufExtra extra; + buf = visionstream_get(&stream, &extra); + if (buf == NULL) { + printf("visionstream get failed\n"); + break; + } + + // every other frame + frame_count++; + if ((frame_count%RATE) != 0) { + continue; + } + + uint64_t start = nanos_since_boot(); +#ifdef DSP + int ret = calculator_extract_and_match((uint8_t *)buf->addr, ORBD_HEIGHT*ORBD_WIDTH, (uint8_t *)features, sizeof(struct orb_features)); +#else + int ret = extract_and_match_gpyrs((uint8_t *) buf->addr, features); +#endif + uint64_t end = nanos_since_boot(); + LOGD("total(%d): %6.2f ms to get %4d features on %d", ret, (end-start)/1000000.0, features->n_corners, extra.frame_id); + assert(ret == 0); + + if (last_frame_id+RATE != extra.frame_id) { + LOGW("dropped frame!"); + } + + last_frame_id = extra.frame_id; + + if (timestamp_last_eof == 0) { + timestamp_last_eof = extra.timestamp_eof; + continue; + } + + int match_count = 0; + + // *** send OrbFeatures *** + { + // create capnp message + capnp::MallocMessageBuilder msg; + cereal::Event::Builder event = msg.initRoot(); + event.setLogMonoTime(nanos_since_boot()); + + auto orb_features = event.initOrbFeatures(); + + // set timestamps + orb_features.setTimestampEof(extra.timestamp_eof); + orb_features.setTimestampLastEof(timestamp_last_eof); + + // init descriptors for send + kj::ArrayPtr descriptorsPtr = kj::arrayPtr((uint8_t *)features->des, ORBD_DESCRIPTOR_LENGTH * features->n_corners); + orb_features.setDescriptors(descriptorsPtr); + + auto xs = orb_features.initXs(features->n_corners); + auto ys = orb_features.initYs(features->n_corners); + auto octaves = orb_features.initOctaves(features->n_corners); + auto matches = orb_features.initMatches(features->n_corners); + + // copy out normalized keypoints + for (int i = 0; i < features->n_corners; i++) { + xs.set(i, (features->xy[i][0] * 1.0f - ORBD_WIDTH / 2) / ORBD_FOCAL); + ys.set(i, (features->xy[i][1] * 1.0f - ORBD_HEIGHT / 2) / ORBD_FOCAL); + octaves.set(i, features->octave[i]); + matches.set(i, features->matches[i]); + match_count += features->matches[i] != -1; + } + + auto words = capnp::messageToFlatArray(msg); + auto bytes = words.asBytes(); + zmq_send(orb_features_sock, bytes.begin(), bytes.size(), 0); + } + + // *** send OrbFeaturesSummary *** + + { + // create capnp message + capnp::MallocMessageBuilder msg; + cereal::Event::Builder event = msg.initRoot(); + event.setLogMonoTime(nanos_since_boot()); + + auto orb_features_summary = event.initOrbFeaturesSummary(); + + orb_features_summary.setTimestampEof(extra.timestamp_eof); + orb_features_summary.setTimestampLastEof(timestamp_last_eof); + orb_features_summary.setFeatureCount(features->n_corners); + orb_features_summary.setMatchCount(match_count); + orb_features_summary.setComputeNs(end-start); + + auto words = capnp::messageToFlatArray(msg); + auto bytes = words.asBytes(); + zmq_send(orb_features_summary_sock, bytes.begin(), bytes.size(), 0); + } + + timestamp_last_eof = extra.timestamp_eof; + } + } + visionstream_destroy(&stream); + return 0; +} + diff --git a/selfdrive/orbd/orbd_wrapper.sh b/selfdrive/orbd/orbd_wrapper.sh new file mode 100755 index 00000000000000..8ec7443a30d4f7 --- /dev/null +++ b/selfdrive/orbd/orbd_wrapper.sh @@ -0,0 +1,13 @@ +#!/bin/sh +finish() { + echo "exiting orbd" + pkill -SIGINT -P $$ +} + +trap finish EXIT + +while true; do + ./orbd & + wait $! +done + diff --git a/selfdrive/pandad.py b/selfdrive/pandad.py new file mode 100644 index 00000000000000..981546ccf95411 --- /dev/null +++ b/selfdrive/pandad.py @@ -0,0 +1,14 @@ +#!/usr/bin/env python +# simple boardd wrapper that updates the panda first +import os +from panda import ensure_st_up_to_date + +def main(gctx=None): + ensure_st_up_to_date() + + os.chdir("boardd") + os.execvp("./boardd", ["./boardd"]) + +if __name__ == "__main__": + main() + diff --git a/selfdrive/proclogd/Makefile b/selfdrive/proclogd/Makefile new file mode 100644 index 00000000000000..a7cd3682b29a6b --- /dev/null +++ b/selfdrive/proclogd/Makefile @@ -0,0 +1,51 @@ +CC = clang +CXX = clang++ + +PHONELIBS = ../../phonelibs +BASEDIR = ../.. + +WARN_FLAGS = -Werror=implicit-function-declaration \ + -Werror=incompatible-pointer-types \ + -Werror=int-conversion \ + -Werror=return-type \ + -Werror=format-extra-args + +CFLAGS = -std=gnu11 -g -fPIC -O2 $(WARN_FLAGS) +CXXFLAGS = -std=c++11 -g -fPIC -O2 $(WARN_FLAGS) + +ZMQ_FLAGS = -I$(PHONELIBS)/zmq/aarch64/include +ZMQ_LIBS = -L$(PHONELIBS)/zmq/aarch64/lib \ + -l:libczmq.a -l:libzmq.a \ + -lgnustl_shared + +.PHONY: all +all: proclogd + +include ../common/cereal.mk + +OBJS = proclogd.o \ + $(CEREAL_OBJS) + +DEPS := $(OBJS:.o=.d) + +proclogd: $(OBJS) + @echo "[ LINK ] $@" + $(CXX) -fPIC -o '$@' $^ \ + $(CEREAL_LIBS) \ + $(ZMQ_LIBS) \ + -llog + +%.o: %.cc + @echo "[ CXX ] $@" + $(CXX) $(CXXFLAGS) \ + $(CEREAL_CXXFLAGS) \ + $(ZMQ_FLAGS) \ + -I../ \ + -I../../ \ + -c -o '$@' '$<' + +.PHONY: clean +clean: + rm -f proclogd $(OBJS) $(DEPS) + +-include $(DEPS) diff --git a/selfdrive/proclogd/proclogd.cc b/selfdrive/proclogd/proclogd.cc new file mode 100644 index 00000000000000..fbb7704e0378e7 --- /dev/null +++ b/selfdrive/proclogd/proclogd.cc @@ -0,0 +1,245 @@ +#include +#include +#include +#include + +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include "cereal/gen/cpp/log.capnp.h" + +#include "common/timing.h" +#include "common/utilpp.h" + +namespace { + +struct ProcCache { + std::string name; + std::vector cmdline; + std::string exe; +}; + +} + +int main() { + int err; + + void *context = zmq_ctx_new(); + void *publisher = zmq_socket(context, ZMQ_PUB); + err = zmq_bind(publisher, "tcp://*:8031"); + assert(err == 0); + + double jiffy = sysconf(_SC_CLK_TCK); + size_t page_size = sysconf(_SC_PAGE_SIZE); + + std::unordered_map proc_cache; + + while (1) { + + capnp::MallocMessageBuilder msg; + cereal::Event::Builder event = msg.initRoot(); + event.setLogMonoTime(nanos_since_boot()); + auto procLog = event.initProcLog(); + + auto orphanage = msg.getOrphanage(); + + // stat + { + std::vector> otimes; + + std::ifstream sstat("/proc/stat"); + std::string stat_line; + while (std::getline(sstat, stat_line)) { + if (util::starts_with(stat_line, "cpu ")) { + // cpu total + } else if (util::starts_with(stat_line, "cpu")) { + // specific cpu + int id; + unsigned long utime, ntime, stime, itime; + unsigned long iowtime, irqtime, sirqtime; + + int count = sscanf(stat_line.data(), "cpu%d %lu %lu %lu %lu %lu %lu %lu", + &id, &utime, &ntime, &stime, &itime, &iowtime, &irqtime, &sirqtime); + + auto ltimeo = orphanage.newOrphan(); + auto ltime = ltimeo.get(); + ltime.setCpuNum(id); + ltime.setUser(utime / jiffy); + ltime.setNice(ntime / jiffy); + ltime.setSystem(stime / jiffy); + ltime.setIdle(itime / jiffy); + ltime.setIowait(iowtime / jiffy); + ltime.setIrq(irqtime / jiffy); + ltime.setSoftirq(irqtime / jiffy); + + otimes.push_back(std::move(ltimeo)); + + } else { + break; + } + } + + auto ltimes = procLog.initCpuTimes(otimes.size()); + for (size_t i = 0; i < otimes.size(); i++) { + ltimes.adoptWithCaveats(i, std::move(otimes[i])); + } + } + + // meminfo + { + auto mem = procLog.initMem(); + + std::ifstream smem("/proc/meminfo"); + std::string mem_line; + + uint64_t mem_total = 0, mem_free = 0, mem_available = 0, mem_buffers = 0; + uint64_t mem_cached = 0, mem_active = 0, mem_inactive = 0, mem_shared = 0; + + while (std::getline(smem, mem_line)) { + if (util::starts_with(mem_line, "MemTotal:")) sscanf(mem_line.data(), "MemTotal: %lu kB", &mem_total); + else if (util::starts_with(mem_line, "MemFree:")) sscanf(mem_line.data(), "MemFree: %lu kB", &mem_free); + else if (util::starts_with(mem_line, "MemAvailable:")) sscanf(mem_line.data(), "MemAvailable: %lu kB", &mem_available); + else if (util::starts_with(mem_line, "Buffers:")) sscanf(mem_line.data(), "Buffers: %lu kB", &mem_buffers); + else if (util::starts_with(mem_line, "Cached:")) sscanf(mem_line.data(), "Cached: %lu kB", &mem_cached); + else if (util::starts_with(mem_line, "Active:")) sscanf(mem_line.data(), "Active: %lu kB", &mem_active); + else if (util::starts_with(mem_line, "Inactive:")) sscanf(mem_line.data(), "Inactive: %lu kB", &mem_inactive); + else if (util::starts_with(mem_line, "Shmem:")) sscanf(mem_line.data(), "Shmem: %lu kB", &mem_shared); + } + + mem.setTotal(mem_total * 1024); + mem.setFree(mem_free * 1024); + mem.setAvailable(mem_available * 1024); + mem.setBuffers(mem_buffers * 1024); + mem.setCached(mem_cached * 1024); + mem.setActive(mem_active * 1024); + mem.setInactive(mem_inactive * 1024); + mem.setShared(mem_shared * 1024); + } + + // processes + { + std::vector> oprocs; + struct dirent *de = NULL; + DIR *d = opendir("/proc"); + assert(d); + while ((de = readdir(d))) { + if (!isdigit(de->d_name[0])) continue; + pid_t pid = atoi(de->d_name); + + + auto lproco = orphanage.newOrphan(); + auto lproc = lproco.get(); + + lproc.setPid(pid); + + char tcomm[PATH_MAX] = {0}; + + { + std::string stat = util::read_file(util::string_format("/proc/%d/stat", pid)); + + char state; + + int ppid; + unsigned long utime, stime; + long cutime, cstime, priority, nice, num_threads; + unsigned long long starttime; + unsigned long vms, rss; + int processor; + + int count = sscanf(stat.data(), + "%*d (%1024[^)]) %c %d %*d %*d %*d %*d %*d %*d %*d %*d %*d " + "%lu %lu %ld %ld %ld %ld %ld %*d %lld " + "%lu %lu %*d %*d %*d %*d %*d %*d %*d " + "%*d %*d %*d %*d %*d %*d %*d %d", + tcomm, &state, &ppid, + &utime, &stime, &cutime, &cstime, &priority, &nice, &num_threads, &starttime, + &vms, &rss, &processor); + + if (count != 14) continue; + + lproc.setState(state); + lproc.setPpid(ppid); + lproc.setCpuUser(utime / jiffy); + lproc.setCpuSystem(stime / jiffy); + lproc.setCpuChildrenUser(cutime / jiffy); + lproc.setCpuChildrenSystem(cstime / jiffy); + lproc.setPriority(priority); + lproc.setNice(nice); + lproc.setNumThreads(num_threads); + lproc.setStartTime(starttime / jiffy); + lproc.setMemVms(vms); + lproc.setMemRss((uint64_t)rss * page_size); + lproc.setProcessor(processor); + } + + std::string name(tcomm); + lproc.setName(name); + + // populate other things from cache + auto cache_it = proc_cache.find(pid); + ProcCache cache; + if (cache_it != proc_cache.end()) { + cache = cache_it->second; + } + if (cache_it == proc_cache.end() || cache.name != name) { + cache = (ProcCache){ + .name = name, + .exe = util::readlink(util::string_format("/proc/%d/exe", pid)), + }; + + // null-delimited cmdline arguments to vector + std::string cmdline_s = util::read_file(util::string_format("/proc/%d/cmdline", pid)); + const char* cmdline_p = cmdline_s.c_str(); + const char* cmdline_ep = cmdline_p + cmdline_s.size(); + + // strip trailing null bytes + while ((cmdline_ep-1) > cmdline_p && *(cmdline_ep-1) == 0) { + cmdline_ep--; + } + + while (cmdline_p < cmdline_ep) { + std::string arg(cmdline_p); + cache.cmdline.push_back(arg); + cmdline_p += arg.size() + 1; + } + + proc_cache[pid] = cache; + } + + auto lcmdline = lproc.initCmdline(cache.cmdline.size()); + for (size_t i = 0; i < lcmdline.size(); i++) { + lcmdline.set(i, cache.cmdline[i]); + } + lproc.setExe(cache.exe); + + oprocs.push_back(std::move(lproco)); + } + closedir(d); + + auto lprocs = procLog.initProcs(oprocs.size()); + for (size_t i = 0; i < oprocs.size(); i++) { + lprocs.adoptWithCaveats(i, std::move(oprocs[i])); + } + } + + auto words = capnp::messageToFlatArray(msg); + auto bytes = words.asBytes(); + zmq_send(publisher, bytes.begin(), bytes.size(), 0); + + usleep(2000000); // 2 secs + } + + return 0; +} diff --git a/selfdrive/registration.py b/selfdrive/registration.py new file mode 100644 index 00000000000000..9b7e6964ef92b5 --- /dev/null +++ b/selfdrive/registration.py @@ -0,0 +1,54 @@ +import json +import subprocess + +from selfdrive.swaglog import cloudlog +from selfdrive.version import version, training_version +from common.api import api_get +from common.params import Params + +def get_imei(): + ret = subprocess.check_output(["getprop", "oem.device.imeicache"]).strip() + if ret == "": + ret = "000000000000000" + return ret + +def get_serial(): + return subprocess.check_output(["getprop", "ro.serialno"]).strip() + +def get_git_commit(): + return subprocess.check_output(["git", "rev-parse", "HEAD"]).strip() + +def get_git_branch(): + return subprocess.check_output(["git", "rev-parse", "--abbrev-ref", "HEAD"]).strip() + +def get_git_remote(): + return subprocess.check_output(["git", "config", "--get", "remote.origin.url"]).strip() + +def register(): + params = Params() + params.put("Version", version) + params.put("TrainingVersion", training_version) + params.put("GitCommit", get_git_commit()) + params.put("GitBranch", get_git_branch()) + params.put("GitRemote", get_git_remote()) + + dongle_id, access_token = params.get("DongleId"), params.get("AccessToken") + + try: + if dongle_id is None or access_token is None: + cloudlog.info("getting pilotauth") + resp = api_get("v1/pilotauth/", method='POST', timeout=15, + imei=get_imei(), serial=get_serial()) + dongleauth = json.loads(resp.text) + dongle_id, access_token = dongleauth["dongle_id"].encode('ascii'), dongleauth["access_token"].encode('ascii') + + params.put("DongleId", dongle_id) + params.put("AccessToken", access_token) + return dongle_id, access_token + except Exception: + cloudlog.exception("failed to authenticate") + return None + +if __name__ == "__main__": + print(api_get("").text) + print(register()) diff --git a/selfdrive/sensord/Makefile b/selfdrive/sensord/Makefile new file mode 100644 index 00000000000000..98508d8d1aad92 --- /dev/null +++ b/selfdrive/sensord/Makefile @@ -0,0 +1,4 @@ +-include build_from_src.mk + +release: + @echo "sensord: this is a release" diff --git a/selfdrive/sensord/gpsd b/selfdrive/sensord/gpsd new file mode 100755 index 00000000000000..76862e44c9d3a5 Binary files /dev/null and b/selfdrive/sensord/gpsd differ diff --git a/selfdrive/sensord/sensord b/selfdrive/sensord/sensord new file mode 100755 index 00000000000000..dd95ea9d198e06 Binary files /dev/null and b/selfdrive/sensord/sensord differ diff --git a/selfdrive/service_list.yaml b/selfdrive/service_list.yaml new file mode 100644 index 00000000000000..7a875d219b638a --- /dev/null +++ b/selfdrive/service_list.yaml @@ -0,0 +1,137 @@ +# TODO: these port numbers are hardcoded in c, fix this + +# LogRotate: 8001 is a PUSH PULL socket between loggerd and visiond + +# all ZMQ pub sub: + +# frame syncing packet +frame: [8002, true] +# accel, gyro, and compass +sensorEvents: [8003, true] +# GPS data, also global timestamp +gpsNMEA: [8004, true] +# CPU+MEM+GPU+BAT temps +thermal: [8005, true] +# List(CanData), list of can messages +can: [8006, true] +live100: [8007, true] + +# random events we want to log + +#liveEvent: [8008, true] +model: [8009, true] +features: [8010, true] +health: [8011, true] +live20: [8012, true] +#liveUI: [8014, true] +encodeIdx: [8015, true] +liveTracks: [8016, true] +sendcan: [8017, true] +logMessage: [8018, true] +liveCalibration: [8019, true] +androidLog: [8020, true] +carState: [8021, true] +# 8022 is reserved for sshd +carControl: [8023, true] +plan: [8024, true] +liveLocation: [8025, true] +gpsLocation: [8026, true] +ethernetData: [8027, true] +navUpdate: [8028, true] +qcomGnss: [8029, true] +lidarPts: [8030, true] +procLog: [8031, true] +gpsLocationExternal: [8032, true] +ubloxGnss: [8033, true] +clocks: [8034, true] +liveMpc: [8035, true] +liveLongitudinalMpc: [8036, true] +plusFrame: [8037, false] +navStatus: [8038, true] +gpsLocationTrimble: [8039, true] +trimbleGnss: [8041, true] +ubloxRaw: [8042, true] +gpsPlannerPoints: [8043, true] +gpsPlannerPlan: [8044, true] +applanixRaw: [8046, true] +orbLocation: [8047, true] +trafficEvents: [8048, true] +liveLocationTiming: [8049, true] +orbslamCorrection: [8050, true] +liveLocationCorrected: [8051, true] +orbObservation: [8052, true] +applanixLocation: [8053, true] +liveLocationKalman: [8054, true] +uiNavigationEvent: [8055, true] +orbOdometry: [8057, true] +orbFeatures: [8058, false] +orbKeyFrame: [8059, true] +uiLayoutState: [8060, true] +frontEncodeIdx: [8061, true] +orbFeaturesSummary: [8062, true] +driverMonitoring: [8063, true] +liveParameters: [8064, true] +liveMapData: [8065, true] + +testModel: [8040, false] +testLiveLocation: [8045, false] +testJoystick: [8056, false] + +# 8080 is reserved for slave testing daemon +# 8762 is reserved for logserver + +# manager -- base process to manage starting and stopping of all others +# subscribes: health +# publishes: thermal + +# **** processes that communicate with the outside world **** + +# boardd -- communicates with the car +# subscribes: sendcan +# publishes: can, health, ubloxRaw + +# sensord -- publishes the IMU and GPS +# publishes: sensorEvents, gpsNMEA + +# visiond -- talks to the cameras, runs the model, saves the videos +# subscribes: liveCalibration, sensorEvents, live100 +# publishes: frame, encodeIdx, model, liveCalibration + +# **** stateful data transformers **** + +# plannerd -- decides where to drive the car +# subscribes: carState, model, live20 +# publishes: plan + +# controlsd -- actually drives the car +# subscribes: can, thermal, plan +# publishes: carState, carControl, sendcan, live100 + +# radard -- processes the radar data +# blocks: CarParams +# subscribes: can, live100, model +# publishes: live20, liveTracks + +# **** LOGGING SERVICE **** + +# loggerd +# subscribes: EVERYTHING + +# **** NON VITAL SERVICES **** + +# ui +# subscribes: live100, live20, liveCalibration, model, (raw frames) + +# uploader +# communicates through file system with loggerd + +# logmessaged -- central logging service, can log to cloud +# publishes: logMessage + +# logcatd -- fetches logcat info from android +# publishes: androidLog + +# proclogd -- fetches process information +# publishes: procLog + +# tombstoned -- reports native crashes diff --git a/selfdrive/services.py b/selfdrive/services.py new file mode 100644 index 00000000000000..bd804afe7926bb --- /dev/null +++ b/selfdrive/services.py @@ -0,0 +1,14 @@ +import os +import yaml + +class Service(object): + def __init__(self, port, should_log): + self.port = port + self.should_log = should_log + +service_list_path = os.path.join(os.path.dirname(__file__), "service_list.yaml") + +service_list = {} +with open(service_list_path, "r") as f: + for k, v in yaml.load(f).items(): + service_list[k] = Service(v[0], v[1]) diff --git a/selfdrive/swaglog.py b/selfdrive/swaglog.py new file mode 100644 index 00000000000000..012bb9380616fb --- /dev/null +++ b/selfdrive/swaglog.py @@ -0,0 +1,38 @@ +import os +import logging + +import zmq + +from common.logging_extra import SwagLogger, SwagFormatter + +class LogMessageHandler(logging.Handler): + def __init__(self, formatter): + logging.Handler.__init__(self) + self.setFormatter(formatter) + self.pid = None + + def connect(self): + self.zctx = zmq.Context() + self.sock = self.zctx.socket(zmq.PUSH) + self.sock.connect("ipc:///tmp/logmessage") + self.pid = os.getpid() + + def emit(self, record): + if os.getpid() != self.pid: + self.connect() + + msg = self.format(record).rstrip('\n') + # print "SEND", repr(msg) + try: + self.sock.send(chr(record.levelno)+msg, zmq.NOBLOCK) + except zmq.error.Again: + # drop :/ + pass + +cloudlog = log = SwagLogger() +log.setLevel(logging.DEBUG) + +outhandler = logging.StreamHandler() +log.addHandler(outhandler) + +log.addHandler(LogMessageHandler(SwagFormatter(log))) diff --git a/selfdrive/test/__init__.py b/selfdrive/test/__init__.py new file mode 100644 index 00000000000000..e69de29bb2d1d6 diff --git a/selfdrive/test/plant/__init__.py b/selfdrive/test/plant/__init__.py new file mode 100644 index 00000000000000..e69de29bb2d1d6 diff --git a/selfdrive/test/plant/maneuver.py b/selfdrive/test/plant/maneuver.py new file mode 100644 index 00000000000000..1564aac51deca6 --- /dev/null +++ b/selfdrive/test/plant/maneuver.py @@ -0,0 +1,72 @@ +from maneuverplots import ManeuverPlot +from plant import Plant +import numpy as np + + +class Maneuver(object): + def __init__(self, title, duration, **kwargs): + # Was tempted to make a builder class + self.distance_lead = kwargs.get("initial_distance_lead", 200.0) + self.speed = kwargs.get("initial_speed", 0.0) + self.lead_relevancy = kwargs.get("lead_relevancy", 0) + + self.grade_values = kwargs.get("grade_values", [0.0, 0.0]) + self.grade_breakpoints = kwargs.get("grade_breakpoints", [0.0, duration]) + self.speed_lead_values = kwargs.get("speed_lead_values", [0.0, 0.0]) + self.speed_lead_breakpoints = kwargs.get("speed_lead_breakpoints", [0.0, duration]) + + self.cruise_button_presses = kwargs.get("cruise_button_presses", []) + + self.duration = duration + self.title = title + + def evaluate(self): + """runs the plant sim and returns (score, run_data)""" + plant = Plant( + lead_relevancy = self.lead_relevancy, + speed = self.speed, + distance_lead = self.distance_lead + ) + + last_live100 = None + plot = ManeuverPlot(self.title) + + buttons_sorted = sorted(self.cruise_button_presses, key=lambda a: a[1]) + current_button = 0 + while plant.current_time() < self.duration: + while buttons_sorted and plant.current_time() >= buttons_sorted[0][1]: + current_button = buttons_sorted[0][0] + buttons_sorted = buttons_sorted[1:] + print "current button changed to", current_button + + grade = np.interp(plant.current_time(), self.grade_breakpoints, self.grade_values) + speed_lead = np.interp(plant.current_time(), self.speed_lead_breakpoints, self.speed_lead_values) + + distance, speed, acceleration, distance_lead, brake, gas, steer_torque, fcw, live100= plant.step(speed_lead, current_button, grade) + if live100: + last_live100 = live100[-1] + + d_rel = distance_lead - distance if self.lead_relevancy else 200. + v_rel = speed_lead - speed if self.lead_relevancy else 0. + + if last_live100: + # print last_live100 + #develop plots + plot.add_data( + time=plant.current_time(), + gas=gas, brake=brake, steer_torque=steer_torque, + distance=distance, speed=speed, acceleration=acceleration, + up_accel_cmd=last_live100.upAccelCmd, ui_accel_cmd=last_live100.uiAccelCmd, + uf_accel_cmd=last_live100.ufAccelCmd, + d_rel=d_rel, v_rel=v_rel, v_lead=speed_lead, + v_target_lead=last_live100.vTargetLead, pid_speed=last_live100.vPid, + cruise_speed=last_live100.vCruise, + jerk_factor=last_live100.jerkFactor, + a_target=last_live100.aTarget, + fcw=fcw) + + print "maneuver end" + + return (None, plot) + + diff --git a/selfdrive/test/plant/maneuverplots.py b/selfdrive/test/plant/maneuverplots.py new file mode 100644 index 00000000000000..36b3e5bf8372e0 --- /dev/null +++ b/selfdrive/test/plant/maneuverplots.py @@ -0,0 +1,143 @@ +import os + +import numpy as np +import matplotlib.pyplot as plt +import pylab + +from selfdrive.config import Conversions as CV + +class ManeuverPlot(object): + def __init__(self, title = None): + self.time_array = [] + + self.gas_array = [] + self.brake_array = [] + self.steer_torque_array = [] + + self.distance_array = [] + self.speed_array = [] + self.acceleration_array = [] + + self.up_accel_cmd_array = [] + self.ui_accel_cmd_array = [] + self.uf_accel_cmd_array = [] + + self.d_rel_array = [] + self.v_rel_array = [] + self.v_lead_array = [] + self.v_target_lead_array = [] + self.pid_speed_array = [] + self.cruise_speed_array = [] + self.jerk_factor_array = [] + + self.a_target_array = [] + + self.v_target_array = [] + + self.fcw_array = [] + + self.title = title + + def add_data(self, time, gas, brake, steer_torque, distance, speed, + acceleration, up_accel_cmd, ui_accel_cmd, uf_accel_cmd, d_rel, v_rel, + v_lead, v_target_lead, pid_speed, cruise_speed, jerk_factor, a_target, fcw): + self.time_array.append(time) + self.gas_array.append(gas) + self.brake_array.append(brake) + self.steer_torque_array.append(steer_torque) + self.distance_array.append(distance) + self.speed_array.append(speed) + self.acceleration_array.append(acceleration) + self.up_accel_cmd_array.append(up_accel_cmd) + self.ui_accel_cmd_array.append(ui_accel_cmd) + self.uf_accel_cmd_array.append(uf_accel_cmd) + self.d_rel_array.append(d_rel) + self.v_rel_array.append(v_rel) + self.v_lead_array.append(v_lead) + self.v_target_lead_array.append(v_target_lead) + self.pid_speed_array.append(pid_speed) + self.cruise_speed_array.append(cruise_speed) + self.jerk_factor_array.append(jerk_factor) + self.a_target_array.append(a_target) + self.fcw_array.append(fcw) + + + def write_plot(self, path, maneuver_name): + # title = self.title or maneuver_name + # TODO: Missing plots from the old one: + # long_control_state + # proportional_gb, intergral_gb + if not os.path.exists(path + "/" + maneuver_name): + os.makedirs(path + "/" + maneuver_name) + plt_num = 0 + + # speed chart =================== + plt_num += 1 + plt.figure(plt_num) + plt.plot( + np.array(self.time_array), np.array(self.speed_array) * CV.MS_TO_MPH, 'r', + np.array(self.time_array), np.array(self.pid_speed_array) * CV.MS_TO_MPH, 'y--', + np.array(self.time_array), np.array(self.v_target_lead_array) * CV.MS_TO_MPH, 'b', + np.array(self.time_array), np.array(self.cruise_speed_array) * CV.KPH_TO_MPH, 'k', + np.array(self.time_array), np.array(self.v_lead_array) * CV.MS_TO_MPH, 'm' + ) + plt.xlabel('Time [s]') + plt.ylabel('Speed [mph]') + plt.legend(['speed', 'pid speed', 'Target (lead) speed', 'Cruise speed', 'Lead speed'], loc=0) + plt.grid() + pylab.savefig("/".join([path, maneuver_name, 'speeds.svg']), dpi=1000) + + # acceleration chart ============ + plt_num += 1 + plt.figure(plt_num) + plt.plot( + np.array(self.time_array), np.array(self.acceleration_array), 'g', + np.array(self.time_array), np.array(self.a_target_array), 'k--', + np.array(self.time_array), np.array(self.fcw_array), 'ro', + ) + plt.xlabel('Time [s]') + plt.ylabel('Acceleration [m/s^2]') + plt.legend(['ego-plant', 'target', 'fcw'], loc=0) + plt.grid() + pylab.savefig("/".join([path, maneuver_name, 'acceleration.svg']), dpi=1000) + + # pedal chart =================== + plt_num += 1 + plt.figure(plt_num) + plt.plot( + np.array(self.time_array), np.array(self.gas_array), 'g', + np.array(self.time_array), np.array(self.brake_array), 'r', + ) + plt.xlabel('Time [s]') + plt.ylabel('Pedal []') + plt.legend(['Gas pedal', 'Brake pedal'], loc=0) + plt.grid() + pylab.savefig("/".join([path, maneuver_name, 'pedals.svg']), dpi=1000) + + # pid chart ====================== + plt_num += 1 + plt.figure(plt_num) + plt.plot( + np.array(self.time_array), np.array(self.up_accel_cmd_array), 'g', + np.array(self.time_array), np.array(self.ui_accel_cmd_array), 'b', + np.array(self.time_array), np.array(self.uf_accel_cmd_array), 'r' + ) + plt.xlabel("Time, [s]") + plt.ylabel("Accel Cmd [m/s^2]") + plt.grid() + plt.legend(["Proportional", "Integral", "feedforward"], loc=0) + pylab.savefig("/".join([path, maneuver_name, "pid.svg"]), dpi=1000) + + # relative distances chart ======= + plt_num += 1 + plt.figure(plt_num) + plt.plot( + np.array(self.time_array), np.array(self.d_rel_array), 'g', + ) + plt.xlabel('Time [s]') + plt.ylabel('Relative Distance [m]') + plt.grid() + pylab.savefig("/".join([path, maneuver_name, 'distance.svg']), dpi=1000) + + plt.close("all") + diff --git a/selfdrive/test/plant/plant.py b/selfdrive/test/plant/plant.py new file mode 100755 index 00000000000000..29c9e0c330a195 --- /dev/null +++ b/selfdrive/test/plant/plant.py @@ -0,0 +1,355 @@ +#!/usr/bin/env python +import os +import struct +from collections import namedtuple +import zmq +import numpy as np + +from opendbc import DBC_PATH + +from common.realtime import Ratekeeper +from selfdrive.config import Conversions as CV +import selfdrive.messaging as messaging +from selfdrive.services import service_list +from selfdrive.car.honda.hondacan import fix +from selfdrive.car.honda.values import CAR +from selfdrive.car.honda.carstate import get_can_signals +from selfdrive.boardd.boardd import can_capnp_to_can_list, can_list_to_can_capnp + +from selfdrive.can.plant_can_parser import CANParser +from selfdrive.car.honda.interface import CarInterface + +from common.dbc import dbc +honda = dbc(os.path.join(DBC_PATH, "honda_civic_touring_2016_can_generated.dbc")) + +# Trick: set 0x201 (interceptor) in fingerprints for gas is controlled like if there was an interceptor +CP = CarInterface.get_params(CAR.CIVIC, {0x201}) + + +def car_plant(pos, speed, grade, gas, brake): + # vehicle parameters + mass = 1700 + aero_cd = 0.3 + force_peak = mass*3. + force_brake_peak = -mass*10. #1g + power_peak = 100000 # 100kW + speed_base = power_peak/force_peak + rolling_res = 0.01 + g = 9.81 + frontal_area = 2.2 + air_density = 1.225 + gas_to_peak_linear_slope = 3.33 + brake_to_peak_linear_slope = 0.3 + creep_accel_v = [1., 0.] + creep_accel_bp = [0., 1.5] + + #*** longitudinal model *** + # find speed where peak torque meets peak power + force_brake = brake * force_brake_peak * brake_to_peak_linear_slope + if speed < speed_base: # torque control + force_gas = gas * force_peak * gas_to_peak_linear_slope + else: # power control + force_gas = gas * power_peak / speed * gas_to_peak_linear_slope + + force_grade = - grade * mass # positive grade means uphill + + creep_accel = np.interp(speed, creep_accel_bp, creep_accel_v) + force_creep = creep_accel * mass + + force_resistance = -(rolling_res * mass * g + 0.5 * speed**2 * aero_cd * air_density * frontal_area) + force = force_gas + force_brake + force_resistance + force_grade + force_creep + acceleration = force / mass + + # TODO: lateral model + return speed, acceleration + +def get_car_can_parser(): + dbc_f = 'honda_civic_touring_2016_can_generated.dbc' + signals = [ + ("STEER_TORQUE", 0xe4, 0), + ("STEER_TORQUE_REQUEST", 0xe4, 0), + ("COMPUTER_BRAKE", 0x1fa, 0), + ("COMPUTER_BRAKE_REQUEST", 0x1fa, 0), + ("GAS_COMMAND", 0x200, 0), + ] + checks = [ + (0xe4, 100), + (0x1fa, 50), + (0x200, 50), + ] + return CANParser(dbc_f, signals, checks) + +def to_3_byte(x): + return struct.pack("!H", int(x)).encode("hex")[1:] + +def to_3s_byte(x): + return struct.pack("!h", int(x)).encode("hex")[1:] + +class Plant(object): + messaging_initialized = False + + def __init__(self, lead_relevancy=False, rate=100, speed=0.0, distance_lead=2.0): + self.rate = rate + + if not Plant.messaging_initialized: + context = zmq.Context() + Plant.logcan = messaging.pub_sock(context, service_list['can'].port) + Plant.sendcan = messaging.sub_sock(context, service_list['sendcan'].port) + Plant.model = messaging.pub_sock(context, service_list['model'].port) + Plant.cal = messaging.pub_sock(context, service_list['liveCalibration'].port) + Plant.live100 = messaging.sub_sock(context, service_list['live100'].port) + Plant.plan = messaging.sub_sock(context, service_list['plan'].port) + Plant.messaging_initialized = True + + self.angle_steer = 0. + self.gear_choice = 0 + self.speed, self.speed_prev = 0., 0. + + self.esp_disabled = 0 + self.main_on = 1 + self.user_gas = 0 + self.computer_brake,self.user_brake = 0,0 + self.brake_pressed = 0 + self.angle_steer_rate = 0 + self.distance, self.distance_prev = 0., 0. + self.speed, self.speed_prev = speed, speed + self.steer_error, self.brake_error, self.steer_not_allowed = 0, 0, 0 + self.gear_shifter = 8 # D gear + self.pedal_gas = 0 + self.cruise_setting = 0 + + self.seatbelt, self.door_all_closed = True, True + self.steer_torque, self.v_cruise, self.acc_status = 0, 0, 0 # v_cruise is reported from can, not the one used for controls + + self.lead_relevancy = lead_relevancy + + # lead car + self.distance_lead, self.distance_lead_prev = distance_lead , distance_lead + + self.rk = Ratekeeper(rate, print_delay_threshold=100) + self.ts = 1./rate + + self.cp = get_car_can_parser() + + def close(self): + Plant.logcan.close() + Plant.model.close() + + def speed_sensor(self, speed): + if speed<0.3: + return 0 + else: + return speed * CV.MS_TO_KPH + + def current_time(self): + return float(self.rk.frame) / self.rate + + def step(self, v_lead=0.0, cruise_buttons=None, grade=0.0, publish_model = True): + gen_signals, gen_checks = get_can_signals(CP) + sgs = [s[0] for s in gen_signals] + msgs = [s[1] for s in gen_signals] + cks_msgs = set(check[0] for check in gen_checks) + cks_msgs.add(0x18F) + cks_msgs.add(0x30C) + + # ******** get messages sent to the car ******** + can_msgs = [] + for a in messaging.drain_sock(Plant.sendcan): + can_msgs.extend(can_capnp_to_can_list(a.sendcan, [0,2])) + self.cp.update_can(can_msgs) + + # ******** get live100 messages for plotting *** + live100_msgs = [] + for a in messaging.drain_sock(Plant.live100): + live100_msgs.append(a.live100) + + fcw = None + for a in messaging.drain_sock(Plant.plan): + if a.plan.fcw: + fcw = True + + if self.cp.vl[0x1fa]['COMPUTER_BRAKE_REQUEST']: + brake = self.cp.vl[0x1fa]['COMPUTER_BRAKE'] * 0.003906248 + else: + brake = 0.0 + + if self.cp.vl[0x200]['GAS_COMMAND'] > 0: + gas = self.cp.vl[0x200]['GAS_COMMAND'] / 256.0 + else: + gas = 0.0 + + if self.cp.vl[0xe4]['STEER_TORQUE_REQUEST']: + steer_torque = self.cp.vl[0xe4]['STEER_TORQUE']*1.0/0xf00 + else: + steer_torque = 0.0 + + distance_lead = self.distance_lead_prev + v_lead * self.ts + + # ******** run the car ******** + speed, acceleration = car_plant(self.distance_prev, self.speed_prev, grade, gas, brake) + distance = self.distance_prev + speed * self.ts + speed = self.speed_prev + self.ts * acceleration + if speed <= 0: + speed = 0 + acceleration = 0 + + # ******** lateral ******** + self.angle_steer -= (steer_torque/10.0) * self.ts + + # *** radar model *** + if self.lead_relevancy: + d_rel = np.maximum(0., distance_lead - distance) + v_rel = v_lead - speed + else: + d_rel = 200. + v_rel = 0. + lateral_pos_rel = 0. + + # print at 5hz + if (self.rk.frame%(self.rate/5)) == 0: + print "%6.2f m %6.2f m/s %6.2f m/s2 %.2f ang gas: %.2f brake: %.2f steer: %5.2f lead_rel: %6.2f m %6.2f m/s" % (distance, speed, acceleration, self.angle_steer, gas, brake, steer_torque, d_rel, v_rel) + + # ******** publish the car ******** + vls_tuple = namedtuple('vls', [ + 'XMISSION_SPEED', + 'WHEEL_SPEED_FL', 'WHEEL_SPEED_FR', 'WHEEL_SPEED_RL', 'WHEEL_SPEED_RR', + 'STEER_ANGLE', 'STEER_ANGLE_RATE', 'STEER_TORQUE_SENSOR', + 'LEFT_BLINKER', 'RIGHT_BLINKER', + 'GEAR', + 'WHEELS_MOVING', + 'BRAKE_ERROR_1', 'BRAKE_ERROR_2', + 'SEATBELT_DRIVER_LAMP', 'SEATBELT_DRIVER_LATCHED', + 'BRAKE_PRESSED', 'BRAKE_SWITCH', + 'CRUISE_BUTTONS', + 'ESP_DISABLED', + 'HUD_LEAD', + 'USER_BRAKE', + 'STEER_STATUS', + 'GEAR_SHIFTER', + 'PEDAL_GAS', + 'CRUISE_SETTING', + 'ACC_STATUS', + + 'CRUISE_SPEED_PCM', + 'CRUISE_SPEED_OFFSET', + + 'DOOR_OPEN_FL', 'DOOR_OPEN_FR', 'DOOR_OPEN_RL', 'DOOR_OPEN_RR', + + 'CAR_GAS', + 'MAIN_ON', + 'EPB_STATE', + 'BRAKE_HOLD_ACTIVE', + 'INTERCEPTOR_GAS', + ]) + vls = vls_tuple( + self.speed_sensor(speed), + self.speed_sensor(speed), self.speed_sensor(speed), self.speed_sensor(speed), self.speed_sensor(speed), + self.angle_steer, self.angle_steer_rate, 0, #Steer torque sensor + 0, 0, # Blinkers + self.gear_choice, + speed != 0, + self.brake_error, self.brake_error, + not self.seatbelt, self.seatbelt, # Seatbelt + self.brake_pressed, 0., #Brake pressed, Brake switch + cruise_buttons, + self.esp_disabled, + 0, # HUD lead + self.user_brake, + self.steer_error, + self.gear_shifter, + self.pedal_gas, + self.cruise_setting, + self.acc_status, + + self.v_cruise, + 0, # Cruise speed offset + + 0, 0, 0, 0, # Doors + + self.user_gas, + self.main_on, + 0, # EPB State + 0, # Brake hold + 0 # Interceptor feedback + ) + + # TODO: publish each message at proper frequency + can_msgs = [] + for msg in set(msgs): + msg_struct = {} + indxs = [i for i, x in enumerate(msgs) if msg == msgs[i]] + for i in indxs: + msg_struct[sgs[i]] = getattr(vls, sgs[i]) + + if "COUNTER" in honda.get_signals(msg): + msg_struct["COUNTER"] = self.rk.frame % 4 + + msg = honda.lookup_msg_id(msg) + msg_data = honda.encode(msg, msg_struct) + + if "CHECKSUM" in honda.get_signals(msg): + msg_data = fix(msg_data, msg) + + can_msgs.append([msg, 0, msg_data, 0]) + + # add the radar message + # TODO: use the DBC + if self.rk.frame % 5 == 0: + radar_state_msg = '\x79\x00\x00\x00\x00\x00\x00\x00' + radar_msg = to_3_byte(d_rel*16.0) + \ + to_3_byte(int(lateral_pos_rel*16.0)&0x3ff) + \ + to_3s_byte(int(v_rel*32.0)) + \ + "0f00000" + can_msgs.append([0x400, 0, radar_state_msg, 1]) + can_msgs.append([0x445, 0, radar_msg.decode("hex"), 1]) + + # add camera msg so controlsd thinks it's alive + msg_struct["COUNTER"] = self.rk.frame % 4 + msg = honda.lookup_msg_id(0xe4) + msg_data = honda.encode(msg, msg_struct) + msg_data = fix(msg_data, 0xe4) + can_msgs.append([0xe4, 0, msg_data, 2]) + + Plant.logcan.send(can_list_to_can_capnp(can_msgs).to_bytes()) + + # ******** publish a fake model going straight and fake calibration ******** + # note that this is worst case for MPC, since model will delay long mpc by one time step + if publish_model and self.rk.frame % 5 == 0: + md = messaging.new_message() + cal = messaging.new_message() + md.init('model') + cal.init('liveCalibration') + md.model.frameId = 0 + for x in [md.model.path, md.model.leftLane, md.model.rightLane]: + x.points = [0.0]*50 + x.prob = 1.0 + x.std = 1.0 + md.model.lead.dist = float(d_rel) + md.model.lead.prob = 1. + md.model.lead.std = 0.1 + cal.liveCalibration.calStatus = 1 + cal.liveCalibration.calPerc = 100 + # fake values? + Plant.model.send(md.to_bytes()) + Plant.cal.send(cal.to_bytes()) + + # ******** update prevs ******** + self.speed = speed + self.distance = distance + self.distance_lead = distance_lead + + self.speed_prev = speed + self.distance_prev = distance + self.distance_lead_prev = distance_lead + + self.rk.keep_time() + return (distance, speed, acceleration, distance_lead, brake, gas, steer_torque, fcw, live100_msgs) + +# simple engage in standalone mode +def plant_thread(rate=100): + plant = Plant(rate) + while 1: + plant.step() + +if __name__ == "__main__": + plant_thread() diff --git a/selfdrive/test/plant/plant_ui.py b/selfdrive/test/plant/plant_ui.py new file mode 100755 index 00000000000000..d7b4bf1856fdc9 --- /dev/null +++ b/selfdrive/test/plant/plant_ui.py @@ -0,0 +1,120 @@ +#!/usr/bin/env python +import pygame +from plant import Plant +from selfdrive.car.honda.values import CruiseButtons +import numpy as np +import selfdrive.messaging as messaging +import math + +CAR_WIDTH = 2.0 +CAR_LENGTH = 4.5 + +METER = 8 + +def rot_center(image, angle): + """rotate an image while keeping its center and size""" + orig_rect = image.get_rect() + rot_image = pygame.transform.rotate(image, angle) + rot_rect = orig_rect.copy() + rot_rect.center = rot_image.get_rect().center + rot_image = rot_image.subsurface(rot_rect).copy() + return rot_image + +def car_w_color(c): + car = pygame.Surface((METER*CAR_LENGTH, METER*CAR_LENGTH)) # pylint: disable=too-many-function-args + car.set_alpha(0) + car.fill((10,10,10)) + car.set_alpha(128) + pygame.draw.rect(car, c, (METER*1.25, 0, METER*CAR_WIDTH, METER*CAR_LENGTH), 1) + return car + +if __name__ == "__main__": + pygame.init() + display = pygame.display.set_mode((1000, 1000)) + pygame.display.set_caption('Plant UI') + + car = car_w_color((255,0,255)) + leadcar = car_w_color((255,0,0)) + + carx, cary, heading = 10.0, 50.0, 0.0 + + plant = Plant(100, distance_lead = 40.0) + + control_offset = 2.0 + control_pts = zip(np.arange(0, 100.0, 10.0), [50.0 + control_offset]*10) + + def pt_to_car(pt): + x,y = pt + x -= carx + y -= cary + rx = x * math.cos(-heading) + y * -math.sin(-heading) + ry = x * math.sin(-heading) + y * math.cos(-heading) + return rx, ry + + def pt_from_car(pt): + x,y = pt + rx = x * math.cos(heading) + y * -math.sin(heading) + ry = x * math.sin(heading) + y * math.cos(heading) + rx += carx + ry += cary + return rx, ry + + while 1: + if plant.rk.frame%100 >= 20 and plant.rk.frame%100 <= 25: + cruise_buttons = CruiseButtons.RES_ACCEL + else: + cruise_buttons = 0 + + md = messaging.new_message() + md.init('model') + md.model.frameId = 0 + for x in [md.model.path, md.model.leftLane, md.model.rightLane]: + x.points = [0.0]*50 + x.prob = 0.0 + x.std = 1.0 + + car_pts = map(pt_to_car, control_pts) + + print car_pts + + car_poly = np.polyfit([x[0] for x in car_pts], [x[1] for x in car_pts], 3) + md.model.path.points = np.polyval(car_poly, np.arange(0, 50)).tolist() + md.model.path.prob = 1.0 + Plant.model.send(md.to_bytes()) + + plant.step(cruise_buttons = cruise_buttons, v_lead = 2.0, publish_model = False) + + display.fill((10,10,10)) + + carx += plant.speed * plant.ts * math.cos(heading) + cary += plant.speed * plant.ts * math.sin(heading) + + # positive steering angle = steering right + print plant.angle_steer + heading += plant.angle_steer * plant.ts + print heading + + # draw my car + display.blit(pygame.transform.rotate(car, 90-math.degrees(heading)), (carx*METER, cary*METER)) + + # draw control pts + for x,y in control_pts: + pygame.draw.circle(display, (255,255,0), (int(x * METER),int(y * METER)), 2) + + # draw path + path_pts = zip(np.arange(0, 50), md.model.path.points) + + for x,y in path_pts: + x,y = pt_from_car((x,y)) + pygame.draw.circle(display, (0,255,0), (int(x * METER),int(y * METER)), 1) + + """ + # draw lead car + dl = (plant.distance_lead - plant.distance) + 4.5 + lx = carx + dl * math.cos(heading) + ly = cary + dl * math.sin(heading) + + display.blit(pygame.transform.rotate(leadcar, 90-math.degrees(heading)), (lx*METER, ly*METER)) + """ + + pygame.display.flip() diff --git a/selfdrive/test/test_openpilot.py b/selfdrive/test/test_openpilot.py new file mode 100644 index 00000000000000..0a825e3a34cb1b --- /dev/null +++ b/selfdrive/test/test_openpilot.py @@ -0,0 +1,93 @@ +import os +os.environ['FAKEUPLOAD'] = "1" + +from common.testing import phone_only +from selfdrive.manager import manager_init, manager_prepare +from selfdrive.manager import start_managed_process, kill_managed_process, get_running +from functools import wraps +import time + +DID_INIT = False + +# must run first +@phone_only +def test_manager_prepare(): + global DID_INIT + manager_init() + manager_prepare() + DID_INIT = True + +def with_processes(processes): + def wrapper(func): + @wraps(func) + def wrap(): + if not DID_INIT: + test_manager_prepare() + + # start and assert started + [start_managed_process(p) for p in processes] + assert all(get_running()[name].exitcode is None for name in processes) + + # call the function + func() + + # assert processes are still started + assert all(get_running()[name].exitcode is None for name in processes) + + # kill and assert all stopped + [kill_managed_process(p) for p in processes] + assert len(get_running()) == 0 + return wrap + return wrapper + +#@phone_only +#@with_processes(['controlsd', 'radard']) +#def test_controls(): +# from selfdrive.test.plant.plant import Plant +# +# # start the fake car for 2 seconds +# plant = Plant(100) +# for i in range(200): +# if plant.rk.frame >= 20 and plant.rk.frame <= 25: +# cruise_buttons = CruiseButtons.RES_ACCEL +# # rolling forward +# assert plant.speed > 0 +# else: +# cruise_buttons = 0 +# plant.step(cruise_buttons = cruise_buttons) +# plant.close() +# +# # assert that we stopped +# assert plant.speed == 0.0 + +@phone_only +@with_processes(['loggerd', 'logmessaged', 'tombstoned', 'proclogd', 'logcatd']) +def test_logging(): + print "LOGGING IS SET UP" + time.sleep(1.0) + +@phone_only +@with_processes(['visiond']) +def test_visiond(): + print "VISIOND IS SET UP" + time.sleep(5.0) + +@phone_only +@with_processes(['sensord']) +def test_sensord(): + print "SENSORS ARE SET UP" + time.sleep(1.0) + +@phone_only +@with_processes(['ui']) +def test_ui(): + print "RUNNING UI" + time.sleep(1.0) + +# will have one thing to upload if loggerd ran +# TODO: assert it actually uploaded +@phone_only +@with_processes(['uploader']) +def test_uploader(): + print "UPLOADER" + time.sleep(10.0) diff --git a/selfdrive/test/tests/plant/__init__.py b/selfdrive/test/tests/plant/__init__.py new file mode 100644 index 00000000000000..e69de29bb2d1d6 diff --git a/selfdrive/test/tests/plant/test_longitudinal.py b/selfdrive/test/tests/plant/test_longitudinal.py new file mode 100755 index 00000000000000..e5affb62765d45 --- /dev/null +++ b/selfdrive/test/tests/plant/test_longitudinal.py @@ -0,0 +1,324 @@ +#!/usr/bin/env python +import os +os.environ['OLD_CAN'] = '1' +os.environ['NOCRASH'] = '1' + +import time +import unittest +import shutil +import matplotlib +matplotlib.use('svg') + +from selfdrive.config import Conversions as CV +from selfdrive.car.honda.values import CruiseButtons as CB +from selfdrive.test.plant.maneuver import Maneuver +import selfdrive.manager as manager +from common.params import Params + + +def create_dir(path): + try: + os.makedirs(path) + except OSError: + pass + +maneuvers = [ + Maneuver( + 'while cruising at 40 mph, change cruise speed to 50mph', + duration=30., + initial_speed = 40. * CV.MPH_TO_MS, + cruise_button_presses = [(CB.DECEL_SET, 2.), (0, 2.3), + (CB.RES_ACCEL, 10.), (0, 10.1), + (CB.RES_ACCEL, 10.2), (0, 10.3)] + ), + Maneuver( + 'while cruising at 60 mph, change cruise speed to 50mph', + duration=30., + initial_speed=60. * CV.MPH_TO_MS, + cruise_button_presses = [(CB.DECEL_SET, 2.), (0, 2.3), + (CB.DECEL_SET, 10.), (0, 10.1), + (CB.DECEL_SET, 10.2), (0, 10.3)] + ), + Maneuver( + 'while cruising at 20mph, grade change +10%', + duration=25., + initial_speed=20. * CV.MPH_TO_MS, + cruise_button_presses = [(CB.DECEL_SET, 1.2), (0, 1.3)], + grade_values = [0., 0., 1.0], + grade_breakpoints = [0., 10., 11.] + ), + Maneuver( + 'while cruising at 20mph, grade change -10%', + duration=25., + initial_speed=20. * CV.MPH_TO_MS, + cruise_button_presses = [(CB.DECEL_SET, 1.2), (0, 1.3)], + grade_values = [0., 0., -1.0], + grade_breakpoints = [0., 10., 11.] + ), + Maneuver( + 'approaching a 40mph car while cruising at 60mph from 100m away', + duration=30., + initial_speed = 60. * CV.MPH_TO_MS, + lead_relevancy=True, + initial_distance_lead=100., + speed_lead_values = [40.*CV.MPH_TO_MS, 40.*CV.MPH_TO_MS], + speed_lead_breakpoints = [0., 100.], + cruise_button_presses = [(CB.DECEL_SET, 1.2), (0, 1.3)] + ), + Maneuver( + 'approaching a 0mph car while cruising at 40mph from 150m away', + duration=30., + initial_speed = 40. * CV.MPH_TO_MS, + lead_relevancy=True, + initial_distance_lead=150., + speed_lead_values = [0.*CV.MPH_TO_MS, 0.*CV.MPH_TO_MS], + speed_lead_breakpoints = [0., 100.], + cruise_button_presses = [(CB.DECEL_SET, 1.2), (0, 1.3)] + ), + Maneuver( + 'steady state following a car at 20m/s, then lead decel to 0mph at 1m/s^2', + duration=50., + initial_speed = 20., + lead_relevancy=True, + initial_distance_lead=35., + speed_lead_values = [20., 20., 0.], + speed_lead_breakpoints = [0., 15., 35.0], + cruise_button_presses = [(CB.DECEL_SET, 1.2), (0, 1.3)] + ), + Maneuver( + 'steady state following a car at 20m/s, then lead decel to 0mph at 2m/s^2', + duration=50., + initial_speed = 20., + lead_relevancy=True, + initial_distance_lead=35., + speed_lead_values = [20., 20., 0.], + speed_lead_breakpoints = [0., 15., 25.0], + cruise_button_presses = [(CB.DECEL_SET, 1.2), (0, 1.3)] + ), + Maneuver( + 'steady state following a car at 20m/s, then lead decel to 0mph at 3m/s^2', + duration=50., + initial_speed = 20., + lead_relevancy=True, + initial_distance_lead=35., + speed_lead_values = [20., 20., 0.], + speed_lead_breakpoints = [0., 15., 21.66], + cruise_button_presses = [(CB.DECEL_SET, 1.2), (0, 1.3)] + ), + Maneuver( + 'starting at 0mph, approaching a stopped car 100m away', + duration=30., + initial_speed = 0., + lead_relevancy=True, + initial_distance_lead=100., + cruise_button_presses = [(CB.DECEL_SET, 1.2), (0, 1.3), + (CB.RES_ACCEL, 1.4), (0.0, 1.5), + (CB.RES_ACCEL, 1.6), (0.0, 1.7), + (CB.RES_ACCEL, 1.8), (0.0, 1.9)] + ), + Maneuver( + "following a car at 60mph, lead accel and decel at 0.5m/s^2 every 2s", + duration=25., + initial_speed=30., + lead_relevancy=True, + initial_distance_lead=49., + speed_lead_values=[30.,30.,29.,31.,29.,31.,29.], + speed_lead_breakpoints=[0., 6., 8., 12.,16.,20.,24.], + cruise_button_presses = [(CB.DECEL_SET, 1.2), (0, 1.3), + (CB.RES_ACCEL, 1.4), (0.0, 1.5), + (CB.RES_ACCEL, 1.6), (0.0, 1.7)] + ), + Maneuver( + "following a car at 10mph, stop and go at 1m/s2 lead dece1 and accel", + duration=70., + initial_speed=10., + lead_relevancy=True, + initial_distance_lead=20., + speed_lead_values=[10., 0., 0., 10., 0.,10.], + speed_lead_breakpoints=[10., 20., 30., 40., 50., 60.], + cruise_button_presses = [(CB.DECEL_SET, 1.2), (0, 1.3), + (CB.RES_ACCEL, 1.4), (0.0, 1.5), + (CB.RES_ACCEL, 1.6), (0.0, 1.7)] + ), + Maneuver( + "green light: stopped behind lead car, lead car accelerates at 1.5 m/s", + duration=30., + initial_speed=0., + lead_relevancy=True, + initial_distance_lead=4., + speed_lead_values=[0, 0 , 45], + speed_lead_breakpoints=[0, 10., 40.], + cruise_button_presses = [(CB.DECEL_SET, 1.2), (0, 1.3), + (CB.RES_ACCEL, 1.4), (0.0, 1.5), + (CB.RES_ACCEL, 1.6), (0.0, 1.7), + (CB.RES_ACCEL, 1.8), (0.0, 1.9), + (CB.RES_ACCEL, 2.0), (0.0, 2.1), + (CB.RES_ACCEL, 2.2), (0.0, 2.3)] + ), + Maneuver( + "stop and go with 1m/s2 lead decel and accel, with full stops", + duration=70., + initial_speed=0., + lead_relevancy=True, + initial_distance_lead=20., + speed_lead_values=[10., 0., 0., 10., 0., 0.] , + speed_lead_breakpoints=[10., 20., 30., 40., 50., 60.], + cruise_button_presses = [(CB.DECEL_SET, 1.2), (0, 1.3), + (CB.RES_ACCEL, 1.4), (0.0, 1.5), + (CB.RES_ACCEL, 1.6), (0.0, 1.7)] + ), + Maneuver( + "stop and go with 1.5m/s2 lead accel and 3.3m/s^2 lead decel, with full stops", + duration=45., + initial_speed=0., + lead_relevancy=True, + initial_distance_lead=20., + speed_lead_values=[10., 0., 0., 10., 0., 0.] , + speed_lead_breakpoints=[10., 13., 26., 33., 36., 45.], + cruise_button_presses = [(CB.DECEL_SET, 1.2), (0, 1.3), + (CB.RES_ACCEL, 1.4), (0.0, 1.5), + (CB.RES_ACCEL, 1.6), (0.0, 1.7)] + ), + Maneuver( + "accelerate from 20 while lead vehicle decelerates from 40 to 20 at 1m/s2", + duration=30., + initial_speed=10., + lead_relevancy=True, + initial_distance_lead=10., + speed_lead_values=[20., 10.], + speed_lead_breakpoints=[1., 11.], + cruise_button_presses = [(CB.DECEL_SET, 1.2), (0, 1.3), + (CB.RES_ACCEL, 1.4), (0.0, 1.5), + (CB.RES_ACCEL, 1.6), (0.0, 1.7), + (CB.RES_ACCEL, 1.8), (0.0, 1.9), + (CB.RES_ACCEL, 2.0), (0.0, 2.1), + (CB.RES_ACCEL, 2.2), (0.0, 2.3)] + ), + Maneuver( + "accelerate from 20 while lead vehicle decelerates from 40 to 0 at 2m/s2", + duration=30., + initial_speed=10., + lead_relevancy=True, + initial_distance_lead=10., + speed_lead_values=[20., 0.], + speed_lead_breakpoints=[1., 11.], + cruise_button_presses = [(CB.DECEL_SET, 1.2), (0, 1.3), + (CB.RES_ACCEL, 1.4), (0.0, 1.5), + (CB.RES_ACCEL, 1.6), (0.0, 1.7), + (CB.RES_ACCEL, 1.8), (0.0, 1.9), + (CB.RES_ACCEL, 2.0), (0.0, 2.1), + (CB.RES_ACCEL, 2.2), (0.0, 2.3)] + ), + Maneuver( + "fcw: traveling at 30 m/s and approaching lead traveling at 20m/s", + duration=15., + initial_speed=30., + lead_relevancy=True, + initial_distance_lead=100., + speed_lead_values=[20.], + speed_lead_breakpoints=[1.], + cruise_button_presses = [] + ), + Maneuver( + "fcw: traveling at 20 m/s following a lead that decels from 20m/s to 0 at 1m/s2", + duration=18., + initial_speed=20., + lead_relevancy=True, + initial_distance_lead=35., + speed_lead_values=[20., 0.], + speed_lead_breakpoints=[3., 23.], + cruise_button_presses = [] + ), + Maneuver( + "fcw: traveling at 20 m/s following a lead that decels from 20m/s to 0 at 3m/s2", + duration=13., + initial_speed=20., + lead_relevancy=True, + initial_distance_lead=35., + speed_lead_values=[20., 0.], + speed_lead_breakpoints=[3., 9.6], + cruise_button_presses = [] + ), + Maneuver( + "fcw: traveling at 20 m/s following a lead that decels from 20m/s to 0 at 5m/s2", + duration=8., + initial_speed=20., + lead_relevancy=True, + initial_distance_lead=35., + speed_lead_values=[20., 0.], + speed_lead_breakpoints=[3., 7.], + cruise_button_presses = [] + ) +] + +#maneuvers = [maneuvers[-1]] + +def setup_output(): + output_dir = os.path.join(os.getcwd(), 'out/longitudinal') + if not os.path.exists(os.path.join(output_dir, "index.html")): + # write test output header + + css_style = """ + .maneuver_title { + font-size: 24px; + text-align: center; + } + .maneuver_graph { + width: 100%; + } + """ + + view_html = "" % (css_style,) + for i, man in enumerate(maneuvers): + view_html += "" % (man.title,) + for c in ['distance.svg', 'speeds.svg', 'acceleration.svg', 'pedals.svg', 'pid.svg']: + view_html += "" % (os.path.join("maneuver" + str(i+1).zfill(2), c), ) + view_html += "" + + create_dir(output_dir) + with open(os.path.join(output_dir, "index.html"), "w") as f: + f.write(view_html) + +class LongitudinalControl(unittest.TestCase): + @classmethod + def setUpClass(cls): + + setup_output() + + shutil.rmtree('/data/params', ignore_errors=True) + params = Params() + params.put("Passive", "1" if os.getenv("PASSIVE") else "0") + params.put("IsFcwEnabled", "1") + + manager.gctx = {} + manager.prepare_managed_process('radard') + manager.prepare_managed_process('controlsd') + + manager.start_managed_process('radard') + manager.start_managed_process('controlsd') + + @classmethod + def tearDownClass(cls): + manager.kill_managed_process('radard') + manager.kill_managed_process('controlsd') + time.sleep(5) + + # hack + def test_longitudinal_setup(self): + pass + +WORKERS = 8 +def run_maneuver_worker(k): + output_dir = os.path.join(os.getcwd(), 'out/longitudinal') + for i, man in enumerate(maneuvers[k::WORKERS]): + score, plot = man.evaluate() + plot.write_plot(output_dir, "maneuver" + str(WORKERS * i + k+1).zfill(2)) + +for k in xrange(WORKERS): + setattr(LongitudinalControl, + "test_longitudinal_maneuvers_%d" % (k+1), + lambda self, k=k: run_maneuver_worker(k)) + +if __name__ == "__main__": + unittest.main() + diff --git a/selfdrive/thermald.py b/selfdrive/thermald.py new file mode 100755 index 00000000000000..3bb6da9331b15a --- /dev/null +++ b/selfdrive/thermald.py @@ -0,0 +1,334 @@ +#!/usr/bin/env python2.7 +import os +import zmq +from smbus2 import SMBus +from cereal import log +from selfdrive.version import training_version +from selfdrive.swaglog import cloudlog +import selfdrive.messaging as messaging +from selfdrive.services import service_list +from selfdrive.loggerd.config import ROOT +from common.params import Params +from common.realtime import sec_since_boot +from common.numpy_fast import clip +from common.filter_simple import FirstOrderFilter +from selfdrive.kegman_conf import kegman_conf + +ThermalStatus = log.ThermalData.ThermalStatus +CURRENT_TAU = 2. # 2s time constant + +def read_tz(x): + with open("/sys/devices/virtual/thermal/thermal_zone%d/temp" % x) as f: + ret = max(0, int(f.read())) + return ret + +def read_thermal(): + dat = messaging.new_message() + dat.init('thermal') + dat.thermal.cpu0 = read_tz(5) + dat.thermal.cpu1 = read_tz(7) + dat.thermal.cpu2 = read_tz(10) + dat.thermal.cpu3 = read_tz(12) + dat.thermal.mem = read_tz(2) + dat.thermal.gpu = read_tz(16) + dat.thermal.bat = read_tz(29) + return dat + +LEON = False +def setup_eon_fan(): + global LEON + + os.system("echo 2 > /sys/module/dwc3_msm/parameters/otg_switch") + + bus = SMBus(7, force=True) + try: + bus.write_byte_data(0x21, 0x10, 0xf) # mask all interrupts + bus.write_byte_data(0x21, 0x03, 0x1) # set drive current and global interrupt disable + bus.write_byte_data(0x21, 0x02, 0x2) # needed? + bus.write_byte_data(0x21, 0x04, 0x4) # manual override source + except IOError: + print "LEON detected" + #os.system("echo 1 > /sys/devices/soc/6a00000.ssusb/power_supply/usb/usb_otg") + LEON = True + bus.close() + +last_eon_fan_val = None +def set_eon_fan(val): + global LEON, last_eon_fan_val + + if last_eon_fan_val is None or last_eon_fan_val != val: + bus = SMBus(7, force=True) + if LEON: + try: + i = [0x1, 0x3 | 0, 0x3 | 0x08, 0x3 | 0x10][val] + bus.write_i2c_block_data(0x3d, 0, [i]) + except IOError: + # tusb320 + if val == 0: + bus.write_i2c_block_data(0x67, 0xa, [0]) + else: + bus.write_i2c_block_data(0x67, 0xa, [0x20]) + bus.write_i2c_block_data(0x67, 0x8, [(val-1)<<6]) + else: + bus.write_byte_data(0x21, 0x04, 0x2) + bus.write_byte_data(0x21, 0x03, (val*2)+1) + bus.write_byte_data(0x21, 0x04, 0x4) + bus.close() + last_eon_fan_val = val + +# temp thresholds to control fan speed - high hysteresis +_TEMP_THRS_H = [50., 65., 80., 10000] +# temp thresholds to control fan speed - low hysteresis +_TEMP_THRS_L = [42.5, 57.5, 72.5, 10000] +# fan speed options +_FAN_SPEEDS = [0, 16384, 32768, 65535] +# max fan speed only allowed if battery is hot +_BAT_TEMP_THERSHOLD = 45. + + +def handle_fan(max_cpu_temp, bat_temp, fan_speed): + new_speed_h = next(speed for speed, temp_h in zip(_FAN_SPEEDS, _TEMP_THRS_H) if temp_h > max_cpu_temp) + new_speed_l = next(speed for speed, temp_l in zip(_FAN_SPEEDS, _TEMP_THRS_L) if temp_l > max_cpu_temp) + + if new_speed_h > fan_speed: + # update speed if using the high thresholds results in fan speed increment + fan_speed = new_speed_h + elif new_speed_l < fan_speed: + # update speed if using the low thresholds results in fan speed decrement + fan_speed = new_speed_l + + if bat_temp < _BAT_TEMP_THERSHOLD: + # no max fan speed unless battery is hot + fan_speed = min(fan_speed, _FAN_SPEEDS[-2]) + + set_eon_fan(fan_speed/16384) + + return fan_speed + + +def check_car_battery_voltage(should_start, health, charging_disabled, msg): + + # charging disallowed if: + # - there are health packets from panda, and; + # - 12V battery voltage is too low, and; + # - onroad isn't started + # - keep battery within 67-70% State of Charge to preserve longevity + k = kegman_conf() + print k + + if charging_disabled and (health is None or health.health.voltage > 11800) and msg.thermal.batteryPercent < int(k.conf['battChargeMin']): + charging_disabled = False + os.system('echo "1" > /sys/class/power_supply/battery/charging_enabled') + elif not charging_disabled and (msg.thermal.batteryPercent > int(k.conf['battChargeMax']) or (health is not None and health.health.voltage < 11500 and not should_start)): + charging_disabled = True + os.system('echo "0" > /sys/class/power_supply/battery/charging_enabled') + elif msg.thermal.batteryCurrent < 0 and msg.thermal.batteryPercent > int(k.conf['battChargeMax']): + charging_disabled = True + os.system('echo "0" > /sys/class/power_supply/battery/charging_enabled') + + return charging_disabled + + +class LocationStarter(object): + def __init__(self): + self.last_good_loc = 0 + def update(self, started_ts, location): + rt = sec_since_boot() + + if location is None or location.accuracy > 50 or location.speed < 2: + # bad location, stop if we havent gotten a location in a while + # dont stop if we're been going for less than a minute + if started_ts: + if rt-self.last_good_loc > 60. and rt-started_ts > 60: + cloudlog.event("location_stop", + ts=rt, + started_ts=started_ts, + last_good_loc=self.last_good_loc, + location=location.to_dict() if location else None) + return False + else: + return True + else: + return False + + self.last_good_loc = rt + + if started_ts: + return True + else: + cloudlog.event("location_start", location=location.to_dict() if location else None) + return location.speed*3.6 > 10 + + +def thermald_thread(): + setup_eon_fan() + + # prevent LEECO from undervoltage + BATT_PERC_OFF = 10 if LEON else 3 + + # now loop + context = zmq.Context() + thermal_sock = messaging.pub_sock(context, service_list['thermal'].port) + health_sock = messaging.sub_sock(context, service_list['health'].port) + location_sock = messaging.sub_sock(context, service_list['gpsLocation'].port) + fan_speed = 0 + count = 0 + + off_ts = None + started_ts = None + ignition_seen = False + started_seen = False + passive_starter = LocationStarter() + thermal_status = ThermalStatus.green + health_sock.RCVTIMEO = 1500 + current_filter = FirstOrderFilter(0., CURRENT_TAU, 1.) + + # Make sure charging is enabled + charging_disabled = False + os.system('echo "1" > /sys/class/power_supply/battery/charging_enabled') + + params = Params() + + while 1: + health = messaging.recv_sock(health_sock, wait=True) + location = messaging.recv_sock(location_sock) + location = location.gpsLocation if location else None + msg = read_thermal() + + # loggerd is gated based on free space + statvfs = os.statvfs(ROOT) + avail = (statvfs.f_bavail * 1.0)/statvfs.f_blocks + + # thermal message now also includes free space + msg.thermal.freeSpace = avail + with open("/sys/class/power_supply/battery/capacity") as f: + msg.thermal.batteryPercent = int(f.read()) + with open("/sys/class/power_supply/battery/status") as f: + msg.thermal.batteryStatus = f.read().strip() + with open("/sys/class/power_supply/battery/current_now") as f: + msg.thermal.batteryCurrent = int(f.read()) + with open("/sys/class/power_supply/battery/voltage_now") as f: + msg.thermal.batteryVoltage = int(f.read()) + with open("/sys/class/power_supply/usb/present") as f: + msg.thermal.usbOnline = bool(int(f.read())) + + current_filter.update(msg.thermal.batteryCurrent / 1e6) + + # TODO: add car battery voltage check + max_cpu_temp = max(msg.thermal.cpu0, msg.thermal.cpu1, + msg.thermal.cpu2, msg.thermal.cpu3) / 10.0 + max_comp_temp = max(max_cpu_temp, msg.thermal.mem / 10., msg.thermal.gpu / 10.) + bat_temp = msg.thermal.bat/1000. + fan_speed = handle_fan(max_cpu_temp, bat_temp, fan_speed) + msg.thermal.fanSpeed = fan_speed + + # thermal logic with hysterisis + if max_cpu_temp > 107. or bat_temp >= 63.: + # onroad not allowed + thermal_status = ThermalStatus.danger + elif max_comp_temp > 95. or bat_temp > 60.: + # hysteresis between onroad not allowed and engage not allowed + thermal_status = clip(thermal_status, ThermalStatus.red, ThermalStatus.danger) + elif max_cpu_temp > 90.0: + # hysteresis between engage not allowed and uploader not allowed + thermal_status = clip(thermal_status, ThermalStatus.yellow, ThermalStatus.red) + elif max_cpu_temp > 85.0: + # uploader not allowed + thermal_status = ThermalStatus.yellow + elif max_cpu_temp > 75.0: + # hysteresis between uploader not allowed and all good + thermal_status = clip(thermal_status, ThermalStatus.green, ThermalStatus.yellow) + else: + # all good + thermal_status = ThermalStatus.green + + # **** starting logic **** + + # start constellation of processes when the car starts + ignition = health is not None and health.health.started + ignition_seen = ignition_seen or ignition + + # add voltage check for ignition + if not ignition_seen and health is not None and health.health.voltage > 13500: + ignition = True + + do_uninstall = params.get("DoUninstall") == "1" + accepted_terms = params.get("HasAcceptedTerms") == "1" + completed_training = params.get("CompletedTrainingVersion") == training_version + + should_start = ignition + + # have we seen a panda? + passive = (params.get("Passive") == "1") + + # start on gps movement if we haven't seen ignition and are in passive mode + should_start = should_start or (not (ignition_seen and health) # seen ignition and panda is connected + and passive + and passive_starter.update(started_ts, location)) + + # with 2% left, we killall, otherwise the phone will take a long time to boot + should_start = should_start and msg.thermal.freeSpace > 0.02 + + # require usb power in passive mode + should_start = should_start and (not passive or msg.thermal.usbOnline) + + # confirm we have completed training and aren't uninstalling + should_start = should_start and accepted_terms and (passive or completed_training) and (not do_uninstall) + + # if any CPU gets above 107 or the battery gets above 63, kill all processes + # controls will warn with CPU above 95 or battery above 60 + if thermal_status >= ThermalStatus.danger: + # TODO: Add a better warning when this is happening + should_start = False + + if should_start: + off_ts = None + if started_ts is None: + params.car_start() + started_ts = sec_since_boot() + started_seen = True + else: + started_ts = None + if off_ts is None: + off_ts = sec_since_boot() + + # shutdown if the battery gets lower than 3%, it's discharging, we aren't running for + # more than a minute but we were running + if msg.thermal.batteryPercent < BATT_PERC_OFF and msg.thermal.batteryStatus == "Discharging" and \ + started_seen and (sec_since_boot() - off_ts) > 60: + os.system('LD_LIBRARY_PATH="" svc power shutdown') + + charging_disabled = check_car_battery_voltage(should_start, health, charging_disabled, msg) + + # need to force batteryStatus because after NEOS update for 0.5.7 this doesn't work properly + if msg.thermal.batteryCurrent > 0: + msg.thermal.batteryStatus = "Discharging" + else: + msg.thermal.batteryStatus = "Charging" + + msg.thermal.chargingDisabled = charging_disabled + msg.thermal.chargingError = current_filter.x > 1.0 # if current is > 1A out, then charger might be off + msg.thermal.started = started_ts is not None + msg.thermal.startedTs = int(1e9*(started_ts or 0)) + + msg.thermal.thermalStatus = thermal_status + thermal_sock.send(msg.to_bytes()) + print msg + + # report to server once per minute + if (count%60) == 0: + cloudlog.event("STATUS_PACKET", + count=count, + health=(health.to_dict() if health else None), + location=(location.to_dict() if location else None), + thermal=msg.to_dict()) + + count += 1 + + +def main(gctx=None): + thermald_thread() + +if __name__ == "__main__": + main() + diff --git a/selfdrive/tombstoned.py b/selfdrive/tombstoned.py new file mode 100644 index 00000000000000..bac43a0a19772a --- /dev/null +++ b/selfdrive/tombstoned.py @@ -0,0 +1,85 @@ +import os +import re +import time +import uuid +import datetime + +from raven import Client +from raven.transport.http import HTTPTransport + +from selfdrive.version import version, dirty +from selfdrive.swaglog import cloudlog + +def get_tombstones(): + return [("/data/tombstones/"+fn, int(os.stat("/data/tombstones/"+fn).st_ctime) ) + for fn in os.listdir("/data/tombstones") if fn.startswith("tombstone")] + +def report_tombstone(fn, client): + mtime = os.path.getmtime(fn) + with open(fn, "r") as f: + dat = f.read() + + # see system/core/debuggerd/tombstone.cpp + parsed = re.match(r"[* ]*\n" + r"(?P
    CM Version:[\s\S]*?ABI:.*\n)" + r"(?Ppid:.*\n)" + r"(?Psignal.*\n)?" + r"(?PAbort.*\n)?" + r"(?P\s+x0[\s\S]*?\n)\n" + r"(?:backtrace:\n" + r"(?P[\s\S]*?\n)\n" + r"stack:\n" + r"(?P[\s\S]*?\n)\n" + r")?", dat) + + logtail = re.search(r"--------- tail end of.*\n([\s\S]*?\n)---", dat) + logtail = logtail and logtail.group(1) + + if parsed: + parsedict = parsed.groupdict() + message = parsedict.get('thread') or '' + message += parsedict.get('signal') or '' + message += parsedict.get('abort') or '' + else: + parsedict = {} + message = fn+"\n"+dat[:1024] + + client.send( + event_id=uuid.uuid4().hex, + timestamp=datetime.datetime.utcfromtimestamp(mtime), + logger='tombstoned', + platform='other', + sdk={'name': 'tombstoned', 'version': '0'}, + extra={ + 'tombstone_fn': fn, + 'header': parsedict.get('header'), + 'registers': parsedict.get('registers'), + 'backtrace': parsedict.get('backtrace'), + 'logtail': logtail, + 'version': version, + 'dirty': not bool(os.environ.get('CLEAN')), + }, + user={'id': os.environ.get('DONGLE_ID')}, + message=message, + ) + cloudlog.error({"tombstone": message}) + + +def main(gctx): + initial_tombstones = set(get_tombstones()) + + client = Client('https://d3b175702f62402c91ade04d1c547e68:b20d68c813c74f63a7cdf9c4039d8f56@sentry.io/157615', + install_sys_hook=False, transport=HTTPTransport, release=version, tags={'dirty': dirty}) + + while True: + now_tombstones = set(get_tombstones()) + + for fn, ctime in (now_tombstones - initial_tombstones): + cloudlog.info("reporting new tombstone %s", fn) + report_tombstone(fn, client) + + initial_tombstones = now_tombstones + time.sleep(5) + +if __name__ == "__main__": + main(None) diff --git a/selfdrive/ui/.gitignore b/selfdrive/ui/.gitignore new file mode 100644 index 00000000000000..2c850c209048d5 --- /dev/null +++ b/selfdrive/ui/.gitignore @@ -0,0 +1 @@ +ui diff --git a/selfdrive/ui/Makefile b/selfdrive/ui/Makefile new file mode 100644 index 00000000000000..a78a48cf2a9193 --- /dev/null +++ b/selfdrive/ui/Makefile @@ -0,0 +1,109 @@ +CC = clang +CXX = clang++ + + +PHONELIBS = ../../phonelibs + +WARN_FLAGS = -Werror=implicit-function-declaration \ + -Werror=incompatible-pointer-types \ + -Werror=int-conversion \ + -Werror=return-type \ + -Werror=format-extra-args + +CFLAGS = -std=gnu11 -g -fPIC -O2 $(WARN_FLAGS) +CXXFLAGS = -std=c++11 -g -fPIC -O2 $(WARN_FLAGS) + +ZMQ_FLAGS = -I$(PHONELIBS)/zmq/aarch64/include +ZMQ_LIBS = -L$(PHONELIBS)/zmq/aarch64/lib \ + -l:libczmq.a -l:libzmq.a \ + -lgnustl_shared + +CEREAL_CFLAGS = -I$(PHONELIBS)/capnp-c/include +CEREAL_LIBS = -L$(PHONELIBS)/capnp-c/aarch64/lib -l:libcapn.a +CEREAL_OBJS = ../../cereal/gen/c/log.capnp.o + +NANOVG_FLAGS = -I$(PHONELIBS)/nanovg +JSON_FLAGS = -I$(PHONELIBS)/json/src + +OPENCL_FLAGS = -I$(PHONELIBS)/opencl/include +OPENCL_LIBS = -lgsl -lCB -lOpenCL + +OPENGL_LIBS = -lGLESv3 + +OPENSL_LIBS = -lOpenSLES + +FRAMEBUFFER_LIBS = -lutils -lgui -lEGL + +CFLAGS += -DQCOM +CXXFLAGS += -DQCOM + +OBJS = slplay.o \ + ui.o \ + ../common/glutil.o \ + ../common/visionipc.o \ + ../common/ipc.o \ + ../common/visionimg.o \ + ../common/visionbuf_ion.o \ + ../common/framebuffer.o \ + ../common/params.o \ + ../common/util.o \ + ../common/touch.o \ + ../common/swaglog.o \ + $(PHONELIBS)/nanovg/nanovg.o \ + $(PHONELIBS)/json/src/json.o \ + $(CEREAL_OBJS) + +DEPS := $(OBJS:.o=.d) + +all: ui + +ui: $(OBJS) + @echo "[ LINK ] $@" + $(CXX) -fPIC -o '$@' $^ \ + $(FRAMEBUFFER_LIBS) \ + $(CEREAL_LIBS) \ + $(ZMQ_LIBS) \ + -L/system/vendor/lib64 \ + -lhardware -lui \ + $(OPENGL_LIBS) \ + $(OPENCL_LIBS) \ + ${OPENSL_LIBS} \ + -Wl,-rpath=/system/lib64,-rpath=/system/comma/usr/lib \ + -lcutils -lm -llog -lui -ladreno_utils + +slplay.o: slplay.c + @echo "[ CC ] $@" + $(CC) $(CFLAGS) -fPIC \ + -I../ \ + $(OPENSL_LIBS) \ + -c -o '$@' $^ + +%.o: %.cc + @echo "[ CXX ] $@" + $(CXX) $(CXXFLAGS) -MMD \ + -Iinclude -I.. -I../.. \ + $(OPENCL_FLAGS) \ + -I$(PHONELIBS)/android_frameworks_native/include \ + -I$(PHONELIBS)/android_system_core/include \ + -I$(PHONELIBS)/android_hardware_libhardware/include \ + -I$(PHONELIBS)/libgralloc/include \ + -I$(PHONELIBS)/linux/include \ + -c -o '$@' '$<' + +%.o: %.c + @echo "[ CC ] $@" + $(CC) $(CFLAGS) -MMD \ + -Iinclude -I.. -I../.. \ + $(NANOVG_FLAGS) \ + $(ZMQ_FLAGS) \ + $(CEREAL_CFLAGS) \ + $(JSON_FLAGS) \ + $(OPENCL_FLAGS) \ + -I$(PHONELIBS)/linux/include \ + -c -o '$@' '$<' + +.PHONY: clean +clean: + rm -f ui $(OBJS) $(DEPS) + +-include $(DEPS) diff --git a/selfdrive/ui/slplay.c b/selfdrive/ui/slplay.c new file mode 100644 index 00000000000000..6e5d8b95389140 --- /dev/null +++ b/selfdrive/ui/slplay.c @@ -0,0 +1,184 @@ +#include +#include +#include +#include +#include + +#include "common/timing.h" +#include "slplay.h" + +SLEngineItf engineInterface = NULL; +SLObjectItf outputMix = NULL; +SLObjectItf engine = NULL; +uri_player players[32] = {{NULL, NULL, NULL}}; + +uint64_t loop_start = 0; +uint64_t loop_start_ctx = 0; + +uri_player* get_player_by_uri(const char* uri) { + for (uri_player *s = players; s->uri != NULL; s++) { + if (strcmp(s->uri, uri) == 0) { + return s; + } + } + + return NULL; +} + +uri_player* slplay_create_player_for_uri(const char* uri, char **error) { + uri_player player = { uri, NULL, NULL }; + + SLresult result; + SLDataLocator_URI locUri = {SL_DATALOCATOR_URI, (SLchar *) uri}; + SLDataFormat_MIME formatMime = {SL_DATAFORMAT_MIME, NULL, SL_CONTAINERTYPE_UNSPECIFIED}; + SLDataSource audioSrc = {&locUri, &formatMime}; + + SLDataLocator_OutputMix outMix = {SL_DATALOCATOR_OUTPUTMIX, outputMix}; + SLDataSink audioSnk = {&outMix, NULL}; + + result = (*engineInterface)->CreateAudioPlayer(engineInterface, &player.player, &audioSrc, &audioSnk, 0, NULL, NULL); + if (result != SL_RESULT_SUCCESS) { + *error = strdup("Failed to create audio player"); + return NULL; + } + + result = (*(player.player))->Realize(player.player, SL_BOOLEAN_FALSE); + if (result != SL_RESULT_SUCCESS) { + *error = strdup("Failed to realize audio player"); + return NULL; + } + + result = (*(player.player))->GetInterface(player.player, SL_IID_PLAY, &(player.playInterface)); + if (result != SL_RESULT_SUCCESS) { + *error = strdup("Failed to get player interface"); + return NULL; + } + + result = (*(player.playInterface))->SetPlayState(player.playInterface, SL_PLAYSTATE_PAUSED); + if (result != SL_RESULT_SUCCESS) { + *error = strdup("Failed to initialize playstate to SL_PLAYSTATE_PAUSED"); + return NULL; + } + + uri_player *p = players; + while (p->uri != NULL) { + p++; + } + *p = player; + + return p; +} + +void slplay_setup(char **error) { + SLresult result; + SLEngineOption engineOptions[] = {{SL_ENGINEOPTION_THREADSAFE, SL_BOOLEAN_TRUE}}; + result = slCreateEngine(&engine, 1, engineOptions, 0, NULL, NULL); + if (result != SL_RESULT_SUCCESS) { + *error = strdup("Failed to create OpenSL engine"); + } + + result = (*engine)->Realize(engine, SL_BOOLEAN_FALSE); + if (result != SL_RESULT_SUCCESS) { + *error = strdup("Failed to realize OpenSL engine"); + } + + result = (*engine)->GetInterface(engine, SL_IID_ENGINE, &engineInterface); + if (result != SL_RESULT_SUCCESS) { + *error = strdup("Failed to realize OpenSL engine"); + } + + const SLInterfaceID ids[1] = {SL_IID_VOLUME}; + const SLboolean req[1] = {SL_BOOLEAN_FALSE}; + result = (*engineInterface)->CreateOutputMix(engineInterface, &outputMix, 1, ids, req); + if (result != SL_RESULT_SUCCESS) { + *error = strdup("Failed to create output mix"); + } + + result = (*outputMix)->Realize(outputMix, SL_BOOLEAN_FALSE); + if (result != SL_RESULT_SUCCESS) { + *error = strdup("Failed to realize output mix"); + } +} + +void slplay_destroy() { + for (uri_player *player = players; player->uri != NULL; player++) { + if (player->player) { + (*(player->player))->Destroy(player->player); + } + } + + (*outputMix)->Destroy(outputMix); + (*engine)->Destroy(engine); +} + +void slplay_stop (uri_player* player, char **error) { + SLPlayItf playInterface = player->playInterface; + SLresult result; + + // stop a loop + loop_start = 0; + + result = (*playInterface)->SetPlayState(playInterface, SL_PLAYSTATE_PAUSED); + if (result != SL_RESULT_SUCCESS) { + *error = strdup("Failed to set SL_PLAYSTATE_STOPPED"); + return; + } +} + +void slplay_stop_uri(const char* uri, char **error) { + uri_player* player = get_player_by_uri(uri); + slplay_stop(player, error); +} + +void SLAPIENTRY slplay_callback(SLPlayItf playItf, void *context, SLuint32 event) { + uint64_t cb_loop_start = *((uint64_t*)context); + if (event == SL_PLAYEVENT_HEADATEND && cb_loop_start == loop_start) { + (*playItf)->SetPlayState(playItf, SL_PLAYSTATE_STOPPED); + (*playItf)->SetMarkerPosition(playItf, 0); + (*playItf)->SetPlayState(playItf, SL_PLAYSTATE_PLAYING); + } +} + +void slplay_play (const char *uri, bool loop, char **error) { + SLresult result; + + uri_player* player = get_player_by_uri(uri); + if (player == NULL) { + player = slplay_create_player_for_uri(uri, error); + if (*error) { + return; + } + } + + SLPlayItf playInterface = player->playInterface; + if (loop) { + loop_start = nanos_since_boot(); + loop_start_ctx = loop_start; + result = (*playInterface)->RegisterCallback(playInterface, slplay_callback, &loop_start_ctx); + if (result != SL_RESULT_SUCCESS) { + char error[64]; + snprintf(error, sizeof(error), "Failed to register callback. %d", result); + *error = error[0]; + return; + } + + result = (*playInterface)->SetCallbackEventsMask(playInterface, SL_PLAYEVENT_HEADATEND); + if (result != SL_RESULT_SUCCESS) { + *error = strdup("Failed to set callback event mask"); + return; + } + } + + // Reset the audio player + result = (*playInterface)->ClearMarkerPosition(playInterface); + if (result != SL_RESULT_SUCCESS) { + *error = strdup("Failed to clear marker position"); + return; + } + result = (*playInterface)->SetPlayState(playInterface, SL_PLAYSTATE_PAUSED); + result = (*playInterface)->SetPlayState(playInterface, SL_PLAYSTATE_STOPPED); + result = (*playInterface)->SetPlayState(playInterface, SL_PLAYSTATE_PLAYING); + if (result != SL_RESULT_SUCCESS) { + *error = strdup("Failed to set SL_PLAYSTATE_PLAYING"); + } +} diff --git a/selfdrive/ui/slplay.h b/selfdrive/ui/slplay.h new file mode 100644 index 00000000000000..f8c39ceeb7cb2c --- /dev/null +++ b/selfdrive/ui/slplay.h @@ -0,0 +1,21 @@ +#ifndef SLPLAY_H +#define SLPLAY_H + +#include +#include +#include + +typedef struct { + const char* uri; + SLObjectItf player; + SLPlayItf playInterface; +} uri_player; + +void slplay_setup(char **error); +uri_player* slplay_create_player_for_uri(const char* uri, char **error); +void slplay_play (const char *uri, bool loop, char **error); +void slplay_stop_uri (const char* uri, char **error); +void slplay_destroy(); + +#endif + diff --git a/selfdrive/ui/spinner/spinner b/selfdrive/ui/spinner/spinner new file mode 100755 index 00000000000000..326a377aa3ffde Binary files /dev/null and b/selfdrive/ui/spinner/spinner differ diff --git a/selfdrive/ui/spinner/spinner.c b/selfdrive/ui/spinner/spinner.c new file mode 100644 index 00000000000000..477cfe1cf3abd1 --- /dev/null +++ b/selfdrive/ui/spinner/spinner.c @@ -0,0 +1,99 @@ +#include +#include +#include +#include +#include +#include + +#include +#include + +#include "nanovg.h" +#define NANOVG_GLES3_IMPLEMENTATION +#include "nanovg_gl.h" +#include "nanovg_gl_utils.h" + +#include "common/framebuffer.h" + +int main(int argc, char** argv) { + int err; + + const char* spintext = NULL; + if (argc >= 2) { + spintext = argv[1]; + } + + // spinner + int fb_w, fb_h; + EGLDisplay display; + EGLSurface surface; + FramebufferState *fb = framebuffer_init("spinner", 0x00001000, false, + &display, &surface, &fb_w, &fb_h); + assert(fb); + + NVGcontext *vg = nvgCreateGLES3(NVG_ANTIALIAS | NVG_STENCIL_STROKES); + assert(vg); + + int font = nvgCreateFont(vg, "Bold", "../../assets/OpenSans-SemiBold.ttf"); + assert(font >= 0); + + int spinner_img = nvgCreateImage(vg, "../../assets/img_spinner_track.png", 0); + assert(spinner_img >= 0); + int spinner_img_s = 360; + int spinner_img_x = ((fb_w/2)-(spinner_img_s/2)); + int spinner_img_y = 260; + int spinner_img_xc = (fb_w/2); + int spinner_img_yc = (fb_h/2)-100; + int spinner_comma_img = nvgCreateImage(vg, "../../assets/img_spinner_comma.png", 0); + assert(spinner_comma_img >= 0); + + for (int cnt = 0; ; cnt++) { + glClearColor(0.1, 0.1, 0.1, 1.0); + glClear(GL_STENCIL_BUFFER_BIT | GL_COLOR_BUFFER_BIT); + glEnable(GL_BLEND); + glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); + nvgBeginFrame(vg, fb_w, fb_h, 1.0f); + + // background + nvgBeginPath(vg); + NVGpaint bg = nvgLinearGradient(vg, fb_w, 0, fb_w, fb_h, + nvgRGBA(0, 0, 0, 175), nvgRGBA(0, 0, 0, 255)); + nvgFillPaint(vg, bg); + nvgRect(vg, 0, 0, fb_w, fb_h); + nvgFill(vg); + + // spin track + nvgSave(vg); + nvgTranslate(vg, spinner_img_xc, spinner_img_yc); + nvgRotate(vg, (3.75*M_PI * cnt/120.0)); + nvgTranslate(vg, -spinner_img_xc, -spinner_img_yc); + NVGpaint spinner_imgPaint = nvgImagePattern(vg, spinner_img_x, spinner_img_y, + spinner_img_s, spinner_img_s, 0, spinner_img, 0.6f); + nvgBeginPath(vg); + nvgFillPaint(vg, spinner_imgPaint); + nvgRect(vg, spinner_img_x, spinner_img_y, spinner_img_s, spinner_img_s); + nvgFill(vg); + nvgRestore(vg); + + // comma + NVGpaint comma_imgPaint = nvgImagePattern(vg, spinner_img_x, spinner_img_y, + spinner_img_s, spinner_img_s, 0, spinner_comma_img, 1.0f); + nvgBeginPath(vg); + nvgFillPaint(vg, comma_imgPaint); + nvgRect(vg, spinner_img_x, spinner_img_y, spinner_img_s, spinner_img_s); + nvgFill(vg); + + // message + if (spintext) { + nvgTextAlign(vg, NVG_ALIGN_CENTER | NVG_ALIGN_TOP); + nvgFontSize(vg, 96.0f); + nvgText(vg, fb_w/2, (fb_h*2/3)+24, spintext, NULL); + } + + nvgEndFrame(vg); + eglSwapBuffers(display, surface); + assert(glGetError() == GL_NO_ERROR); + } + + return 0; +} diff --git a/selfdrive/ui/start.sh b/selfdrive/ui/start.sh new file mode 100755 index 00000000000000..89704a5b6edf93 --- /dev/null +++ b/selfdrive/ui/start.sh @@ -0,0 +1,6 @@ +#!/bin/sh +set -e + +make +export LD_LIBRARY_PATH=/system/lib64:$LD_LIBRARY_PATH +exec ./ui diff --git a/selfdrive/ui/ui.c b/selfdrive/ui/ui.c new file mode 100644 index 00000000000000..44ee330d0d5d20 --- /dev/null +++ b/selfdrive/ui/ui.c @@ -0,0 +1,2644 @@ +#include +#include +#include +#include +#include +#include +#include + +#include + +#include +#include + +#include +#include + +#include "nanovg.h" +#define NANOVG_GLES3_IMPLEMENTATION +#include "nanovg_gl.h" +#include "nanovg_gl_utils.h" + +#include "common/timing.h" +#include "common/util.h" +#include "common/swaglog.h" +#include "common/mat.h" +#include "common/glutil.h" + +#include "common/touch.h" +#include "common/framebuffer.h" +#include "common/visionipc.h" +#include "common/visionimg.h" +#include "common/modeldata.h" +#include "common/params.h" + +#include "cereal/gen/c/log.capnp.h" +#include "slplay.h" + +#define STATUS_STOPPED 0 +#define STATUS_DISENGAGED 1 +#define STATUS_ENGAGED 2 +#define STATUS_WARNING 3 +#define STATUS_ALERT 4 +#define STATUS_MAX 5 + +#define ALERTSIZE_NONE 0 +#define ALERTSIZE_SMALL 1 +#define ALERTSIZE_MID 2 +#define ALERTSIZE_FULL 3 + +#define UI_BUF_COUNT 4 +//#define DEBUG_TURN + +const int vwp_w = 1920; +const int vwp_h = 1080; +const int nav_w = 640; +const int nav_ww= 760; +const int sbr_w = 300; +const int bdr_s = 30; +const int box_x = sbr_w+bdr_s; +const int box_y = bdr_s; +const int box_w = vwp_w-sbr_w-(bdr_s*2); +const int box_h = vwp_h-(bdr_s*2); +const int viz_w = vwp_w-(bdr_s*2); +const int header_h = 420; +const int footer_h = 280; +const int footer_y = vwp_h-bdr_s-footer_h; + +const int UI_FREQ = 60; // Hz + +const uint8_t bg_colors[][4] = { + [STATUS_STOPPED] = {0x07, 0x23, 0x39, 0xff}, + [STATUS_DISENGAGED] = {0x17, 0x33, 0x49, 0xff}, + [STATUS_ENGAGED] = {0x17, 0x86, 0x44, 0xff}, + [STATUS_WARNING] = {0xDA, 0x6F, 0x25, 0xff}, + [STATUS_ALERT] = {0xC9, 0x22, 0x31, 0xff}, +}; + +const uint8_t alert_colors[][4] = { + [STATUS_STOPPED] = {0x07, 0x23, 0x39, 0xf1}, + [STATUS_DISENGAGED] = {0x17, 0x33, 0x49, 0xc8}, + [STATUS_ENGAGED] = {0x17, 0x86, 0x44, 0xf1}, + [STATUS_WARNING] = {0xDA, 0x6F, 0x25, 0xf1}, + [STATUS_ALERT] = {0xC9, 0x22, 0x31, 0xf1}, +}; + +const int alert_sizes[] = { + [ALERTSIZE_NONE] = 0, + [ALERTSIZE_SMALL] = 241, + [ALERTSIZE_MID] = 390, + [ALERTSIZE_FULL] = vwp_h, +}; + +const int SET_SPEED_NA = 255; + +// TODO: this is also hardcoded in common/transformations/camera.py +const mat3 intrinsic_matrix = (mat3){{ + 910., 0., 582., + 0., 910., 437., + 0., 0., 1. +}}; + +typedef struct UIScene { + int frontview; + int fullview; + + int transformed_width, transformed_height; + + uint64_t model_ts; + ModelData model; + + float mpc_x[50]; + float mpc_y[50]; + + bool world_objects_visible; + mat3 warp_matrix; // transformed box -> frame. + mat4 extrinsic_matrix; // Last row is 0 so we can use mat4. + + float v_cruise; + uint64_t v_cruise_update_ts; + float v_ego; + float v_curvature; + bool decel_for_turn; + + float speedlimit; + bool speedlimit_valid; + bool map_valid; + + float curvature; + int engaged; + bool engageable; + bool monitoring_active; + + bool uilayout_sidebarcollapsed; + bool uilayout_mapenabled; + // responsive layout + int ui_viz_rx; + int ui_viz_rw; + int ui_viz_ro; + + int lead_status; + float lead_d_rel, lead_y_rel, lead_v_rel; + + int front_box_x, front_box_y, front_box_width, front_box_height; + + uint64_t alert_ts; + char alert_text1[1024]; + char alert_text2[1024]; + uint8_t alert_size; + float alert_blinkingrate; + + float awareness_status; + + uint64_t started_ts; + + //BB CPU TEMP + uint16_t maxCpuTemp; + uint32_t maxBatTemp; + float gpsAccuracy ; + float freeSpace; + float angleSteers; + float angleSteersDes; + //BB END CPU TEMP + + // Used to show gps planner status + bool gps_planner_active; + + bool is_playing_alert; +} UIScene; + +typedef struct UIState { + pthread_mutex_t lock; + pthread_cond_t bg_cond; + + FramebufferState *fb; + int fb_w, fb_h; + EGLDisplay display; + EGLSurface surface; + + NVGcontext *vg; + + int font_courbd; + int font_sans_regular; + int font_sans_semibold; + int font_sans_bold; + int img_wheel; + int img_turn; + int img_face; + int img_map; + + zsock_t *thermal_sock; + void *thermal_sock_raw; + zsock_t *model_sock; + void *model_sock_raw; + zsock_t *live100_sock; + void *live100_sock_raw; + zsock_t *livecalibration_sock; + void *livecalibration_sock_raw; + zsock_t *live20_sock; + void *live20_sock_raw; + zsock_t *livempc_sock; + void *livempc_sock_raw; + zsock_t *plus_sock; + void *plus_sock_raw; + zsock_t *gps_sock; + void *gps_sock_raw; + zsock_t *map_data_sock; + void *map_data_sock_raw; + + zsock_t *uilayout_sock; + void *uilayout_sock_raw; + + int plus_state; + + // vision state + bool vision_connected; + bool vision_connect_firstrun; + int ipc_fd; + + VIPCBuf bufs[UI_BUF_COUNT]; + VIPCBuf front_bufs[UI_BUF_COUNT]; + int cur_vision_idx; + int cur_vision_front_idx; + + GLuint frame_program; + GLuint frame_texs[UI_BUF_COUNT]; + GLuint frame_front_texs[UI_BUF_COUNT]; + + GLint frame_pos_loc, frame_texcoord_loc; + GLint frame_texture_loc, frame_transform_loc; + + GLuint line_program; + GLint line_pos_loc, line_color_loc; + GLint line_transform_loc; + + unsigned int rgb_width, rgb_height, rgb_stride; + size_t rgb_buf_len; + mat4 rgb_transform; + + unsigned int rgb_front_width, rgb_front_height, rgb_front_stride; + size_t rgb_front_buf_len; + + bool intrinsic_matrix_loaded; + mat3 intrinsic_matrix; + + UIScene scene; + + bool awake; + int awake_timeout; + + int volume_timeout; + int speed_lim_off_timeout; + int is_metric_timeout; + int limit_set_speed_timeout; + + int status; + bool is_metric; + bool limit_set_speed; + float speed_lim_off; + bool is_ego_over_limit; + bool passive; + char alert_type[64]; + char alert_sound[64]; + int alert_size; + float alert_blinking_alpha; + bool alert_blinked; + + float light_sensor; +} UIState; + +static int last_brightness = -1; +static void set_brightness(UIState *s, int brightness) { + if (last_brightness != brightness && (s->awake || brightness == 0)) { + FILE *f = fopen("/sys/class/leds/lcd-backlight/brightness", "wb"); + if (f != NULL) { + fprintf(f, "%d", brightness); + fclose(f); + last_brightness = brightness; + } + } +} + +static void set_awake(UIState *s, bool awake) { + if (awake) { + // 30 second timeout at 30 fps + s->awake_timeout = 30*30; + } + if (s->awake != awake) { + s->awake = awake; + + if (awake) { + LOG("awake normal"); + framebuffer_set_power(s->fb, HWC_POWER_MODE_NORMAL); + } else { + LOG("awake off"); + set_brightness(s, 0); + framebuffer_set_power(s->fb, HWC_POWER_MODE_OFF); + } + } +} + +static void set_volume(UIState *s, int volume) { + char volume_change_cmd[64]; + sprintf(volume_change_cmd, "service call audio 3 i32 3 i32 %d i32 1", volume); + + // 5 second timeout at 60fps + s->volume_timeout = 5 * UI_FREQ; + int volume_changed = system(volume_change_cmd); +} + +volatile int do_exit = 0; +static void set_do_exit(int sig) { + do_exit = 1; +} + +static void read_speed_lim_off(UIState *s) { + char *speed_lim_off = NULL; + read_db_value(NULL, "SpeedLimitOffset", &speed_lim_off, NULL); + s->speed_lim_off = 0.; + if (speed_lim_off) { + s->speed_lim_off = strtod(speed_lim_off, NULL); + free(speed_lim_off); + } + s->speed_lim_off_timeout = 2 * UI_FREQ; // 0.5Hz +} + +static void read_is_metric(UIState *s) { + char *is_metric; + const int result = read_db_value(NULL, "IsMetric", &is_metric, NULL); + if (result == 0) { + s->is_metric = is_metric[0] == '1'; + free(is_metric); + } + s->is_metric_timeout = 2 * UI_FREQ; // 0.5Hz +} + +static void read_limit_set_speed(UIState *s) { + char *limit_set_speed; + const int result = read_db_value(NULL, "LimitSetSpeed", &limit_set_speed, NULL); + if (result == 0) { + s->limit_set_speed = limit_set_speed[0] == '1'; + free(limit_set_speed); + } + s->limit_set_speed_timeout = 2 * UI_FREQ; // 0.2Hz +} +static const char frame_vertex_shader[] = + "attribute vec4 aPosition;\n" + "attribute vec4 aTexCoord;\n" + "uniform mat4 uTransform;\n" + "varying vec4 vTexCoord;\n" + "void main() {\n" + " gl_Position = uTransform * aPosition;\n" + " vTexCoord = aTexCoord;\n" + "}\n"; + +static const char frame_fragment_shader[] = + "precision mediump float;\n" + "uniform sampler2D uTexture;\n" + "varying vec4 vTexCoord;\n" + "void main() {\n" + " gl_FragColor = texture2D(uTexture, vTexCoord.xy);\n" + "}\n"; + +static const char line_vertex_shader[] = + "attribute vec4 aPosition;\n" + "attribute vec4 aColor;\n" + "uniform mat4 uTransform;\n" + "varying vec4 vColor;\n" + "void main() {\n" + " gl_Position = uTransform * aPosition;\n" + " vColor = aColor;\n" + "}\n"; + +static const char line_fragment_shader[] = + "precision mediump float;\n" + "uniform sampler2D uTexture;\n" + "varying vec4 vColor;\n" + "void main() {\n" + " gl_FragColor = vColor;\n" + "}\n"; + + +static const mat4 device_transform = {{ + 1.0, 0.0, 0.0, 0.0, + 0.0, 1.0, 0.0, 0.0, + 0.0, 0.0, 1.0, 0.0, + 0.0, 0.0, 0.0, 1.0, +}}; + +// frame from 4/3 to box size with a 2x zoom +static const mat4 frame_transform = {{ + 2*(4./3.)/((float)viz_w/box_h), 0.0, 0.0, 0.0, + 0.0, 2.0, 0.0, 0.0, + 0.0, 0.0, 1.0, 0.0, + 0.0, 0.0, 0.0, 1.0, +}}; + +// frame from 4/3 to 16/9 display +static const mat4 full_to_wide_frame_transform = {{ + .75, 0.0, 0.0, 0.0, + 0.0, 1.0, 0.0, 0.0, + 0.0, 0.0, 1.0, 0.0, + 0.0, 0.0, 0.0, 1.0, +}}; + +typedef struct { + const char* name; + const char* uri; + bool loop; +} sound_file; + +sound_file sound_table[] = { + { "chimeDisengage", "../assets/sounds/disengaged.wav", false }, + { "chimeEngage", "../assets/sounds/engaged.wav", false }, + { "chimeWarning1", "../assets/sounds/warning_1.wav", false }, + { "chimeWarning2", "../assets/sounds/warning_2.wav", false }, + { "chimeWarningRepeat", "../assets/sounds/warning_2.wav", true }, + { "chimeError", "../assets/sounds/error.wav", false }, + { "chimePrompt", "../assets/sounds/error.wav", false }, + { NULL, NULL, false }, +}; + +sound_file* get_sound_file_by_name(const char* name) { + for (sound_file *s = sound_table; s->name != NULL; s++) { + if (strcmp(s->name, name) == 0) { + return s; + } + } + + return NULL; +} + +void ui_sound_init(char **error) { + slplay_setup(error); + if (*error) return; + + for (sound_file *s = sound_table; s->name != NULL; s++) { + slplay_create_player_for_uri(s->uri, error); + if (*error) return; + } +} + +static void ui_init(UIState *s) { + memset(s, 0, sizeof(UIState)); + + pthread_mutex_init(&s->lock, NULL); + pthread_cond_init(&s->bg_cond, NULL); + + // init connections + + s->thermal_sock = zsock_new_sub(">tcp://127.0.0.1:8005", ""); + assert(s->thermal_sock); + s->thermal_sock_raw = zsock_resolve(s->thermal_sock); + + s->gps_sock = zsock_new_sub(">tcp://127.0.0.1:8032", ""); + assert(s->gps_sock); + s->gps_sock_raw = zsock_resolve(s->gps_sock); + + s->model_sock = zsock_new_sub(">tcp://127.0.0.1:8009", ""); + assert(s->model_sock); + s->model_sock_raw = zsock_resolve(s->model_sock); + + s->live100_sock = zsock_new_sub(">tcp://127.0.0.1:8007", ""); + assert(s->live100_sock); + s->live100_sock_raw = zsock_resolve(s->live100_sock); + + s->uilayout_sock = zsock_new_sub(">tcp://127.0.0.1:8060", ""); + assert(s->uilayout_sock); + s->uilayout_sock_raw = zsock_resolve(s->uilayout_sock); + + s->livecalibration_sock = zsock_new_sub(">tcp://127.0.0.1:8019", ""); + assert(s->livecalibration_sock); + s->livecalibration_sock_raw = zsock_resolve(s->livecalibration_sock); + + s->live20_sock = zsock_new_sub(">tcp://127.0.0.1:8012", ""); + assert(s->live20_sock); + s->live20_sock_raw = zsock_resolve(s->live20_sock); + + s->livempc_sock = zsock_new_sub(">tcp://127.0.0.1:8035", ""); + assert(s->livempc_sock); + s->livempc_sock_raw = zsock_resolve(s->livempc_sock); + + s->plus_sock = zsock_new_sub(">tcp://127.0.0.1:8037", ""); + assert(s->plus_sock); + s->plus_sock_raw = zsock_resolve(s->plus_sock); + + s->map_data_sock = zsock_new_sub(">tcp://127.0.0.1:8065", ""); + assert(s->map_data_sock); + s->map_data_sock_raw = zsock_resolve(s->map_data_sock); + + s->ipc_fd = -1; + + // init display + s->fb = framebuffer_init("ui", 0x00010000, true, + &s->display, &s->surface, &s->fb_w, &s->fb_h); + assert(s->fb); + + set_awake(s, true); + + // init drawing + s->vg = nvgCreateGLES3(NVG_ANTIALIAS | NVG_STENCIL_STROKES | NVG_DEBUG); + assert(s->vg); + + s->font_courbd = nvgCreateFont(s->vg, "courbd", "../assets/courbd.ttf"); + assert(s->font_courbd >= 0); + s->font_sans_regular = nvgCreateFont(s->vg, "sans-regular", "../assets/OpenSans-Regular.ttf"); + assert(s->font_sans_regular >= 0); + s->font_sans_semibold = nvgCreateFont(s->vg, "sans-semibold", "../assets/OpenSans-SemiBold.ttf"); + assert(s->font_sans_semibold >= 0); + s->font_sans_bold = nvgCreateFont(s->vg, "sans-bold", "../assets/OpenSans-Bold.ttf"); + assert(s->font_sans_bold >= 0); + + assert(s->img_wheel >= 0); + s->img_wheel = nvgCreateImage(s->vg, "../assets/img_chffr_wheel.png", 1); + + assert(s->img_turn >= 0); + s->img_turn = nvgCreateImage(s->vg, "../assets/img_trafficSign_turn.png", 1); + + assert(s->img_face >= 0); + s->img_face = nvgCreateImage(s->vg, "../assets/img_driver_face.png", 1); + + assert(s->img_map >= 0); + s->img_map = nvgCreateImage(s->vg, "../assets/img_map.png", 1); + + // init gl + s->frame_program = load_program(frame_vertex_shader, frame_fragment_shader); + assert(s->frame_program); + + s->frame_pos_loc = glGetAttribLocation(s->frame_program, "aPosition"); + s->frame_texcoord_loc = glGetAttribLocation(s->frame_program, "aTexCoord"); + + s->frame_texture_loc = glGetUniformLocation(s->frame_program, "uTexture"); + s->frame_transform_loc = glGetUniformLocation(s->frame_program, "uTransform"); + + s->line_program = load_program(line_vertex_shader, line_fragment_shader); + assert(s->line_program); + + s->line_pos_loc = glGetAttribLocation(s->line_program, "aPosition"); + s->line_color_loc = glGetAttribLocation(s->line_program, "aColor"); + s->line_transform_loc = glGetUniformLocation(s->line_program, "uTransform"); + + glViewport(0, 0, s->fb_w, s->fb_h); + + glDisable(GL_DEPTH_TEST); + + assert(glGetError() == GL_NO_ERROR); + + { + char *value; + const int result = read_db_value(NULL, "Passive", &value, NULL); + if (result == 0) { + s->passive = value[0] == '1'; + free(value); + } + } +} + +// If the intrinsics are in the params entry, this copies them to +// intrinsic_matrix and returns true. Otherwise returns false. +static bool try_load_intrinsics(mat3 *intrinsic_matrix) { + char *value; + const int result = read_db_value(NULL, "CloudCalibration", &value, NULL); + + if (result == 0) { + JsonNode* calibration_json = json_decode(value); + free(value); + + JsonNode *intrinsic_json = + json_find_member(calibration_json, "intrinsic_matrix"); + + if (intrinsic_json == NULL || intrinsic_json->tag != JSON_ARRAY) { + json_delete(calibration_json); + return false; + } + + int i = 0; + JsonNode* json_num; + json_foreach(json_num, intrinsic_json) { + intrinsic_matrix->v[i++] = json_num->number_; + } + json_delete(calibration_json); + + return true; + } else { + return false; + } +} + +static void ui_init_vision(UIState *s, const VisionStreamBufs back_bufs, + int num_back_fds, const int *back_fds, + const VisionStreamBufs front_bufs, int num_front_fds, + const int *front_fds) { + const VisionUIInfo ui_info = back_bufs.buf_info.ui_info; + + assert(num_back_fds == UI_BUF_COUNT); + assert(num_front_fds == UI_BUF_COUNT); + + vipc_bufs_load(s->bufs, &back_bufs, num_back_fds, back_fds); + vipc_bufs_load(s->front_bufs, &front_bufs, num_front_fds, front_fds); + + s->cur_vision_idx = -1; + s->cur_vision_front_idx = -1; + + s->scene = (UIScene){ + .frontview = getenv("FRONTVIEW") != NULL, + .fullview = getenv("FULLVIEW") != NULL, + .transformed_width = ui_info.transformed_width, + .transformed_height = ui_info.transformed_height, + .front_box_x = ui_info.front_box_x, + .front_box_y = ui_info.front_box_y, + .front_box_width = ui_info.front_box_width, + .front_box_height = ui_info.front_box_height, + .world_objects_visible = false, // Invisible until we receive a calibration message. + .gps_planner_active = false, + }; + + s->rgb_width = back_bufs.width; + s->rgb_height = back_bufs.height; + s->rgb_stride = back_bufs.stride; + s->rgb_buf_len = back_bufs.buf_len; + + s->rgb_front_width = front_bufs.width; + s->rgb_front_height = front_bufs.height; + s->rgb_front_stride = front_bufs.stride; + s->rgb_front_buf_len = front_bufs.buf_len; + + s->rgb_transform = (mat4){{ + 2.0/s->rgb_width, 0.0, 0.0, -1.0, + 0.0, 2.0/s->rgb_height, 0.0, -1.0, + 0.0, 0.0, 1.0, 0.0, + 0.0, 0.0, 0.0, 1.0, + }}; + + read_speed_lim_off(s); + read_is_metric(s); + read_limit_set_speed(s); + s->is_metric_timeout = UI_FREQ / 2; // offset so values isn't read together with limit offset + s->limit_set_speed_timeout = UI_FREQ; // offset so values isn't read together with limit offset +} + +static void ui_draw_transformed_box(UIState *s, uint32_t color) { + const UIScene *scene = &s->scene; + + const mat3 bbt = scene->warp_matrix; + + struct { + vec3 pos; + uint32_t color; + } verts[] = { + {matvecmul3(bbt, (vec3){{0.0, 0.0, 1.0,}}), color}, + {matvecmul3(bbt, (vec3){{scene->transformed_width, 0.0, 1.0,}}), color}, + {matvecmul3(bbt, (vec3){{scene->transformed_width, scene->transformed_height, 1.0,}}), color}, + {matvecmul3(bbt, (vec3){{0.0, scene->transformed_height, 1.0,}}), color}, + {matvecmul3(bbt, (vec3){{0.0, 0.0, 1.0,}}), color}, + }; + + for (int i=0; irgb_height - verts[i].pos.v[1] / verts[i].pos.v[2]; + } + + glUseProgram(s->line_program); + + mat4 out_mat = matmul(device_transform, + matmul(frame_transform, s->rgb_transform)); + glUniformMatrix4fv(s->line_transform_loc, 1, GL_TRUE, out_mat.v); + + glEnableVertexAttribArray(s->line_pos_loc); + glVertexAttribPointer(s->line_pos_loc, 2, GL_FLOAT, GL_FALSE, sizeof(verts[0]), &verts[0].pos.v[0]); + + glEnableVertexAttribArray(s->line_color_loc); + glVertexAttribPointer(s->line_color_loc, 4, GL_UNSIGNED_BYTE, GL_TRUE, sizeof(verts[0]), &verts[0].color); + + assert(glGetError() == GL_NO_ERROR); + glDrawArrays(GL_LINE_STRIP, 0, ARRAYSIZE(verts)); +} + +// Projects a point in car to space to the corresponding point in full frame +// image space. +vec3 car_space_to_full_frame(const UIState *s, vec4 car_space_projective) { + const UIScene *scene = &s->scene; + + // We'll call the car space point p. + // First project into normalized image coordinates with the extrinsics matrix. + const vec4 Ep4 = matvecmul(scene->extrinsic_matrix, car_space_projective); + + // The last entry is zero because of how we store E (to use matvecmul). + const vec3 Ep = {{Ep4.v[0], Ep4.v[1], Ep4.v[2]}}; + const vec3 KEp = matvecmul3(intrinsic_matrix, Ep); + + // Project. + const vec3 p_image = {{KEp.v[0] / KEp.v[2], KEp.v[1] / KEp.v[2], 1.}}; + return p_image; +} + +// Calculate an interpolation between two numbers at a specific increment +static float lerp(float v0, float v1, float t) { + return (1 - t) * v0 + t * v1; +} + +static void draw_chevron(UIState *s, float x_in, float y_in, float sz, + NVGcolor fillColor, NVGcolor glowColor) { + const UIScene *scene = &s->scene; + + nvgSave(s->vg); + + nvgTranslate(s->vg, 240.0f, 0.0); + nvgTranslate(s->vg, -1440.0f / 2, -1080.0f / 2); + nvgScale(s->vg, 2.0, 2.0); + nvgScale(s->vg, 1440.0f / s->rgb_width, 1080.0f / s->rgb_height); + + const vec4 p_car_space = (vec4){{x_in, y_in, 0., 1.}}; + const vec3 p_full_frame = car_space_to_full_frame(s, p_car_space); + + sz *= 30; + sz /= (x_in / 3 + 30); + if (sz > 30) sz = 30; + if (sz < 15) sz = 15; + + float x = p_full_frame.v[0]; + float y = p_full_frame.v[1]; + + // glow + nvgBeginPath(s->vg); + float g_xo = sz/5; + float g_yo = sz/10; + if (x >= 0 && y >= 0.) { + nvgMoveTo(s->vg, x+(sz*1.35)+g_xo, y+sz+g_yo); + nvgLineTo(s->vg, x, y-g_xo); + nvgLineTo(s->vg, x-(sz*1.35)-g_xo, y+sz+g_yo); + nvgLineTo(s->vg, x+(sz*1.35)+g_xo, y+sz+g_yo); + nvgClosePath(s->vg); + } + nvgFillColor(s->vg, glowColor); + nvgFill(s->vg); + + // chevron + nvgBeginPath(s->vg); + if (x >= 0 && y >= 0.) { + nvgMoveTo(s->vg, x+(sz*1.25), y+sz); + nvgLineTo(s->vg, x, y); + nvgLineTo(s->vg, x-(sz*1.25), y+sz); + nvgLineTo(s->vg, x+(sz*1.25), y+sz); + nvgClosePath(s->vg); + } + nvgFillColor(s->vg, fillColor); + nvgFill(s->vg); + + nvgRestore(s->vg); +} + +static void ui_draw_lane_line(UIState *s, const float *points, float off, + NVGcolor color, bool is_ghost) { + const UIScene *scene = &s->scene; + + nvgSave(s->vg); + nvgTranslate(s->vg, 240.0f, 0.0); // rgb-box space + nvgTranslate(s->vg, -1440.0f / 2, -1080.0f / 2); // zoom 2x + nvgScale(s->vg, 2.0, 2.0); + nvgScale(s->vg, 1440.0f / s->rgb_width, 1080.0f / s->rgb_height); + nvgBeginPath(s->vg); + + bool started = false; + for (int i=0; i<49; i++) { + float px = (float)i; + float py = points[i] - off; + vec4 p_car_space = (vec4){{px, py, 0., 1.}}; + vec3 p_full_frame = car_space_to_full_frame(s, p_car_space); + float x = p_full_frame.v[0]; + float y = p_full_frame.v[1]; + if (x < 0 || y < 0.) { + continue; + } + if (!started) { + nvgMoveTo(s->vg, x, y); + started = true; + } else { + nvgLineTo(s->vg, x, y); + } + } + + for (int i=49; i>0; i--) { + float px = (float)i; + float py = is_ghost?(points[i]-off):(points[i]+off); + vec4 p_car_space = (vec4){{px, py, 0., 1.}}; + vec3 p_full_frame = car_space_to_full_frame(s, p_car_space); + float x = p_full_frame.v[0]; + float y = p_full_frame.v[1]; + if (x < 0 || y < 0.) { + continue; + } + nvgLineTo(s->vg, x, y); + } + + nvgClosePath(s->vg); + nvgFillColor(s->vg, color); + nvgFill(s->vg); + nvgRestore(s->vg); +} + +static void ui_draw_lane(UIState *s, const PathData path, NVGcolor color) { + ui_draw_lane_line(s, path.points, 0.025*path.prob, color, false); + float var = min(path.std, 0.7); + color.a /= 4; + ui_draw_lane_line(s, path.points, -var, color, true); + ui_draw_lane_line(s, path.points, var, color, true); +} + +static void ui_draw_track(UIState *s, bool is_mpc) { + const UIScene *scene = &s->scene; + const PathData path = scene->model.path; + const float *mpc_x_coords = &scene->mpc_x[0]; + const float *mpc_y_coords = &scene->mpc_y[0]; + + nvgSave(s->vg); + nvgTranslate(s->vg, 240.0f, 0.0); // rgb-box space + nvgTranslate(s->vg, -1440.0f / 2, -1080.0f / 2); // zoom 2x + nvgScale(s->vg, 2.0, 2.0); + nvgScale(s->vg, 1440.0f / s->rgb_width, 1080.0f / s->rgb_height); + nvgBeginPath(s->vg); + + bool started = false; + float off = is_mpc?0.3:0.5; + float lead_d = scene->lead_d_rel*2.; + float path_height = is_mpc?(lead_d>5.)?min(lead_d, 25.)-min(lead_d*0.35, 10.):20. + :(lead_d>0.)?min(lead_d, 50.)-min(lead_d*0.35, 10.):49.; + + // left side up + for (int i=0; i<=path_height; i++) { + float px, py, mpx; + if (is_mpc) { + mpx = i==0?0.0:mpc_x_coords[i]; + px = lerp(mpx+1.0, mpx, i/100.0); + py = mpc_y_coords[i] - off; + } else { + px = lerp(i+1.0, i, i/100.0); + py = path.points[i] - off; + } + + vec4 p_car_space = (vec4){{px, py, 0., 1.}}; + vec3 p_full_frame = car_space_to_full_frame(s, p_car_space); + float x = p_full_frame.v[0]; + float y = p_full_frame.v[1]; + if (x < 0 || y < 0) { + continue; + } + + if (!started) { + nvgMoveTo(s->vg, x, y); + started = true; + } else { + nvgLineTo(s->vg, x, y); + } + } + + // right side down + for (int i=path_height; i>=0; i--) { + float px, py, mpx; + if (is_mpc) { + mpx = i==0?0.0:mpc_x_coords[i]; + px = lerp(mpx+1.0, mpx, i/100.0); + py = mpc_y_coords[i] + off; + } else { + px = lerp(i+1.0, i, i/100.0); + py = path.points[i] + off; + } + + vec4 p_car_space = (vec4){{px, py, 0., 1.}}; + vec3 p_full_frame = car_space_to_full_frame(s, p_car_space); + float x = p_full_frame.v[0]; + float y = p_full_frame.v[1]; + if (x < 0 || y < 0.) { + continue; + } + + nvgLineTo(s->vg, x, y); + } + + nvgClosePath(s->vg); + + NVGpaint track_bg; + if (is_mpc) { + // Draw colored MPC track + const uint8_t *clr = bg_colors[s->status]; + track_bg = nvgLinearGradient(s->vg, vwp_w, vwp_h, vwp_w, vwp_h*.4, + nvgRGBA(clr[0], clr[1], clr[2], 255), nvgRGBA(clr[0], clr[1], clr[2], 255/2)); + } else { + // Draw white vision track + track_bg = nvgLinearGradient(s->vg, vwp_w, vwp_h, vwp_w, vwp_h*.4, + nvgRGBA(255, 255, 255, 255), nvgRGBA(255, 255, 255, 0)); + } + + nvgFillPaint(s->vg, track_bg); + nvgFill(s->vg); + nvgRestore(s->vg); +} + +static void draw_steering(UIState *s, float curvature) { + float points[50]; + for (int i = 0; i < 50; i++) { + float y_actual = i * tan(asin(clamp(i * curvature, -0.999, 0.999)) / 2.); + points[i] = y_actual; + } + + // ui_draw_lane_edge(s, points, 0.0, nvgRGBA(0, 0, 255, 128), 5); +} + +static void draw_frame(UIState *s) { + const UIScene *scene = &s->scene; + + mat4 out_mat; + float x1, x2, y1, y2; + if (s->scene.frontview) { + out_mat = device_transform; // full 16/9 + // flip horizontally so it looks like a mirror + x1 = (float)scene->front_box_x / s->rgb_front_width; + x2 = (float)(scene->front_box_x + scene->front_box_width) / s->rgb_front_width; + y2 = (float)scene->front_box_y / s->rgb_front_height; + y1 = (float)(scene->front_box_y + scene->front_box_height) / s->rgb_front_height; + } else { + out_mat = matmul(device_transform, frame_transform); + x1 = 1.0; + x2 = 0.0; + y1 = 1.0; + y2 = 0.0; + } + + const uint8_t frame_indicies[] = {0, 1, 2, 0, 2, 3}; + const float frame_coords[4][4] = { + {-1.0, -1.0, x2, y1}, //bl + {-1.0, 1.0, x2, y2}, //tl + { 1.0, 1.0, x1, y2}, //tr + { 1.0, -1.0, x1, y1}, //br + }; + + glActiveTexture(GL_TEXTURE0); + if (s->scene.frontview && s->cur_vision_front_idx >= 0) { + glBindTexture(GL_TEXTURE_2D, s->frame_front_texs[s->cur_vision_front_idx]); + } else if (!scene->frontview && s->cur_vision_idx >= 0) { + glBindTexture(GL_TEXTURE_2D, s->frame_texs[s->cur_vision_idx]); + } + + glUseProgram(s->frame_program); + + glUniform1i(s->frame_texture_loc, 0); + glUniformMatrix4fv(s->frame_transform_loc, 1, GL_TRUE, out_mat.v); + + glEnableVertexAttribArray(s->frame_pos_loc); + glVertexAttribPointer(s->frame_pos_loc, 2, GL_FLOAT, GL_FALSE, + sizeof(frame_coords[0]), frame_coords); + + glEnableVertexAttribArray(s->frame_texcoord_loc); + glVertexAttribPointer(s->frame_texcoord_loc, 2, GL_FLOAT, GL_FALSE, + sizeof(frame_coords[0]), &frame_coords[0][2]); + + assert(glGetError() == GL_NO_ERROR); + glDrawElements(GL_TRIANGLES, 6, GL_UNSIGNED_BYTE, &frame_indicies[0]); +} + +static void ui_draw_vision_lanes(UIState *s) { + const UIScene *scene = &s->scene; + // Draw left lane edge + ui_draw_lane( + s, scene->model.left_lane, + nvgRGBAf(1.0, 1.0, 1.0, scene->model.left_lane.prob)); + + // Draw right lane edge + ui_draw_lane( + s, scene->model.right_lane, + nvgRGBAf(1.0, 1.0, 1.0, scene->model.right_lane.prob)); + + // Draw vision path + ui_draw_track(s, false); + + if (scene->engaged) { + // Draw MPC path when engaged + ui_draw_track(s, true); + } +} + +// Draw all world space objects. +static void ui_draw_world(UIState *s) { + const UIScene *scene = &s->scene; + if (!scene->world_objects_visible) { + return; + } + + if ((nanos_since_boot() - scene->model_ts) < 1000000000ULL) { + // Draw lane edges and vision/mpc tracks + ui_draw_vision_lanes(s); + } + + if (scene->lead_status) { + // Draw lead car indicator + float fillAlpha = 0; + float speedBuff = 10.; + float leadBuff = 40.; + if (scene->lead_d_rel < leadBuff) { + fillAlpha = 255*(1.0-(scene->lead_d_rel/leadBuff)); + if (scene->lead_v_rel < 0) { + fillAlpha += 255*(-1*(scene->lead_v_rel/speedBuff)); + } + fillAlpha = (int)(min(fillAlpha, 255)); + } + draw_chevron(s, scene->lead_d_rel+2.7, scene->lead_y_rel, 25, + nvgRGBA(201, 34, 49, fillAlpha), nvgRGBA(218, 202, 37, 255)); + } +} + +//BB START: functions added for the display of various items +static int bb_ui_draw_measure(UIState *s, const char* bb_value, const char* bb_uom, const char* bb_label, + int bb_x, int bb_y, int bb_uom_dx, + NVGcolor bb_valueColor, NVGcolor bb_labelColor, NVGcolor bb_uomColor, + int bb_valueFontSize, int bb_labelFontSize, int bb_uomFontSize ) { + const UIScene *scene = &s->scene; + nvgTextAlign(s->vg, NVG_ALIGN_CENTER | NVG_ALIGN_BASELINE); + int dx = 0; + if (strlen(bb_uom) > 0) { + dx = (int)(bb_uomFontSize*2.5/2); + } + //print value + nvgFontFace(s->vg, "sans-semibold"); + nvgFontSize(s->vg, bb_valueFontSize*2.5); + nvgFillColor(s->vg, bb_valueColor); + nvgText(s->vg, bb_x-dx/2, bb_y+ (int)(bb_valueFontSize*2.5)+5, bb_value, NULL); + //print label + nvgFontFace(s->vg, "sans-regular"); + nvgFontSize(s->vg, bb_labelFontSize*2.5); + nvgFillColor(s->vg, bb_labelColor); + nvgText(s->vg, bb_x, bb_y + (int)(bb_valueFontSize*2.5)+5 + (int)(bb_labelFontSize*2.5)+5, bb_label, NULL); + //print uom + if (strlen(bb_uom) > 0) { + nvgSave(s->vg); + int rx =bb_x + bb_uom_dx + bb_valueFontSize -3; + int ry = bb_y + (int)(bb_valueFontSize*2.5/2)+25; + nvgTranslate(s->vg,rx,ry); + nvgRotate(s->vg, -1.5708); //-90deg in radians + nvgFontFace(s->vg, "sans-regular"); + nvgFontSize(s->vg, (int)(bb_uomFontSize*2.5)); + nvgFillColor(s->vg, bb_uomColor); + nvgText(s->vg, 0, 0, bb_uom, NULL); + nvgRestore(s->vg); + } + return (int)((bb_valueFontSize + bb_labelFontSize)*2.5) + 5; +} + +static void bb_ui_draw_measures_left(UIState *s, int bb_x, int bb_y, int bb_w ) { + const UIScene *scene = &s->scene; + int bb_rx = bb_x + (int)(bb_w/2); + int bb_ry = bb_y; + int bb_h = 5; + NVGcolor lab_color = nvgRGBA(255, 255, 255, 200); + NVGcolor uom_color = nvgRGBA(255, 255, 255, 200); + int value_fontSize=30; + int label_fontSize=15; + int uom_fontSize = 15; + int bb_uom_dx = (int)(bb_w /2 - uom_fontSize*2.5) ; + + //add CPU temperature + if (true) { + char val_str[16]; + char uom_str[6]; + NVGcolor val_color = nvgRGBA(255, 255, 255, 200); + if((int)(scene->maxCpuTemp/10) > 80) { + val_color = nvgRGBA(255, 188, 3, 200); + } + if((int)(scene->maxCpuTemp/10) > 92) { + val_color = nvgRGBA(255, 0, 0, 200); + } + // temp is alway in C * 10 + snprintf(val_str, sizeof(val_str), "%d C", (int)(scene->maxCpuTemp/10)); + snprintf(uom_str, sizeof(uom_str), ""); + bb_h +=bb_ui_draw_measure(s, val_str, uom_str, "CPU TEMP", + bb_rx, bb_ry, bb_uom_dx, + val_color, lab_color, uom_color, + value_fontSize, label_fontSize, uom_fontSize ); + bb_ry = bb_y + bb_h; + } + + //add battery temperature + if (true) { + char val_str[16]; + char uom_str[6]; + NVGcolor val_color = nvgRGBA(255, 255, 255, 200); + if((int)(scene->maxBatTemp/1000) > 40) { + val_color = nvgRGBA(255, 188, 3, 200); + } + if((int)(scene->maxBatTemp/1000) > 50) { + val_color = nvgRGBA(255, 0, 0, 200); + } + // temp is alway in C * 1000 + snprintf(val_str, sizeof(val_str), "%d C", (int)(scene->maxBatTemp/1000)); + snprintf(uom_str, sizeof(uom_str), ""); + bb_h +=bb_ui_draw_measure(s, val_str, uom_str, "BAT TEMP", + bb_rx, bb_ry, bb_uom_dx, + val_color, lab_color, uom_color, + value_fontSize, label_fontSize, uom_fontSize ); + bb_ry = bb_y + bb_h; + } + + //add grey panda GPS accuracy + if (true) { + char val_str[16]; + char uom_str[3]; + NVGcolor val_color = nvgRGBA(255, 255, 255, 200); + //show red/orange if gps accuracy is high + if(scene->gpsAccuracy > 0.59) { + val_color = nvgRGBA(255, 188, 3, 200); + } + if(scene->gpsAccuracy > 0.8) { + val_color = nvgRGBA(255, 0, 0, 200); + } + + // gps accuracy is always in meters + snprintf(val_str, sizeof(val_str), "%.2f", (s->scene.gpsAccuracy)); + snprintf(uom_str, sizeof(uom_str), "m");; + bb_h +=bb_ui_draw_measure(s, val_str, uom_str, "GPS PREC", + bb_rx, bb_ry, bb_uom_dx, + val_color, lab_color, uom_color, + value_fontSize, label_fontSize, uom_fontSize ); + bb_ry = bb_y + bb_h; + } + + //add free space - from bthaler1 + if (true) { + char val_str[16]; + char uom_str[3]; + NVGcolor val_color = nvgRGBA(255, 255, 255, 200); + + //show red/orange if free space is low + if(scene->freeSpace < 0.4) { + val_color = nvgRGBA(255, 188, 3, 200); + } + if(scene->freeSpace < 0.2) { + val_color = nvgRGBA(255, 0, 0, 200); + } + + snprintf(val_str, sizeof(val_str), "%.1f", s->scene.freeSpace* 100); + snprintf(uom_str, sizeof(uom_str), "%%"); + + bb_h +=bb_ui_draw_measure(s, val_str, uom_str, "FREE", + bb_rx, bb_ry, bb_uom_dx, + val_color, lab_color, uom_color, + value_fontSize, label_fontSize, uom_fontSize ); + bb_ry = bb_y + bb_h; + } + //finally draw the frame + bb_h += 20; + nvgBeginPath(s->vg); + nvgRoundedRect(s->vg, bb_x, bb_y, bb_w, bb_h, 20); + nvgStrokeColor(s->vg, nvgRGBA(255,255,255,80)); + nvgStrokeWidth(s->vg, 6); + nvgStroke(s->vg); +} + + +static void bb_ui_draw_measures_right(UIState *s, int bb_x, int bb_y, int bb_w ) { + const UIScene *scene = &s->scene; + int bb_rx = bb_x + (int)(bb_w/2); + int bb_ry = bb_y; + int bb_h = 5; + NVGcolor lab_color = nvgRGBA(255, 255, 255, 200); + NVGcolor uom_color = nvgRGBA(255, 255, 255, 200); + int value_fontSize=30; + int label_fontSize=15; + int uom_fontSize = 15; + int bb_uom_dx = (int)(bb_w /2 - uom_fontSize*2.5) ; + + //add visual radar relative distance + if (true) { + char val_str[16]; + char uom_str[6]; + NVGcolor val_color = nvgRGBA(255, 255, 255, 200); + if (scene->lead_status) { + //show RED if less than 5 meters + //show orange if less than 15 meters + if((int)(scene->lead_d_rel) < 15) { + val_color = nvgRGBA(255, 188, 3, 200); + } + if((int)(scene->lead_d_rel) < 5) { + val_color = nvgRGBA(255, 0, 0, 200); + } + // lead car relative distance is always in meters + snprintf(val_str, sizeof(val_str), "%d", (int)scene->lead_d_rel); + } else { + snprintf(val_str, sizeof(val_str), "-"); + } + snprintf(uom_str, sizeof(uom_str), "m "); + bb_h +=bb_ui_draw_measure(s, val_str, uom_str, "REL DIST", + bb_rx, bb_ry, bb_uom_dx, + val_color, lab_color, uom_color, + value_fontSize, label_fontSize, uom_fontSize ); + bb_ry = bb_y + bb_h; + } + + //add visual radar relative speed + if (true) { + char val_str[16]; + char uom_str[6]; + NVGcolor val_color = nvgRGBA(255, 255, 255, 200); + if (scene->lead_status) { + //show Orange if negative speed (approaching) + //show Orange if negative speed faster than 5mph (approaching fast) + if((int)(scene->lead_v_rel) < 0) { + val_color = nvgRGBA(255, 188, 3, 200); + } + if((int)(scene->lead_v_rel) < -5) { + val_color = nvgRGBA(255, 0, 0, 200); + } + // lead car relative speed is always in meters + if (s->is_metric) { + snprintf(val_str, sizeof(val_str), "%d", (int)(scene->lead_v_rel * 3.6 + 0.5)); + } else { + snprintf(val_str, sizeof(val_str), "%d", (int)(scene->lead_v_rel * 2.2374144 + 0.5)); + } + } else { + snprintf(val_str, sizeof(val_str), "-"); + } + if (s->is_metric) { + snprintf(uom_str, sizeof(uom_str), "km/h");; + } else { + snprintf(uom_str, sizeof(uom_str), "mph"); + } + bb_h +=bb_ui_draw_measure(s, val_str, uom_str, "REL SPD", + bb_rx, bb_ry, bb_uom_dx, + val_color, lab_color, uom_color, + value_fontSize, label_fontSize, uom_fontSize ); + bb_ry = bb_y + bb_h; + } + + //add steering angle + if (true) { + char val_str[16]; + char uom_str[6]; + NVGcolor val_color = nvgRGBA(255, 255, 255, 200); + //show Orange if more than 6 degrees + //show red if more than 12 degrees + if(((int)(scene->angleSteers) < -6) || ((int)(scene->angleSteers) > 6)) { + val_color = nvgRGBA(255, 188, 3, 200); + } + if(((int)(scene->angleSteers) < -12) || ((int)(scene->angleSteers) > 12)) { + val_color = nvgRGBA(255, 0, 0, 200); + } + // steering is in degrees + snprintf(val_str, sizeof(val_str), "%.1f",(scene->angleSteers)); + + snprintf(uom_str, sizeof(uom_str), "deg"); + bb_h +=bb_ui_draw_measure(s, val_str, uom_str, "STEER", + bb_rx, bb_ry, bb_uom_dx, + val_color, lab_color, uom_color, + value_fontSize, label_fontSize, uom_fontSize ); + bb_ry = bb_y + bb_h; + } + + //add desired steering angle + if (true) { + char val_str[16]; + char uom_str[6]; + NVGcolor val_color = nvgRGBA(255, 255, 255, 200); + //show Orange if more than 6 degrees + //show red if more than 12 degrees + if(((int)(scene->angleSteersDes) < -6) || ((int)(scene->angleSteersDes) > 6)) { + val_color = nvgRGBA(255, 188, 3, 200); + } + if(((int)(scene->angleSteersDes) < -12) || ((int)(scene->angleSteersDes) > 12)) { + val_color = nvgRGBA(255, 0, 0, 200); + } + // steering is in degrees + snprintf(val_str, sizeof(val_str), "%.1f",(scene->angleSteersDes)); + + snprintf(uom_str, sizeof(uom_str), "deg"); + bb_h +=bb_ui_draw_measure(s, val_str, uom_str, "DES STEER", + bb_rx, bb_ry, bb_uom_dx, + val_color, lab_color, uom_color, + value_fontSize, label_fontSize, uom_fontSize ); + bb_ry = bb_y + bb_h; + } + + + //finally draw the frame + bb_h += 20; + nvgBeginPath(s->vg); + nvgRoundedRect(s->vg, bb_x, bb_y, bb_w, bb_h, 20); + nvgStrokeColor(s->vg, nvgRGBA(255,255,255,80)); + nvgStrokeWidth(s->vg, 6); + nvgStroke(s->vg); +} + +//draw grid from wiki +static void ui_draw_vision_grid(UIState *s) { + const UIScene *scene = &s->scene; + bool is_cruise_set = (s->scene.v_cruise != 0 && s->scene.v_cruise != 255); + if (!is_cruise_set) { + const int grid_spacing = 30; + + int ui_viz_rx = scene->ui_viz_rx; + int ui_viz_rw = scene->ui_viz_rw; + + nvgSave(s->vg); + + // path coords are worked out in rgb-box space + nvgTranslate(s->vg, 240.0f, 0.0); + + // zooom in 2x + nvgTranslate(s->vg, -1440.0f / 2, -1080.0f / 2); + nvgScale(s->vg, 2.0, 2.0); + + nvgScale(s->vg, 1440.0f / s->rgb_width, 1080.0f / s->rgb_height); + + nvgBeginPath(s->vg); + nvgStrokeColor(s->vg, nvgRGBA(255,255,255,128)); + nvgStrokeWidth(s->vg, 1); + + for (int i=box_y; i < box_h; i+=grid_spacing) { + nvgMoveTo(s->vg, ui_viz_rx, i); + //nvgLineTo(s->vg, ui_viz_rx, i); + nvgLineTo(s->vg, ((ui_viz_rw + ui_viz_rx) / 2)+ 10, i); + } + + for (int i=ui_viz_rx + 12; i <= ui_viz_rw; i+=grid_spacing) { + nvgMoveTo(s->vg, i, 0); + nvgLineTo(s->vg, i, 1000); + } + nvgStroke(s->vg); + nvgRestore(s->vg); + } +} + +static void bb_ui_draw_UI(UIState *s) { + //get 3-state switch position + int tri_state_fd; + int tri_state_switch; + char buffer[10]; + tri_state_switch = 1; //set to 2 for default UI + //tri_state_fd = open ("/sys/devices/virtual/switch/tri-state-key/state", O_RDONLY); + //if we can't open then switch should be considered in the middle, nothing done + //if (tri_state_fd == -1) { + // tri_state_switch = 2; + //} else { + // read (tri_state_fd, &buffer, 10); + ///tri_state_switch = buffer[0] -48; + ///close(tri_state_fd); + ///} + if (tri_state_switch == 1) { + const UIScene *scene = &s->scene; + const int bb_dml_w = 180; + const int bb_dml_x = (scene->ui_viz_rx + (bdr_s*2)); + const int bb_dml_y = (box_y + (bdr_s*1.5))+220; + + const int bb_dmr_w = 180; + const int bb_dmr_x = scene->ui_viz_rx + scene->ui_viz_rw - bb_dmr_w - (bdr_s*2) ; + const int bb_dmr_y = (box_y + (bdr_s*1.5))+220; + + bb_ui_draw_measures_left(s,bb_dml_x, bb_dml_y, bb_dml_w ); + bb_ui_draw_measures_right(s,bb_dmr_x, bb_dmr_y, bb_dmr_w ); + } + if (tri_state_switch ==3) { + ui_draw_vision_grid(s); + } + } + + +//BB END: functions added for the display of various items + + +static void ui_draw_vision_maxspeed(UIState *s) { + const UIScene *scene = &s->scene; + int ui_viz_rx = scene->ui_viz_rx; + int ui_viz_rw = scene->ui_viz_rw; + + char maxspeed_str[32]; + float maxspeed = s->scene.v_cruise; + int maxspeed_calc = maxspeed * 0.6225 + 0.5; + float speedlimit = s->scene.speedlimit; + int speedlim_calc = speedlimit * 2.2369363 + 0.5; + int speed_lim_off = s->speed_lim_off * 2.2369363 + 0.5; + if (s->is_metric) { + maxspeed_calc = maxspeed + 0.5; + speedlim_calc = speedlimit * 3.6 + 0.5; + speed_lim_off = s->speed_lim_off * 3.6 + 0.5; + } + + bool is_cruise_set = (maxspeed != 0 && maxspeed != SET_SPEED_NA); + bool is_speedlim_valid = s->scene.speedlimit_valid; + bool is_set_over_limit = is_speedlim_valid && s->scene.engaged && + is_cruise_set && maxspeed_calc > (speedlim_calc + speed_lim_off); + + int viz_maxspeed_w = 184; + int viz_maxspeed_h = 202; + int viz_maxspeed_x = (ui_viz_rx + (bdr_s*2)); + int viz_maxspeed_y = (box_y + (bdr_s*1.5)); + int viz_maxspeed_xo = 180; + viz_maxspeed_w += viz_maxspeed_xo; + viz_maxspeed_x += viz_maxspeed_w - (viz_maxspeed_xo * 2); + + // Draw Background + nvgBeginPath(s->vg); + nvgRoundedRect(s->vg, viz_maxspeed_x, viz_maxspeed_y, viz_maxspeed_w, viz_maxspeed_h, 30); + if (is_set_over_limit) { + nvgFillColor(s->vg, nvgRGBA(218, 111, 37, 180)); + } else { + nvgFillColor(s->vg, nvgRGBA(0, 0, 0, 100)); + } + nvgFill(s->vg); + + // Draw Border + nvgBeginPath(s->vg); + nvgRoundedRect(s->vg, viz_maxspeed_x, viz_maxspeed_y, viz_maxspeed_w, viz_maxspeed_h, 20); + if (is_set_over_limit) { + nvgStrokeColor(s->vg, nvgRGBA(218, 111, 37, 255)); + } else if (is_speedlim_valid && !s->is_ego_over_limit) { + nvgStrokeColor(s->vg, nvgRGBA(255, 255, 255, 255)); + } else if (is_speedlim_valid && s->is_ego_over_limit) { + nvgStrokeColor(s->vg, nvgRGBA(255, 255, 255, 20)); + } else { + nvgStrokeColor(s->vg, nvgRGBA(255, 255, 255, 100)); + } + nvgStrokeWidth(s->vg, 10); + nvgStroke(s->vg); + + // Draw "MAX" Text + nvgTextAlign(s->vg, NVG_ALIGN_CENTER | NVG_ALIGN_BASELINE); + nvgFontFace(s->vg, "sans-regular"); + nvgFontSize(s->vg, 26*2.5); + if (is_cruise_set) { + nvgFillColor(s->vg, nvgRGBA(255, 255, 255, 200)); + } else { + nvgFillColor(s->vg, nvgRGBA(255, 255, 255, 100)); + } + nvgText(s->vg, viz_maxspeed_x+(viz_maxspeed_xo/2)+(viz_maxspeed_w/2), 148, "MAX", NULL); + + // Draw Speed Text + nvgFontFace(s->vg, "sans-bold"); + nvgFontSize(s->vg, 48*2.5); + if (is_cruise_set) { + snprintf(maxspeed_str, sizeof(maxspeed_str), "%d", maxspeed_calc); + nvgFillColor(s->vg, nvgRGBA(255, 255, 255, 255)); + nvgText(s->vg, viz_maxspeed_x+(viz_maxspeed_xo/2)+(viz_maxspeed_w/2), 242, maxspeed_str, NULL); + } else { + nvgFontFace(s->vg, "sans-semibold"); + nvgFontSize(s->vg, 42*2.5); + nvgFillColor(s->vg, nvgRGBA(255, 255, 255, 100)); + nvgText(s->vg, viz_maxspeed_x+(viz_maxspeed_xo/2)+(viz_maxspeed_w/2), 242, "N/A", NULL); + } + + //BB START: add new measures panel const int bb_dml_w = 180; + bb_ui_draw_UI(s) ; + //BB END: add new measures panel +#ifdef DEBUG_TURN + if (s->scene.decel_for_turn && s->scene.engaged){ + int v_curvature = s->scene.v_curvature * 2.2369363 + 0.5; + snprintf(maxspeed_str, sizeof(maxspeed_str), "%d", v_curvature); + nvgFillColor(s->vg, nvgRGBA(255, 255, 255, 255)); + nvgFontSize(s->vg, 25*2.5); + nvgText(s->vg, 200 + viz_maxspeed_x+(viz_maxspeed_xo/2)+(viz_maxspeed_w/2), 148, "TURN", NULL); + nvgFontSize(s->vg, 50*2.5); + nvgText(s->vg, 200 + viz_maxspeed_x+(viz_maxspeed_xo/2)+(viz_maxspeed_w/2), 242, maxspeed_str, NULL); + } +#endif +} + +static void ui_draw_vision_speedlimit(UIState *s) { + const UIScene *scene = &s->scene; + int ui_viz_rx = scene->ui_viz_rx; + int ui_viz_rw = scene->ui_viz_rw; + + char speedlim_str[32]; + float speedlimit = s->scene.speedlimit; + int speedlim_calc = speedlimit * 2.2369363 + 0.5; + if (s->is_metric) { + speedlim_calc = speedlimit * 3.6 + 0.5; + } + + bool is_speedlim_valid = s->scene.speedlimit_valid; + float hysteresis_offset = 0.5; + if (s->is_ego_over_limit) { + hysteresis_offset = 0.0; + } + s->is_ego_over_limit = is_speedlim_valid && s->scene.v_ego > (speedlimit + s->speed_lim_off + hysteresis_offset); + + int viz_speedlim_w = 180; + int viz_speedlim_h = 202; + int viz_speedlim_x = (ui_viz_rx + (bdr_s*2)); + int viz_speedlim_y = (box_y + (bdr_s*1.5)); + if (!is_speedlim_valid) { + viz_speedlim_w -= 5; + viz_speedlim_h -= 10; + viz_speedlim_x += 9; + viz_speedlim_y += 5; + } + int viz_speedlim_bdr = is_speedlim_valid ? 30 : 15; + + // Draw Background + nvgBeginPath(s->vg); + nvgRoundedRect(s->vg, viz_speedlim_x, viz_speedlim_y, viz_speedlim_w, viz_speedlim_h, viz_speedlim_bdr); + if (is_speedlim_valid && s->is_ego_over_limit) { + nvgFillColor(s->vg, nvgRGBA(218, 111, 37, 180)); + } else if (is_speedlim_valid) { + nvgFillColor(s->vg, nvgRGBA(255, 255, 255, 255)); + } else { + nvgFillColor(s->vg, nvgRGBA(255, 255, 255, 100)); + } + nvgFill(s->vg); + + // Draw Border + if (is_speedlim_valid) { + nvgStrokeWidth(s->vg, 10); + nvgStroke(s->vg); + nvgBeginPath(s->vg); + nvgRoundedRect(s->vg, viz_speedlim_x, viz_speedlim_y, viz_speedlim_w, viz_speedlim_h, 20); + if (s->is_ego_over_limit) { + nvgStrokeColor(s->vg, nvgRGBA(218, 111, 37, 255)); + } else if (is_speedlim_valid) { + nvgStrokeColor(s->vg, nvgRGBA(255, 255, 255, 255)); + } + } + + // Draw "Speed Limit" Text + nvgTextAlign(s->vg, NVG_ALIGN_CENTER | NVG_ALIGN_BASELINE); + nvgFontFace(s->vg, "sans-semibold"); + nvgFontSize(s->vg, 50); + nvgFillColor(s->vg, nvgRGBA(0, 0, 0, 255)); + if (is_speedlim_valid && s->is_ego_over_limit) { + nvgFillColor(s->vg, nvgRGBA(255, 255, 255, 255)); + } + nvgText(s->vg, viz_speedlim_x+viz_speedlim_w/2 + (is_speedlim_valid ? 6 : 0), viz_speedlim_y + (is_speedlim_valid ? 50 : 45), "SPEED", NULL); + nvgText(s->vg, viz_speedlim_x+viz_speedlim_w/2 + (is_speedlim_valid ? 6 : 0), viz_speedlim_y + (is_speedlim_valid ? 90 : 85), "LIMIT", NULL); + + // Draw Speed Text + nvgFontFace(s->vg, "sans-bold"); + nvgFontSize(s->vg, 48*2.5); + if (s->is_ego_over_limit) { + nvgFillColor(s->vg, nvgRGBA(255, 255, 255, 255)); + } else { + nvgFillColor(s->vg, nvgRGBA(0, 0, 0, 255)); + } + if (is_speedlim_valid) { + snprintf(speedlim_str, sizeof(speedlim_str), "%d", speedlim_calc); + nvgText(s->vg, viz_speedlim_x+viz_speedlim_w/2, viz_speedlim_y + (is_speedlim_valid ? 170 : 165), speedlim_str, NULL); + } else { + nvgFontFace(s->vg, "sans-semibold"); + nvgFontSize(s->vg, 42*2.5); + nvgText(s->vg, viz_speedlim_x+viz_speedlim_w/2, viz_speedlim_y + (is_speedlim_valid ? 170 : 165), "N/A", NULL); + } +} + +static void ui_draw_vision_speed(UIState *s) { + const UIScene *scene = &s->scene; + int ui_viz_rx = scene->ui_viz_rx; + int ui_viz_rw = scene->ui_viz_rw; + float speed = s->scene.v_ego; + + const int viz_speed_w = 280; + const int viz_speed_x = ui_viz_rx+((ui_viz_rw/2)-(viz_speed_w/2)); + char speed_str[32]; + + nvgBeginPath(s->vg); + nvgRect(s->vg, viz_speed_x, box_y, viz_speed_w, header_h); + nvgTextAlign(s->vg, NVG_ALIGN_CENTER | NVG_ALIGN_BASELINE); + + if (s->is_metric) { + snprintf(speed_str, sizeof(speed_str), "%d", (int)(speed * 3.6 + 0.5)); + } else { + snprintf(speed_str, sizeof(speed_str), "%d", (int)(speed * 2.2374144 + 0.5)); + } + nvgFontFace(s->vg, "sans-bold"); + nvgFontSize(s->vg, 96*2.5); + nvgFillColor(s->vg, nvgRGBA(255, 255, 255, 255)); + nvgText(s->vg, viz_speed_x+viz_speed_w/2, 240, speed_str, NULL); + + nvgFontFace(s->vg, "sans-regular"); + nvgFontSize(s->vg, 36*2.5); + nvgFillColor(s->vg, nvgRGBA(255, 255, 255, 200)); + + if (s->is_metric) { + nvgText(s->vg, viz_speed_x+viz_speed_w/2, 320, "kph", NULL); + } else { + nvgText(s->vg, viz_speed_x+viz_speed_w/2, 320, "mph", NULL); + } +} + +static void ui_draw_vision_event(UIState *s) { + const UIScene *scene = &s->scene; + const int ui_viz_rx = scene->ui_viz_rx; + const int ui_viz_rw = scene->ui_viz_rw; + const int viz_event_w = 220; + const int viz_event_x = ((ui_viz_rx + ui_viz_rw) - (viz_event_w + (bdr_s*2))); + const int viz_event_y = (box_y + (bdr_s*1.5)); + const int viz_event_h = (header_h - (bdr_s*1.5)); + if (s->scene.decel_for_turn && s->scene.engaged && s->limit_set_speed) { + // draw winding road sign + const int img_turn_size = 160*1.5; + const int img_turn_x = viz_event_x-(img_turn_size/4); + const int img_turn_y = viz_event_y+bdr_s-25; + float img_turn_alpha = 1.0f; + nvgBeginPath(s->vg); + NVGpaint imgPaint = nvgImagePattern(s->vg, img_turn_x, img_turn_y, + img_turn_size, img_turn_size, 0, s->img_turn, img_turn_alpha); + nvgRect(s->vg, img_turn_x, img_turn_y, img_turn_size, img_turn_size); + nvgFillPaint(s->vg, imgPaint); + nvgFill(s->vg); + } else { + // draw steering wheel + const int bg_wheel_size = 96; + const int bg_wheel_x = viz_event_x + (viz_event_w-bg_wheel_size); + const int bg_wheel_y = viz_event_y + (bg_wheel_size/2); + const int img_wheel_size = bg_wheel_size*1.5; + const int img_wheel_x = bg_wheel_x-(img_wheel_size/2); + const int img_wheel_y = bg_wheel_y-25; + float img_wheel_alpha = 0.1f; + bool is_engaged = (s->status == STATUS_ENGAGED); + bool is_warning = (s->status == STATUS_WARNING); + bool is_engageable = scene->engageable; + if (is_engaged || is_warning || is_engageable) { + nvgBeginPath(s->vg); + nvgCircle(s->vg, bg_wheel_x, (bg_wheel_y + (bdr_s*1.5)), bg_wheel_size); + if (is_engaged) { + nvgFillColor(s->vg, nvgRGBA(23, 134, 68, 255)); + } else if (is_warning) { + nvgFillColor(s->vg, nvgRGBA(218, 111, 37, 255)); + } else if (is_engageable) { + nvgFillColor(s->vg, nvgRGBA(23, 51, 73, 255)); + } + nvgFill(s->vg); + img_wheel_alpha = 1.0f; + } + nvgBeginPath(s->vg); + NVGpaint imgPaint = nvgImagePattern(s->vg, img_wheel_x, img_wheel_y, + img_wheel_size, img_wheel_size, 0, s->img_wheel, img_wheel_alpha); + nvgRect(s->vg, img_wheel_x, img_wheel_y, img_wheel_size, img_wheel_size); + nvgFillPaint(s->vg, imgPaint); + nvgFill(s->vg); + } +} + +static void ui_draw_vision_map(UIState *s) { + const UIScene *scene = &s->scene; + const int map_size = 96; + const int map_x = (scene->ui_viz_rx + (map_size * 3) + (bdr_s * 3)); + const int map_y = (footer_y + ((footer_h - map_size) / 2)); + const int map_img_size = (map_size * 1.5); + const int map_img_x = (map_x - (map_img_size / 2)); + const int map_img_y = (map_y - (map_size / 4)); + + bool map_valid = s->scene.map_valid; + float map_img_alpha = map_valid ? 1.0f : 0.15f; + float map_bg_alpha = map_valid ? 0.3f : 0.1f; + NVGcolor map_bg = nvgRGBA(0, 0, 0, (255 * map_bg_alpha)); + NVGpaint map_img = nvgImagePattern(s->vg, map_img_x, map_img_y, + map_img_size, map_img_size, 0, s->img_map, map_img_alpha); + + nvgBeginPath(s->vg); + nvgCircle(s->vg, map_x, (map_y + (bdr_s * 1.5)), map_size); + nvgFillColor(s->vg, map_bg); + nvgFill(s->vg); + + nvgBeginPath(s->vg); + nvgRect(s->vg, map_img_x, map_img_y, map_img_size, map_img_size); + nvgFillPaint(s->vg, map_img); + nvgFill(s->vg); +} + +static void ui_draw_vision_face(UIState *s) { + const UIScene *scene = &s->scene; + const int face_size = 96; + const int face_x = (scene->ui_viz_rx + face_size + (bdr_s * 2)); + const int face_y = (footer_y + ((footer_h - face_size) / 2)); + const int face_img_size = (face_size * 1.5); + const int face_img_x = (face_x - (face_img_size / 2)); + const int face_img_y = (face_y - (face_size / 4)); + float face_img_alpha = scene->monitoring_active ? 1.0f : 0.15f; + float face_bg_alpha = scene->monitoring_active ? 0.3f : 0.1f; + NVGcolor face_bg = nvgRGBA(0, 0, 0, (255 * face_bg_alpha)); + NVGpaint face_img = nvgImagePattern(s->vg, face_img_x, face_img_y, + face_img_size, face_img_size, 0, s->img_face, face_img_alpha); + + nvgBeginPath(s->vg); + nvgCircle(s->vg, face_x, (face_y + (bdr_s * 1.5)), face_size); + nvgFillColor(s->vg, face_bg); + nvgFill(s->vg); + + nvgBeginPath(s->vg); + nvgRect(s->vg, face_img_x, face_img_y, face_img_size, face_img_size); + nvgFillPaint(s->vg, face_img); + nvgFill(s->vg); +} + +static void ui_draw_vision_header(UIState *s) { + const UIScene *scene = &s->scene; + int ui_viz_rx = scene->ui_viz_rx; + int ui_viz_rw = scene->ui_viz_rw; + + nvgBeginPath(s->vg); + NVGpaint gradient = nvgLinearGradient(s->vg, ui_viz_rx, + (box_y+(header_h-(header_h/2.5))), + ui_viz_rx, box_y+header_h, + nvgRGBAf(0,0,0,0.45), nvgRGBAf(0,0,0,0)); + nvgFillPaint(s->vg, gradient); + nvgRect(s->vg, ui_viz_rx, box_y, ui_viz_rw, header_h); + nvgFill(s->vg); + + ui_draw_vision_maxspeed(s); + ui_draw_vision_speedlimit(s); + ui_draw_vision_speed(s); + ui_draw_vision_event(s); +} + +static void ui_draw_vision_footer(UIState *s) { + const UIScene *scene = &s->scene; + int ui_viz_rx = scene->ui_viz_rx; + int ui_viz_rw = scene->ui_viz_rw; + + nvgBeginPath(s->vg); + nvgRect(s->vg, ui_viz_rx, footer_y, ui_viz_rw, footer_h); + + ui_draw_vision_face(s); + ui_draw_vision_map(s); +} + +static void ui_draw_vision_alert(UIState *s, int va_size, int va_color, + const char* va_text1, const char* va_text2) { + const UIScene *scene = &s->scene; + int ui_viz_rx = scene->ui_viz_rx; + int ui_viz_rw = scene->ui_viz_rw; + bool hasSidebar = !s->scene.uilayout_sidebarcollapsed; + bool mapEnabled = s->scene.uilayout_mapenabled; + bool longAlert1 = strlen(va_text1) > 15; + + const uint8_t *color = alert_colors[va_color]; + const int alr_s = alert_sizes[va_size]; + const int alr_x = ui_viz_rx-(mapEnabled?(hasSidebar?nav_w:(nav_ww)):0)-bdr_s; + const int alr_w = ui_viz_rw+(mapEnabled?(hasSidebar?nav_w:(nav_ww)):0)+(bdr_s*2); + const int alr_h = alr_s+(va_size==ALERTSIZE_NONE?0:bdr_s); + const int alr_y = vwp_h-alr_h; + + nvgBeginPath(s->vg); + nvgRect(s->vg, alr_x, alr_y, alr_w, alr_h); + nvgFillColor(s->vg, nvgRGBA(color[0],color[1],color[2],(color[3]*s->alert_blinking_alpha))); + nvgFill(s->vg); + + nvgBeginPath(s->vg); + NVGpaint gradient = nvgLinearGradient(s->vg, alr_x, alr_y, alr_x, alr_y+alr_h, + nvgRGBAf(0.0,0.0,0.0,0.05), nvgRGBAf(0.0,0.0,0.0,0.35)); + nvgFillPaint(s->vg, gradient); + nvgRect(s->vg, alr_x, alr_y, alr_w, alr_h); + nvgFill(s->vg); + + nvgFillColor(s->vg, nvgRGBA(255, 255, 255, 255)); + nvgTextAlign(s->vg, NVG_ALIGN_CENTER | NVG_ALIGN_BASELINE); + + if (va_size == ALERTSIZE_SMALL) { + nvgFontFace(s->vg, "sans-semibold"); + nvgFontSize(s->vg, 40*2.5); + nvgText(s->vg, alr_x+alr_w/2, alr_y+alr_h/2+15, va_text1, NULL); + } else if (va_size== ALERTSIZE_MID) { + nvgFontFace(s->vg, "sans-bold"); + nvgFontSize(s->vg, 48*2.5); + nvgText(s->vg, alr_x+alr_w/2, alr_y+alr_h/2-45, va_text1, NULL); + nvgFontFace(s->vg, "sans-regular"); + nvgFontSize(s->vg, 36*2.5); + nvgText(s->vg, alr_x+alr_w/2, alr_y+alr_h/2+75, va_text2, NULL); + } else if (va_size== ALERTSIZE_FULL) { + nvgFontSize(s->vg, (longAlert1?72:96)*2.5); + nvgFontFace(s->vg, "sans-bold"); + nvgTextAlign(s->vg, NVG_ALIGN_CENTER | NVG_ALIGN_MIDDLE); + nvgTextBox(s->vg, alr_x, alr_y+(longAlert1?360:420), alr_w-60, va_text1, NULL); + nvgFontSize(s->vg, 48*2.5); + nvgFontFace(s->vg, "sans-regular"); + nvgTextAlign(s->vg, NVG_ALIGN_CENTER | NVG_ALIGN_BOTTOM); + nvgTextBox(s->vg, alr_x, alr_h-(longAlert1?300:360), alr_w-60, va_text2, NULL); + } +} + +static void ui_draw_vision(UIState *s) { + const UIScene *scene = &s->scene; + int ui_viz_rx = scene->ui_viz_rx; + int ui_viz_rw = scene->ui_viz_rw; + int ui_viz_ro = scene->ui_viz_ro; + + glClearColor(0.0, 0.0, 0.0, 0.0); + glClear(GL_STENCIL_BUFFER_BIT | GL_COLOR_BUFFER_BIT); + + // Draw video frames + glEnable(GL_SCISSOR_TEST); + glViewport(ui_viz_rx+ui_viz_ro, s->fb_h-(box_y+box_h), viz_w, box_h); + glScissor(ui_viz_rx, s->fb_h-(box_y+box_h), ui_viz_rw, box_h); + draw_frame(s); + glViewport(0, 0, s->fb_w, s->fb_h); + glDisable(GL_SCISSOR_TEST); + + glEnable(GL_BLEND); + glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); + glClear(GL_STENCIL_BUFFER_BIT); + + nvgBeginFrame(s->vg, s->fb_w, s->fb_h, 1.0f); + nvgSave(s->vg); + + // Draw augmented elements + const int inner_height = viz_w*9/16; + nvgScissor(s->vg, ui_viz_rx, box_y, ui_viz_rw, box_h); + nvgTranslate(s->vg, ui_viz_rx+ui_viz_ro, box_y + (box_h-inner_height)/2.0); + nvgScale(s->vg, (float)viz_w / s->fb_w, (float)inner_height / s->fb_h); + if (!scene->frontview && !scene->fullview) { + ui_draw_world(s); + + } + + nvgRestore(s->vg); + + // Set Speed, Current Speed, Status/Events + ui_draw_vision_header(s); + + if (s->scene.alert_size != ALERTSIZE_NONE) { + // Controls Alerts + ui_draw_vision_alert(s, s->scene.alert_size, s->status, + s->scene.alert_text1, s->scene.alert_text2); + } else { + ui_draw_vision_footer(s); + } + + nvgEndFrame(s->vg); + glDisable(GL_BLEND); +} + +static void ui_draw_blank(UIState *s) { + glClearColor(0.0, 0.0, 0.0, 0.0); + glClear(GL_STENCIL_BUFFER_BIT | GL_COLOR_BUFFER_BIT); +} + +static void ui_draw(UIState *s) { + if (s->vision_connected && s->plus_state == 0) { + ui_draw_vision(s); + } else { + ui_draw_blank(s); + } + + { + glEnable(GL_BLEND); + glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); + glClear(GL_STENCIL_BUFFER_BIT); + + nvgBeginFrame(s->vg, s->fb_w, s->fb_h, 1.0f); + + nvgEndFrame(s->vg); + glDisable(GL_BLEND); + } + + assert(glGetError() == GL_NO_ERROR); +} + +static PathData read_path(cereal_ModelData_PathData_ptr pathp) { + PathData ret = {0}; + + struct cereal_ModelData_PathData pathd; + cereal_read_ModelData_PathData(&pathd, pathp); + + ret.prob = pathd.prob; + ret.std = pathd.std; + + capn_list32 pointl = pathd.points; + capn_resolve(&pointl.p); + for (int i = 0; i < 50; i++) { + ret.points[i] = capn_to_f32(capn_get32(pointl, i)); + } + + return ret; +} + +static ModelData read_model(cereal_ModelData_ptr modelp) { + struct cereal_ModelData modeld; + cereal_read_ModelData(&modeld, modelp); + + ModelData d = {0}; + + d.path = read_path(modeld.path); + d.left_lane = read_path(modeld.leftLane); + d.right_lane = read_path(modeld.rightLane); + + struct cereal_ModelData_LeadData leadd; + cereal_read_ModelData_LeadData(&leadd, modeld.lead); + d.lead = (LeadData){ + .dist = leadd.dist, .prob = leadd.prob, .std = leadd.std, + }; + + return d; +} + +static void update_status(UIState *s, int status) { + if (s->status != status) { + s->status = status; + // wake up bg thread to change + pthread_cond_signal(&s->bg_cond); + } +} + +static void ui_update(UIState *s) { + int err; + + if (!s->intrinsic_matrix_loaded) { + s->intrinsic_matrix_loaded = try_load_intrinsics(&s->intrinsic_matrix); + } + + if (s->vision_connect_firstrun) { + // cant run this in connector thread because opengl. + // do this here for now in lieu of a run_on_main_thread event + + for (int i=0; iframe_texs[i]); + + VisionImg img = { + .fd = s->bufs[i].fd, + .format = VISIONIMG_FORMAT_RGB24, + .width = s->rgb_width, + .height = s->rgb_height, + .stride = s->rgb_stride, + .bpp = 3, + .size = s->rgb_buf_len, + }; + s->frame_texs[i] = visionimg_to_gl(&img); + + glBindTexture(GL_TEXTURE_2D, s->frame_texs[i]); + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_NEAREST); + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_NEAREST); + + // BGR + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_SWIZZLE_R, GL_BLUE); + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_SWIZZLE_G, GL_GREEN); + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_SWIZZLE_B, GL_RED); + } + + for (int i=0; iframe_front_texs[i]); + + VisionImg img = { + .fd = s->front_bufs[i].fd, + .format = VISIONIMG_FORMAT_RGB24, + .width = s->rgb_front_width, + .height = s->rgb_front_height, + .stride = s->rgb_front_stride, + .bpp = 3, + .size = s->rgb_front_buf_len, + }; + s->frame_front_texs[i] = visionimg_to_gl(&img); + + glBindTexture(GL_TEXTURE_2D, s->frame_front_texs[i]); + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_NEAREST); + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_NEAREST); + + // BGR + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_SWIZZLE_R, GL_BLUE); + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_SWIZZLE_G, GL_GREEN); + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_SWIZZLE_B, GL_RED); + } + + assert(glGetError() == GL_NO_ERROR); + + // Default UI Measurements (Assumes sidebar collapsed) + s->scene.ui_viz_rx = (box_x-sbr_w+bdr_s*2); + s->scene.ui_viz_rw = (box_w+sbr_w-(bdr_s*2)); + s->scene.ui_viz_ro = 0; + + s->vision_connect_firstrun = false; + + s->alert_blinking_alpha = 1.0; + s->alert_blinked = false; + } + + // poll for events + while (true) { + zmq_pollitem_t polls[11] = {{0}}; + polls[0].socket = s->live100_sock_raw; + polls[0].events = ZMQ_POLLIN; + polls[1].socket = s->livecalibration_sock_raw; + polls[1].events = ZMQ_POLLIN; + polls[2].socket = s->model_sock_raw; + polls[2].events = ZMQ_POLLIN; + polls[3].socket = s->live20_sock_raw; + polls[3].events = ZMQ_POLLIN; + polls[4].socket = s->livempc_sock_raw; + polls[4].events = ZMQ_POLLIN; + polls[5].socket = s->thermal_sock_raw; + polls[5].events = ZMQ_POLLIN; + polls[6].socket = s->uilayout_sock_raw; + polls[6].events = ZMQ_POLLIN; + polls[7].socket = s->map_data_sock_raw; + polls[7].events = ZMQ_POLLIN; + polls[8].socket = s->gps_sock_raw; + polls[8].events = ZMQ_POLLIN; + polls[9].socket = s->plus_sock_raw; // plus_sock should be last + polls[9].events = ZMQ_POLLIN; + + int num_polls = 10; + if (s->vision_connected) { + assert(s->ipc_fd >= 0); + polls[10].fd = s->ipc_fd; + polls[10].events = ZMQ_POLLIN; + num_polls++; + } + + int ret = zmq_poll(polls, num_polls, 0); + if (ret < 0) { + LOGW("poll failed (%d)", ret); + break; + } + if (ret == 0) { + break; + } + + if (polls[0].revents || polls[1].revents || polls[2].revents || + polls[3].revents || polls[4].revents || polls[6].revents || + polls[7].revents || polls[8].revents || polls[9].revents) { + // awake on any (old) activity + set_awake(s, true); + } + + if (s->vision_connected && polls[10].revents) { + // vision ipc event + VisionPacket rp; + err = vipc_recv(s->ipc_fd, &rp); + if (err <= 0) { + LOGW("vision disconnected"); + close(s->ipc_fd); + s->ipc_fd = -1; + s->vision_connected = false; + continue; + } + if (rp.type == VIPC_STREAM_ACQUIRE) { + bool front = rp.d.stream_acq.type == VISION_STREAM_RGB_FRONT; + int idx = rp.d.stream_acq.idx; + + int release_idx; + if (front) { + release_idx = s->cur_vision_front_idx; + } else { + release_idx = s->cur_vision_idx; + } + if (release_idx >= 0) { + VisionPacket rep = { + .type = VIPC_STREAM_RELEASE, + .d = { .stream_rel = { + .type = rp.d.stream_acq.type, + .idx = release_idx, + }}, + }; + vipc_send(s->ipc_fd, &rep); + } + + if (front) { + assert(idx < UI_BUF_COUNT); + s->cur_vision_front_idx = idx; + } else { + assert(idx < UI_BUF_COUNT); + s->cur_vision_idx = idx; + // printf("v %d\n", ((uint8_t*)s->bufs[idx].addr)[0]); + } + } else { + assert(false); + } + } else if (polls[8].revents) + { + // gps socket + + zmq_msg_t msg; + err = zmq_msg_init(&msg); + assert(err == 0); + err = zmq_msg_recv(&msg, s->gps_sock_raw, 0); + assert(err >= 0); + + struct capn ctx; + capn_init_mem(&ctx, zmq_msg_data(&msg), zmq_msg_size(&msg), 0); + + cereal_Event_ptr eventp; + eventp.p = capn_getp(capn_root(&ctx), 0, 1); + struct cereal_Event eventd; + cereal_read_Event(&eventd, eventp); + + struct cereal_GpsLocationData datad; + cereal_read_GpsLocationData(&datad, eventd.gpsLocation); + + s->scene.gpsAccuracy= datad.accuracy; + if (s->scene.gpsAccuracy>100) + { + s->scene.gpsAccuracy=99.99; + } + else if (s->scene.gpsAccuracy==0) + { + s->scene.gpsAccuracy=99.8; + } + capn_free(&ctx); + zmq_msg_close(&msg); + + } else if (polls[9].revents) { + // plus socket + + zmq_msg_t msg; + err = zmq_msg_init(&msg); + assert(err == 0); + err = zmq_msg_recv(&msg, s->plus_sock_raw, 0); + assert(err >= 0); + + assert(zmq_msg_size(&msg) == 1); + + s->plus_state = ((char*)zmq_msg_data(&msg))[0]; + + zmq_msg_close(&msg); + + } else { + // zmq messages + void* which = NULL; + for (int i=0; i= 0); + + struct capn ctx; + capn_init_mem(&ctx, zmq_msg_data(&msg), zmq_msg_size(&msg), 0); + + cereal_Event_ptr eventp; + eventp.p = capn_getp(capn_root(&ctx), 0, 1); + struct cereal_Event eventd; + cereal_read_Event(&eventd, eventp); + + if (eventd.which == cereal_Event_live100) { + struct cereal_Live100Data datad; + cereal_read_Live100Data(&datad, eventd.live100); + + if (datad.vCruise != s->scene.v_cruise) { + s->scene.v_cruise_update_ts = eventd.logMonoTime; + } + s->scene.v_cruise = datad.vCruise; + s->scene.v_ego = datad.vEgo; + s->scene.angleSteers = datad.angleSteers; + s->scene.angleSteersDes = datad.angleSteersDes; + s->scene.curvature = datad.curvature; + s->scene.engaged = datad.enabled; + s->scene.engageable = datad.engageable; + s->scene.gps_planner_active = datad.gpsPlannerActive; + s->scene.monitoring_active = datad.driverMonitoringOn; + + s->scene.frontview = datad.rearViewCam; + + s->scene.v_curvature = datad.vCurvature; + s->scene.decel_for_turn = datad.decelForTurn; + + if (datad.alertSound.str && datad.alertSound.str[0] != '\0' && strcmp(s->alert_type, datad.alertType.str) != 0) { + char* error = NULL; + if (s->alert_sound[0] != '\0') { + sound_file* active_sound = get_sound_file_by_name(s->alert_sound); + slplay_stop_uri(active_sound->uri, &error); + if (error) { + LOGW("error stopping active sound %s", error); + } + } + + sound_file* sound = get_sound_file_by_name(datad.alertSound.str); + slplay_play(sound->uri, sound->loop, &error); + if(error) { + LOGW("error playing sound: %s", error); + } + + snprintf(s->alert_sound, sizeof(s->alert_sound), "%s", datad.alertSound.str); + snprintf(s->alert_type, sizeof(s->alert_type), "%s", datad.alertType.str); + } else if ((!datad.alertSound.str || datad.alertSound.str[0] == '\0') && s->alert_sound[0] != '\0') { + sound_file* sound = get_sound_file_by_name(s->alert_sound); + + char* error = NULL; + + slplay_stop_uri(sound->uri, &error); + if(error) { + LOGW("error stopping sound: %s", error); + } + s->alert_type[0] = '\0'; + s->alert_sound[0] = '\0'; + } + + if (datad.alertText1.str) { + snprintf(s->scene.alert_text1, sizeof(s->scene.alert_text1), "%s", datad.alertText1.str); + } else { + s->scene.alert_text1[0] = '\0'; + } + if (datad.alertText2.str) { + snprintf(s->scene.alert_text2, sizeof(s->scene.alert_text2), "%s", datad.alertText2.str); + } else { + s->scene.alert_text2[0] = '\0'; + } + s->scene.awareness_status = datad.awarenessStatus; + + s->scene.alert_ts = eventd.logMonoTime; + + s->scene.alert_size = datad.alertSize; + if (datad.alertSize == cereal_Live100Data_AlertSize_none) { + s->alert_size = ALERTSIZE_NONE; + } else if (datad.alertSize == cereal_Live100Data_AlertSize_small) { + s->alert_size = ALERTSIZE_SMALL; + } else if (datad.alertSize == cereal_Live100Data_AlertSize_mid) { + s->alert_size = ALERTSIZE_MID; + } else if (datad.alertSize == cereal_Live100Data_AlertSize_full) { + s->alert_size = ALERTSIZE_FULL; + } + + if (datad.alertStatus == cereal_Live100Data_AlertStatus_userPrompt) { + update_status(s, STATUS_WARNING); + } else if (datad.alertStatus == cereal_Live100Data_AlertStatus_critical) { + update_status(s, STATUS_ALERT); + } else if (datad.enabled) { + update_status(s, STATUS_ENGAGED); + } else { + update_status(s, STATUS_DISENGAGED); + } + + s->scene.alert_blinkingrate = datad.alertBlinkingRate; + if (datad.alertBlinkingRate > 0.) { + if (s->alert_blinked) { + if (s->alert_blinking_alpha > 0.0 && s->alert_blinking_alpha < 1.0) { + s->alert_blinking_alpha += (0.05*datad.alertBlinkingRate); + } else { + s->alert_blinked = false; + } + } else { + if (s->alert_blinking_alpha > 0.25) { + s->alert_blinking_alpha -= (0.05*datad.alertBlinkingRate); + } else { + s->alert_blinking_alpha += 0.25; + s->alert_blinked = true; + } + } + } + } else if (eventd.which == cereal_Event_live20) { + struct cereal_Live20Data datad; + cereal_read_Live20Data(&datad, eventd.live20); + struct cereal_Live20Data_LeadData leaddatad; + cereal_read_Live20Data_LeadData(&leaddatad, datad.leadOne); + s->scene.lead_status = leaddatad.status; + s->scene.lead_d_rel = leaddatad.dRel; + s->scene.lead_y_rel = leaddatad.yRel; + s->scene.lead_v_rel = leaddatad.vRel; + } else if (eventd.which == cereal_Event_liveCalibration) { + s->scene.world_objects_visible = true; + struct cereal_LiveCalibrationData datad; + cereal_read_LiveCalibrationData(&datad, eventd.liveCalibration); + + // should we still even have this? + capn_list32 warpl = datad.warpMatrix2; + capn_resolve(&warpl.p); // is this a bug? + for (int i = 0; i < 3 * 3; i++) { + s->scene.warp_matrix.v[i] = capn_to_f32(capn_get32(warpl, i)); + } + + capn_list32 extrinsicl = datad.extrinsicMatrix; + capn_resolve(&extrinsicl.p); // is this a bug? + for (int i = 0; i < 3 * 4; i++) { + s->scene.extrinsic_matrix.v[i] = + capn_to_f32(capn_get32(extrinsicl, i)); + } + } else if (eventd.which == cereal_Event_model) { + s->scene.model_ts = eventd.logMonoTime; + s->scene.model = read_model(eventd.model); + } else if (eventd.which == cereal_Event_liveMpc) { + struct cereal_LiveMpcData datad; + cereal_read_LiveMpcData(&datad, eventd.liveMpc); + + capn_list32 x_list = datad.x; + capn_resolve(&x_list.p); + + for (int i = 0; i < 50; i++){ + s->scene.mpc_x[i] = capn_to_f32(capn_get32(x_list, i)); + } + + capn_list32 y_list = datad.y; + capn_resolve(&y_list.p); + + for (int i = 0; i < 50; i++){ + s->scene.mpc_y[i] = capn_to_f32(capn_get32(y_list, i)); + } + } else if (eventd.which == cereal_Event_thermal) { + struct cereal_ThermalData datad; + cereal_read_ThermalData(&datad, eventd.thermal); + + if (!datad.started) { + update_status(s, STATUS_STOPPED); + } else if (s->status == STATUS_STOPPED) { + // car is started but controls doesn't have fingerprint yet + update_status(s, STATUS_DISENGAGED); + } + + s->scene.started_ts = datad.startedTs; + + //BBB CPU TEMP + s->scene.maxCpuTemp=datad.cpu0; + if (s->scene.maxCpuTempscene.maxCpuTemp=datad.cpu1; + } + else if (s->scene.maxCpuTempscene.maxCpuTemp=datad.cpu2; + } + else if (s->scene.maxCpuTempscene.maxCpuTemp=datad.cpu3; + } + s->scene.maxBatTemp=datad.bat; + s->scene.freeSpace=datad.freeSpace; + //BBB END CPU TEMP + } else if (eventd.which == cereal_Event_uiLayoutState) { + struct cereal_UiLayoutState datad; + cereal_read_UiLayoutState(&datad, eventd.uiLayoutState); + s->scene.uilayout_sidebarcollapsed = datad.sidebarCollapsed; + s->scene.uilayout_mapenabled = datad.mapEnabled; + + bool hasSidebar = !s->scene.uilayout_sidebarcollapsed; + bool mapEnabled = s->scene.uilayout_mapenabled; + if (mapEnabled) { + s->scene.ui_viz_rx = hasSidebar ? (box_x+nav_w) : (box_x+nav_w-(bdr_s*4)); + s->scene.ui_viz_rw = hasSidebar ? (box_w-nav_w) : (box_w-nav_w+(bdr_s*4)); + s->scene.ui_viz_ro = -(sbr_w + 4*bdr_s); + } else { + s->scene.ui_viz_rx = hasSidebar ? box_x : (box_x-sbr_w+bdr_s*2); + s->scene.ui_viz_rw = hasSidebar ? box_w : (box_w+sbr_w-(bdr_s*2)); + s->scene.ui_viz_ro = hasSidebar ? -(sbr_w - 6*bdr_s) : 0; + } + } else if (eventd.which == cereal_Event_liveMapData) { + struct cereal_LiveMapData datad; + cereal_read_LiveMapData(&datad, eventd.liveMapData); + s->scene.speedlimit = datad.speedLimit; + s->scene.speedlimit_valid = datad.speedLimitValid; + s->scene.map_valid = datad.mapValid; + } + capn_free(&ctx); + zmq_msg_close(&msg); + } + } + +} + +static int vision_subscribe(int fd, VisionPacket *rp, int type) { + int err; + LOGW("vision_subscribe type:%d", type); + + VisionPacket p1 = { + .type = VIPC_STREAM_SUBSCRIBE, + .d = { .stream_sub = { .type = type, .tbuffer = true, }, }, + }; + err = vipc_send(fd, &p1); + if (err < 0) { + close(fd); + return 0; + } + + do { + err = vipc_recv(fd, rp); + if (err <= 0) { + close(fd); + return 0; + } + + // release what we aren't ready for yet + if (rp->type == VIPC_STREAM_ACQUIRE) { + VisionPacket rep = { + .type = VIPC_STREAM_RELEASE, + .d = { .stream_rel = { + .type = rp->d.stream_acq.type, + .idx = rp->d.stream_acq.idx, + }}, + }; + vipc_send(fd, &rep); + } + } while (rp->type != VIPC_STREAM_BUFS || rp->d.stream_bufs.type != type); + + return 1; +} + +static void* vision_connect_thread(void *args) { + int err; + + UIState *s = args; + while (!do_exit) { + usleep(100000); + pthread_mutex_lock(&s->lock); + bool connected = s->vision_connected; + pthread_mutex_unlock(&s->lock); + if (connected) continue; + + int fd = vipc_connect(); + if (fd < 0) continue; + + VisionPacket back_rp, front_rp; + if (!vision_subscribe(fd, &back_rp, VISION_STREAM_RGB_BACK)) continue; + if (!vision_subscribe(fd, &front_rp, VISION_STREAM_RGB_FRONT)) continue; + + pthread_mutex_lock(&s->lock); + assert(!s->vision_connected); + s->ipc_fd = fd; + + ui_init_vision(s, + back_rp.d.stream_bufs, back_rp.num_fds, back_rp.fds, + front_rp.d.stream_bufs, front_rp.num_fds, front_rp.fds); + + s->vision_connected = true; + s->vision_connect_firstrun = true; + pthread_mutex_unlock(&s->lock); + } + return NULL; +} + + +#include +#include + +static void* light_sensor_thread(void *args) { + int err; + + UIState *s = args; + s->light_sensor = 0.0; + + struct sensors_poll_device_t* device; + struct sensors_module_t* module; + + hw_get_module(SENSORS_HARDWARE_MODULE_ID, (hw_module_t const**)&module); + sensors_open(&module->common, &device); + + // need to do this + struct sensor_t const* list; + int count = module->get_sensors_list(module, &list); + + int SENSOR_LIGHT = 7; + + device->activate(device, SENSOR_LIGHT, 0); + device->activate(device, SENSOR_LIGHT, 1); + device->setDelay(device, SENSOR_LIGHT, ms2ns(100)); + + while (!do_exit) { + static const size_t numEvents = 1; + sensors_event_t buffer[numEvents]; + + int n = device->poll(device, buffer, numEvents); + if (n < 0) { + LOG_100("light_sensor_poll failed: %d", n); + } + if (n > 0) { + s->light_sensor = buffer[0].light; + } + } + + return NULL; +} + + +static void* bg_thread(void* args) { + UIState *s = args; + + EGLDisplay bg_display; + EGLSurface bg_surface; + + FramebufferState *bg_fb = framebuffer_init("bg", 0x00001000, false, + &bg_display, &bg_surface, NULL, NULL); + assert(bg_fb); + + int bg_status = -1; + while(!do_exit) { + pthread_mutex_lock(&s->lock); + if (bg_status == s->status) { + // will always be signaled if it changes? + pthread_cond_wait(&s->bg_cond, &s->lock); + } + bg_status = s->status; + pthread_mutex_unlock(&s->lock); + + assert(bg_status < ARRAYSIZE(bg_colors)); + const uint8_t *color = bg_colors[bg_status]; + + glClearColor(color[0]/256.0, color[1]/256.0, color[2]/256.0, 0.0); + glClear(GL_COLOR_BUFFER_BIT); + + eglSwapBuffers(bg_display, bg_surface); + assert(glGetError() == GL_NO_ERROR); + } + + return NULL; +} + +int is_leon() { + #define MAXCHAR 1000 + FILE *fp; + char str[MAXCHAR]; + char* filename = "/proc/cmdline"; + fp = fopen(filename, "r"); + if (fp == NULL){ + printf("Could not open file %s",filename); + return 0; + } + fgets(str, MAXCHAR, fp); + fclose(fp); + return strstr(str, "letv") != NULL; +} + +int main() { + int err; + setpriority(PRIO_PROCESS, 0, -14); + + zsys_handler_set(NULL); + signal(SIGINT, (sighandler_t)set_do_exit); + + UIState uistate; + UIState *s = &uistate; + ui_init(s); + + pthread_t connect_thread_handle; + err = pthread_create(&connect_thread_handle, NULL, + vision_connect_thread, s); + assert(err == 0); + + pthread_t light_sensor_thread_handle; + err = pthread_create(&light_sensor_thread_handle, NULL, + light_sensor_thread, s); + assert(err == 0); + + pthread_t bg_thread_handle; + err = pthread_create(&bg_thread_handle, NULL, + bg_thread, s); + assert(err == 0); + + TouchState touch = {0}; + touch_init(&touch); + + char* error = NULL; + ui_sound_init(&error); + if (error) { + LOGW(error); + exit(1); + } + + // light sensor scaling params + const int EON = (access("/EON", F_OK) != -1); + const int LEON = is_leon(); + + const float BRIGHTNESS_B = LEON? 15.0 : 20.0; + const float BRIGHTNESS_M = LEON? 2.6 : 1.3; + + #define NEO_BRIGHTNESS 100 + + float smooth_brightness = BRIGHTNESS_B; + + set_volume(s, 0); + + while (!do_exit) { + bool should_swap = false; + pthread_mutex_lock(&s->lock); + + if (EON) { + // light sensor is only exposed on EONs + + float clipped_brightness = (s->light_sensor*BRIGHTNESS_M) + BRIGHTNESS_B; + if (clipped_brightness > 255) clipped_brightness = 255; + smooth_brightness = clipped_brightness * 0.01 + smooth_brightness * 0.99; + set_brightness(s, (int)smooth_brightness); + } else { + // compromise for bright and dark envs + set_brightness(s, NEO_BRIGHTNESS); + } + + ui_update(s); + + // awake on any touch + int touch_x = -1, touch_y = -1; + int touched = touch_poll(&touch, &touch_x, &touch_y, s->awake ? 0 : 100); + if (touched == 1) { + // touch event will still happen :( + set_awake(s, true); + } + + // manage wakefulness + if (s->awake_timeout > 0) { + s->awake_timeout--; + } else { + set_awake(s, false); + } + + if (s->awake) { + ui_draw(s); + glFinish(); + should_swap = true; + } + + if (s->volume_timeout > 0) { + s->volume_timeout--; + } else { + int volume = min(13, 11 + s->scene.v_ego / 15); // up one notch every 15 m/s, starting at 11 + set_volume(s, volume); + } + + if (s->speed_lim_off_timeout > 0) { + s->speed_lim_off_timeout--; + } else { + read_speed_lim_off(s); + } + + if (s->is_metric_timeout > 0) { + s->is_metric_timeout--; + } else { + read_is_metric(s); + } + + if (s->limit_set_speed_timeout > 0) { + s->limit_set_speed_timeout--; + } else { + read_limit_set_speed(s); + } + + pthread_mutex_unlock(&s->lock); + + // the bg thread needs to be scheduled, so the main thread needs time without the lock + // safe to do this outside the lock? + if (should_swap) { + eglSwapBuffers(s->display, s->surface); + } + } + + set_awake(s, true); + + slplay_destroy(); + + // wake up bg thread to exit + pthread_mutex_lock(&s->lock); + pthread_cond_signal(&s->bg_cond); + pthread_mutex_unlock(&s->lock); + err = pthread_join(bg_thread_handle, NULL); + assert(err == 0); + + err = pthread_join(connect_thread_handle, NULL); + assert(err == 0); + + return 0; +} diff --git a/selfdrive/updated.py b/selfdrive/updated.py new file mode 100755 index 00000000000000..c8efd8f3a86bf7 --- /dev/null +++ b/selfdrive/updated.py @@ -0,0 +1,34 @@ +#!/usr/bin/env python + +# simple service that waits for network access and tries to update every hour + +import time +import subprocess +from selfdrive.swaglog import cloudlog + +NICE_LOW_PRIORITY = ["nice", "-n", "19"] +def main(gctx=None): + while True: + # try network + r = subprocess.call(["ping", "-W", "4", "-c", "1", "8.8.8.8"]) + if r: + time.sleep(60) + continue + + # download application update + try: + r = subprocess.check_output(NICE_LOW_PRIORITY + ["git", "fetch"], stderr=subprocess.STDOUT) + except subprocess.CalledProcessError, e: + cloudlog.event("git fetch failed", + cmd=e.cmd, + output=e.output, + returncode=e.returncode) + time.sleep(60) + continue + cloudlog.info("git fetch success: %s", r) + + time.sleep(60*60) + +if __name__ == "__main__": + main() + diff --git a/selfdrive/version.py b/selfdrive/version.py new file mode 100644 index 00000000000000..8166c662f40dbf --- /dev/null +++ b/selfdrive/version.py @@ -0,0 +1,21 @@ +import os +import subprocess +with open(os.path.join(os.path.dirname(os.path.abspath(__file__)), "common", "version.h")) as _versionf: + version = _versionf.read().split('"')[1] + +try: + origin = subprocess.check_output(["git", "config", "--get", "remote.origin.url"]).rstrip() + if origin.startswith('git@github.com:commaai') or origin.startswith('https://github.com/commaai'): + if origin.endswith('/one.git'): + dirty = True + else: + branch = subprocess.check_output(["git", "rev-parse", "--abbrev-ref", "HEAD"]).rstrip() + branch = 'origin/' + branch + dirty = subprocess.call(["git", "diff-index", "--quiet", branch, "--"]) != 0 + else: + dirty = True +except subprocess.CalledProcessError: + dirty = True + +# put this here +training_version = "0.1.0" diff --git a/selfdrive/visiond/LICENSE.boringssl b/selfdrive/visiond/LICENSE.boringssl new file mode 100644 index 00000000000000..0b0b9b3292837f --- /dev/null +++ b/selfdrive/visiond/LICENSE.boringssl @@ -0,0 +1,192 @@ +BoringSSL is a fork of OpenSSL. As such, large parts of it fall under OpenSSL +licensing. Files that are completely new have a Google copyright and an ISC +license. This license is reproduced at the bottom of this file. + +Contributors to BoringSSL are required to follow the CLA rules for Chromium: +https://cla.developers.google.com/clas + +Some files from Intel are under yet another license, which is also included +underneath. + +The OpenSSL toolkit stays under a dual license, i.e. both the conditions of the +OpenSSL License and the original SSLeay license apply to the toolkit. See below +for the actual license texts. Actually both licenses are BSD-style Open Source +licenses. In case of any license issues related to OpenSSL please contact +openssl-core@openssl.org. + +The following are Google-internal bug numbers where explicit permission from +some authors is recorded for use of their work. (This is purely for our own +record keeping.) + 27287199 + 27287880 + 27287883 + + OpenSSL License + --------------- + +/* ==================================================================== + * Copyright (c) 1998-2011 The OpenSSL Project. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * + * 3. All advertising materials mentioning features or use of this + * software must display the following acknowledgment: + * "This product includes software developed by the OpenSSL Project + * for use in the OpenSSL Toolkit. (http://www.openssl.org/)" + * + * 4. The names "OpenSSL Toolkit" and "OpenSSL Project" must not be used to + * endorse or promote products derived from this software without + * prior written permission. For written permission, please contact + * openssl-core@openssl.org. + * + * 5. Products derived from this software may not be called "OpenSSL" + * nor may "OpenSSL" appear in their names without prior written + * permission of the OpenSSL Project. + * + * 6. Redistributions of any form whatsoever must retain the following + * acknowledgment: + * "This product includes software developed by the OpenSSL Project + * for use in the OpenSSL Toolkit (http://www.openssl.org/)" + * + * THIS SOFTWARE IS PROVIDED BY THE OpenSSL PROJECT ``AS IS'' AND ANY + * EXPRESSED OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR + * PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE OpenSSL PROJECT OR + * ITS CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, + * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT + * NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + * STRICT LIABILITY, OR TORT (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 product includes cryptographic software written by Eric Young + * (eay@cryptsoft.com). This product includes software written by Tim + * Hudson (tjh@cryptsoft.com). + * + */ + + Original SSLeay License + ----------------------- + +/* Copyright (C) 1995-1998 Eric Young (eay@cryptsoft.com) + * All rights reserved. + * + * This package is an SSL implementation written + * by Eric Young (eay@cryptsoft.com). + * The implementation was written so as to conform with Netscapes SSL. + * + * This library is free for commercial and non-commercial use as long as + * the following conditions are aheared to. The following conditions + * apply to all code found in this distribution, be it the RC4, RSA, + * lhash, DES, etc., code; not just the SSL code. The SSL documentation + * included with this distribution is covered by the same copyright terms + * except that the holder is Tim Hudson (tjh@cryptsoft.com). + * + * Copyright remains Eric Young's, and as such any Copyright notices in + * the code are not to be removed. + * If this package is used in a product, Eric Young should be given attribution + * as the author of the parts of the library used. + * This can be in the form of a textual message at program startup or + * in documentation (online or textual) provided with the package. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must 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. All advertising materials mentioning features or use of this software + * must display the following acknowledgement: + * "This product includes cryptographic software written by + * Eric Young (eay@cryptsoft.com)" + * The word 'cryptographic' can be left out if the rouines from the library + * being used are not cryptographic related :-). + * 4. If you include any Windows specific code (or a derivative thereof) from + * the apps directory (application code) you must include an acknowledgement: + * "This product includes software written by Tim Hudson (tjh@cryptsoft.com)" + * + * THIS SOFTWARE IS PROVIDED BY ERIC YOUNG ``AS IS'' AND + * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHOR OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (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 licence and distribution terms for any publically available version or + * derivative of this code cannot be changed. i.e. this code cannot simply be + * copied and put under another distribution licence + * [including the GNU Public Licence.] + */ + + +ISC license used for completely new code in BoringSSL: + +/* Copyright (c) 2015, Google Inc. + * + * Permission to use, copy, modify, and/or distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY + * SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN ACTION + * OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF OR IN + * CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. */ + + +Some files from Intel carry the following license: + +# Copyright (c) 2012, Intel Corporation +# +# All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions are +# met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# +# * Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in the +# documentation and/or other materials provided with the +# distribution. +# +# * Neither the name of the Intel Corporation nor the names of its +# contributors may be used to endorse or promote products derived from +# this software without specific prior written permission. +# +# +# THIS SOFTWARE IS PROVIDED BY INTEL CORPORATION ""AS IS"" AND ANY +# EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR +# PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL INTEL CORPORATION OR +# CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, +# EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, +# PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +# PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +# LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +# NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +# SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. diff --git a/selfdrive/visiond/LICENSE.libyuv b/selfdrive/visiond/LICENSE.libyuv new file mode 100644 index 00000000000000..c911747a6b53f0 --- /dev/null +++ b/selfdrive/visiond/LICENSE.libyuv @@ -0,0 +1,29 @@ +Copyright 2011 The LibYuv Project Authors. All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are +met: + + * Redistributions of source code must retain the above copyright + notice, this list of conditions and the following disclaimer. + + * Redistributions in binary form must reproduce the above copyright + notice, this list of conditions and the following disclaimer in + the documentation and/or other materials provided with the + distribution. + + * Neither the name of Google nor the names of its contributors may + be used to endorse or promote products derived from this software + without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +"AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR +A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT +LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, +DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY +THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. diff --git a/selfdrive/visiond/LICENSE.opencv b/selfdrive/visiond/LICENSE.opencv new file mode 100644 index 00000000000000..fce70d71355380 --- /dev/null +++ b/selfdrive/visiond/LICENSE.opencv @@ -0,0 +1,41 @@ +By downloading, copying, installing or using the software you agree to this license. +If you do not agree to this license, do not download, install, +copy or use the software. + + + License Agreement + For Open Source Computer Vision Library + (3-clause BSD License) + +Copyright (C) 2000-2016, Intel Corporation, all rights reserved. +Copyright (C) 2009-2011, Willow Garage Inc., all rights reserved. +Copyright (C) 2009-2016, NVIDIA Corporation, all rights reserved. +Copyright (C) 2010-2013, Advanced Micro Devices, Inc., all rights reserved. +Copyright (C) 2015-2016, OpenCV Foundation, all rights reserved. +Copyright (C) 2015-2016, Itseez Inc., all rights reserved. +Third party copyrights are property of their respective owners. + +Redistribution and use in source and binary forms, with or without modification, +are permitted provided that the following conditions are met: + + * Redistributions of source code must retain the above copyright notice, + this list of conditions and the following disclaimer. + + * Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + + * Neither the names of the copyright holders nor the names of the contributors + may be used to endorse or promote products derived from this software + without specific prior written permission. + +This software is provided by the copyright holders and contributors "as is" and +any express or implied warranties, including, but not limited to, the implied +warranties of merchantability and fitness for a particular purpose are disclaimed. +In no event shall copyright holders or contributors be liable for any direct, +indirect, incidental, special, exemplary, or consequential damages +(including, but not limited to, procurement of substitute goods or services; +loss of use, data, or profits; or business interruption) however caused +and on any theory of liability, whether in contract, strict liability, +or tort (including negligence or otherwise) arising in any way out of +the use of this software, even if advised of the possibility of such damage. diff --git a/selfdrive/visiond/Makefile b/selfdrive/visiond/Makefile new file mode 100644 index 00000000000000..753c5e41ca3182 --- /dev/null +++ b/selfdrive/visiond/Makefile @@ -0,0 +1,4 @@ +-include build_from_src.mk + +release: + @echo "visiond: this is a release" diff --git a/selfdrive/visiond/README b/selfdrive/visiond/README new file mode 100644 index 00000000000000..1b612afcece0ed --- /dev/null +++ b/selfdrive/visiond/README @@ -0,0 +1 @@ +visiond runs the openpilot/chffrplus vision pipeline. Everything running between the camera hardware and model outputs lives here. diff --git a/selfdrive/visiond/SConscript b/selfdrive/visiond/SConscript new file mode 100644 index 00000000000000..e55fbd94d9a63e --- /dev/null +++ b/selfdrive/visiond/SConscript @@ -0,0 +1,17 @@ +Import('env') +lenv = env.Clone() +lenv['CPPPATH'] += ['include'] +lenv['LIBPATH'] += ['/system/vendor/lib64'] +lenv['CFLAGS'] += ' -DQCOM' +lenv['CXXFLAGS'] += ' -DQCOM -U __ANDROID__' +lenv.Program(['visiond.cc', 'model.c', 'transform.c', 'loadyuv.c', 'buffering.c', 'efd.c', + 'yuvmodel.c', 'temporalmodel.c', 'monitoring.c', 'monitoringmodel.c', 'clutil.c', + 'camera_qcom.c', 'visionbuf_ion.c'], + LIBS=['zmq', 'czmq', 'capnp', 'capnp_c', 'kj', 'yaml-cpp', 'z', 'curl', + 'gsl', 'CB', 'OpenCL', + 'opencv_video', 'opencv_imgproc', 'opencv_core', + 'gnustl_shared', 'log', 'cutils', + 'yuv', + 'common', 'cereal', + ]) + diff --git a/selfdrive/visiond/__init__.py b/selfdrive/visiond/__init__.py new file mode 100644 index 00000000000000..e69de29bb2d1d6 diff --git a/selfdrive/visiond/bufs.h b/selfdrive/visiond/bufs.h new file mode 100644 index 00000000000000..71930baede2cfe --- /dev/null +++ b/selfdrive/visiond/bufs.h @@ -0,0 +1,8 @@ +#ifndef _SELFDRIVE_VISIOND_VISIOND_H_ +#define _SELFDRIVE_VISIOND_VISIOND_H_ + +#include + +typedef struct { uint8_t *y, *u, *v; } YUVBuf; + +#endif // _SELFDRIVE_VISIOND_VISIOND_H_ diff --git a/selfdrive/visiond/build_from_src.mk b/selfdrive/visiond/build_from_src.mk new file mode 100644 index 00000000000000..efa151d1d248ef --- /dev/null +++ b/selfdrive/visiond/build_from_src.mk @@ -0,0 +1,227 @@ +CC = clang +CXX = clang++ + +BASEDIR = ../.. +EXTERNAL = ../../external +PHONELIBS = ../../phonelibs + +WARN_FLAGS = -Werror=implicit-function-declaration \ + -Werror=incompatible-pointer-types \ + -Werror=int-conversion \ + -Werror=return-type \ + -Werror=format-extra-args \ + -Wno-deprecated-declarations + +CFLAGS = -std=gnu11 -fPIC -O2 $(WARN_FLAGS) +CXXFLAGS = -std=c++14 -fPIC -O2 $(WARN_FLAGS) + +#ifneq ($(RELEASE),1) +#CFLAGS += -g +#CXXFLAGS += -g +#endif + +JSON_FLAGS = -I$(PHONELIBS)/json/src +JSON11_FLAGS = -I$(PHONELIBS)/json11/ +EIGEN_FLAGS = -I$(PHONELIBS)/eigen + +UNAME_M := $(shell uname -m) +UNAME_S := $(shell uname -s) + +ifeq ($(UNAME_M),x86_64) + +ifeq ($(UNAME_S),Darwin) + LIBYUV_FLAGS = -I$(PHONELIBS)/libyuv/include + LIBYUV_LIBS = $(PHONELIBS)/libyuv/mac/lib/libyuv.a + + ZMQ_FLAGS = -I$(EXTERNAL)/zmq/include + ZMQ_LIBS = $(PHONELIBS)/zmq/mac/lib/libczmq.a \ + $(PHONELIBS)/zmq/mac/lib/libzmq.a + + OPENCL_LIBS = -framework OpenCL +else + LIBYUV_FLAGS = -I$(PHONELIBS)/libyuv/x64/include + LIBYUV_LIBS = $(PHONELIBS)/libyuv/x64/lib/libyuv.a + + ZMQ_FLAGS = -I$(EXTERNAL)/zmq/include + ZMQ_LIBS = -L$(EXTERNAL)/zmq/lib \ + -l:libczmq.a -l:libzmq.a + + OPENCL_LIBS = -lOpenCL +endif + + CURL_FLAGS = -I/usr/include/curl + CURL_LIBS = -lcurl -lz + + SSL_FLAGS = -I/usr/include/openssl/ + SSL_LIBS = -lssl -lcrypto + + OPENCV_FLAGS = + OPENCV_LIBS = -lopencv_video \ + -lopencv_imgproc \ + -lopencv_core + OTHER_LIBS = -lz -lm -lpthread + + PLATFORM_OBJS = camera_fake.o \ + ../common/visionbuf_cl.o + + CFLAGS += -D_GNU_SOURCE \ + -DCLU_NO_CACHE +else + # assume phone + + LIBYUV_FLAGS = -I$(PHONELIBS)/libyuv/include + LIBYUV_LIBS = $(PHONELIBS)/libyuv/lib/libyuv.a + + ZMQ_FLAGS = -I$(PHONELIBS)/zmq/aarch64/include + ZMQ_LIBS = -L$(PHONELIBS)/zmq/aarch64/lib \ + -l:libczmq.a -l:libzmq.a \ + -lgnustl_shared + + CURL_FLAGS = -I$(PHONELIBS)/curl/include + CURL_LIBS = $(PHONELIBS)/curl/lib/libcurl.a \ + $(PHONELIBS)/zlib/lib/libz.a + + SSL_FLAGS = -I$(PHONELIBS)/boringssl/include + SSL_LIBS = $(PHONELIBS)/boringssl/lib/libssl_static.a \ + $(PHONELIBS)/boringssl/lib/libcrypto_static.a + + OPENCL_FLAGS = -I$(PHONELIBS)/opencl/include + OPENCL_LIBS = -lgsl -lCB -lOpenCL + + OPENCV_FLAGS = -I/usr/local/sdk/native/jni/include + OPENCV_LIBS = -L/usr/local/sdk/native/libs \ + -l:libopencv_video.a \ + -l:libopencv_imgproc.a \ + -l:libopencv_core.a + + OPENGL_LIBS = -lGLESv3 -lEGL + + SNPE_FLAGS = -I$(PHONELIBS)/snpe/include/ + SNPE_LIBS = -L$(PHONELIBS)/snpe/lib -lSNPE -lsymphony-cpu -lsymphonypower + + OTHER_LIBS = -lz -lcutils -lm -llog -lui -ladreno_utils + + PLATFORM_OBJS = camera_qcom.o \ + ../common/visionbuf_ion.o + + CFLAGS += -DQCOM + CXXFLAGS += -DQCOM +endif + +OBJS = visiond.o +OUTPUT = visiond + +.PHONY: all +all: $(OUTPUT) + +include ../common/cereal.mk + +OBJS += $(PLATFORM_OBJS) \ + ../common/swaglog.o \ + ../common/ipc.o \ + ../common/visionipc.o \ + ../common/visionimg.o \ + ../common/util.o \ + ../common/params.o \ + ../common/efd.o \ + ../common/buffering.o \ + transform.o \ + loadyuv.o \ + commonmodel.o \ + snpemodel.o \ + monitoring.o \ + model.o \ + clutil.o \ + $(PHONELIBS)/json/src/json.o \ + $(PHONELIBS)/json11/json11.o \ + $(CEREAL_OBJS) + +#MODEL_DATA = ../../models/driving_bigmodel.dlc ../../models/monitoring_model.dlc +MODEL_DATA = ../../models/driving_model.dlc ../../models/monitoring_model.dlc +MODEL_OBJS = $(MODEL_DATA:.dlc=.o) +OBJS += $(MODEL_OBJS) + +ifeq ($(RELEASE),1) +CFLAGS += -DCLU_NO_SRC +CXXFLAGS += -DCLU_NO_SRC +CLCACHE_FILES = $(wildcard /tmp/clcache/*.clb) +CLCACHE_OBJS += $(CLCACHE_FILES:.clb=.o) +OBJS += $(CLCACHE_OBJS) + +clutil.o: clcache_bins.h +clcache_bins.h: $(CLCACHE_FILES) /tmp/clcache/index.cli + rm -f '$@' + for hash in $(basename $(notdir $(CLCACHE_FILES))) ; do \ + echo "extern const uint8_t clb_$$hash[] asm(\"_binary_$${hash}_clb_start\");" ; \ + echo "extern const uint8_t clb_$${hash}_end[] asm(\"_binary_$${hash}_clb_end\");" ; \ + done >> '$@' + echo "static const CLUProgramIndex clu_index[] = {" >> '$@' + while read idx_hash code_hash; do \ + echo "{ 0x$$idx_hash, clb_$${code_hash}, clb_$${code_hash}_end }," ; \ + done < /tmp/clcache/index.cli >> '$@' + echo "};" >> '$@' + +$(CLCACHE_OBJS): %.o: %.clb + @echo "[ bin2o ] $@" + cd '$(dir $<)' && ld -r -b binary '$(notdir $<)' -o '$(abspath $@)' + +LDFLAGS += -s +endif + +DEPS := $(OBJS:.o=.d) + +$(OUTPUT): $(OBJS) + @echo "[ LINK ] $@" + $(CXX) -fPIC -o '$@' $^ \ + $(LDFLAGS) \ + $(LIBYUV_LIBS) \ + $(OPENCV_LIBS) \ + $(OPENGL_LIBS) \ + $(CEREAL_LIBS) \ + $(ZMQ_LIBS) \ + -L/usr/lib \ + -L/system/vendor/lib64 \ + $(OPENCL_LIBS) \ + $(CURL_LIBS) \ + $(SSL_LIBS) \ + $(SNPE_LIBS) \ + $(OTHER_LIBS) + +$(MODEL_OBJS): %.o: %.dlc + @echo "[ bin2o ] $@" + cd '$(dir $<)' && ld -r -b binary '$(notdir $<)' -o '$(abspath $@)' + +%.o: %.cc + @echo "[ CXX ] $@" + $(CXX) $(CXXFLAGS) -MMD \ + -Iinclude -I.. -I../.. \ + $(OPENCV_FLAGS) $(EIGEN_FLAGS) \ + $(ZMQ_FLAGS) \ + $(CEREAL_CXXFLAGS) \ + $(OPENCL_FLAGS) \ + $(LIBYUV_FLAGS) \ + $(SNPE_FLAGS) \ + $(JSON_FLAGS) \ + $(JSON11_FLAGS) $(CURL_FLAGS) \ + -I$(PHONELIBS)/libgralloc/include \ + -I$(PHONELIBS)/linux/include \ + -c -o '$@' '$<' + +%.o: %.c + @echo "[ CC ] $@" + $(CC) $(CFLAGS) -MMD \ + -Iinclude -I.. -I../.. \ + $(ZMQ_FLAGS) \ + $(CEREAL_CFLAGS) \ + $(OPENCL_FLAGS) \ + $(LIBYUV_FLAGS) \ + $(JSON_FLAGS) \ + -I$(PHONELIBS)/libgralloc/include \ + -I$(PHONELIBS)/linux/include \ + -c -o '$@' '$<' + +.PHONY: clean +clean: + rm -f visiond $(OBJS) $(DEPS) + +-include $(DEPS) diff --git a/selfdrive/visiond/camera_common.h b/selfdrive/visiond/camera_common.h new file mode 100644 index 00000000000000..cea6a9d125d3cd --- /dev/null +++ b/selfdrive/visiond/camera_common.h @@ -0,0 +1,46 @@ +#ifndef CAMERA_COMMON_H +#define CAMERA_COMMON_H + +#include +#include + +#define CAMERA_ID_IMX298 0 +#define CAMERA_ID_IMX179 1 +#define CAMERA_ID_S5K3P8SP 2 +#define CAMERA_ID_OV8865 3 +#define CAMERA_ID_IMX298_FLIPPED 4 +#define CAMERA_ID_OV10640 5 +#define CAMERA_ID_MAX 6 + +#ifdef __cplusplus +extern "C" { +#endif + +typedef struct CameraInfo { + const char* name; + int frame_width, frame_height; + int frame_stride; + bool bayer; + int bayer_flip; + bool hdr; +} CameraInfo; + +typedef struct FrameMetadata { + uint32_t frame_id; + uint64_t timestamp_eof; + unsigned int frame_length; + unsigned int integ_lines; + unsigned int global_gain; + unsigned int lens_pos; + float lens_sag; + float lens_err; + float lens_true_pos; +} FrameMetadata; + +extern CameraInfo cameras_supported[CAMERA_ID_MAX]; + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/selfdrive/visiond/camera_fake.cc b/selfdrive/visiond/camera_fake.cc new file mode 100644 index 00000000000000..5b7c9cb7b92399 --- /dev/null +++ b/selfdrive/visiond/camera_fake.cc @@ -0,0 +1,267 @@ +#include "camera_fake.h" + +#include +#include +#include + +#include +#include +#include +#include "cereal/gen/cpp/log.capnp.h" + +#include "common/util.h" +#include "common/timing.h" +#include "common/swaglog.h" +#include "buffering.h" + +extern volatile int do_exit; + +#define FRAME_WIDTH 1164 +#define FRAME_HEIGHT 874 + +namespace { +void camera_open(CameraState *s, VisionBuf *camera_bufs, bool rear) { + assert(camera_bufs); + s->camera_bufs = camera_bufs; +} + +void camera_close(CameraState *s) { + tbuffer_stop(&s->camera_tb); +} + +void camera_release_buffer(void *cookie, int buf_idx) { + CameraState *s = static_cast(cookie); +} + +void camera_init(CameraState *s, int camera_id, unsigned int fps) { + assert(camera_id < ARRAYSIZE(cameras_supported)); + s->ci = cameras_supported[camera_id]; + assert(s->ci.frame_width != 0); + + s->frame_size = s->ci.frame_height * s->ci.frame_stride; + s->fps = fps; + + tbuffer_init2(&s->camera_tb, FRAME_BUF_COUNT, "frame", camera_release_buffer, + s); +} + + +void run_simulator(DualCameraState *s) { + int err = 0; + + zsock_t *frame_sock = zsock_new_sub(">tcp://127.0.0.1:9003", ""); + assert(frame_sock); + void *frame_sock_raw = zsock_resolve(frame_sock); + + CameraState *const rear_camera = &s->rear; + + auto *tb = &rear_camera->camera_tb; + + while (!do_exit) { + const int buf_idx = tbuffer_select(tb); + + auto *buf = &rear_camera->camera_bufs[buf_idx]; + + zmq_msg_t t_msg; + err = zmq_msg_init(&t_msg); + assert(err == 0); + + zmq_msg_t frame_msg; + err = zmq_msg_init(&frame_msg); + assert(err == 0); + + // recv multipart (t, frame) + err = zmq_msg_recv(&t_msg, frame_sock_raw, 0); + assert(err != -1); + err = zmq_msg_recv(&frame_msg, frame_sock_raw, 0); + assert(err != -1); + + assert(zmq_msg_size(&t_msg) >= 8); + uint8_t* dat = (uint8_t*)zmq_msg_data(&t_msg); + float t = *(float*)&dat[0]; + uint32_t frame = *(uint32_t*)&dat[4]; + + rear_camera->camera_bufs_metadata[buf_idx] = { + .frame_id = frame, + .timestamp_eof = nanos_since_boot(), + .frame_length = 0, + .integ_lines = 0, + .global_gain = 0, + }; + + + assert(zmq_msg_size(&frame_msg) == rear_camera->frame_size); + + err = libyuv::RAWToRGB24((const uint8_t*)zmq_msg_data(&frame_msg), rear_camera->ci.frame_width*3, + (uint8_t*)buf->addr, rear_camera->ci.frame_stride, + rear_camera->ci.frame_width, rear_camera->ci.frame_height); + assert(err == 0); + + visionbuf_sync(buf, VISIONBUF_SYNC_TO_DEVICE); + tbuffer_dispatch(tb, buf_idx); + + err = zmq_msg_close(&frame_msg); + assert(err == 0); + err = zmq_msg_close(&t_msg); + assert(err == 0); + } + + zsock_destroy(&frame_sock); +} + +void run_unlogger(DualCameraState *s) { + zsock_t *frame_sock = zsock_new_sub(NULL, ""); + assert(frame_sock); + int err = zsock_connect(frame_sock, + "ipc:///tmp/9464f05d-9d88-4fc9-aa17-c75352d9590d"); + assert(err == 0); + void *frame_sock_raw = zsock_resolve(frame_sock); + + CameraState *const rear_camera = &s->rear; + auto frame_data = std::vector{}; + + auto *tb = &rear_camera->camera_tb; + + while (!do_exit) { + // Handle rear camera only. + zmq_msg_t msg; + int rc = zmq_msg_init(&msg); + assert(rc == 0); + rc = zmq_msg_recv(&msg, frame_sock_raw, 0); + if (rc == -1) { + if (do_exit) { + break; + } else { + fprintf(stderr, "Could not recv frame message: %d\n", errno); + } + } + assert(rc != -1); + + const size_t msg_size_words = zmq_msg_size(&msg) / sizeof(capnp::word); + assert(msg_size_words * sizeof(capnp::word) == zmq_msg_size(&msg)); + + if (frame_data.size() < msg_size_words) { + frame_data = std::vector{msg_size_words}; + } + std::memcpy(frame_data.data(), zmq_msg_data(&msg), + msg_size_words * sizeof(*frame_data.data())); + zmq_msg_close(&msg); + + capnp::FlatArrayMessageReader message{ + kj::arrayPtr(frame_data.data(), msg_size_words), {}}; + + const auto &event = message.getRoot(); + assert(event.which() == cereal::Event::FRAME); + const auto reader = event.getFrame(); + assert(reader.hasImage()); + const auto yuv_image = reader.getImage(); + + // Copy camera data to buffer. + const size_t width = rear_camera->ci.frame_width; + const size_t height = rear_camera->ci.frame_height; + + const size_t y_len = width * height; + const uint8_t *const y = yuv_image.begin(); + const uint8_t *const u = y + y_len; + const uint8_t *const v = u + y_len / 4; + + assert(yuv_image.size() == y_len * 3 / 2); + + const int buf_idx = tbuffer_select(tb); + rear_camera->camera_bufs_metadata[buf_idx] = { + .frame_id = reader.getFrameId(), + .timestamp_eof = reader.getTimestampEof(), + .frame_length = static_cast(reader.getFrameLength()), + .integ_lines = static_cast(reader.getIntegLines()), + .global_gain = static_cast(reader.getGlobalGain()), + }; + + auto *buf = &rear_camera->camera_bufs[buf_idx]; + uint8_t *const rgb = static_cast(buf->addr); + + // Convert to RGB. + const int result = libyuv::I420ToRGB24(y, width, u, width / 2, v, width / 2, + rgb, width * 3, width, height); + assert(result == 0); + + visionbuf_sync(buf, VISIONBUF_SYNC_TO_DEVICE); + + // HACK(mgraczyk): Do not drop frames. + while (*(volatile int*)&tb->pending_idx != -1) { + usleep(20000); + } + tbuffer_dispatch(tb, buf_idx); + } + + zsock_destroy(&frame_sock); +} + +} // namespace + +CameraInfo cameras_supported[CAMERA_ID_MAX] = { + [CAMERA_ID_IMX298] = { + .frame_width = FRAME_WIDTH, + .frame_height = FRAME_HEIGHT, + .frame_stride = FRAME_WIDTH*3, + .bayer = false, + .bayer_flip = false, + }, +}; + +void cameras_init(DualCameraState *s) { + memset(s, 0, sizeof(*s)); + + camera_init(&s->rear, CAMERA_ID_IMX298, 20); + camera_init(&s->front, CAMERA_ID_IMX298, 20); + + if (getenv("SIMULATOR2")) { + // simulator camera is flipped vertically + s->rear.transform = (mat3){{ + 1.0, 0.0, 0.0, + 0.0, -1.0, s->rear.ci.frame_height - 1.0f, + 0.0, 0.0, 1.0, + }}; + } else { + // assume the input is upside-down + s->rear.transform = (mat3){{ + -1.0, 0.0, s->rear.ci.frame_width - 1.0f, + 0.0, -1.0, s->rear.ci.frame_height - 1.0f, + 0.0, 0.0, 1.0, + }}; + } +} + +void cameras_open(DualCameraState *s, VisionBuf *camera_bufs_rear, + VisionBuf *camera_bufs_focus, VisionBuf *camera_bufs_stats, + VisionBuf *camera_bufs_front) { + assert(camera_bufs_rear); + assert(camera_bufs_front); + int err; + + // LOG("*** open front ***"); + camera_open(&s->front, camera_bufs_front, false); + + // LOG("*** open rear ***"); + camera_open(&s->rear, camera_bufs_rear, true); +} + +void cameras_close(DualCameraState *s) { + camera_close(&s->rear); + camera_close(&s->front); +} + +void camera_autoexposure(CameraState *s, float grey_frac) {} + + +void cameras_run(DualCameraState *s) { + set_thread_name("fake_camera"); + + if (getenv("SIMULATOR2")) { + run_simulator(s); + } else { + run_unlogger(s); + } + + cameras_close(s); + +} diff --git a/selfdrive/visiond/camera_fake.h b/selfdrive/visiond/camera_fake.h new file mode 100644 index 00000000000000..04ad01a6d06ef7 --- /dev/null +++ b/selfdrive/visiond/camera_fake.h @@ -0,0 +1,52 @@ +#ifndef FAKE_CAMERA_H +#define FAKE_CAMERA_H + +#include + +#include "common/mat.h" + +#include "buffering.h" +#include "common/visionbuf.h" +#include "camera_common.h" + +#define FRAME_BUF_COUNT 4 + +#ifdef __cplusplus +extern "C" { +#endif + +typedef struct CameraState { + int camera_id; + CameraInfo ci; + int frame_size; + + VisionBuf *camera_bufs; + FrameMetadata camera_bufs_metadata[FRAME_BUF_COUNT]; + TBuffer camera_tb; + + int fps; + float digital_gain; + + mat3 transform; +} CameraState; + + +typedef struct DualCameraState { + int ispif_fd; + + CameraState rear; + CameraState front; +} DualCameraState; + +void cameras_init(DualCameraState *s); +void cameras_open(DualCameraState *s, VisionBuf *camera_bufs_rear, VisionBuf *camera_bufs_focus, VisionBuf *camera_bufs_stats, VisionBuf *camera_bufs_front); +void cameras_run(DualCameraState *s); +void cameras_close(DualCameraState *s); + +void camera_autoexposure(CameraState *s, float grey_frac); + +#ifdef __cplusplus +} // extern "C" +#endif + +#endif diff --git a/selfdrive/visiond/camera_qcom.c b/selfdrive/visiond/camera_qcom.c new file mode 100644 index 00000000000000..08a1dff6526e8c --- /dev/null +++ b/selfdrive/visiond/camera_qcom.c @@ -0,0 +1,2275 @@ +#include +#include +#include +#include +#include +#include +#include +#include + +#include + +#include + +#include +#include + +#include "msmb_isp.h" +#include "msmb_ispif.h" +#include "msmb_camera.h" +#include "msm_cam_sensor.h" + +#include "common/util.h" +#include "common/timing.h" +#include "common/swaglog.h" +#include "common/params.h" + +#include "cereal/gen/c/log.capnp.h" + +#include "sensor_i2c.h" + +#include "camera_qcom.h" + + +// enable this to run the camera at 60fps and sample every third frame +// supposed to reduce 33ms of lag, but no results +//#define HIGH_FPS + +#define CAMERA_MSG_AUTOEXPOSE 0 + +typedef struct CameraMsg { + int type; + int camera_num; + + float grey_frac; +} CameraMsg; + +extern volatile int do_exit; + +CameraInfo cameras_supported[CAMERA_ID_MAX] = { + [CAMERA_ID_IMX298] = { + .frame_width = 2328, + .frame_height = 1748, + .frame_stride = 2912, + .bayer = true, + .bayer_flip = 0, + .hdr = true + }, + [CAMERA_ID_IMX179] = { + .frame_width = 3280, + .frame_height = 2464, + .frame_stride = 4104, + .bayer = true, + .bayer_flip = 0, + .hdr = false + }, + [CAMERA_ID_S5K3P8SP] = { + .frame_width = 2304, + .frame_height = 1728, + .frame_stride = 2880, + .bayer = true, + .bayer_flip = 1, + .hdr = false + }, + [CAMERA_ID_OV8865] = { + .frame_width = 1632, + .frame_height = 1224, + .frame_stride = 2040, // seems right + .bayer = true, + .bayer_flip = 3, + .hdr = false + }, + // this exists to get the kernel to build for the LeEco in release + [CAMERA_ID_IMX298_FLIPPED] = { + .frame_width = 2328, + .frame_height = 1748, + .frame_stride = 2912, + .bayer = true, + .bayer_flip = 3, + .hdr = true + }, + [CAMERA_ID_OV10640] = { + .frame_width = 1280, + .frame_height = 1080, + .frame_stride = 2040, + .bayer = true, + .bayer_flip = 0, + .hdr = true + }, +}; + +static void camera_release_buffer(void* cookie, int buf_idx) { + CameraState *s = cookie; + // printf("camera_release_buffer %d\n", buf_idx); + s->ss[0].qbuf_info[buf_idx].dirty_buf = 1; + ioctl(s->isp_fd, VIDIOC_MSM_ISP_ENQUEUE_BUF, &s->ss[0].qbuf_info[buf_idx]); +} + +static void camera_init(CameraState *s, int camera_id, int camera_num, + uint32_t pixel_clock, uint32_t line_length_pclk, + unsigned int max_gain, unsigned int fps) { + memset(s, 0, sizeof(*s)); + + s->camera_num = camera_num; + s->camera_id = camera_id; + + assert(camera_id < ARRAYSIZE(cameras_supported)); + s->ci = cameras_supported[camera_id]; + assert(s->ci.frame_width != 0); + s->frame_size = s->ci.frame_height * s->ci.frame_stride; + + s->pixel_clock = pixel_clock; + s->line_length_pclk = line_length_pclk; + s->max_gain = max_gain; + s->fps = fps; + + zsock_t *ops_sock = zsock_new_push(">inproc://cameraops"); + assert(ops_sock); + s->ops_sock = zsock_resolve(ops_sock); + + tbuffer_init2(&s->camera_tb, FRAME_BUF_COUNT, "frame", + camera_release_buffer, s); + + pthread_mutex_init(&s->frame_info_lock, NULL); +} + + +int sensor_write_regs(CameraState *s, struct msm_camera_i2c_reg_array* arr, size_t size, int data_type) { + struct msm_camera_i2c_reg_setting out_settings = { + .reg_setting = arr, + .size = size, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .data_type = data_type, + .delay = 0, + }; + struct sensorb_cfg_data cfg_data = {0}; + cfg_data.cfgtype = CFG_WRITE_I2C_ARRAY; + cfg_data.cfg.setting = &out_settings; + return ioctl(s->sensor_fd, VIDIOC_MSM_SENSOR_CFG, &cfg_data); +} + +static int imx298_apply_exposure(CameraState *s, int gain, int integ_lines, int frame_length) { + int err; + + int analog_gain = min(gain, 448); + + if (gain > 448) { + s->digital_gain = (512.0/(512-(gain))) / 8.0; + } else { + s->digital_gain = 1.0; + } + + //printf("%5d/%5d %5d %f\n", s->cur_integ_lines, s->cur_frame_length, analog_gain, s->digital_gain); + + int digital_gain = 0x100; + + float white_balance[] = {0.4609375, 1.0, 0.546875}; + //float white_balance[] = {1.0, 1.0, 1.0}; + + int digital_gain_gr = digital_gain / white_balance[1]; + int digital_gain_gb = digital_gain / white_balance[1]; + int digital_gain_r = digital_gain / white_balance[0]; + int digital_gain_b = digital_gain / white_balance[2]; + + struct msm_camera_i2c_reg_array reg_array[] = { + // REG_HOLD + {0x104,0x1,0}, + {0x3002,0x0,0}, // long autoexposure off + + // FRM_LENGTH + {0x340, frame_length >> 8, 0}, {0x341, frame_length & 0xff, 0}, + // INTEG_TIME aka coarse_int_time_addr aka shutter speed + {0x202, integ_lines >> 8, 0}, {0x203, integ_lines & 0xff,0}, + // global_gain_addr + // if you assume 1x gain is 32, 448 is 14x gain, aka 2^14=16384 + {0x204, analog_gain >> 8, 0}, {0x205, analog_gain & 0xff,0}, + + // digital gain for colors: gain_greenR, gain_red, gain_blue, gain_greenB + /*{0x20e, digital_gain_gr >> 8, 0}, {0x20f,digital_gain_gr & 0xFF,0}, + {0x210, digital_gain_r >> 8, 0}, {0x211,digital_gain_r & 0xFF,0}, + {0x212, digital_gain_b >> 8, 0}, {0x213,digital_gain_b & 0xFF,0}, + {0x214, digital_gain_gb >> 8, 0}, {0x215,digital_gain_gb & 0xFF,0},*/ + + // REG_HOLD + {0x104,0x0,0}, + }; + + err = sensor_write_regs(s, reg_array, ARRAYSIZE(reg_array), MSM_CAMERA_I2C_BYTE_DATA); + if (err != 0) { + LOGE("apply_exposure err %d", err); + } + return err; +} + +static inline int ov8865_get_coarse_gain(int gain) { + static const int gains[] = {0, 256, 384, 448, 480}; + int i; + + for (i = 1; i < ARRAYSIZE(gains); i++) { + if (gain >= gains[i - 1] && gain < gains[i]) + break; + } + + return i - 1; +} + +static int ov8865_apply_exposure(CameraState *s, int gain, int integ_lines, int frame_length) { + //printf("front camera: %d %d %d\n", gain, integ_lines, frame_length); + int err, gain_bitmap; + gain_bitmap = (1 << ov8865_get_coarse_gain(gain)) - 1; + integ_lines *= 16; // The exposure value in reg is in 16ths of a line + struct msm_camera_i2c_reg_array reg_array[] = { + //{0x104,0x1,0}, + + // FRM_LENGTH + {0x380e, frame_length >> 8, 0}, {0x380f, frame_length & 0xff, 0}, + // AEC EXPO + {0x3500, integ_lines >> 16, 0}, {0x3501, integ_lines >> 8, 0}, {0x3502, integ_lines & 0xff,0}, + // AEC MANUAL + {0x3503, 0x4, 0}, + // AEC GAIN + {0x3508, gain_bitmap, 0}, {0x3509, 0xf8, 0}, + + //{0x104,0x0,0}, + }; + err = sensor_write_regs(s, reg_array, ARRAYSIZE(reg_array), MSM_CAMERA_I2C_BYTE_DATA); + if (err != 0) { + LOGE("apply_exposure err %d", err); + } + return err; +} + +static int imx179_s5k3p8sp_apply_exposure(CameraState *s, int gain, int integ_lines, int frame_length) { + //printf("front camera: %d %d %d\n", gain, integ_lines, frame_length); + int err; + + if (gain > 448) { + s->digital_gain = (512.0/(512-(gain))) / 8.0; + } else { + s->digital_gain = 1.0; + } + + struct msm_camera_i2c_reg_array reg_array[] = { + {0x104,0x1,0}, + + // FRM_LENGTH + {0x340, frame_length >> 8, 0}, {0x341, frame_length & 0xff, 0}, + // coarse_int_time + {0x202, integ_lines >> 8, 0}, {0x203, integ_lines & 0xff,0}, + // global_gain + {0x204, gain >> 8, 0}, {0x205, gain & 0xff,0}, + + {0x104,0x0,0}, + }; + err = sensor_write_regs(s, reg_array, ARRAYSIZE(reg_array), MSM_CAMERA_I2C_BYTE_DATA); + if (err != 0) { + LOGE("apply_exposure err %d", err); + } + return err; +} + +void cameras_init(DualCameraState *s) { + memset(s, 0, sizeof(*s)); + + char project_name[1024] = {0}; + property_get("ro.boot.project_name", project_name, ""); + + char product_name[1024] = {0}; + property_get("ro.product.name", product_name, ""); + + if (strlen(project_name) == 0) { + LOGD("LePro 3 op system detected"); + s->device = DEVICE_LP3; + + // sensor is flipped in LP3 + // IMAGE_ORIENT = 3 + init_array_imx298[0].reg_data = 3; + cameras_supported[CAMERA_ID_IMX298].bayer_flip = 3; + } else if (strcmp(product_name, "OnePlus3") == 0 && strcmp(project_name, "15811") != 0) { + // no more OP3 support + s->device = DEVICE_OP3; + assert(false); + } else if (strcmp(product_name, "OnePlus3") == 0 && strcmp(project_name, "15811") == 0) { + // only OP3T support + s->device = DEVICE_OP3T; + } else if (strcmp(product_name, "LePro3") == 0) { + LOGD("LePro 3 detected"); + s->device = DEVICE_LP3; + assert(false); + } else { + assert(false); + } + + // 0 = ISO 100 + // 256 = ISO 200 + // 384 = ISO 400 + // 448 = ISO 800 + // 480 = ISO 1600 + // 496 = ISO 3200 + // 504 = ISO 6400, 8x digital gain + // 508 = ISO 12800, 16x digital gain + // 510 = ISO 25600, 32x digital gain + + camera_init(&s->rear, CAMERA_ID_IMX298, 0, + /*pixel_clock=*/600000000, /*line_length_pclk=*/5536, + /*max_gain=*/510, //0 (ISO 100)- 448 (ISO 800, max analog gain) - 511 (super noisy) +#ifdef HIGH_FPS + /*fps*/60 +#else + /*fps*/20 +#endif + ); + s->rear.apply_exposure = imx298_apply_exposure; + + if (s->device == DEVICE_OP3T) { + camera_init(&s->front, CAMERA_ID_S5K3P8SP, 1, + /*pixel_clock=*/561000000, /*line_length_pclk=*/5120, + /*max_gain=*/510, 10); + s->front.apply_exposure = imx179_s5k3p8sp_apply_exposure; + } else if (s->device == DEVICE_LP3) { + camera_init(&s->front, CAMERA_ID_OV8865, 1, + /*pixel_clock=*/251200000, /*line_length_pclk=*/7000, + /*max_gain=*/510, 10); + s->front.apply_exposure = ov8865_apply_exposure; + } else { + camera_init(&s->front, CAMERA_ID_IMX179, 1, + /*pixel_clock=*/251200000, /*line_length_pclk=*/3440, + /*max_gain=*/224, 20); + s->front.apply_exposure = imx179_s5k3p8sp_apply_exposure; + } + + // assume the device is upside-down (not anymore) + s->rear.transform = (mat3){{ + 1.0, 0.0, 0.0, + 0.0, 1.0, 0.0, + 0.0, 0.0, 1.0, + }}; + + // probably wrong + s->front.transform = (mat3){{ + 1.0, 0.0, 0.0, + 0.0, 1.0, 0.0, + 0.0, 0.0, 1.0, + }}; + + s->rear.device = s->device; + s->front.device = s->device; +} + +static void set_exposure(CameraState *s, float exposure_frac, float gain_frac) { + int err = 0; + + unsigned int frame_length = s->pixel_clock / s->line_length_pclk / s->fps; + + unsigned int gain = s->cur_gain; + unsigned int integ_lines = s->cur_integ_lines; + + if (exposure_frac >= 0) { + exposure_frac = clamp(exposure_frac, 2.0 / frame_length, 1.0); + integ_lines = frame_length * exposure_frac; + + // See page 79 of the datasheet, this is the max allowed (-1 for phase adjust) + integ_lines = min(integ_lines, frame_length-11); + } + + // done after exposure to not adjust it + if (s->using_pll) { + // can adjust frame length by up to +/- 1 + const int PHASE_DEADZONE = 20000; // 20 us + int phase_max = 1000000000 / s->fps; + int phase_diff = s->phase_actual - s->phase_request; + phase_diff = ((phase_diff + phase_max/2) % phase_max) - phase_max/2; + + if (phase_diff < -PHASE_DEADZONE) { + frame_length += 1; + } else if (phase_diff > PHASE_DEADZONE) { + frame_length -= 1; + } + } + + if (gain_frac >= 0) { + // ISO200 is minimum gain + gain_frac = clamp(gain_frac, 1.0/64, 1.0); + + // linearize gain response + // TODO: will be wrong for front camera + // 0.125 -> 448 + // 0.25 -> 480 + // 0.5 -> 496 + // 1.0 -> 504 + // 512 - 512/(128*gain_frac) + gain = (s->max_gain/510) * (512 - 512/(256*gain_frac)); + } + + if (gain != s->cur_gain + || integ_lines != s->cur_integ_lines + || frame_length != s->cur_frame_length) { + + if (s->apply_exposure) { + err = s->apply_exposure(s, gain, integ_lines, frame_length); + } + + if (err == 0) { + pthread_mutex_lock(&s->frame_info_lock); + s->cur_gain = gain; + s->cur_integ_lines = integ_lines; + s->cur_frame_length = frame_length; + pthread_mutex_unlock(&s->frame_info_lock); + } + } + + if (err == 0) { + s->cur_exposure_frac = exposure_frac; + s->cur_gain_frac = gain_frac; + } + + LOGD("set exposure: %f %f - %d", exposure_frac, gain_frac, err); +} + +static void do_autoexposure(CameraState *s, float grey_frac) { + const float target_grey = 0.3; + + float new_exposure = s->cur_exposure_frac; + new_exposure *= pow(1.05, (target_grey - grey_frac) / 0.05 ); + LOGD("diff %f: %f to %f", target_grey - grey_frac, s->cur_exposure_frac, new_exposure); + + float new_gain = s->cur_gain_frac; + if (new_exposure < 0.10) { + new_gain *= 0.95; + } else if (new_exposure > 0.40) { + new_gain *= 1.05; + } + + set_exposure(s, new_exposure, new_gain); +} + +void camera_autoexposure(CameraState *s, float grey_frac) { + CameraMsg msg = { + .type = CAMERA_MSG_AUTOEXPOSE, + .camera_num = s->camera_num, + .grey_frac = grey_frac, + }; + + zmq_send(s->ops_sock, &msg, sizeof(msg), ZMQ_DONTWAIT); +} + +static uint8_t* get_eeprom(int eeprom_fd, size_t *out_len) { + int err; + + struct msm_eeprom_cfg_data cfg = {0}; + cfg.cfgtype = CFG_EEPROM_GET_CAL_DATA; + err = ioctl(eeprom_fd, VIDIOC_MSM_EEPROM_CFG, &cfg); + assert(err >= 0); + + uint32_t num_bytes = cfg.cfg.get_data.num_bytes; + assert(num_bytes > 100); + + uint8_t* buffer = malloc(num_bytes); + assert(buffer); + memset(buffer, 0, num_bytes); + + cfg.cfgtype = CFG_EEPROM_READ_CAL_DATA; + cfg.cfg.read_data.num_bytes = num_bytes; + cfg.cfg.read_data.dbuffer = buffer; + err = ioctl(eeprom_fd, VIDIOC_MSM_EEPROM_CFG, &cfg); + assert(err >= 0); + + *out_len = num_bytes; + return buffer; +} + +static void imx298_ois_calibration(int ois_fd, uint8_t* eeprom) { + int err; + + const int ois_registers[][2] = { + // == SET_FADJ_PARAM() == (factory adjustment) + + // Set Hall Current DAC + {0x8230, *(uint16_t*)(eeprom+0x102)}, //_P_30_ADC_CH0 (CURDAT) + + // Set Hall PreAmp Offset + {0x8231, *(uint16_t*)(eeprom+0x104)}, //_P_31_ADC_CH1 (HALOFS_X) + {0x8232, *(uint16_t*)(eeprom+0x106)}, //_P_32_ADC_CH2 (HALOFS_Y) + + // Set Hall-X/Y PostAmp Offset + {0x841e, *(uint16_t*)(eeprom+0x108)}, //_M_X_H_ofs + {0x849e, *(uint16_t*)(eeprom+0x10a)}, //_M_Y_H_ofs + + // Set Residual Offset + {0x8239, *(uint16_t*)(eeprom+0x10c)}, //_P_39_Ch3_VAL_1 (PSTXOF) + {0x823b, *(uint16_t*)(eeprom+0x10e)}, //_P_3B_Ch3_VAL_3 (PSTYOF) + + // DIGITAL GYRO OFFSET + {0x8406, *(uint16_t*)(eeprom+0x110)}, //_M_Kgx00 + {0x8486, *(uint16_t*)(eeprom+0x112)}, //_M_Kgy00 + {0x846a, *(uint16_t*)(eeprom+0x120)}, //_M_TMP_X_ + {0x846b, *(uint16_t*)(eeprom+0x122)}, //_M_TMP_Y_ + + // HALLSENSE + // Set Hall Gain + {0x8446, *(uint16_t*)(eeprom+0x114)}, //_M_KgxHG + {0x84c6, *(uint16_t*)(eeprom+0x116)}, //_M_KgyHG + // Set Cross Talk Canceller + {0x8470, *(uint16_t*)(eeprom+0x124)}, //_M_KgxH0 + {0x8472, *(uint16_t*)(eeprom+0x126)}, //_M_KgyH0 + + // LOOPGAIN + {0x840f, *(uint16_t*)(eeprom+0x118)}, //_M_KgxG + {0x848f, *(uint16_t*)(eeprom+0x11a)}, //_M_KgyG + + // Position Servo ON ( OIS OFF ) + {0x847f, 0x0c0c}, //_M_EQCTL + }; + + + struct msm_ois_cfg_data cfg = {0}; + struct msm_camera_i2c_seq_reg_array ois_reg_settings[ARRAYSIZE(ois_registers)] = {{0}}; + for (int i=0; i> 8) & 0xff; + ois_reg_settings[i].reg_data_size = 2; + } + struct msm_camera_i2c_seq_reg_setting ois_reg_setting = { + .reg_setting = &ois_reg_settings[0], + .size = ARRAYSIZE(ois_reg_settings), + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .delay = 0, + }; + cfg.cfgtype = CFG_OIS_I2C_WRITE_SEQ_TABLE; + cfg.cfg.settings = &ois_reg_setting; + err = ioctl(ois_fd, VIDIOC_MSM_OIS_CFG, &cfg); + LOG("ois reg calibration: %d", err); +} + + + + +static void sensors_init(DualCameraState *s) { + int err; + + int sensorinit_fd = -1; + if (s->device == DEVICE_LP3) { + sensorinit_fd = open("/dev/v4l-subdev11", O_RDWR | O_NONBLOCK); + } else { + sensorinit_fd = open("/dev/v4l-subdev12", O_RDWR | O_NONBLOCK); + } + assert(sensorinit_fd >= 0); + + struct sensor_init_cfg_data sensor_init_cfg = {0}; + + // init rear sensor + + struct msm_camera_sensor_slave_info slave_info = {0}; + if (s->device == DEVICE_LP3) { + slave_info = (struct msm_camera_sensor_slave_info){ + .sensor_name = "imx298", + .eeprom_name = "sony_imx298", + .actuator_name = "dw9800w", + .ois_name = "", + .flash_name = "pmic", + .camera_id = 0, + .slave_addr = 32, + .i2c_freq_mode = 1, + .addr_type = 2, + .sensor_id_info = { + .sensor_id_reg_addr = 22, + .sensor_id = 664, + .sensor_id_mask = 0, + .module_id = 9, + .vcm_id = 6, + }, + .power_setting_array = { + .power_setting_a = { + { + .seq_type = 1, + .seq_val = 0, + .config_val = 0, + .delay = 1, + },{ + .seq_type = 2, + .seq_val = 2, + .config_val = 0, + .delay = 0, + },{ + .seq_type = 1, + .seq_val = 5, + .config_val = 2, + .delay = 0, + },{ + .seq_type = 2, + .seq_val = 1, + .config_val = 0, + .delay = 0, + },{ + .seq_type = 2, + .seq_val = 3, + .config_val = 0, + .delay = 1, + },{ + .seq_type = 0, + .seq_val = 0, + .config_val = 24000000, + .delay = 1, + },{ + .seq_type = 1, + .seq_val = 0, + .config_val = 2, + .delay = 10, + }, + }, + .size = 7, + .power_down_setting_a = { + { + .seq_type = 0, + .seq_val = 0, + .config_val = 0, + .delay = 1, + },{ + .seq_type = 1, + .seq_val = 0, + .config_val = 0, + .delay = 1, + },{ + .seq_type = 2, + .seq_val = 1, + .config_val = 0, + .delay = 0, + },{ + .seq_type = 1, + .seq_val = 5, + .config_val = 0, + .delay = 0, + },{ + .seq_type = 2, + .seq_val = 2, + .config_val = 0, + .delay = 0, + },{ + .seq_type = 2, + .seq_val = 3, + .config_val = 0, + .delay = 1, + }, + }, + .size_down = 6, + }, + .is_init_params_valid = 0, + .sensor_init_params = { + .modes_supported = 1, + .position = 0, + .sensor_mount_angle = 90, + }, + .output_format = 0, + }; + } else { + slave_info = (struct msm_camera_sensor_slave_info){ + .sensor_name = "imx298", + .eeprom_name = "sony_imx298", + .actuator_name = "rohm_bu63165gwl", + .ois_name = "rohm_bu63165gwl", + .camera_id = 0, + .slave_addr = 52, + .i2c_freq_mode = 2, + .addr_type = 2, + .sensor_id_info = { + .sensor_id_reg_addr = 22, + .sensor_id = 664, + .sensor_id_mask = 0, + }, + .power_setting_array = { + .power_setting_a = { + { + .seq_type = 1, + .seq_val = 0, + .config_val = 0, + .delay = 2, + },{ + .seq_type = 2, + .seq_val = 2, + .config_val = 0, + .delay = 2, + },{ + .seq_type = 2, + .seq_val = 0, + .config_val = 0, + .delay = 2, + },{ + .seq_type = 2, + .seq_val = 1, + .config_val = 0, + .delay = 2, + },{ + .seq_type = 1, + .seq_val = 6, + .config_val = 2, + .delay = 0, + },{ + .seq_type = 2, + .seq_val = 3, + .config_val = 0, + .delay = 5, + },{ + .seq_type = 2, + .seq_val = 4, + .config_val = 0, + .delay = 5, + },{ + .seq_type = 0, + .seq_val = 0, + .config_val = 24000000, + .delay = 2, + },{ + .seq_type = 1, + .seq_val = 0, + .config_val = 2, + .delay = 2, + }, + }, + .size = 9, + .power_down_setting_a = { + { + .seq_type = 1, + .seq_val = 0, + .config_val = 0, + .delay = 10, + },{ + .seq_type = 0, + .seq_val = 0, + .config_val = 0, + .delay = 1, + },{ + .seq_type = 2, + .seq_val = 4, + .config_val = 0, + .delay = 0, + },{ + .seq_type = 2, + .seq_val = 3, + .config_val = 0, + .delay = 1, + },{ + .seq_type = 1, + .seq_val = 6, + .config_val = 0, + .delay = 0, + },{ + .seq_type = 2, + .seq_val = 1, + .config_val = 0, + .delay = 0, + },{ + .seq_type = 2, + .seq_val = 0, + .config_val = 0, + .delay = 0, + },{ + .seq_type = 2, + .seq_val = 2, + .config_val = 0, + .delay = 0, + }, + }, + .size_down = 8, + }, + .is_init_params_valid = 0, + .sensor_init_params = { + .modes_supported = 1, + .position = 0, + .sensor_mount_angle = 360, + }, + .output_format = 0, + }; + } + slave_info.power_setting_array.power_setting = + (struct msm_sensor_power_setting *)&slave_info.power_setting_array.power_setting_a[0]; + slave_info.power_setting_array.power_down_setting = + (struct msm_sensor_power_setting *)&slave_info.power_setting_array.power_down_setting_a[0]; + sensor_init_cfg.cfgtype = CFG_SINIT_PROBE; + sensor_init_cfg.cfg.setting = &slave_info; + err = ioctl(sensorinit_fd, VIDIOC_MSM_SENSOR_INIT_CFG, &sensor_init_cfg); + LOG("sensor init cfg (rear): %d", err); + assert(err >= 0); + + + struct msm_camera_sensor_slave_info slave_info2 = {0}; + if (s->device == DEVICE_LP3) { + slave_info2 = (struct msm_camera_sensor_slave_info){ + .sensor_name = "ov8865_sunny", + .eeprom_name = "ov8865_plus", + .actuator_name = "", + .ois_name = "", + .flash_name = "", + .camera_id = 2, + .slave_addr = 108, + .i2c_freq_mode = 1, + .addr_type = 2, + .sensor_id_info = { + .sensor_id_reg_addr = 12299, + .sensor_id = 34917, + .sensor_id_mask = 0, + .module_id = 2, + .vcm_id = 0, + }, + .power_setting_array = { + .power_setting_a = { + { + .seq_type = 1, + .seq_val = 0, + .config_val = 0, + .delay = 5, + },{ + .seq_type = 2, + .seq_val = 1, + .config_val = 0, + .delay = 0, + },{ + .seq_type = 2, + .seq_val = 2, + .config_val = 0, + .delay = 0, + },{ + .seq_type = 2, + .seq_val = 0, + .config_val = 0, + .delay = 0, + },{ + .seq_type = 0, + .seq_val = 0, + .config_val = 24000000, + .delay = 1, + },{ + .seq_type = 1, + .seq_val = 0, + .config_val = 2, + .delay = 1, + }, + }, + .size = 6, + .power_down_setting_a = { + { + .seq_type = 1, + .seq_val = 0, + .config_val = 0, + .delay = 5, + },{ + .seq_type = 0, + .seq_val = 0, + .config_val = 0, + .delay = 1, + },{ + .seq_type = 2, + .seq_val = 0, + .config_val = 0, + .delay = 0, + },{ + .seq_type = 2, + .seq_val = 1, + .config_val = 0, + .delay = 0, + },{ + .seq_type = 2, + .seq_val = 2, + .config_val = 0, + .delay = 1, + }, + }, + .size_down = 5, + }, + .is_init_params_valid = 0, + .sensor_init_params = { + .modes_supported = 1, + .position = 1, + .sensor_mount_angle = 270, + }, + .output_format = 0, + }; + } else if (s->front.camera_id == CAMERA_ID_S5K3P8SP) { + // init front camera + slave_info2 = (struct msm_camera_sensor_slave_info){ + .sensor_name = "s5k3p8sp", + .eeprom_name = "s5k3p8sp_m24c64s", + .actuator_name = "", + .ois_name = "", + .camera_id = 1, + .slave_addr = 32, + .i2c_freq_mode = 1, + .addr_type = 2, + .sensor_id_info = { + .sensor_id_reg_addr = 0, + .sensor_id = 12552, + .sensor_id_mask = 0, + }, + .power_setting_array = { + .power_setting_a = { + { + .seq_type = 1, + .seq_val = 0, + .config_val = 0, + .delay = 1, + },{ + .seq_type = 2, + .seq_val = 2, + .config_val = 0, + .delay = 1, + },{ + .seq_type = 2, + .seq_val = 1, + .config_val = 0, + .delay = 1, + },{ + .seq_type = 2, + .seq_val = 0, + .config_val = 0, + .delay = 1, + },{ + .seq_type = 0, + .seq_val = 0, + .config_val = 24000000, + .delay = 1, + },{ + .seq_type = 1, + .seq_val = 0, + .config_val = 2, + .delay = 1, + }, + }, + .size = 6, + .power_down_setting_a = { + { + .seq_type = 0, + .seq_val = 0, + .config_val = 0, + .delay = 1, + },{ + .seq_type = 1, + .seq_val = 0, + .config_val = 0, + .delay = 1, + },{ + .seq_type = 2, + .seq_val = 0, + .config_val = 0, + .delay = 1, + },{ + .seq_type = 2, + .seq_val = 1, + .config_val = 0, + .delay = 1, + },{ + .seq_type = 2, + .seq_val = 2, + .config_val = 0, + .delay = 1, + }, + }, + .size_down = 5, + }, + .is_init_params_valid = 0, + .sensor_init_params = { + .modes_supported = 1, + .position = 1, + .sensor_mount_angle = 270, + }, + .output_format = 0, + }; + } else { + // init front camera + slave_info2 = (struct msm_camera_sensor_slave_info){ + .sensor_name = "imx179", + .eeprom_name = "sony_imx179", + .actuator_name = "", + .ois_name = "", + .camera_id = 1, + .slave_addr = 32, + .i2c_freq_mode = 1, + .addr_type = 2, + .sensor_id_info = { + .sensor_id_reg_addr = 2, + .sensor_id = 377, + .sensor_id_mask = 4095, + }, + .power_setting_array = { + .power_setting_a = { + { + .seq_type = 2, + .seq_val = 2, + .config_val = 0, + .delay = 0, + },{ + .seq_type = 2, + .seq_val = 1, + .config_val = 0, + .delay = 0, + },{ + .seq_type = 2, + .seq_val = 0, + .config_val = 0, + .delay = 0, + },{ + .seq_type = 1, + .seq_val = 0, + .config_val = 2, + .delay = 0, + },{ + .seq_type = 0, + .seq_val = 0, + .config_val = 24000000, + .delay = 0, + }, + }, + .size = 5, + .power_down_setting_a = { + { + .seq_type = 0, + .seq_val = 0, + .config_val = 0, + .delay = 0, + },{ + .seq_type = 1, + .seq_val = 0, + .config_val = 0, + .delay = 1, + },{ + .seq_type = 2, + .seq_val = 0, + .config_val = 0, + .delay = 2, + },{ + .seq_type = 2, + .seq_val = 1, + .config_val = 0, + .delay = 0, + },{ + .seq_type = 2, + .seq_val = 2, + .config_val = 0, + .delay = 0, + }, + }, + .size_down = 5, + }, + .is_init_params_valid = 0, + .sensor_init_params = { + .modes_supported = 1, + .position = 1, + .sensor_mount_angle = 270, + }, + .output_format = 0, + }; + } + slave_info2.power_setting_array.power_setting = + (struct msm_sensor_power_setting *)&slave_info2.power_setting_array.power_setting_a[0]; + slave_info2.power_setting_array.power_down_setting = + (struct msm_sensor_power_setting *)&slave_info2.power_setting_array.power_down_setting_a[0]; + sensor_init_cfg.cfgtype = CFG_SINIT_PROBE; + sensor_init_cfg.cfg.setting = &slave_info2; + err = ioctl(sensorinit_fd, VIDIOC_MSM_SENSOR_INIT_CFG, &sensor_init_cfg); + LOG("sensor init cfg (front): %d", err); + assert(err >= 0); +} + +static void camera_open(CameraState *s, bool rear) { + int err; + + struct sensorb_cfg_data sensorb_cfg_data = {0}; + struct csid_cfg_data csid_cfg_data = {0}; + struct csiphy_cfg_data csiphy_cfg_data = {0}; + struct msm_camera_csiphy_params csiphy_params = {0}; + struct msm_camera_csid_params csid_params = {0}; + struct msm_vfe_input_cfg input_cfg = {0}; + struct msm_vfe_axi_stream_update_cmd update_cmd = {0}; + struct v4l2_event_subscription sub = {0}; + struct ispif_cfg_data ispif_cfg_data = {0}; + struct msm_vfe_cfg_cmd_list cfg_cmd_list = {0}; + + struct msm_actuator_cfg_data actuator_cfg_data = {0}; + struct msm_ois_cfg_data ois_cfg_data = {0}; + + // open devices + if (rear) { + s->csid_fd = open("/dev/v4l-subdev3", O_RDWR | O_NONBLOCK); + assert(s->csid_fd >= 0); + s->csiphy_fd = open("/dev/v4l-subdev0", O_RDWR | O_NONBLOCK); + assert(s->csiphy_fd >= 0); + if (s->device == DEVICE_LP3) { + s->sensor_fd = open("/dev/v4l-subdev17", O_RDWR | O_NONBLOCK); + } else { + s->sensor_fd = open("/dev/v4l-subdev18", O_RDWR | O_NONBLOCK); + } + assert(s->sensor_fd >= 0); + if (s->device == DEVICE_LP3) { + s->isp_fd = open("/dev/v4l-subdev13", O_RDWR | O_NONBLOCK); + } else { + s->isp_fd = open("/dev/v4l-subdev14", O_RDWR | O_NONBLOCK); + } + assert(s->isp_fd >= 0); + s->eeprom_fd = open("/dev/v4l-subdev8", O_RDWR | O_NONBLOCK); + assert(s->eeprom_fd >= 0); + + s->actuator_fd = open("/dev/v4l-subdev7", O_RDWR | O_NONBLOCK); + assert(s->actuator_fd >= 0); + + if (s->device != DEVICE_LP3) { + s->ois_fd = open("/dev/v4l-subdev10", O_RDWR | O_NONBLOCK); + assert(s->ois_fd >= 0); + } + } else { + s->csid_fd = open("/dev/v4l-subdev5", O_RDWR | O_NONBLOCK); + assert(s->csid_fd >= 0); + s->csiphy_fd = open("/dev/v4l-subdev2", O_RDWR | O_NONBLOCK); + assert(s->csiphy_fd >= 0); + if (s->device == DEVICE_LP3) { + s->sensor_fd = open("/dev/v4l-subdev18", O_RDWR | O_NONBLOCK); + } else { + s->sensor_fd = open("/dev/v4l-subdev19", O_RDWR | O_NONBLOCK); + } + assert(s->sensor_fd >= 0); + if (s->device == DEVICE_LP3) { + s->isp_fd = open("/dev/v4l-subdev14", O_RDWR | O_NONBLOCK); + } else { + s->isp_fd = open("/dev/v4l-subdev15", O_RDWR | O_NONBLOCK); + } + assert(s->isp_fd >= 0); + s->eeprom_fd = open("/dev/v4l-subdev9", O_RDWR | O_NONBLOCK); + assert(s->eeprom_fd >= 0); + } + + // *** SHUTDOWN ALL *** + + // CSIPHY: release csiphy + struct msm_camera_csi_lane_params csi_lane_params = {0}; + csi_lane_params.csi_lane_mask = 0x1f; + csiphy_cfg_data.cfg.csi_lane_params = &csi_lane_params; + csiphy_cfg_data.cfgtype = CSIPHY_RELEASE; + err = ioctl(s->csiphy_fd, VIDIOC_MSM_CSIPHY_IO_CFG, &csiphy_cfg_data); + LOG("release csiphy: %d", err); + + // CSID: release csid + csid_cfg_data.cfgtype = CSID_RELEASE; + err = ioctl(s->csid_fd, VIDIOC_MSM_CSID_IO_CFG, &csid_cfg_data); + LOG("release csid: %d", err); + + // SENSOR: send power down + memset(&sensorb_cfg_data, 0, sizeof(sensorb_cfg_data)); + sensorb_cfg_data.cfgtype = CFG_POWER_DOWN; + err = ioctl(s->sensor_fd, VIDIOC_MSM_SENSOR_CFG, &sensorb_cfg_data); + LOG("sensor power down: %d", err); + + if (rear && s->device != DEVICE_LP3) { + // ois powerdown + ois_cfg_data.cfgtype = CFG_OIS_POWERDOWN; + err = ioctl(s->ois_fd, VIDIOC_MSM_OIS_CFG, &ois_cfg_data); + LOG("ois powerdown: %d", err); + } + + // actuator powerdown + actuator_cfg_data.cfgtype = CFG_ACTUATOR_POWERDOWN; + err = ioctl(s->actuator_fd, VIDIOC_MSM_ACTUATOR_CFG, &actuator_cfg_data); + LOG("actuator powerdown: %d", err); + + // reset isp + // struct msm_vfe_axi_halt_cmd halt_cmd = { + // .stop_camif = 1, + // .overflow_detected = 1, + // .blocking_halt = 1, + // }; + // err = ioctl(s->isp_fd, VIDIOC_MSM_ISP_AXI_HALT, &halt_cmd); + // printf("axi halt: %d\n", err); + + // struct msm_vfe_axi_reset_cmd reset_cmd = { + // .blocking = 1, + // .frame_id = 1, + // }; + // err = ioctl(s->isp_fd, VIDIOC_MSM_ISP_AXI_RESET, &reset_cmd); + // printf("axi reset: %d\n", err); + + // struct msm_vfe_axi_restart_cmd restart_cmd = { + // .enable_camif = 1, + // }; + // err = ioctl(s->isp_fd, VIDIOC_MSM_ISP_AXI_RESTART, &restart_cmd); + // printf("axi restart: %d\n", err); + + // **** GO GO GO **** + LOG("******************** GO GO GO ************************"); + + s->eeprom = get_eeprom(s->eeprom_fd, &s->eeprom_size); + + // printf("eeprom:\n"); + // for (int i=0; ieeprom_size; i++) { + // printf("%02x", s->eeprom[i]); + // } + // printf("\n"); + + // CSID: init csid + csid_cfg_data.cfgtype = CSID_INIT; + err = ioctl(s->csid_fd, VIDIOC_MSM_CSID_IO_CFG, &csid_cfg_data); + LOG("init csid: %d", err); + + // CSIPHY: init csiphy + memset(&csiphy_cfg_data, 0, sizeof(csiphy_cfg_data)); + csiphy_cfg_data.cfgtype = CSIPHY_INIT; + err = ioctl(s->csiphy_fd, VIDIOC_MSM_CSIPHY_IO_CFG, &csiphy_cfg_data); + LOG("init csiphy: %d", err); + + // SENSOR: stop stream + struct msm_camera_i2c_reg_setting stop_settings = { + .reg_setting = stop_reg_array, + .size = ARRAYSIZE(stop_reg_array), + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .data_type = MSM_CAMERA_I2C_BYTE_DATA, + .delay = 0 + }; + sensorb_cfg_data.cfgtype = CFG_SET_STOP_STREAM_SETTING; + sensorb_cfg_data.cfg.setting = &stop_settings; + err = ioctl(s->sensor_fd, VIDIOC_MSM_SENSOR_CFG, &sensorb_cfg_data); + LOG("stop stream: %d", err); + + // SENSOR: send power up + memset(&sensorb_cfg_data, 0, sizeof(sensorb_cfg_data)); + sensorb_cfg_data.cfgtype = CFG_POWER_UP; + err = ioctl(s->sensor_fd, VIDIOC_MSM_SENSOR_CFG, &sensorb_cfg_data); + LOG("sensor power up: %d", err); + + // **** configure the sensor **** + + // SENSOR: send i2c configuration + if (s->camera_id == CAMERA_ID_IMX298) { + err = sensor_write_regs(s, init_array_imx298, ARRAYSIZE(init_array_imx298), MSM_CAMERA_I2C_BYTE_DATA); + } else if (s->camera_id == CAMERA_ID_S5K3P8SP) { + err = sensor_write_regs(s, init_array_s5k3p8sp, ARRAYSIZE(init_array_s5k3p8sp), MSM_CAMERA_I2C_WORD_DATA); + } else if (s->camera_id == CAMERA_ID_IMX179) { + err = sensor_write_regs(s, init_array_imx179, ARRAYSIZE(init_array_imx179), MSM_CAMERA_I2C_BYTE_DATA); + } else if (s->camera_id == CAMERA_ID_OV8865) { + err = sensor_write_regs(s, init_array_ov8865, ARRAYSIZE(init_array_ov8865), MSM_CAMERA_I2C_BYTE_DATA); + } else { + assert(false); + } + LOG("sensor init i2c: %d", err); + + if (rear) { + // init the actuator + actuator_cfg_data.cfgtype = CFG_ACTUATOR_POWERUP; + err = ioctl(s->actuator_fd, VIDIOC_MSM_ACTUATOR_CFG, &actuator_cfg_data); + LOG("actuator powerup: %d", err); + + actuator_cfg_data.cfgtype = CFG_ACTUATOR_INIT; + err = ioctl(s->actuator_fd, VIDIOC_MSM_ACTUATOR_CFG, &actuator_cfg_data); + LOG("actuator init: %d", err); + + + // no OIS in LP3 + if (s->device != DEVICE_LP3) { + // see sony_imx298_eeprom_format_afdata in libmmcamera_sony_imx298_eeprom.so + const float far_margin = -0.28; + uint16_t macro_dac = *(uint16_t*)(s->eeprom + 0x24); + s->infinity_dac = *(uint16_t*)(s->eeprom + 0x26); + LOG("macro_dac: %d infinity_dac: %d", macro_dac, s->infinity_dac); + + int dac_range = macro_dac - s->infinity_dac; + s->infinity_dac += far_margin * dac_range; + + LOG(" -> macro_dac: %d infinity_dac: %d", macro_dac, s->infinity_dac); + + struct msm_actuator_reg_params_t actuator_reg_params[] = { + { + .reg_write_type = MSM_ACTUATOR_WRITE_DAC, + .hw_mask = 0, + .reg_addr = 240, + .hw_shift = 0, + .data_type = 10, + .addr_type = 4, + .reg_data = 0, + .delay = 0, + }, { + .reg_write_type = MSM_ACTUATOR_WRITE_DAC, + .hw_mask = 0, + .reg_addr = 241, + .hw_shift = 0, + .data_type = 10, + .addr_type = 4, + .reg_data = 0, + .delay = 0, + }, { + .reg_write_type = MSM_ACTUATOR_WRITE_DAC, + .hw_mask = 0, + .reg_addr = 242, + .hw_shift = 0, + .data_type = 10, + .addr_type = 4, + .reg_data = 0, + .delay = 0, + }, { + .reg_write_type = MSM_ACTUATOR_WRITE_DAC, + .hw_mask = 0, + .reg_addr = 243, + .hw_shift = 0, + .data_type = 10, + .addr_type = 4, + .reg_data = 0, + .delay = 0, + }, + }; + + //... + struct reg_settings_t actuator_init_settings[1] = {0}; + + struct region_params_t region_params[] = { + { + .step_bound = {512, 0,}, + .code_per_step = 118, + .qvalue = 128, + }, + }; + + actuator_cfg_data.cfgtype = CFG_SET_ACTUATOR_INFO; + actuator_cfg_data.cfg.set_info = (struct msm_actuator_set_info_t){ + .actuator_params = { + .act_type = ACTUATOR_VCM, + .reg_tbl_size = 4, + .data_size = 10, + .init_setting_size = 0, + .i2c_freq_mode = I2C_CUSTOM_MODE, + .i2c_addr = 28, + .i2c_addr_type = MSM_ACTUATOR_BYTE_ADDR, + .i2c_data_type = MSM_ACTUATOR_BYTE_DATA, + .reg_tbl_params = &actuator_reg_params[0], + .init_settings = &actuator_init_settings[0], + .park_lens = { + .damping_step = 1023, + .damping_delay = 15000, + .hw_params = 58404, + .max_step = 20, + } + }, + .af_tuning_params = { + .initial_code = s->infinity_dac, + .pwd_step = 0, + .region_size = 1, + .total_steps = 512, + .region_params = ®ion_params[0], + }, + }; + err = ioctl(s->actuator_fd, VIDIOC_MSM_ACTUATOR_CFG, &actuator_cfg_data); + LOG("actuator set info: %d", err); + + // power up ois + ois_cfg_data.cfgtype = CFG_OIS_POWERUP; + err = ioctl(s->ois_fd, VIDIOC_MSM_OIS_CFG, &ois_cfg_data); + LOG("ois powerup: %d", err); + + ois_cfg_data.cfgtype = CFG_OIS_INIT; + err = ioctl(s->ois_fd, VIDIOC_MSM_OIS_CFG, &ois_cfg_data); + LOG("ois init: %d", err); + + ois_cfg_data.cfgtype = CFG_OIS_CONTROL; + ois_cfg_data.cfg.set_info.ois_params = (struct msm_ois_params_t){ + // .data_size = 26312, + .setting_size = 120, + .i2c_addr = 28, + .i2c_freq_mode = I2C_CUSTOM_MODE, + // .i2c_addr_type = wtf + // .i2c_data_type = wtf + .settings = &ois_init_settings[0], + }; + err = ioctl(s->ois_fd, VIDIOC_MSM_OIS_CFG, &ois_cfg_data); + LOG("ois init settings: %d", err); + } else { + // leeco actuator + // from sniff + s->infinity_dac = 364; + + struct msm_actuator_reg_params_t actuator_reg_params[] = { + { + .reg_write_type = MSM_ACTUATOR_WRITE_DAC, + .hw_mask = 0, + .reg_addr = 3, + .hw_shift = 0, + .data_type = 9, + .addr_type = 4, + .reg_data = 0, + .delay = 0, + }, + }; + + struct reg_settings_t actuator_init_settings[] = { + { .reg_addr=2, .addr_type=MSM_ACTUATOR_BYTE_ADDR, .reg_data=1, .data_type = MSM_ACTUATOR_BYTE_DATA, .i2c_operation = MSM_ACT_WRITE, .delay = 0 }, + { .reg_addr=2, .addr_type=MSM_ACTUATOR_BYTE_ADDR, .reg_data=0, .data_type = MSM_ACTUATOR_BYTE_DATA, .i2c_operation = MSM_ACT_WRITE, .delay = 2 }, + { .reg_addr=2, .addr_type=MSM_ACTUATOR_BYTE_ADDR, .reg_data=2, .data_type = MSM_ACTUATOR_BYTE_DATA, .i2c_operation = MSM_ACT_WRITE, .delay = 2 }, + { .reg_addr=6, .addr_type=MSM_ACTUATOR_BYTE_ADDR, .reg_data=64, .data_type = MSM_ACTUATOR_BYTE_DATA, .i2c_operation = MSM_ACT_WRITE, .delay = 0 }, + { .reg_addr=7, .addr_type=MSM_ACTUATOR_BYTE_ADDR, .reg_data=113, .data_type = MSM_ACTUATOR_BYTE_DATA, .i2c_operation = MSM_ACT_WRITE, .delay = 0 }, + }; + + struct region_params_t region_params[] = { + { + .step_bound = {238, 0,}, + .code_per_step = 235, + .qvalue = 128, + }, + }; + + actuator_cfg_data.cfgtype = CFG_SET_ACTUATOR_INFO; + actuator_cfg_data.cfg.set_info = (struct msm_actuator_set_info_t){ + .actuator_params = { + .act_type = ACTUATOR_BIVCM, + .reg_tbl_size = 1, + .data_size = 10, + .init_setting_size = 5, + .i2c_freq_mode = I2C_STANDARD_MODE, + .i2c_addr = 24, + .i2c_addr_type = MSM_ACTUATOR_BYTE_ADDR, + .i2c_data_type = MSM_ACTUATOR_WORD_DATA, + .reg_tbl_params = &actuator_reg_params[0], + .init_settings = &actuator_init_settings[0], + .park_lens = { + .damping_step = 1023, + .damping_delay = 14000, + .hw_params = 11, + .max_step = 20, + } + }, + .af_tuning_params = { + .initial_code = s->infinity_dac, + .pwd_step = 0, + .region_size = 1, + .total_steps = 238, + .region_params = ®ion_params[0], + }, + }; + + err = ioctl(s->actuator_fd, VIDIOC_MSM_ACTUATOR_CFG, &actuator_cfg_data); + LOG("actuator set info: %d", err); + } + } + + if (s->camera_id == CAMERA_ID_IMX298) { + err = sensor_write_regs(s, mode_setting_array_imx298, ARRAYSIZE(mode_setting_array_imx298), MSM_CAMERA_I2C_BYTE_DATA); + LOG("sensor setup: %d", err); + } + + // CSIPHY: configure csiphy + if (s->camera_id == CAMERA_ID_IMX298) { + csiphy_params.lane_cnt = 4; + csiphy_params.settle_cnt = 14; + csiphy_params.lane_mask = 0x1f; + csiphy_params.csid_core = 0; + } else if (s->camera_id == CAMERA_ID_S5K3P8SP) { + csiphy_params.lane_cnt = 4; + csiphy_params.settle_cnt = 24; + csiphy_params.lane_mask = 0x1f; + csiphy_params.csid_core = 0; + } else if (s->camera_id == CAMERA_ID_IMX179) { + csiphy_params.lane_cnt = 4; + csiphy_params.settle_cnt = 11; + csiphy_params.lane_mask = 0x1f; + csiphy_params.csid_core = 2; + } else if (s->camera_id == CAMERA_ID_OV8865) { + // guess! + csiphy_params.lane_cnt = 4; + csiphy_params.settle_cnt = 24; + csiphy_params.lane_mask = 0x1f; + csiphy_params.csid_core = 2; + } + csiphy_cfg_data.cfgtype = CSIPHY_CFG; + csiphy_cfg_data.cfg.csiphy_params = &csiphy_params; + err = ioctl(s->csiphy_fd, VIDIOC_MSM_CSIPHY_IO_CFG, &csiphy_cfg_data); + LOG("csiphy configure: %d", err); + + // CSID: configure csid + csid_params.lane_cnt = 4; + csid_params.lane_assign = 0x4320; + if (rear) { + csid_params.phy_sel = 0; + } else { + csid_params.phy_sel = 2; + } + csid_params.lut_params.num_cid = rear ? 3 : 1; + +#define CSI_STATS 0x35 +#define CSI_PD 0x36 + + csid_params.lut_params.vc_cfg_a[0].cid = 0; + csid_params.lut_params.vc_cfg_a[0].dt = CSI_RAW10; + csid_params.lut_params.vc_cfg_a[0].decode_format = CSI_DECODE_10BIT; + csid_params.lut_params.vc_cfg_a[1].cid = 1; + csid_params.lut_params.vc_cfg_a[1].dt = CSI_PD; + csid_params.lut_params.vc_cfg_a[1].decode_format = CSI_DECODE_10BIT; + csid_params.lut_params.vc_cfg_a[2].cid = 2; + csid_params.lut_params.vc_cfg_a[2].dt = CSI_STATS; + csid_params.lut_params.vc_cfg_a[2].decode_format = CSI_DECODE_10BIT; + + csid_params.lut_params.vc_cfg[0] = &csid_params.lut_params.vc_cfg_a[0]; + csid_params.lut_params.vc_cfg[1] = &csid_params.lut_params.vc_cfg_a[1]; + csid_params.lut_params.vc_cfg[2] = &csid_params.lut_params.vc_cfg_a[2]; + + csid_cfg_data.cfgtype = CSID_CFG; + csid_cfg_data.cfg.csid_params = &csid_params; + err = ioctl(s->csid_fd, VIDIOC_MSM_CSID_IO_CFG, &csid_cfg_data); + LOG("csid configure: %d", err); + + // ISP: SMMU_ATTACH + struct msm_vfe_smmu_attach_cmd smmu_attach_cmd = { + .security_mode = 0, + .iommu_attach_mode = IOMMU_ATTACH + }; + err = ioctl(s->isp_fd, VIDIOC_MSM_ISP_SMMU_ATTACH, &smmu_attach_cmd); + LOG("isp smmu attach: %d", err); + + // ******************* STREAM RAW ***************************** + + // configure QMET input + for (int i = 0; i < (rear ? 3 : 1); i++) { + StreamState *ss = &s->ss[i]; + + memset(&input_cfg, 0, sizeof(struct msm_vfe_input_cfg)); + input_cfg.input_src = VFE_RAW_0+i; + input_cfg.input_pix_clk = s->pixel_clock; + input_cfg.d.rdi_cfg.cid = i; + input_cfg.d.rdi_cfg.frame_based = 1; + err = ioctl(s->isp_fd, VIDIOC_MSM_ISP_INPUT_CFG, &input_cfg); + LOG("configure input(%d): %d", i, err); + + // ISP: REQUEST_STREAM + ss->stream_req.axi_stream_handle = 0; + if (rear) { + ss->stream_req.session_id = 2; + ss->stream_req.stream_id = /*ISP_META_CHANNEL_BIT | */ISP_NATIVE_BUF_BIT | (1+i); + } else { + ss->stream_req.session_id = 3; + ss->stream_req.stream_id = ISP_NATIVE_BUF_BIT | 1; + } + + if (i == 0) { + ss->stream_req.output_format = v4l2_fourcc('R', 'G', '1', '0'); + } else { + ss->stream_req.output_format = v4l2_fourcc('Q', 'M', 'E', 'T'); + } + ss->stream_req.stream_src = RDI_INTF_0+i; + +#ifdef HIGH_FPS + if (rear) { + ss->stream_req.frame_skip_pattern = EVERY_3FRAME; + } +#endif + + ss->stream_req.frame_base = 1; + ss->stream_req.buf_divert = 1; //i == 0; + + // setup stream plane. doesn't even matter? + /*s->stream_req.plane_cfg[0].output_plane_format = Y_PLANE; + s->stream_req.plane_cfg[0].output_width = s->ci.frame_width; + s->stream_req.plane_cfg[0].output_height = s->ci.frame_height; + s->stream_req.plane_cfg[0].output_stride = s->ci.frame_width; + s->stream_req.plane_cfg[0].output_scan_lines = s->ci.frame_height; + s->stream_req.plane_cfg[0].rdi_cid = 0;*/ + + err = ioctl(s->isp_fd, VIDIOC_MSM_ISP_REQUEST_STREAM, &ss->stream_req); + LOG("isp request stream: %d -> 0x%x", err, ss->stream_req.axi_stream_handle); + + // ISP: REQUEST_BUF + ss->buf_request.session_id = ss->stream_req.session_id; + ss->buf_request.stream_id = ss->stream_req.stream_id; + ss->buf_request.num_buf = FRAME_BUF_COUNT; + ss->buf_request.buf_type = ISP_PRIVATE_BUF; + ss->buf_request.handle = 0; + err = ioctl(s->isp_fd, VIDIOC_MSM_ISP_REQUEST_BUF, &ss->buf_request); + LOG("isp request buf: %d", err); + LOG("got buf handle: 0x%x", ss->buf_request.handle); + + // ENQUEUE all buffers + for (int j = 0; j < ss->buf_request.num_buf; j++) { + ss->qbuf_info[j].handle = ss->buf_request.handle; + ss->qbuf_info[j].buf_idx = j; + ss->qbuf_info[j].buffer.num_planes = 1; + ss->qbuf_info[j].buffer.planes[0].addr = ss->bufs[j].fd; + ss->qbuf_info[j].buffer.planes[0].length = ss->bufs[j].len; + err = ioctl(s->isp_fd, VIDIOC_MSM_ISP_ENQUEUE_BUF, &ss->qbuf_info[j]); + } + + // ISP: UPDATE_STREAM + update_cmd.num_streams = 1; + update_cmd.update_info[0].user_stream_id = ss->stream_req.stream_id; + update_cmd.update_info[0].stream_handle = ss->stream_req.axi_stream_handle; + update_cmd.update_type = UPDATE_STREAM_ADD_BUFQ; + err = ioctl(s->isp_fd, VIDIOC_MSM_ISP_UPDATE_STREAM, &update_cmd); + LOG("isp update stream: %d", err); + } + + LOG("******** START STREAMS ********"); + + sub.id = 0; + sub.type = 0x1ff; + err = ioctl(s->isp_fd, VIDIOC_SUBSCRIBE_EVENT, &sub); + LOG("isp subscribe: %d", err); + + // ISP: START_STREAM + s->stream_cfg.cmd = START_STREAM; + s->stream_cfg.num_streams = rear ? 3 : 1; + for (int i = 0; i < s->stream_cfg.num_streams; i++) { + s->stream_cfg.stream_handle[i] = s->ss[i].stream_req.axi_stream_handle; + } + err = ioctl(s->isp_fd, VIDIOC_MSM_ISP_CFG_STREAM, &s->stream_cfg); + LOG("isp start stream: %d", err); +} + + +static struct damping_params_t actuator_ringing_params = { + .damping_step = 1023, + .damping_delay = 15000, + .hw_params = 0x0000e422, +}; + +static void rear_start(CameraState *s) { + int err; + + struct msm_actuator_cfg_data actuator_cfg_data = {0}; + + set_exposure(s, 1.0, 1.0); + + err = sensor_write_regs(s, start_reg_array, ARRAYSIZE(start_reg_array), MSM_CAMERA_I2C_BYTE_DATA); + LOG("sensor start regs: %d", err); + + // focus on infinity assuming phone is perpendicular + int inf_step; + + if (s->device != DEVICE_LP3) { + imx298_ois_calibration(s->ois_fd, s->eeprom); + inf_step = 332 - s->infinity_dac; + + // initial guess + s->lens_true_pos = 300; + } else { + // default is OP3, this is for LeEco + actuator_ringing_params.damping_step = 1023; + actuator_ringing_params.damping_delay = 20000; + actuator_ringing_params.hw_params = 13; + + inf_step = 512 - s->infinity_dac; + + // initial guess + s->lens_true_pos = 400; + } + + // reset lens position + memset(&actuator_cfg_data, 0, sizeof(actuator_cfg_data)); + actuator_cfg_data.cfgtype = CFG_SET_POSITION; + actuator_cfg_data.cfg.setpos = (struct msm_actuator_set_position_t){ + .number_of_steps = 1, + .hw_params = (s->device != DEVICE_LP3) ? 0x0000e424 : 7, + .pos = {s->infinity_dac, 0}, + .delay = {0,} + }; + err = ioctl(s->actuator_fd, VIDIOC_MSM_ACTUATOR_CFG, &actuator_cfg_data); + LOG("actuator set pos: %d", err); + + // TODO: confirm this isn't needed + /*memset(&actuator_cfg_data, 0, sizeof(actuator_cfg_data)); + actuator_cfg_data.cfgtype = CFG_MOVE_FOCUS; + actuator_cfg_data.cfg.move = (struct msm_actuator_move_params_t){ + .dir = 0, + .sign_dir = 1, + .dest_step_pos = inf_step, + .num_steps = inf_step, + .curr_lens_pos = 0, + .ringing_params = &actuator_ringing_params, + }; + err = ioctl(s->actuator_fd, VIDIOC_MSM_ACTUATOR_CFG, &actuator_cfg_data); // should be ~332 at startup ? + LOG("init actuator move focus: %d", err);*/ + //actuator_cfg_data.cfg.move.curr_lens_pos; + + s->cur_lens_pos = 0; + s->cur_step_pos = inf_step; + + actuator_move(s, s->cur_lens_pos); + + LOG("init lens pos: %d", s->cur_lens_pos); +} + +void actuator_move(CameraState *s, uint16_t target) { + int err; + + int step = target - s->cur_lens_pos; + // LP3 moves only on even positions. TODO: use proper sensor params + if (s->device == DEVICE_LP3) { + step /= 2; + } + + int dest_step_pos = s->cur_step_pos + step; + dest_step_pos = clamp(dest_step_pos, 0, 255); + + struct msm_actuator_cfg_data actuator_cfg_data = {0}; + actuator_cfg_data.cfgtype = CFG_MOVE_FOCUS; + actuator_cfg_data.cfg.move = (struct msm_actuator_move_params_t){ + .dir = (step > 0) ? 0 : 1, + .sign_dir = (step > 0) ? 1 : -1, + .dest_step_pos = dest_step_pos, + .num_steps = abs(step), + .curr_lens_pos = s->cur_lens_pos, + .ringing_params = &actuator_ringing_params, + }; + err = ioctl(s->actuator_fd, VIDIOC_MSM_ACTUATOR_CFG, &actuator_cfg_data); + LOGD("actuator move focus: %d", err); + + s->cur_step_pos = dest_step_pos; + s->cur_lens_pos = actuator_cfg_data.cfg.move.curr_lens_pos; + + LOGD("step %d target: %d lens pos: %d", dest_step_pos, target, s->cur_lens_pos); +} + +static void parse_autofocus(CameraState *s, uint8_t *d) { + int good_count = 0; + int16_t max_focus = -32767; + int avg_focus = 0; + + /*printf("FOCUS: "); + for (int i = 0; i < 0x10; i++) { + printf("%2.2X ", d[i]); + }*/ + + for (int i = 0; i < NUM_FOCUS; i++) { + int doff = i*5+5; + s->confidence[i] = d[doff]; + int16_t focus_t = (d[doff+1] << 3) | (d[doff+2] >> 5); + if (focus_t >= 1024) focus_t = -(2048-focus_t); + s->focus[i] = focus_t; + //printf("%x->%d ", d[doff], focus_t); + if (s->confidence[i] > 0x20) { + good_count++; + max_focus = max(max_focus, s->focus[i]); + avg_focus += s->focus[i]; + } + } + + //printf("\n"); + if (good_count < 4) { + s->focus_err = nan(""); + return; + } + + avg_focus /= good_count; + + // outlier rejection + if (abs(avg_focus - max_focus) > 200) { + s->focus_err = nan(""); + return; + } + + s->focus_err = max_focus*1.0; +} + +static void do_autofocus(CameraState *s) { + // params for focus PI controller + const float focus_kp = 0.005; + + float err = s->focus_err; + float offset = 0; + float sag = (s->last_sag_acc_z/9.8) * 128; + + const int dac_up = s->device == DEVICE_LP3? 634:456; + const int dac_down = s->device == DEVICE_LP3? 366:224; + + if (!isnan(err)) { + // learn lens_true_pos + s->lens_true_pos -= err*focus_kp; + } + + // stay off the walls + s->lens_true_pos = clamp(s->lens_true_pos, dac_down, dac_up); + + int target = clamp(s->lens_true_pos - sag, dac_down, dac_up); + + char debug[4096]; + char *pdebug = debug; + pdebug += sprintf(pdebug, "focus "); + for (int i = 0; i < NUM_FOCUS; i++) pdebug += sprintf(pdebug, "%2x(%4d) ", s->confidence[i], s->focus[i]); + pdebug += sprintf(pdebug, " err: %7.2f offset: %6.2f sag: %6.2f lens_true_pos: %6.2f cur_lens_pos: %4d->%4d", err * focus_kp, offset, sag, s->lens_true_pos, s->cur_lens_pos, target); + LOGD(debug); + + actuator_move(s, target); +} + + +static void front_start(CameraState *s) { + int err; + + set_exposure(s, 1.0, 1.0); + + err = sensor_write_regs(s, start_reg_array, ARRAYSIZE(start_reg_array), MSM_CAMERA_I2C_BYTE_DATA); + LOG("sensor start regs: %d", err); +} + + + +void cameras_open(DualCameraState *s, VisionBuf *camera_bufs_rear, VisionBuf *camera_bufs_focus, VisionBuf *camera_bufs_stats, VisionBuf *camera_bufs_front) { + int err; + + struct ispif_cfg_data ispif_cfg_data = {0}; + + struct msm_ispif_param_data ispif_params = {0}; + ispif_params.num = 4; + // rear camera + ispif_params.entries[0].vfe_intf = 0; + ispif_params.entries[0].intftype = RDI0; + ispif_params.entries[0].num_cids = 1; + ispif_params.entries[0].cids[0] = 0; + ispif_params.entries[0].csid = 0; + // front camera + ispif_params.entries[1].vfe_intf = 1; + ispif_params.entries[1].intftype = RDI0; + ispif_params.entries[1].num_cids = 1; + ispif_params.entries[1].cids[0] = 0; + ispif_params.entries[1].csid = 2; + // rear camera (focus) + ispif_params.entries[2].vfe_intf = 0; + ispif_params.entries[2].intftype = RDI1; + ispif_params.entries[2].num_cids = 1; + ispif_params.entries[2].cids[0] = 1; + ispif_params.entries[2].csid = 0; + // rear camera (stats, for AE) + ispif_params.entries[3].vfe_intf = 0; + ispif_params.entries[3].intftype = RDI2; + ispif_params.entries[3].num_cids = 1; + ispif_params.entries[3].cids[0] = 2; + ispif_params.entries[3].csid = 0; + + assert(camera_bufs_rear); + assert(camera_bufs_front); + + int msmcfg_fd = open("/dev/media0", O_RDWR | O_NONBLOCK); + assert(msmcfg_fd >= 0); + + sensors_init(s); + + int v4l_fd = open("/dev/video0", O_RDWR | O_NONBLOCK); + assert(v4l_fd >= 0); + + if (s->device == DEVICE_LP3) { + s->ispif_fd = open("/dev/v4l-subdev15", O_RDWR | O_NONBLOCK); + } else { + s->ispif_fd = open("/dev/v4l-subdev16", O_RDWR | O_NONBLOCK); + } + assert(s->ispif_fd >= 0); + + // ISPIF: stop + // memset(&ispif_cfg_data, 0, sizeof(ispif_cfg_data)); + // ispif_cfg_data.cfg_type = ISPIF_STOP_FRAME_BOUNDARY; + // ispif_cfg_data.params = ispif_params; + // err = ioctl(s->ispif_fd, VIDIOC_MSM_ISPIF_CFG, &ispif_cfg_data); + // LOG("ispif stop: %d", err); + + LOG("*** open front ***"); + s->front.ss[0].bufs = camera_bufs_front; + camera_open(&s->front, false); + + LOG("*** open rear ***"); + s->rear.ss[0].bufs = camera_bufs_rear; + s->rear.ss[1].bufs = camera_bufs_focus; + s->rear.ss[2].bufs = camera_bufs_stats; + camera_open(&s->rear, true); + + if (getenv("CAMERA_TEST")) { + cameras_close(s); + exit(0); + } + + // ISPIF: set vfe info + memset(&ispif_cfg_data, 0, sizeof(ispif_cfg_data)); + ispif_cfg_data.cfg_type = ISPIF_SET_VFE_INFO; + ispif_cfg_data.vfe_info.num_vfe = 2; + err = ioctl(s->ispif_fd, VIDIOC_MSM_ISPIF_CFG, &ispif_cfg_data); + LOG("ispif set vfe info: %d", err); + + // ISPIF: setup + memset(&ispif_cfg_data, 0, sizeof(ispif_cfg_data)); + ispif_cfg_data.cfg_type = ISPIF_INIT; + ispif_cfg_data.csid_version = 0x30050000; //CSID_VERSION_V35 + err = ioctl(s->ispif_fd, VIDIOC_MSM_ISPIF_CFG, &ispif_cfg_data); + LOG("ispif setup: %d", err); + + memset(&ispif_cfg_data, 0, sizeof(ispif_cfg_data)); + ispif_cfg_data.cfg_type = ISPIF_CFG; + ispif_cfg_data.params = ispif_params; + + err = ioctl(s->ispif_fd, VIDIOC_MSM_ISPIF_CFG, &ispif_cfg_data); + LOG("ispif cfg: %d", err); + + ispif_cfg_data.cfg_type = ISPIF_START_FRAME_BOUNDARY; + err = ioctl(s->ispif_fd, VIDIOC_MSM_ISPIF_CFG, &ispif_cfg_data); + LOG("ispif start_frame_boundary: %d", err); + + front_start(&s->front); + rear_start(&s->rear); +} + + +static void camera_close(CameraState *s) { + int err; + + tbuffer_stop(&s->camera_tb); + + // ISP: STOP_STREAM + s->stream_cfg.cmd = STOP_STREAM; + err = ioctl(s->isp_fd, VIDIOC_MSM_ISP_CFG_STREAM, &s->stream_cfg); + LOG("isp stop stream: %d", err); + + for (int i = 0; i < 3; i++) { + StreamState *ss = &s->ss[i]; + if (ss->stream_req.axi_stream_handle != 0) { + err = ioctl(s->isp_fd, VIDIOC_MSM_ISP_RELEASE_BUF, &ss->buf_request); + LOG("isp release buf: %d", err); + + struct msm_vfe_axi_stream_release_cmd stream_release = { + .stream_handle = ss->stream_req.axi_stream_handle, + }; + err = ioctl(s->isp_fd, VIDIOC_MSM_ISP_RELEASE_STREAM, &stream_release); + LOG("isp release stream: %d", err); + } + } +} + + +const char* get_isp_event_name(unsigned int type) { + switch (type) { + case ISP_EVENT_REG_UPDATE: return "ISP_EVENT_REG_UPDATE"; + case ISP_EVENT_EPOCH_0: return "ISP_EVENT_EPOCH_0"; + case ISP_EVENT_EPOCH_1: return "ISP_EVENT_EPOCH_1"; + case ISP_EVENT_START_ACK: return "ISP_EVENT_START_ACK"; + case ISP_EVENT_STOP_ACK: return "ISP_EVENT_STOP_ACK"; + case ISP_EVENT_IRQ_VIOLATION: return "ISP_EVENT_IRQ_VIOLATION"; + case ISP_EVENT_STATS_OVERFLOW: return "ISP_EVENT_STATS_OVERFLOW"; + case ISP_EVENT_ERROR: return "ISP_EVENT_ERROR"; + case ISP_EVENT_SOF: return "ISP_EVENT_SOF"; + case ISP_EVENT_EOF: return "ISP_EVENT_EOF"; + case ISP_EVENT_BUF_DONE: return "ISP_EVENT_BUF_DONE"; + case ISP_EVENT_BUF_DIVERT: return "ISP_EVENT_BUF_DIVERT"; + case ISP_EVENT_STATS_NOTIFY: return "ISP_EVENT_STATS_NOTIFY"; + case ISP_EVENT_COMP_STATS_NOTIFY: return "ISP_EVENT_COMP_STATS_NOTIFY"; + case ISP_EVENT_FE_READ_DONE: return "ISP_EVENT_FE_READ_DONE"; + case ISP_EVENT_IOMMU_P_FAULT: return "ISP_EVENT_IOMMU_P_FAULT"; + case ISP_EVENT_HW_FATAL_ERROR: return "ISP_EVENT_HW_FATAL_ERROR"; + case ISP_EVENT_PING_PONG_MISMATCH: return "ISP_EVENT_PING_PONG_MISMATCH"; + case ISP_EVENT_REG_UPDATE_MISSING: return "ISP_EVENT_REG_UPDATE_MISSING"; + case ISP_EVENT_BUF_FATAL_ERROR: return "ISP_EVENT_BUF_FATAL_ERROR"; + case ISP_EVENT_STREAM_UPDATE_DONE: return "ISP_EVENT_STREAM_UPDATE_DONE"; + default: return "unknown"; + } +} + +static FrameMetadata get_frame_metadata(CameraState *s, uint32_t frame_id) { + pthread_mutex_lock(&s->frame_info_lock); + for (int i=0; iframe_metadata[i].frame_id == frame_id) { + pthread_mutex_unlock(&s->frame_info_lock); + return s->frame_metadata[i]; + } + } + pthread_mutex_unlock(&s->frame_info_lock); + + // should never happen + return (FrameMetadata){ + .frame_id = -1, + }; +} + +static bool acceleration_from_sensor_sock(void* sock, float* vs) { + int err; + + zmq_msg_t msg; + err = zmq_msg_init(&msg); + assert(err == 0); + + err = zmq_msg_recv(&msg, sock, 0); + assert(err >= 0); + + struct capn ctx; + capn_init_mem(&ctx, zmq_msg_data(&msg), zmq_msg_size(&msg), 0); + + cereal_Event_ptr eventp; + eventp.p = capn_getp(capn_root(&ctx), 0, 1); + struct cereal_Event eventd; + cereal_read_Event(&eventd, eventp); + + bool ret = false; + + if (eventd.which == cereal_Event_sensorEvents) { + cereal_SensorEventData_list lst = eventd.sensorEvents; + int len = capn_len(lst); + for (int i=0; i= 0); + + struct capn ctx; + capn_init_mem(&ctx, zmq_msg_data(&msg), zmq_msg_size(&msg), 0); + + cereal_Event_ptr eventp; + eventp.p = capn_getp(capn_root(&ctx), 0, 1); + struct cereal_Event eventd; + cereal_read_Event(&eventd, eventp); + + bool ret = false; + + if (eventd.which == cereal_Event_liveLocationTiming) { + struct cereal_LiveLocationData lld; + cereal_read_LiveLocationData(&lld, eventd.liveLocationTiming); + + *mono_time = lld.fixMonoTime; + *vs = lld.timeOfWeek; + ret = true; + } + + capn_free(&ctx); + zmq_msg_close(&msg); + + return ret; +} + +static void ops_term() { + zsock_t *ops_sock = zsock_new_push(">inproc://cameraops"); + assert(ops_sock); + + CameraMsg msg = {.type = -1}; + zmq_send(zsock_resolve(ops_sock), &msg, sizeof(msg), ZMQ_DONTWAIT); + + zsock_destroy(&ops_sock); +} + +static void* ops_thread(void* arg) { + int err; + DualCameraState *s = (DualCameraState*)arg; + + set_thread_name("camera_settings"); + + zsock_t *cameraops = zsock_new_pull("@inproc://cameraops"); + assert(cameraops); + + zsock_t *sensor_sock = zsock_new_sub(">tcp://127.0.0.1:8003", ""); + assert(sensor_sock); + + zsock_t *livelocationtiming_sock = zsock_new_sub(">tcp://127.0.0.1:8049", ""); + assert(livelocationtiming_sock); + + zsock_t *terminate = zsock_new_sub(">inproc://terminate", ""); + assert(terminate); + + zpoller_t *poller = zpoller_new(cameraops, sensor_sock, livelocationtiming_sock, terminate, NULL); + assert(poller); + + while (!do_exit) { + + zsock_t *which = (zsock_t*)zpoller_wait(poller, -1); + if (which == terminate || which == NULL) { + break; + } + void* sockraw = zsock_resolve(which); + + if (which == cameraops) { + zmq_msg_t msg; + err = zmq_msg_init(&msg); + assert(err == 0); + + err = zmq_msg_recv(&msg, sockraw, 0); + assert(err >= 0); + + CameraMsg cmsg; + if (zmq_msg_size(&msg) == sizeof(cmsg)) { + memcpy(&cmsg, zmq_msg_data(&msg), zmq_msg_size(&msg)); + + LOGD("cameraops %d", cmsg.type); + + if (cmsg.type == CAMERA_MSG_AUTOEXPOSE) { + if (cmsg.camera_num == 0) { + do_autoexposure(&s->rear, cmsg.grey_frac); + do_autofocus(&s->rear); + } else { + do_autoexposure(&s->front, cmsg.grey_frac); + } + } else if (cmsg.type == -1) { + break; + } + } + + zmq_msg_close(&msg); + + } else if (which == sensor_sock) { + float vs[3] = {0.0}; + bool got_accel = acceleration_from_sensor_sock(sockraw, vs); + + uint64_t ts = nanos_since_boot(); + if (got_accel && ts - s->rear.last_sag_ts > 10000000) { // 10 ms + s->rear.last_sag_ts = ts; + s->rear.last_sag_acc_z = -vs[2]; + } + } else if (which == livelocationtiming_sock) { + uint64_t mono_time; + double gps_time; + if (gps_time_from_timing_sock(sockraw, &mono_time, &gps_time)) { + s->rear.global_time_offset = (uint64_t)(gps_time*1e9) - mono_time; + //LOGW("%f %lld = %lld", gps_time, mono_time, s->rear.global_time_offset); + s->rear.phase_request = 10000000; + s->rear.using_pll = true; + } + } + } + + zpoller_destroy(&poller); + zsock_destroy(&cameraops); + zsock_destroy(&sensor_sock); + zsock_destroy(&terminate); + + return NULL; +} + +void cameras_run(DualCameraState *s) { + int err; + + pthread_t ops_thread_handle; + err = pthread_create(&ops_thread_handle, NULL, + ops_thread, s); + assert(err == 0); + + CameraState* cameras[2] = {&s->rear, &s->front}; + + while (!do_exit) { + struct pollfd fds[2] = {{0}}; + + fds[0].fd = cameras[0]->isp_fd; + fds[0].events = POLLPRI; + + fds[1].fd = cameras[1]->isp_fd; + fds[1].events = POLLPRI; + + int ret = poll(fds, ARRAYSIZE(fds), 1000); + if (ret <= 0) { + LOGE("poll failed (%d)", ret); + break; + } + + // process cameras + for (int i=0; i<2; i++) { + if (!fds[i].revents) continue; + + CameraState *c = cameras[i]; + + struct v4l2_event ev; + ret = ioctl(c->isp_fd, VIDIOC_DQEVENT, &ev); + struct msm_isp_event_data *isp_event_data = (struct msm_isp_event_data *)ev.u.data; + unsigned int event_type = ev.type; + + uint64_t timestamp = (isp_event_data->mono_timestamp.tv_sec*1000000000ULL + + isp_event_data->mono_timestamp.tv_usec*1000); + + int buf_idx = isp_event_data->u.buf_done.buf_idx; + int stream_id = isp_event_data->u.buf_done.stream_id; + int buffer = (stream_id&0xFFFF) - 1; + + uint64_t t = nanos_since_boot(); + + /*if (i == 1) { + printf("%10.2f: VIDIOC_DQEVENT: %d type:%X (%s)\n", t*1.0/1e6, ret, event_type, get_isp_event_name(event_type)); + }*/ + + // printf("%d: %s\n", i, get_isp_event_name(event_type)); + + switch (event_type) { + case ISP_EVENT_BUF_DIVERT: + + /*if (c->is_samsung) { + printf("write %d\n", c->frame_size); + FILE *f = fopen("/tmp/test", "wb"); + fwrite((void*)c->camera_bufs[i].addr, 1, c->frame_size, f); + fclose(f); + }*/ + //printf("divert: %d %d %d\n", i, buffer, buf_idx); + + if (buffer == 0) { + c->camera_bufs_metadata[buf_idx] = get_frame_metadata(c, isp_event_data->frame_id); + tbuffer_dispatch(&c->camera_tb, buf_idx); + } else { + uint8_t *d = c->ss[buffer].bufs[buf_idx].addr; + if (buffer == 1) { + parse_autofocus(c, d); + } + c->ss[buffer].qbuf_info[buf_idx].dirty_buf = 1; + ioctl(c->isp_fd, VIDIOC_MSM_ISP_ENQUEUE_BUF, &c->ss[buffer].qbuf_info[buf_idx]); + } + break; + case ISP_EVENT_EOF: + // printf("ISP_EVENT_EOF delta %f\n", (t-last_t)/1e6); + c->last_t = t; + + if (c->using_pll) { + int mod = ((int)1000000000 / c->fps); + c->phase_actual = (((timestamp + c->global_time_offset) % mod) + mod) % mod; + LOGD("phase is %12d request is %12d with offset %lld", c->phase_actual, c->phase_request, c->global_time_offset); + } + + pthread_mutex_lock(&c->frame_info_lock); + c->frame_metadata[c->frame_metadata_idx] = (FrameMetadata){ + .frame_id = isp_event_data->frame_id, + .timestamp_eof = timestamp, + .frame_length = c->cur_frame_length, + .integ_lines = c->cur_integ_lines, + .global_gain = c->cur_gain, + .lens_pos = c->cur_lens_pos, + .lens_sag = c->last_sag_acc_z, + .lens_err = c->focus_err, + .lens_true_pos = c->lens_true_pos, + }; + c->frame_metadata_idx = (c->frame_metadata_idx+1)%METADATA_BUF_COUNT; + pthread_mutex_unlock(&c->frame_info_lock); + + break; + case ISP_EVENT_ERROR: + LOGE("ISP_EVENT_ERROR! err type: 0x%08x", isp_event_data->u.error_info.err_type); + break; + } + } + } + + LOG(" ************** STOPPING **************"); + + ops_term(); + err = pthread_join(ops_thread_handle, NULL); + assert(err == 0); + + cameras_close(s); +} + +void cameras_close(DualCameraState *s) { + camera_close(&s->rear); + camera_close(&s->front); +} + diff --git a/selfdrive/visiond/camera_qcom.h b/selfdrive/visiond/camera_qcom.h new file mode 100644 index 00000000000000..0cc8f844a57477 --- /dev/null +++ b/selfdrive/visiond/camera_qcom.h @@ -0,0 +1,138 @@ +#ifndef CAMERA_H +#define CAMERA_H + +#include +#include +#include + +#include "msmb_isp.h" +#include "msmb_ispif.h" +#include "msmb_camera.h" +#include "msm_cam_sensor.h" + +#include "common/mat.h" +#include "common/visionbuf.h" +#include "common/buffering.h" + +#include "camera_common.h" + +#define FRAME_BUF_COUNT 4 +#define METADATA_BUF_COUNT 4 + +#define DEVICE_OP3 0 +#define DEVICE_OP3T 1 +#define DEVICE_LP3 2 + +#define NUM_FOCUS 8 + +#ifdef __cplusplus +extern "C" { +#endif + +typedef struct CameraState CameraState; + +typedef int (*camera_apply_exposure_func)(CameraState *s, int gain, int integ_lines, int frame_length); + +typedef struct StreamState { + struct msm_isp_buf_request buf_request; + struct msm_vfe_axi_stream_request_cmd stream_req; + struct msm_isp_qbuf_info qbuf_info[FRAME_BUF_COUNT]; + VisionBuf *bufs; +} StreamState; + +typedef struct CameraState { + int camera_num; + int camera_id; + CameraInfo ci; + int frame_size; + + int device; + + void* ops_sock; + + uint32_t pixel_clock; + uint32_t line_length_pclk; + unsigned int max_gain; + + // PLL to sync cameras in time + // assumes at least 1 FPS + bool using_pll; + int phase_actual; + int phase_request; + int64_t global_time_offset; + + int csid_fd; + int csiphy_fd; + int sensor_fd; + int isp_fd; + int eeprom_fd; + // rear only + int ois_fd, actuator_fd; + uint16_t infinity_dac; + + struct msm_vfe_axi_stream_cfg_cmd stream_cfg; + + size_t eeprom_size; + uint8_t *eeprom; + + // uint32_t camera_bufs_ids[FRAME_BUF_COUNT]; + FrameMetadata camera_bufs_metadata[FRAME_BUF_COUNT]; + TBuffer camera_tb; + + pthread_mutex_t frame_info_lock; + FrameMetadata frame_metadata[METADATA_BUF_COUNT]; + int frame_metadata_idx; + float cur_exposure_frac; + float cur_gain_frac; + int cur_gain; + int cur_frame_length; + int cur_integ_lines; + + float digital_gain; + + StreamState ss[3]; + + uint64_t last_t; + + camera_apply_exposure_func apply_exposure; + + int16_t focus[NUM_FOCUS]; + uint8_t confidence[NUM_FOCUS]; + + float focus_err; + + uint16_t cur_step_pos; + uint16_t cur_lens_pos; + uint64_t last_sag_ts; + float last_sag_acc_z; + float lens_true_pos; + + int fps; + + mat3 transform; +} CameraState; + + +typedef struct DualCameraState { + int device; + + int ispif_fd; + + CameraState rear; + CameraState front; +} DualCameraState; + +void cameras_init(DualCameraState *s); +void cameras_open(DualCameraState *s, VisionBuf *camera_bufs_rear, VisionBuf *camera_bufs_focus, VisionBuf *camera_bufs_stats, VisionBuf *camera_bufs_front); +void cameras_run(DualCameraState *s); +void cameras_close(DualCameraState *s); + +void camera_autoexposure(CameraState *s, float grey_frac); +void actuator_move(CameraState *s, uint16_t target); +int sensor_write_regs(CameraState *s, struct msm_camera_i2c_reg_array* arr, size_t size, int data_type); + +#ifdef __cplusplus +} // extern "C" +#endif + +#endif diff --git a/selfdrive/visiond/clutil.c b/selfdrive/visiond/clutil.c new file mode 100644 index 00000000000000..0040e4dd6af6ad --- /dev/null +++ b/selfdrive/visiond/clutil.c @@ -0,0 +1,418 @@ +#include +#include +#include +#include +#include +#include +#include +#include + +#ifdef __APPLE__ +#include +#else +#include +#endif + +#include "common/util.h" + +#include "clutil.h" + +typedef struct CLUProgramIndex { + uint64_t index_hash; + const uint8_t* bin_data; + const uint8_t* bin_end; +} CLUProgramIndex; + +#ifdef CLU_NO_SRC +#include "clcache_bins.h" +#else +static const CLUProgramIndex clu_index[] = {}; +#endif + +void clu_init(void) { +#ifndef CLU_NO_SRC + mkdir("/tmp/clcache", 0777); + unlink("/tmp/clcache/index.cli"); +#endif +} + +cl_program cl_create_program_from_file(cl_context ctx, const char* path) { + char* src_buf = read_file(path, NULL); + assert(src_buf); + + int err = 0; + cl_program ret = clCreateProgramWithSource(ctx, 1, (const char**)&src_buf, NULL, &err); + assert(err == 0); + + free(src_buf); + + return ret; +} + +static char* get_version_string(cl_platform_id platform) { + size_t size = 0; + int err; + err = clGetPlatformInfo(platform, CL_PLATFORM_VERSION, 0, NULL, &size); + assert(err == 0); + char *str = malloc(size); + assert(str); + err = clGetPlatformInfo(platform, CL_PLATFORM_VERSION, size, str, NULL); + assert(err == 0); + return str; +} + +void cl_print_info(cl_platform_id platform, cl_device_id device) { + char str[4096]; + + clGetPlatformInfo(platform, CL_PLATFORM_VENDOR, sizeof(str), str, NULL); + printf("vendor: '%s'\n", str); + + char* version = get_version_string(platform); + printf("platform version: '%s'\n", version); + free(version); + + clGetPlatformInfo(platform, CL_PLATFORM_PROFILE, sizeof(str), str, NULL); + printf("profile: '%s'\n", str); + + clGetPlatformInfo(platform, CL_PLATFORM_EXTENSIONS, sizeof(str), str, NULL); + printf("extensions: '%s'\n", str); + + clGetDeviceInfo(device, CL_DEVICE_NAME, sizeof(str), str, NULL); + printf("name: '%s'\n", str); + + clGetDeviceInfo(device, CL_DEVICE_VERSION, sizeof(str), str, NULL); + printf("device version: '%s'\n", str); + + size_t sz; + clGetDeviceInfo(device, CL_DEVICE_MAX_WORK_GROUP_SIZE, sizeof(sz), &sz, NULL); + printf("max work group size: %u\n", sz); + + cl_device_type type; + clGetDeviceInfo(device, CL_DEVICE_TYPE, sizeof(type), &type, NULL); + printf("type = 0x%04x = ", (unsigned int)type); + switch(type) { + case CL_DEVICE_TYPE_CPU: + printf("CL_DEVICE_TYPE_CPU\n"); + break; + case CL_DEVICE_TYPE_GPU: + printf("CL_DEVICE_TYPE_GPU\n"); + break; + case CL_DEVICE_TYPE_ACCELERATOR: + printf("CL_DEVICE_TYPE_ACCELERATOR\n"); + break; + default: + printf("Other...\n" ); + break; + } +} + +void cl_print_build_errors(cl_program program, cl_device_id device) { + cl_build_status status; + clGetProgramBuildInfo(program, device, CL_PROGRAM_BUILD_STATUS, + sizeof(cl_build_status), &status, NULL); + + size_t log_size; + clGetProgramBuildInfo(program, device, + CL_PROGRAM_BUILD_LOG, 0, NULL, &log_size); + + char* log = calloc(log_size+1, 1); + assert(log); + + clGetProgramBuildInfo(program, device, + CL_PROGRAM_BUILD_LOG, log_size+1, log, NULL); + + printf("build failed; status=%d, log:\n%s\n", + status, log); + + free(log); +} + +uint64_t clu_index_hash(const char* s) { + size_t sl = strlen(s); + assert(sl < 128); + uint64_t x = 0; + for (int i=127; i>=0; i--) { + x *= 65599ULL; + x += (uint8_t)s[i> 32); +} + +uint64_t clu_fnv_hash(const uint8_t *data, size_t len) { + /* 64 bit Fowler/Noll/Vo FNV-1a hash code */ + uint64_t hval = 0xcbf29ce484222325ULL; + const uint8_t *dp = data; + const uint8_t *de = data + len; + while (dp < de) { + hval ^= (uint64_t) *dp++; + hval += (hval << 1) + (hval << 4) + (hval << 5) + + (hval << 7) + (hval << 8) + (hval << 40); + } + + return hval; +} + +cl_program cl_cached_program_from_hash(cl_context ctx, cl_device_id device_id, uint64_t hash) { + int err; + + char cache_path[1024]; + snprintf(cache_path, sizeof(cache_path), "/tmp/clcache/%016" PRIx64 ".clb", hash); + + size_t bin_size; + uint8_t *bin = read_file(cache_path, &bin_size); + if (!bin) { + return NULL; + } + + cl_program prg = clCreateProgramWithBinary(ctx, 1, &device_id, &bin_size, (const uint8_t**)&bin, NULL, &err); + assert(err == 0); + + free(bin); + + err = clBuildProgram(prg, 1, &device_id, NULL, NULL, NULL); + assert(err == 0); + + return prg; +} + +static uint8_t* get_program_binary(cl_program prg, size_t *out_size) { + int err; + + cl_uint num_devices; + err = clGetProgramInfo(prg, CL_PROGRAM_NUM_DEVICES, sizeof(num_devices), &num_devices, NULL); + assert(err == 0); + assert(num_devices == 1); + + size_t binary_size = 0; + err = clGetProgramInfo(prg, CL_PROGRAM_BINARY_SIZES, sizeof(binary_size), &binary_size, NULL); + assert(err == 0); + assert(binary_size > 0); + + uint8_t *binary_buf = malloc(binary_size); + assert(binary_buf); + + uint8_t* bufs[1] = { binary_buf, }; + + err = clGetProgramInfo(prg, CL_PROGRAM_BINARIES, sizeof(bufs), &bufs, NULL); + assert(err == 0); + + *out_size = binary_size; + return binary_buf; +} + +cl_program cl_cached_program_from_string(cl_context ctx, cl_device_id device_id, + const char* src, const char* args, + uint64_t *out_hash) { + int err; + + cl_platform_id platform; + err = clGetDeviceInfo(device_id, CL_DEVICE_PLATFORM, sizeof(platform), &platform, NULL); + assert(err == 0); + + const char* platform_version = get_version_string(platform); + + const size_t hash_len = strlen(platform_version)+1+strlen(src)+1+strlen(args)+1; + char* hash_buf = malloc(hash_len); + assert(hash_buf); + memset(hash_buf, 0, hash_len); + snprintf(hash_buf, hash_len, "%s%c%s%c%s", platform_version, 1, src, 1, args); + free((void*)platform_version); + + uint64_t hash = clu_fnv_hash((uint8_t*)hash_buf, hash_len); + free(hash_buf); + + cl_program prg = NULL; +#ifndef CLU_NO_CACHE + prg = cl_cached_program_from_hash(ctx, device_id, hash); +#endif + if (prg == NULL) { + prg = clCreateProgramWithSource(ctx, 1, (const char**)&src, NULL, &err); + assert(err == 0); + + err = clBuildProgram(prg, 1, &device_id, args, NULL, NULL); + if (err != 0) { + cl_print_build_errors(prg, device_id); + } + assert(err == 0); + +#ifndef CLU_NO_CACHE + // write program binary to cache + + size_t binary_size; + uint8_t *binary_buf = get_program_binary(prg, &binary_size); + + char cache_path[1024]; + snprintf(cache_path, sizeof(cache_path), "/tmp/clcache/%016" PRIx64 ".clb", hash); + FILE* of = fopen(cache_path, "wb"); + assert(of); + fwrite(binary_buf, 1, binary_size, of); + fclose(of); + + free(binary_buf); +#endif + } + + if (out_hash) *out_hash = hash; + return prg; +} + +cl_program cl_cached_program_from_file(cl_context ctx, cl_device_id device_id, const char* path, const char* args, + uint64_t *out_hash) { + char* src_buf = read_file(path, NULL); + assert(src_buf); + cl_program ret = cl_cached_program_from_string(ctx, device_id, src_buf, args, out_hash); + free(src_buf); + return ret; +} + +static void add_index(uint64_t index_hash, uint64_t src_hash) { + FILE *f = fopen("/tmp/clcache/index.cli", "a"); + assert(f); + fprintf(f, "%016" PRIx64 " %016" PRIx64 "\n", index_hash, src_hash); + fclose(f); +} + + +cl_program cl_program_from_index(cl_context ctx, cl_device_id device_id, uint64_t index_hash) { + int err; + + int i; + for (i=0; i= ARRAYSIZE(clu_index)) { + assert(false); + } + + size_t bin_size = clu_index[i].bin_end - clu_index[i].bin_data; + const uint8_t *bin_data = clu_index[i].bin_data; + + cl_program prg = clCreateProgramWithBinary(ctx, 1, &device_id, &bin_size, (const uint8_t**)&bin_data, NULL, &err); + assert(err == 0); + + err = clBuildProgram(prg, 1, &device_id, NULL, NULL, NULL); + assert(err == 0); + + return prg; +} + +cl_program cl_index_program_from_string(cl_context ctx, cl_device_id device_id, + const char* src, const char* args, + uint64_t index_hash) { + uint64_t src_hash = 0; + cl_program ret = cl_cached_program_from_string(ctx, device_id, src, args, &src_hash); +#ifndef CLU_NO_CACHE + add_index(index_hash, src_hash); +#endif + return ret; +} + +cl_program cl_index_program_from_file(cl_context ctx, cl_device_id device_id, const char* path, const char* args, + uint64_t index_hash) { + uint64_t src_hash = 0; + cl_program ret = cl_cached_program_from_file(ctx, device_id, path, args, &src_hash); +#ifndef CLU_NO_CACHE + add_index(index_hash, src_hash); +#endif + return ret; +} + +/* + * Given a cl code and return a string represenation + */ +const char* cl_get_error_string(int err) { + switch (err) { + case 0: return "CL_SUCCESS"; + case -1: return "CL_DEVICE_NOT_FOUND"; + case -2: return "CL_DEVICE_NOT_AVAILABLE"; + case -3: return "CL_COMPILER_NOT_AVAILABLE"; + case -4: return "CL_MEM_OBJECT_ALLOCATION_FAILURE"; + case -5: return "CL_OUT_OF_RESOURCES"; + case -6: return "CL_OUT_OF_HOST_MEMORY"; + case -7: return "CL_PROFILING_INFO_NOT_AVAILABLE"; + case -8: return "CL_MEM_COPY_OVERLAP"; + case -9: return "CL_IMAGE_FORMAT_MISMATCH"; + case -10: return "CL_IMAGE_FORMAT_NOT_SUPPORTED"; + case -12: return "CL_MAP_FAILURE"; + case -13: return "CL_MISALIGNED_SUB_BUFFER_OFFSET"; + case -14: return "CL_EXEC_STATUS_ERROR_FOR_EVENTS_IN_WAIT_LIST"; + case -15: return "CL_COMPILE_PROGRAM_FAILURE"; + case -16: return "CL_LINKER_NOT_AVAILABLE"; + case -17: return "CL_LINK_PROGRAM_FAILURE"; + case -18: return "CL_DEVICE_PARTITION_FAILED"; + case -19: return "CL_KERNEL_ARG_INFO_NOT_AVAILABLE"; + case -30: return "CL_INVALID_VALUE"; + case -31: return "CL_INVALID_DEVICE_TYPE"; + case -32: return "CL_INVALID_PLATFORM"; + case -33: return "CL_INVALID_DEVICE"; + case -34: return "CL_INVALID_CONTEXT"; + case -35: return "CL_INVALID_QUEUE_PROPERTIES"; + case -36: return "CL_INVALID_COMMAND_QUEUE"; + case -37: return "CL_INVALID_HOST_PTR"; + case -38: return "CL_INVALID_MEM_OBJECT"; + case -39: return "CL_INVALID_IMAGE_FORMAT_DESCRIPTOR"; + case -40: return "CL_INVALID_IMAGE_SIZE"; + case -41: return "CL_INVALID_SAMPLER"; + case -42: return "CL_INVALID_BINARY"; + case -43: return "CL_INVALID_BUILD_OPTIONS"; + case -44: return "CL_INVALID_PROGRAM"; + case -45: return "CL_INVALID_PROGRAM_EXECUTABLE"; + case -46: return "CL_INVALID_KERNEL_NAME"; + case -47: return "CL_INVALID_KERNEL_DEFINITION"; + case -48: return "CL_INVALID_KERNEL"; + case -49: return "CL_INVALID_ARG_INDEX"; + case -50: return "CL_INVALID_ARG_VALUE"; + case -51: return "CL_INVALID_ARG_SIZE"; + case -52: return "CL_INVALID_KERNEL_ARGS"; + case -53: return "CL_INVALID_WORK_DIMENSION"; + case -54: return "CL_INVALID_WORK_GROUP_SIZE"; + case -55: return "CL_INVALID_WORK_ITEM_SIZE"; + case -56: return "CL_INVALID_GLOBAL_OFFSET"; + case -57: return "CL_INVALID_EVENT_WAIT_LIST"; + case -58: return "CL_INVALID_EVENT"; + case -59: return "CL_INVALID_OPERATION"; + case -60: return "CL_INVALID_GL_OBJECT"; + case -61: return "CL_INVALID_BUFFER_SIZE"; + case -62: return "CL_INVALID_MIP_LEVEL"; + case -63: return "CL_INVALID_GLOBAL_WORK_SIZE"; + case -64: return "CL_INVALID_PROPERTY"; + case -65: return "CL_INVALID_IMAGE_DESCRIPTOR"; + case -66: return "CL_INVALID_COMPILER_OPTIONS"; + case -67: return "CL_INVALID_LINKER_OPTIONS"; + case -68: return "CL_INVALID_DEVICE_PARTITION_COUNT"; + case -69: return "CL_INVALID_PIPE_SIZE"; + case -70: return "CL_INVALID_DEVICE_QUEUE"; + case -71: return "CL_INVALID_SPEC_ID"; + case -72: return "CL_MAX_SIZE_RESTRICTION_EXCEEDED"; + case -1002: return "CL_INVALID_D3D10_DEVICE_KHR"; + case -1003: return "CL_INVALID_D3D10_RESOURCE_KHR"; + case -1004: return "CL_D3D10_RESOURCE_ALREADY_ACQUIRED_KHR"; + case -1005: return "CL_D3D10_RESOURCE_NOT_ACQUIRED_KHR"; + case -1006: return "CL_INVALID_D3D11_DEVICE_KHR"; + case -1007: return "CL_INVALID_D3D11_RESOURCE_KHR"; + case -1008: return "CL_D3D11_RESOURCE_ALREADY_ACQUIRED_KHR"; + case -1009: return "CL_D3D11_RESOURCE_NOT_ACQUIRED_KHR"; + case -1010: return "CL_INVALID_DX9_MEDIA_ADAPTER_KHR"; + case -1011: return "CL_INVALID_DX9_MEDIA_SURFACE_KHR"; + case -1012: return "CL_DX9_MEDIA_SURFACE_ALREADY_ACQUIRED_KHR"; + case -1013: return "CL_DX9_MEDIA_SURFACE_NOT_ACQUIRED_KHR"; + case -1093: return "CL_INVALID_EGL_OBJECT_KHR"; + case -1092: return "CL_EGL_RESOURCE_NOT_ACQUIRED_KHR"; + case -1001: return "CL_PLATFORM_NOT_FOUND_KHR"; + case -1057: return "CL_DEVICE_PARTITION_FAILED_EXT"; + case -1058: return "CL_INVALID_PARTITION_COUNT_EXT"; + case -1059: return "CL_INVALID_PARTITION_NAME_EXT"; + case -1094: return "CL_INVALID_ACCELERATOR_INTEL"; + case -1095: return "CL_INVALID_ACCELERATOR_TYPE_INTEL"; + case -1096: return "CL_INVALID_ACCELERATOR_DESCRIPTOR_INTEL"; + case -1097: return "CL_ACCELERATOR_TYPE_NOT_SUPPORTED_INTEL"; + case -1000: return "CL_INVALID_GL_SHAREGROUP_REFERENCE_KHR"; + case -1098: return "CL_INVALID_VA_API_MEDIA_ADAPTER_INTEL"; + case -1099: return "CL_INVALID_VA_API_MEDIA_SURFACE_INTEL"; + case -1100: return "CL_VA_API_MEDIA_SURFACE_ALREADY_ACQUIRED_INTEL"; + case -1101: return "CL_VA_API_MEDIA_SURFACE_NOT_ACQUIRED_INTEL"; + default: return "CL_UNKNOWN_ERROR"; + } +} diff --git a/selfdrive/visiond/clutil.h b/selfdrive/visiond/clutil.h new file mode 100644 index 00000000000000..b87961eacdfbf8 --- /dev/null +++ b/selfdrive/visiond/clutil.h @@ -0,0 +1,87 @@ +#ifndef CLUTIL_H +#define CLUTIL_H + +#include +#include +#include + +#ifdef __APPLE__ +#include +#else +#include +#endif + +#ifdef __cplusplus +extern "C" { +#endif + +void clu_init(void); + +cl_program cl_create_program_from_file(cl_context ctx, const char* path); +void cl_print_info(cl_platform_id platform, cl_device_id device); +void cl_print_build_errors(cl_program program, cl_device_id device); +void cl_print_build_errors(cl_program program, cl_device_id device); + +cl_program cl_cached_program_from_hash(cl_context ctx, cl_device_id device_id, uint64_t hash); +cl_program cl_cached_program_from_string(cl_context ctx, cl_device_id device_id, + const char* src, const char* args, + uint64_t *out_hash); +cl_program cl_cached_program_from_file(cl_context ctx, cl_device_id device_id, const char* path, const char* args, + uint64_t *out_hash); + +cl_program cl_program_from_index(cl_context ctx, cl_device_id device_id, uint64_t index_hash); + +cl_program cl_index_program_from_string(cl_context ctx, cl_device_id device_id, + const char* src, const char* args, + uint64_t index_hash); +cl_program cl_index_program_from_file(cl_context ctx, cl_device_id device_id, const char* path, const char* args, + uint64_t index_hash); + +uint64_t clu_index_hash(const char *s); +uint64_t clu_fnv_hash(const uint8_t *data, size_t len); + +const char* cl_get_error_string(int err); + +static inline int cl_check_error(int err) { + if (err != 0) { + fprintf(stderr, "%s\n", cl_get_error_string(err)); + exit(1); + } + return err; +} + + +// // string hash macro. compiler, I'm so sorry. +#define CLU_H1(s,i,x) (x*65599ULL+(uint8_t)s[(i)>32))) + +#define CLU_STRINGIFY(x) #x +#define CLU_STRINGIFY2(x) CLU_STRINGIFY(x) +#define CLU_LINESTR CLU_STRINGIFY2(__LINE__) + +#ifdef CLU_NO_SRC + + #define CLU_LOAD_FROM_STRING(ctx, device_id, src, args) \ + cl_program_from_index(ctx, device_id, CLU_HASH("\1" __FILE__ "\1" CLU_LINESTR) ^ clu_fnv_hash((const uint8_t*)__func__, strlen(__func__)) ^ clu_fnv_hash((const uint8_t*)args, strlen(args))) + #define CLU_LOAD_FROM_FILE(ctx, device_id, path, args) \ + cl_program_from_index(ctx, device_id, CLU_HASH("\2" path) ^ clu_fnv_hash((const uint8_t*)args, strlen(args))) + +#else + + #define CLU_LOAD_FROM_STRING(ctx, device_id, src, args) \ + cl_index_program_from_string(ctx, device_id, src, args, clu_index_hash("\1" __FILE__ "\1" CLU_LINESTR) ^ clu_fnv_hash((const uint8_t*)__func__, strlen(__func__)) ^ clu_fnv_hash((const uint8_t*)args, strlen(args))) + #define CLU_LOAD_FROM_FILE(ctx, device_id, path, args) \ + cl_index_program_from_file(ctx, device_id, path, args, clu_index_hash("\2" path) ^ clu_fnv_hash((const uint8_t*)args, strlen(args))) + +#endif + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/selfdrive/visiond/commonmodel.c b/selfdrive/visiond/commonmodel.c new file mode 100644 index 00000000000000..595d2609e74d4e --- /dev/null +++ b/selfdrive/visiond/commonmodel.c @@ -0,0 +1,155 @@ +#include "commonmodel.h" + +#include +#include "cereal/gen/c/log.capnp.h" +#include "common/mat.h" +#include "common/timing.h" + +void model_input_init(ModelInput* s, int width, int height, + cl_device_id device_id, cl_context context) { + int err; + s->device_id = device_id; + s->context = context; + + transform_init(&s->transform, context, device_id); + s->transformed_width = width; + s->transformed_height = height; + + s->transformed_y_cl = clCreateBuffer(s->context, CL_MEM_READ_WRITE, + s->transformed_width*s->transformed_height, NULL, &err); + assert(err == 0); + s->transformed_u_cl = clCreateBuffer(s->context, CL_MEM_READ_WRITE, + (s->transformed_width/2)*(s->transformed_height/2), NULL, &err); + assert(err == 0); + s->transformed_v_cl = clCreateBuffer(s->context, CL_MEM_READ_WRITE, + (s->transformed_width/2)*(s->transformed_height/2), NULL, &err); + assert(err == 0); + + s->net_input_size = ((width*height*3)/2)*sizeof(float); + s->net_input = clCreateBuffer(s->context, CL_MEM_READ_WRITE, + s->net_input_size, (void*)NULL, &err); + assert(err == 0); + + loadyuv_init(&s->loadyuv, context, device_id, s->transformed_width, s->transformed_height); +} + +float *model_input_prepare(ModelInput* s, cl_command_queue q, + cl_mem yuv_cl, int width, int height, + mat3 transform) { + int err; + int i = 0; + transform_queue(&s->transform, q, + yuv_cl, width, height, + s->transformed_y_cl, s->transformed_u_cl, s->transformed_v_cl, + s->transformed_width, s->transformed_height, + transform); + loadyuv_queue(&s->loadyuv, q, + s->transformed_y_cl, s->transformed_u_cl, s->transformed_v_cl, + s->net_input); + float *net_input_buf = (float *)clEnqueueMapBuffer(q, s->net_input, CL_TRUE, + CL_MAP_READ, 0, s->net_input_size, + 0, NULL, NULL, &err); + clFinish(q); + return net_input_buf; +} + +void model_input_free(ModelInput* s) { + transform_destroy(&s->transform); + loadyuv_destroy(&s->loadyuv); +} + + +void softmax(const float* input, float* output, size_t len) { + float max_val = -FLT_MAX; + for(int i = 0; i < len; i++) { + const float v = input[i]; + if( v > max_val ) { + max_val = v; + } + } + + float denominator = 0; + for(int i = 0; i < len; i++) { + float const v = input[i]; + float const v_exp = expf(v - max_val); + denominator += v_exp; + output[i] = v_exp; + } + + const float inv_denominator = 1. / denominator; + for(int i = 0; i < len; i++) { + output[i] *= inv_denominator; + } + +} + + +static cereal_ModelData_PathData_ptr path_to_cereal(struct capn_segment *cs, const PathData data) { + capn_list32 points_ptr = capn_new_list32(cs, MODEL_PATH_DISTANCE); + for (int i=0; i + +#include "common/mat.h" +#include "common/modeldata.h" +#include "transform.h" +#include "loadyuv.h" + +#ifdef __cplusplus +extern "C" { +#endif + +void softmax(const float* input, float* output, size_t len); + +typedef struct ModelInput { + cl_device_id device_id; + cl_context context; + + // input + Transform transform; + int transformed_width, transformed_height; + cl_mem transformed_y_cl, transformed_u_cl, transformed_v_cl; + LoadYUVState loadyuv; + cl_mem net_input; + size_t net_input_size; +} ModelInput; + +void model_input_init(ModelInput* s, int width, int height, + cl_device_id device_id, cl_context context); +float *model_input_prepare(ModelInput* s, cl_command_queue q, + cl_mem yuv_cl, int width, int height, + mat3 transform); +void model_input_free(ModelInput* s); + +void model_publish(void* sock, uint32_t frame_id, + const mat3 transform, const ModelData data); + +#ifdef __cplusplus +} +#endif + +#endif + diff --git a/selfdrive/visiond/constants.py b/selfdrive/visiond/constants.py new file mode 100644 index 00000000000000..878478e9cf1531 --- /dev/null +++ b/selfdrive/visiond/constants.py @@ -0,0 +1,2 @@ +MAX_DISTANCE = 140. +LANE_OFFSET = 1.8 diff --git a/selfdrive/visiond/debayer.cl b/selfdrive/visiond/debayer.cl new file mode 100644 index 00000000000000..344ead035672ec --- /dev/null +++ b/selfdrive/visiond/debayer.cl @@ -0,0 +1,130 @@ +const __constant float3 color_correction[3] = { + // Matrix from WBraw -> sRGBD65 (normalized) + (float3)( 1.62393627, -0.2092988, 0.00119886), + (float3)(-0.45734315, 1.5534676, -0.59296798), + (float3)(-0.16659312, -0.3441688, 1.59176912), +}; + +float3 color_correct(float3 x) { + float3 ret = (0,0,0); + + // white balance of daylight + x /= (float3)(0.4609375, 1.0, 0.546875); + x = max(0.0, min(1.0, x)); + + // fix up the colors + ret += x.x * color_correction[0]; + ret += x.y * color_correction[1]; + ret += x.z * color_correction[2]; + return ret; +} + +float3 srgb_gamma(float3 p) { + // go all out and add an sRGB gamma curve + const float3 ph = (1.0f + 0.055f)*pow(p, 1/2.4f) - 0.055f; + const float3 pl = p*12.92f; + return select(ph, pl, islessequal(p, 0.0031308f)); +} + +__constant int dpcm_lookup[512] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 0, -1, -2, -3, -4, -5, -6, -7, -8, -9, -10, -11, -12, -13, -14, -15, -16, -17, -18, -19, -20, -21, -22, -23, -24, -25, -26, -27, -28, -29, -30, -31, 935, 951, 967, 983, 999, 1015, 1031, 1047, 1063, 1079, 1095, 1111, 1127, 1143, 1159, 1175, 1191, 1207, 1223, 1239, 1255, 1271, 1287, 1303, 1319, 1335, 1351, 1367, 1383, 1399, 1415, 1431, -935, -951, -967, -983, -999, -1015, -1031, -1047, -1063, -1079, -1095, -1111, -1127, -1143, -1159, -1175, -1191, -1207, -1223, -1239, -1255, -1271, -1287, -1303, -1319, -1335, -1351, -1367, -1383, -1399, -1415, -1431, 419, 427, 435, 443, 451, 459, 467, 475, 483, 491, 499, 507, 515, 523, 531, 539, 547, 555, 563, 571, 579, 587, 595, 603, 611, 619, 627, 635, 643, 651, 659, 667, 675, 683, 691, 699, 707, 715, 723, 731, 739, 747, 755, 763, 771, 779, 787, 795, 803, 811, 819, 827, 835, 843, 851, 859, 867, 875, 883, 891, 899, 907, 915, 923, -419, -427, -435, -443, -451, -459, -467, -475, -483, -491, -499, -507, -515, -523, -531, -539, -547, -555, -563, -571, -579, -587, -595, -603, -611, -619, -627, -635, -643, -651, -659, -667, -675, -683, -691, -699, -707, -715, -723, -731, -739, -747, -755, -763, -771, -779, -787, -795, -803, -811, -819, -827, -835, -843, -851, -859, -867, -875, -883, -891, -899, -907, -915, -923, 161, 165, 169, 173, 177, 181, 185, 189, 193, 197, 201, 205, 209, 213, 217, 221, 225, 229, 233, 237, 241, 245, 249, 253, 257, 261, 265, 269, 273, 277, 281, 285, 289, 293, 297, 301, 305, 309, 313, 317, 321, 325, 329, 333, 337, 341, 345, 349, 353, 357, 361, 365, 369, 373, 377, 381, 385, 389, 393, 397, 401, 405, 409, 413, -161, -165, -169, -173, -177, -181, -185, -189, -193, -197, -201, -205, -209, -213, -217, -221, -225, -229, -233, -237, -241, -245, -249, -253, -257, -261, -265, -269, -273, -277, -281, -285, -289, -293, -297, -301, -305, -309, -313, -317, -321, -325, -329, -333, -337, -341, -345, -349, -353, -357, -361, -365, -369, -373, -377, -381, -385, -389, -393, -397, -401, -405, -409, -413, 32, 34, 36, 38, 40, 42, 44, 46, 48, 50, 52, 54, 56, 58, 60, 62, 64, 66, 68, 70, 72, 74, 76, 78, 80, 82, 84, 86, 88, 90, 92, 94, 96, 98, 100, 102, 104, 106, 108, 110, 112, 114, 116, 118, 120, 122, 124, 126, 128, 130, 132, 134, 136, 138, 140, 142, 144, 146, 148, 150, 152, 154, 156, 158, -32, -34, -36, -38, -40, -42, -44, -46, -48, -50, -52, -54, -56, -58, -60, -62, -64, -66, -68, -70, -72, -74, -76, -78, -80, -82, -84, -86, -88, -90, -92, -94, -96, -98, -100, -102, -104, -106, -108, -110, -112, -114, -116, -118, -120, -122, -124, -126, -128, -130, -132, -134, -136, -138, -140, -142, -144, -146, -148, -150, -152, -154, -156, -158}; + +inline uint4 decompress(uint4 p, uint4 pl) { + uint4 r1 = (pl + (uint4)(dpcm_lookup[p.s0], dpcm_lookup[p.s1], dpcm_lookup[p.s2], dpcm_lookup[p.s3])); + uint4 r2 = ((p-0x200)<<5) | 0xF; + r2 += select((uint4)(0,0,0,0), (uint4)(1,1,1,1), r2 <= pl); + return select(r2, r1, p < 0x200); +} + +__kernel void debayer10(__global uchar const * const in, + __global uchar * out, float digital_gain) +{ + const int oy = get_global_id(0); + if (oy >= RGB_HEIGHT) return; + const int iy = oy * 2; + + uint4 pint_last; + for (int ox = 0; ox < RGB_WIDTH; ox += 2) { + const int ix = (ox/2) * 5; + + // TODO: why doesn't this work for the frontview + /*const uchar8 v1 = vload8(0, &in[iy * FRAME_STRIDE + ix]); + const uchar ex1 = v1.s4; + const uchar8 v2 = vload8(0, &in[(iy+1) * FRAME_STRIDE + ix]); + const uchar ex2 = v2.s4;*/ + + const uchar4 v1 = vload4(0, &in[iy * FRAME_STRIDE + ix]); + const uchar ex1 = in[iy * FRAME_STRIDE + ix + 4]; + const uchar4 v2 = vload4(0, &in[(iy+1) * FRAME_STRIDE + ix]); + const uchar ex2 = in[(iy+1) * FRAME_STRIDE + ix + 4]; + + uint4 pinta[2]; + pinta[0] = (uint4)( + (((uint)v1.s0 << 2) + ( (ex1 >> 0) & 3)), + (((uint)v1.s1 << 2) + ( (ex1 >> 2) & 3)), + (((uint)v2.s0 << 2) + ( (ex2 >> 0) & 3)), + (((uint)v2.s1 << 2) + ( (ex2 >> 2) & 3))); + pinta[1] = (uint4)( + (((uint)v1.s2 << 2) + ( (ex1 >> 4) & 3)), + (((uint)v1.s3 << 2) + ( (ex1 >> 6) & 3)), + (((uint)v2.s2 << 2) + ( (ex2 >> 4) & 3)), + (((uint)v2.s3 << 2) + ( (ex2 >> 6) & 3))); + + #pragma unroll + for (uint px = 0; px < 2; px++) { + uint4 pint = pinta[px]; + +#if HDR + // decompress HDR + pint = (ox == 0 && px == 0) ? ((pint<<4) | 8) : decompress(pint, pint_last); + pint_last = pint; +#endif + + float4 p = convert_float4(pint); + + // 64 is the black level of the sensor, remove + // (changed to 56 for HDR) + const float black_level = 56.0f; + p = (p - black_level); + + // correct vignetting (no pow function?) + // see https://www.eecis.udel.edu/~jye/lab_research/09/JiUp.pdf the A (4th order) + const float r = ((oy - RGB_HEIGHT/2)*(oy - RGB_HEIGHT/2) + (ox - RGB_WIDTH/2)*(ox - RGB_WIDTH/2)); + const float fake_f = 700.0f; // should be 910, but this fits... + const float lil_a = (1.0f + r/(fake_f*fake_f)); + p = p * lil_a * lil_a; + + // rescale to 1.0 +#if HDR + p /= (16384.0f-black_level); +#else + p /= (1024.0f-black_level); +#endif + + // digital gain + p *= digital_gain; + + // use both green channels +#if BAYER_FLIP == 3 + float3 c1 = (float3)(p.s3, (p.s1+p.s2)/2.0f, p.s0); +#elif BAYER_FLIP == 2 + float3 c1 = (float3)(p.s2, (p.s0+p.s3)/2.0f, p.s1); +#elif BAYER_FLIP == 1 + float3 c1 = (float3)(p.s1, (p.s0+p.s3)/2.0f, p.s2); +#elif BAYER_FLIP == 0 + float3 c1 = (float3)(p.s0, (p.s1+p.s2)/2.0f, p.s3); +#endif + + // color correction + c1 = color_correct(c1); + +#if HDR + // srgb gamma isn't right for YUV, so it's disabled for now + c1 = srgb_gamma(c1); +#endif + + // output BGR + const int ooff = oy * RGB_STRIDE/3 + ox; + vstore3(convert_uchar3_sat(c1.zyx * 255.0f), ooff+px, out); + } + } +} diff --git a/selfdrive/visiond/include/msm_cam_sensor.h b/selfdrive/visiond/include/msm_cam_sensor.h new file mode 100644 index 00000000000000..c75d1fd5272444 --- /dev/null +++ b/selfdrive/visiond/include/msm_cam_sensor.h @@ -0,0 +1,829 @@ +#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/selfdrive/visiond/include/msm_camsensor_sdk.h b/selfdrive/visiond/include/msm_camsensor_sdk.h new file mode 100644 index 00000000000000..62a4da253c9345 --- /dev/null +++ b/selfdrive/visiond/include/msm_camsensor_sdk.h @@ -0,0 +1,386 @@ +#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/selfdrive/visiond/include/msmb_camera.h b/selfdrive/visiond/include/msmb_camera.h new file mode 100644 index 00000000000000..f4c4b3e183e86c --- /dev/null +++ b/selfdrive/visiond/include/msmb_camera.h @@ -0,0 +1,220 @@ +#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/selfdrive/visiond/include/msmb_isp.h b/selfdrive/visiond/include/msmb_isp.h new file mode 100644 index 00000000000000..35589e050a4d06 --- /dev/null +++ b/selfdrive/visiond/include/msmb_isp.h @@ -0,0 +1,880 @@ +#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/selfdrive/visiond/include/msmb_ispif.h b/selfdrive/visiond/include/msmb_ispif.h new file mode 100644 index 00000000000000..2564c33b7b31ed --- /dev/null +++ b/selfdrive/visiond/include/msmb_ispif.h @@ -0,0 +1,125 @@ +#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/selfdrive/visiond/loadyuv.c b/selfdrive/visiond/loadyuv.c new file mode 100644 index 00000000000000..2b50fb9d2a4105 --- /dev/null +++ b/selfdrive/visiond/loadyuv.c @@ -0,0 +1,82 @@ +#include +#include + +#include "clutil.h" + +#include "loadyuv.h" + +void loadyuv_init(LoadYUVState* s, cl_context ctx, cl_device_id device_id, int width, int height) { + int err = 0; + memset(s, 0, sizeof(*s)); + + s->width = width; + s->height = height; + + char args[1024]; + snprintf(args, sizeof(args), + "-cl-fast-relaxed-math -cl-denorms-are-zero " + "-DTRANSFORMED_WIDTH=%d -DTRANSFORMED_HEIGHT=%d", + width, height); + cl_program prg = CLU_LOAD_FROM_FILE(ctx, device_id, "loadyuv.cl", args); + + s->loadys_krnl = clCreateKernel(prg, "loadys", &err); + assert(err == 0); + s->loaduv_krnl = clCreateKernel(prg, "loaduv", &err); + assert(err == 0); + + // done with this + err = clReleaseProgram(prg); + assert(err == 0); +} + +void loadyuv_destroy(LoadYUVState* s) { + int err = 0; + + err = clReleaseKernel(s->loadys_krnl); + assert(err == 0); + err = clReleaseKernel(s->loaduv_krnl); + assert(err == 0); +} + +void loadyuv_queue(LoadYUVState* s, cl_command_queue q, + cl_mem y_cl, cl_mem u_cl, cl_mem v_cl, + cl_mem out_cl) { + int err = 0; + + err = clSetKernelArg(s->loadys_krnl, 0, sizeof(cl_mem), &y_cl); + assert(err == 0); + err = clSetKernelArg(s->loadys_krnl, 1, sizeof(cl_mem), &out_cl); + assert(err == 0); + + const size_t loadys_work_size = (s->width*s->height)/8; + err = clEnqueueNDRangeKernel(q, s->loadys_krnl, 1, NULL, + &loadys_work_size, NULL, 0, 0, NULL); + assert(err == 0); + + const size_t loaduv_work_size = ((s->width/2)*(s->height/2))/8; + cl_int loaduv_out_off = (s->width*s->height); + + err = clSetKernelArg(s->loaduv_krnl, 0, sizeof(cl_mem), &u_cl); + assert(err == 0); + err = clSetKernelArg(s->loaduv_krnl, 1, sizeof(cl_mem), &out_cl); + assert(err == 0); + err = clSetKernelArg(s->loaduv_krnl, 2, sizeof(cl_int), &loaduv_out_off); + assert(err == 0); + + err = clEnqueueNDRangeKernel(q, s->loaduv_krnl, 1, NULL, + &loaduv_work_size, NULL, 0, 0, NULL); + assert(err == 0); + + loaduv_out_off += (s->width/2)*(s->height/2); + + err = clSetKernelArg(s->loaduv_krnl, 0, sizeof(cl_mem), &v_cl); + assert(err == 0); + err = clSetKernelArg(s->loaduv_krnl, 1, sizeof(cl_mem), &out_cl); + assert(err == 0); + err = clSetKernelArg(s->loaduv_krnl, 2, sizeof(cl_int), &loaduv_out_off); + assert(err == 0); + + err = clEnqueueNDRangeKernel(q, s->loaduv_krnl, 1, NULL, + &loaduv_work_size, NULL, 0, 0, NULL); + assert(err == 0); +} diff --git a/selfdrive/visiond/loadyuv.cl b/selfdrive/visiond/loadyuv.cl new file mode 100644 index 00000000000000..e015429156ce91 --- /dev/null +++ b/selfdrive/visiond/loadyuv.cl @@ -0,0 +1,43 @@ +#define UV_SIZE ((TRANSFORMED_WIDTH/2)*(TRANSFORMED_HEIGHT/2)) + +__kernel void loadys(__global uchar8 const * const Y, + __global float * out) +{ + const int gid = get_global_id(0); + const int ois = gid * 8; + const int oy = ois / TRANSFORMED_WIDTH; + const int ox = ois % TRANSFORMED_WIDTH; + + const uchar8 ys = Y[gid]; + + // y = (x - 128) / 128 + const float8 ysf = (convert_float8(ys) - 128.f) * 0.0078125f; + + // 02 + // 13 + + __global float* outy0; + __global float* outy1; + if ((oy & 1) == 0) { + outy0 = out; //y0 + outy1 = out + UV_SIZE*2; //y2 + } else { + outy0 = out + UV_SIZE; //y1 + outy1 = out + UV_SIZE*3; //y3 + } + + vstore4(ysf.s0246, 0, outy0 + (oy/2) * (TRANSFORMED_WIDTH/2) + ox/2); + vstore4(ysf.s1357, 0, outy1 + (oy/2) * (TRANSFORMED_WIDTH/2) + ox/2); +} + +__kernel void loaduv(__global uchar8 const * const in, + __global float8 * out, + int out_offset) +{ + const int gid = get_global_id(0); + const uchar8 inv = in[gid]; + + // y = (x - 128) / 128 + const float8 outv = (convert_float8(inv) - 128.f) * 0.0078125f; + out[gid + out_offset / 8] = outv; +} diff --git a/selfdrive/visiond/loadyuv.h b/selfdrive/visiond/loadyuv.h new file mode 100644 index 00000000000000..be7ea21282af3c --- /dev/null +++ b/selfdrive/visiond/loadyuv.h @@ -0,0 +1,34 @@ +#ifndef LOADYUV_H +#define LOADYUV_H + +#include +#include + +#ifdef __APPLE__ +#include +#else +#include +#endif + +#ifdef __cplusplus +extern "C" { +#endif + +typedef struct { + int width, height; + cl_kernel loadys_krnl, loaduv_krnl; +} LoadYUVState; + +void loadyuv_init(LoadYUVState* s, cl_context ctx, cl_device_id device_id, int width, int height); + +void loadyuv_destroy(LoadYUVState* s); + +void loadyuv_queue(LoadYUVState* s, cl_command_queue q, + cl_mem y_cl, cl_mem u_cl, cl_mem v_cl, + cl_mem out_cl); + +#ifdef __cplusplus +} +#endif + +#endif // LOADYUV_H diff --git a/selfdrive/visiond/model.cc b/selfdrive/visiond/model.cc new file mode 100644 index 00000000000000..ef1a7df9f07b90 --- /dev/null +++ b/selfdrive/visiond/model.cc @@ -0,0 +1,96 @@ +#include "common/timing.h" +#include "model.h" + +#ifdef BIGMODEL + #define MODEL_WIDTH 864 + #define MODEL_HEIGHT 288 + #define MODEL_NAME "driving_bigmodel_dlc" +#else + #define MODEL_WIDTH 320 + #define MODEL_HEIGHT 160 + #define MODEL_NAME "driving_model_dlc" +#endif + +#define OUTPUT_SIZE 161 + +#ifdef TEMPORAL + #define TEMPORAL_SIZE 512 +#else + #define TEMPORAL_SIZE 0 +#endif + +extern const uint8_t driving_model_data[] asm("_binary_" MODEL_NAME "_start"); +extern const uint8_t driving_model_end[] asm("_binary_" MODEL_NAME "_end"); +const size_t driving_model_size = driving_model_end - driving_model_data; + +void model_init(ModelState* s, cl_device_id device_id, cl_context context, int temporal) { + model_input_init(&s->in, MODEL_WIDTH, MODEL_HEIGHT, device_id, context); + const int output_size = OUTPUT_SIZE + TEMPORAL_SIZE; + s->output = (float*)malloc(output_size * sizeof(float)); + memset(s->output, 0, output_size * sizeof(float)); + s->m = new SNPEModel(driving_model_data, driving_model_size, s->output, output_size); +#ifdef TEMPORAL + assert(temporal); + s->m->addRecurrent(&s->output[OUTPUT_SIZE], TEMPORAL_SIZE); +#else + assert(!temporal); +#endif +} + +ModelData model_eval_frame(ModelState* s, cl_command_queue q, + cl_mem yuv_cl, int width, int height, + mat3 transform, void* sock) { + struct { + float *path; + float *left_lane; + float *right_lane; + float *lead; + } net_outputs = {NULL}; + + //for (int i = 0; i < OUTPUT_SIZE + TEMPORAL_SIZE; i++) { printf("%f ", s->output[i]); } printf("\n"); + + float *net_input_buf = model_input_prepare(&s->in, q, yuv_cl, width, height, transform); + s->m->execute(net_input_buf); + + // net outputs + net_outputs.path = &s->output[0]; + net_outputs.left_lane = &s->output[51]; + net_outputs.right_lane = &s->output[51+53]; + net_outputs.lead = &s->output[51+53+53]; + + ModelData model = {0}; + + for (int i=0; i 0. ? model.lead.dist : 0.; + + model.lead.std = max_dist * sqrt(2.) / net_outputs.lead[1]; + softmax(&net_outputs.lead[2], softmax_buff, 2); + model.lead.prob = softmax_buff[0]; + + return model; +} + +void model_free(ModelState* s) { + model_input_free(&s->in); + delete s->m; +} + diff --git a/selfdrive/visiond/model.h b/selfdrive/visiond/model.h new file mode 100644 index 00000000000000..06a65f8539752b --- /dev/null +++ b/selfdrive/visiond/model.h @@ -0,0 +1,27 @@ +#ifndef MODEL_H +#define MODEL_H + +// gate this here +//#define BIGMODEL +#define TEMPORAL + +#include "common/mat.h" +#include "common/modeldata.h" + +#include "commonmodel.h" +#include "snpemodel.h" + +typedef struct ModelState { + ModelInput in; + float *output; + SNPEModel *m; +} ModelState; + +void model_init(ModelState* s, cl_device_id device_id, + cl_context context, int temporal); +ModelData model_eval_frame(ModelState* s, cl_command_queue q, + cl_mem yuv_cl, int width, int height, + mat3 transform, void* sock); +void model_free(ModelState* s); + +#endif diff --git a/selfdrive/visiond/monitoring.cc b/selfdrive/visiond/monitoring.cc new file mode 100644 index 00000000000000..84ed9e8c5bb27d --- /dev/null +++ b/selfdrive/visiond/monitoring.cc @@ -0,0 +1,54 @@ +#include "monitoring.h" +#include "common/mat.h" + +#define MODEL_WIDTH 320 +#define MODEL_HEIGHT 160 +extern const uint8_t monitoring_model_data[] asm("_binary_monitoring_model_dlc_start"); +extern const uint8_t monitoring_model_end[] asm("_binary_monitoring_model_dlc_end"); +const size_t monitoring_model_size = monitoring_model_end - monitoring_model_data; + + +void monitoring_init(MonitoringState* s, cl_device_id device_id, cl_context context) { + model_input_init(&s->in, MODEL_WIDTH, MODEL_HEIGHT, device_id, context); + s->m = new SNPEModel(monitoring_model_data, monitoring_model_size, (float*)&s->output, OUTPUT_SIZE); +} + +MonitoringResult monitoring_eval_frame(MonitoringState* s, cl_command_queue q, + cl_mem yuv_cl, int width, int height) { + const mat3 front_frame_from_scaled_frame = (mat3){{ + width/426.0f, 0.0, 0.0, + 0.0,height/320.0f, 0.0, + 0.0, 0.0, 1.0, + }}; + + const mat3 scaled_frame_from_cropped_frame = (mat3){{ + 1.0, 0.0, 426.0-160.0, + 0.0, 1.0, 0.0, + 0.0, 0.0, 1.0, + }}; + + const mat3 transpose = (mat3){{ + 0.0, 1.0, 0.0, + 1.0, 0.0, 0.0, + 0.0, 0.0, 1.0, + }}; + + const mat3 front_frame_from_cropped_frame = matmul3(front_frame_from_scaled_frame, scaled_frame_from_cropped_frame); + const mat3 front_frame_from_monitoring_frame = matmul3(front_frame_from_cropped_frame, transpose); + + float *net_input_buf = model_input_prepare(&s->in, q, yuv_cl, width, height, front_frame_from_monitoring_frame); + s->m->execute(net_input_buf); + + MonitoringResult ret = {0}; + memcpy(ret.vs, s->output, sizeof(ret.vs)); + ret.std = sqrtf(2.f) / s->output[6]; + + return ret; +} + + +void monitoring_free(MonitoringState* s) { + model_input_free(&s->in); + delete s->m; +} + diff --git a/selfdrive/visiond/monitoring.h b/selfdrive/visiond/monitoring.h new file mode 100644 index 00000000000000..5689e7941573b5 --- /dev/null +++ b/selfdrive/visiond/monitoring.h @@ -0,0 +1,32 @@ +#ifndef MONITORING_H +#define MONITORING_H + +#include "commonmodel.h" +#include "snpemodel.h" + +#ifdef __cplusplus +extern "C" { +#endif + +#define OUTPUT_SIZE 7 + +typedef struct MonitoringResult { + float vs[6]; + float std; +} MonitoringResult; + +typedef struct MonitoringState { + ModelInput in; + SNPEModel *m; + float output[OUTPUT_SIZE]; +} MonitoringState; + +void monitoring_init(MonitoringState* s, cl_device_id device_id, cl_context context); +MonitoringResult monitoring_eval_frame(MonitoringState* s, cl_command_queue q, cl_mem yuv_cl, int width, int height); +void monitoring_free(MonitoringState* s); + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/selfdrive/visiond/sensor_i2c.h b/selfdrive/visiond/sensor_i2c.h new file mode 100644 index 00000000000000..c33bc3468ae5df --- /dev/null +++ b/selfdrive/visiond/sensor_i2c.h @@ -0,0 +1,1830 @@ +static struct msm_camera_i2c_reg_array init_array_imx298[] = { + {0x101,0x0,0}, // IMAGE_ORIENT + {0x601,0x0,0}, // test pattern + //{0xb02,0,0}, // green correction? + // external clock setting + {0x136,0x18,0}, {0x137,0x0,0}, // EXCK_FREQ = Extclk_frequency_mhz + // global setting? + {0x30f4,0x1,0}, + {0x30f5,0x7a,0}, + {0x30f6,0x0,0}, + {0x30f7,0xec,0}, + {0x30fc,0x1,0}, + {0x3101,0x1,0}, + {0x5b2f,0x8,0}, + {0x5d32,0x5,0}, + {0x5d7c,0x0,0}, + {0x5d7d,0x0,0}, + {0x5db9,0x1,0}, + {0x5e43,0x0,0}, + {0x6300,0x0,0}, + {0x6301,0xea,0}, + {0x6302,0x0,0}, + {0x6303,0xb4,0}, + {0x6564,0x0,0}, + {0x6565,0xb6,0}, + {0x6566,0x0,0}, + {0x6567,0xe6,0}, + {0x6714,0x1,0}, + {0x6758,0xb,0}, + {0x6910,0x4,0}, + {0x6916,0x1,0}, + {0x6918,0x4,0}, + {0x691e,0x1,0}, + {0x6931,0x1,0}, + {0x6937,0x2,0}, + {0x693b,0x2,0}, + {0x6d00,0x4a,0}, + {0x6d01,0x41,0}, + {0x6d02,0x23,0}, + {0x6d05,0x4c,0}, + {0x6d06,0x10,0}, + {0x6d08,0x30,0}, + {0x6d09,0x38,0}, + {0x6d0a,0x2c,0}, + {0x6d0b,0x2d,0}, + {0x6d0c,0x34,0}, + {0x6d0d,0x42,0}, + {0x6d19,0x1c,0}, + {0x6d1a,0x71,0}, + {0x6d1b,0xc6,0}, + {0x6d1c,0x94,0}, + {0x6d24,0xe4,0}, + {0x6d30,0xa,0}, + {0x6d31,0x1,0}, + {0x6d33,0xb,0}, + {0x6d34,0x5,0}, + {0x6d35,0x0,0}, + {0x83c2,0x3,0}, + {0x83c3,0x8,0}, + {0x83c4,0x48,0}, + {0x83c7,0x8,0}, + {0x83cb,0x0,0}, + {0xb101,0xff,0}, + {0xb103,0xff,0}, + {0xb105,0xff,0}, + {0xb107,0xff,0}, + {0xb109,0xff,0}, + {0xb10b,0xff,0}, + {0xb10d,0xff,0}, + {0xb10f,0xff,0}, + {0xb111,0xff,0}, + {0xb163,0x3c,0}, + {0xc2a0,0x8,0}, + {0xc2a3,0x3,0}, + {0xc2a5,0x8,0}, + {0xc2a6,0x48,0}, + {0xc2a9,0x0,0}, + {0xf800,0x5e,0}, + {0xf801,0x5e,0}, + {0xf802,0xcd,0}, + {0xf803,0x20,0}, + {0xf804,0x55,0}, + {0xf805,0xd4,0}, + {0xf806,0x1f,0}, + {0xf808,0xf8,0}, + {0xf809,0x3a,0}, + {0xf80a,0xf1,0}, + {0xf80b,0x7e,0}, + {0xf80c,0x55,0}, + {0xf80d,0x38,0}, + {0xf80e,0xe3,0}, + {0xf810,0x74,0}, + {0xf811,0x41,0}, + {0xf812,0xbf,0}, + {0xf844,0x40,0}, + {0xf845,0xba,0}, + {0xf846,0x70,0}, + {0xf847,0x47,0}, + {0xf848,0xc0,0}, + {0xf849,0xba,0}, + {0xf84a,0x70,0}, + {0xf84b,0x47,0}, + {0xf84c,0x82,0}, + {0xf84d,0xf6,0}, + {0xf84e,0x32,0}, + {0xf84f,0xfd,0}, + {0xf851,0xf0,0}, + {0xf852,0x2,0}, + {0xf853,0xf8,0}, + {0xf854,0x81,0}, + {0xf855,0xf6,0}, + {0xf856,0xc0,0}, + {0xf857,0xff,0}, + {0xf858,0x10,0}, + {0xf859,0xb5,0}, + {0xf85a,0xd,0}, + {0xf85b,0x48,0}, + {0xf85c,0x40,0}, + {0xf85d,0x7a,0}, + {0xf85e,0x1,0}, + {0xf85f,0x28,0}, + {0xf860,0x15,0}, + {0xf861,0xd1,0}, + {0xf862,0xc,0}, + {0xf863,0x49,0}, + {0xf864,0xc,0}, + {0xf865,0x46,0}, + {0xf866,0x40,0}, + {0xf867,0x3c,0}, + {0xf868,0x48,0}, + {0xf869,0x8a,0}, + {0xf86a,0x62,0}, + {0xf86b,0x8a,0}, + {0xf86c,0x80,0}, + {0xf86d,0x1a,0}, + {0xf86e,0x8a,0}, + {0xf86f,0x89,0}, + {0xf871,0xb2,0}, + {0xf872,0x10,0}, + {0xf873,0x18,0}, + {0xf874,0xa,0}, + {0xf875,0x46,0}, + {0xf876,0x20,0}, + {0xf877,0x32,0}, + {0xf878,0x12,0}, + {0xf879,0x88,0}, + {0xf87a,0x90,0}, + {0xf87b,0x42,0}, + {0xf87d,0xda,0}, + {0xf87e,0x10,0}, + {0xf87f,0x46,0}, + {0xf880,0x80,0}, + {0xf881,0xb2,0}, + {0xf882,0x88,0}, + {0xf883,0x81,0}, + {0xf884,0x84,0}, + {0xf885,0xf6,0}, + {0xf886,0xd2,0}, + {0xf887,0xf9,0}, + {0xf888,0xe0,0}, + {0xf889,0x67,0}, + {0xf88a,0x85,0}, + {0xf88b,0xf6,0}, + {0xf88c,0xa1,0}, + {0xf88d,0xfc,0}, + {0xf88e,0x10,0}, + {0xf88f,0xbd,0}, + {0xf891,0x18,0}, + {0xf892,0x21,0}, + {0xf893,0x24,0}, + {0xf895,0x18,0}, + {0xf896,0x19,0}, + {0xf897,0xb4,0}, + {0x4e29,0x1,0}, + // PDAF stuff + {0x3166,0x1,0}, //AREA_EN_0 + {0x3167,0x1,0}, + {0x3168,0x1,0}, + {0x3169,0x1,0}, + {0x316a,0x1,0}, + {0x316b,0x1,0}, + {0x316c,0x1,0}, + {0x316d,0x1,0}, + {0x3158,0x2,0}, + {0x3159,0x2,0}, + {0x315a,0x2,0}, + {0x315b,0x3,0}, + {0x3013,0x7,0}, //RMSC_NR_MODE + {0x3035,0x1,0}, + {0x3051,0x0,0}, + {0x3056,0x2,0}, + {0x3057,0x1,0}, + {0x3060,0x0,0}, + {0x8435,0x0,0}, + {0x8455,0x0,0}, + {0x847c,0x0,0}, + {0x84fb,0x1,0}, + {0x9619,0xa0,0}, + {0x961b,0xa0,0}, + {0x961d,0xa0,0}, + {0x961f,0x20,0}, + {0x9621,0x20,0}, + {0x9623,0x20,0}, + {0x9625,0xa0,0}, + {0x9627,0xa0,0}, + {0x9629,0xa0,0}, + {0x962b,0x20,0}, + {0x962d,0x20,0}, + {0x962f,0x20,0}, + {0x9901,0x35,0}, + {0x9903,0x23,0}, + {0x9905,0x23,0}, + {0x9906,0x0,0}, + {0x9907,0x31,0}, + {0x9908,0x0,0}, + {0x9909,0x1b,0}, + {0x990a,0x0,0}, + {0x990b,0x15,0}, + {0x990d,0x3f,0}, + {0x990f,0x3f,0}, + {0x9911,0x3f,0}, + {0x9913,0x64,0}, + {0x9915,0x64,0}, + {0x9917,0x64,0}, + {0x9919,0x50,0}, + {0x991b,0x60,0}, + {0x991d,0x65,0}, + {0x991f,0x1,0}, + {0x9921,0x1,0}, + {0x9923,0x1,0}, + {0x9925,0x23,0}, + {0x9927,0x23,0}, + {0x9929,0x23,0}, + {0x992b,0x2f,0}, + {0x992d,0x1a,0}, + {0x992f,0x14,0}, + {0x9931,0x3f,0}, + {0x9933,0x3f,0}, + {0x9935,0x3f,0}, + {0x9937,0x6b,0}, + {0x9939,0x7c,0}, + {0x993b,0x81,0}, + {0x9943,0xf,0}, + {0x9945,0xf,0}, + {0x9947,0xf,0}, + {0x9949,0xf,0}, + {0x994b,0xf,0}, + {0x994d,0xf,0}, + {0x994f,0x42,0}, + {0x9951,0xf,0}, + {0x9953,0xb,0}, + {0x9955,0x5a,0}, + {0x9957,0x13,0}, + {0x9959,0xc,0}, + {0x995a,0x0,0}, + {0x995b,0x0,0}, + {0x995c,0x0,0}, + {0x996b,0x0,0}, + {0x996d,0x10,0}, + {0x996f,0x10,0}, + {0x9971,0xc8,0}, + {0x9973,0x32,0}, + {0x9975,0x4,0}, + {0x9976,0xa,0}, + {0x9977,0xa,0}, + {0x9978,0xa,0}, + {0x99a4,0x2f,0}, + {0x99a5,0x2f,0}, + {0x99a6,0x2f,0}, + {0x99a7,0xa,0}, + {0x99a8,0xa,0}, + {0x99a9,0xa,0}, + {0x99aa,0x2f,0}, + {0x99ab,0x2f,0}, + {0x99ac,0x2f,0}, + {0x99ad,0x0,0}, + {0x99ae,0x0,0}, + {0x99af,0x0,0}, + {0x99b0,0x40,0}, + {0x99b1,0x40,0}, + {0x99b2,0x40,0}, + {0x99b3,0x30,0}, + {0x99b4,0x30,0}, + {0x99b5,0x30,0}, + {0x99bb,0xa,0}, + {0x99bd,0xa,0}, + {0x99bf,0xa,0}, + {0x99c0,0x9,0}, + {0x99c1,0x9,0}, + {0x99c2,0x9,0}, + {0x99c6,0x3c,0}, + {0x99c7,0x3c,0}, + {0x99c8,0x3c,0}, + {0x99c9,0xff,0}, + {0x99ca,0xff,0}, + {0x99cb,0xff,0}, + {0x9b01,0x35,0}, + {0x9b03,0x14,0}, + {0x9b05,0x14,0}, + {0x9b07,0x31,0}, + {0x9b09,0x1b,0}, + {0x9b0b,0x15,0}, + {0x9b0d,0x1e,0}, + {0x9b0f,0x1e,0}, + {0x9b11,0x1e,0}, + {0x9b13,0x64,0}, + {0x9b15,0x64,0}, + {0x9b17,0x64,0}, + {0x9b19,0x50,0}, + {0x9b1b,0x60,0}, + {0x9b1d,0x65,0}, + {0x9b1f,0x1,0}, + {0x9b21,0x1,0}, + {0x9b23,0x1,0}, + {0x9b25,0x14,0}, + {0x9b27,0x14,0}, + {0x9b29,0x14,0}, + {0x9b2b,0x2f,0}, + {0x9b2d,0x1a,0}, + {0x9b2f,0x14,0}, + {0x9b31,0x1e,0}, + {0x9b33,0x1e,0}, + {0x9b35,0x1e,0}, + {0x9b37,0x6b,0}, + {0x9b39,0x7c,0}, + {0x9b3b,0x81,0}, + {0x9b43,0xf,0}, + {0x9b45,0xf,0}, + {0x9b47,0xf,0}, + {0x9b49,0xf,0}, + {0x9b4b,0xf,0}, + {0x9b4d,0xf,0}, + {0x9b4f,0x2d,0}, + {0x9b51,0xb,0}, + {0x9b53,0x8,0}, + {0x9b55,0x40,0}, + {0x9b57,0xd,0}, + {0x9b59,0x8,0}, + {0x9b5a,0x0,0}, + {0x9b5b,0x0,0}, + {0x9b5c,0x0,0}, + {0x9b6b,0x0,0}, + {0x9b6d,0x10,0}, + {0x9b6f,0x10,0}, + {0x9b71,0xc8,0}, + {0x9b73,0x32,0}, + {0x9b75,0x4,0}, + {0x9bb0,0x40,0}, + {0x9bb1,0x40,0}, + {0x9bb2,0x40,0}, + {0x9bb3,0x30,0}, + {0x9bb4,0x30,0}, + {0x9bb5,0x30,0}, + {0x9bbb,0xa,0}, + {0x9bbd,0xa,0}, + {0x9bbf,0xa,0}, + {0x9bc0,0x9,0}, + {0x9bc1,0x9,0}, + {0x9bc2,0x9,0}, + {0x9bc6,0x18,0}, + {0x9bc7,0x18,0}, + {0x9bc8,0x18,0}, + {0x9bc9,0xff,0}, + {0x9bca,0xff,0}, + {0x9bcb,0xff,0}, + {0xb2b2,0x1,0}, +}; + +static struct msm_camera_i2c_reg_array mode_setting_array_imx298[] = { +// i2c settings for mode 3 +// { +// .x_output = 2328, +// .y_output = 1748, +// .line_length_pclk = 5536, +// .frame_length_lines = 1802, +// .vt_pixel_clk = 299300000, +// .op_pixel_clk = 299300000, +// .binning_factor = 2, +// .min_fps = 15.000000, +// .max_fps = 30.020000, +// .mode = 1, +// .offset_x = 0, +// .offset_y = 0, +// .scale_factor = 1.000000, +// .is_pdaf_supported = 1, +// } + +// mode settings + +// hdr settings +{0x0114, 0x03, 0}, // CSI_LANE_MODE = 4-lane +/*{0x0220, 0x00, 0}, // HDR_MODE = disable +{0x0221, 0x11, 0}, // HDR_RESO_REDU_H/V = Full Pixel +{0x0222, 0x10, 0}, // EXPO_RATIO = 16*/ +{0x0220, 0x01, 0}, // HDR_MODE = enable with combined gain and 16x ratio +{0x0221, 0x22, 0}, // HDR_RESO_REDU_H/V = 2 binning +{0x0222, 0x10, 0}, // EXPO_RATIO = 16 + +{0x0340, 0x07, 0}, {0x0341, 0x0a, 0}, // FRM_LENGTH = frame_length_lines = 1802 +{0x0342, 0x15, 0}, {0x0343, 0xa0, 0}, // LINE_LENGTH = line_length_pclk = 5536 +{0x0344, 0x00, 0}, {0x0345, 0x00, 0}, // x_addr_start +{0x0346, 0x00, 0}, {0x0347, 0x00, 0}, // y_addr_start +{0x0348, 0x12, 0}, {0x0349, 0x2f, 0}, // x_addr_end +{0x034a, 0x0d, 0}, {0x034b, 0xa7, 0}, // y_addr_end +{0x0381, 0x01, 0}, // x_even_inc +{0x0383, 0x01, 0}, // x_odd_inc +{0x0385, 0x01, 0}, // y_even_inc +{0x0387, 0x01, 0}, // y_odd_inc +{0x0900, 0x01, 0}, // BINNING_MODE = enable +{0x0901, 0x22, 0}, // BINING_TYPE_H/V = 2binning +{0x0902, 0x00, 0}, // binning_weighting = average + +{0x0b06, 1, 0}, // SING_DEF_CORR_EN +{0x0b0a, 1, 0}, // combined defect correct + +{0x3010, 0x66, 0}, // HDR_OUTPUT_CTRL = ATR + HDR compose + DPC1D + DCP2D +{0x3011, 0x01, 0}, // HDR_OUTPUT_CTRL2 = PD enable +{0x30c0, 0x11, 0}, // RED_GAIN_CB? +{0x300d, 0x00, 0}, // FORCE_FDSUM = disable +{0x30fd, 0x00, 0}, +{0x8493, 0x00, 0}, +{0x8863, 0x00, 0}, +{0x90d7, 0x19, 0}, + +// set black level +{0x3090, 1, 0}, +{0x3092, 0, 0}, +{0x3093, 0x38, 0}, + +// output size settings +{0x0112, 0x0a, 0}, {0x0113, 0x0a, 0}, // CS_DT_FMT_H = 0x0a0a (RAW10 output) +{0x034c, 0x09, 0}, {0x034d, 0x18, 0}, // X_OUT_SIZE = 2328 (1164*2) +{0x034e, 0x06, 0}, {0x034f, 0xd4, 0}, // Y_OUT_SIZE = 1748 (874*2) +{0x0401, 0x00, 0}, // SCALING_MODE +{0x0404, 0x00, 0}, {0x0405, 0x10, 0}, // SCALE_M +{0x0408, 0x00, 0}, {0x0409, 0x00, 0}, // DCROP_XOFS +{0x040a, 0x00, 0}, {0x040b, 0x00, 0}, // DCROP_YOFS +{0x040c, 0x09, 0}, {0x040d, 0x18, 0}, // DCROP_WIDTH +{0x040e, 0x06, 0}, {0x040f, 0xd4, 0}, // DCROP_HIGT + +// clock settings +// 299300000 +/* +{0x0301, 0x05, 0}, // VT_PIX_CLK_DIV +{0x0303, 0x02, 0}, // VT_SYS_CLK_DIV +{0x0305, 0x04, 0}, // PRE_PLL_CLK_DIV +{0x0306, 0x00, 0}, {0x0307, 0x7d, 0}, // PLL_MULTIPLIER . mode 1: 0xf6 +{0x0309, 0x0a, 0}, // OP_PIX_CLK_DIV +{0x030b, 0x01, 0}, // OP_SYS_CLK_DIV +{0x030d, 0x0f, 0}, // PREPLLCK_OP_DIV +{0x030e, 0x03, 0}, {0x030f, 0x41, 0}, // PLL_OP_MPY +{0x0310, 0x00, 0}, // PLL_MULT_DRIV +*/ +// 600000000 +{0x0301, 0x05, 0}, +{0x0303, 0x02, 0}, +{0x0305, 0x04, 0}, +{0x0306, 0x00, 0}, +{0x0307, 0xfa, 0}, +{0x0309, 0x0a, 0}, +{0x030b, 0x01, 0}, +{0x030d, 0x0f, 0}, +{0x030e, 0x03, 0}, {0x030f, 0x41, 0}, +{0x0310, 0x00, 0}, + +// data rate settings +/*{0x0820, 0x0b, 0}, // requested_link_bit_rate_mbps = 3000 +{0x0821, 0xb8, 0}, +{0x0822, 0x00, 0}, +{0x0823, 0x00, 0},*/ +{0x0820, 0x17, 0}, // requested_link_bit_rate_mbps = 6000 +{0x0821, 0x70, 0}, +{0x0822, 0x00, 0}, +{0x0823, 0x00, 0}, + +//integration time settings +{0x0202, 0x07, 0}, {0x0203, 0x00, 0}, // INTEG_TIME = 1792 +{0x0224, 0x01, 0}, {0x0225, 0xf4, 0}, // ST_COARSE_INTEG_TIME = 506 + +// gain settings +{0x0204, 0x00, 0}, {0x0205, 0x00, 0}, // ANA_GAIN_GLOBAL = 512 / (512 - X) +{0x0216, 0x00, 0}, {0x0217, 0x00, 0}, // ST_ANA_GAIN_GLOBAL[8] +{0x020e, 0x01, 0}, {0x020f, 0x00, 0}, // DIG_GAIN_GR +{0x0210, 0x01, 0}, {0x0211, 0x00, 0}, // DIG_GAIN_R +{0x0212, 0x01, 0}, {0x0213, 0x00, 0}, // DIG_GAIN_B +{0x0214, 0x01, 0}, {0x0215, 0x00, 0}, // DIG_GAIN_GB + +// HDR white balance settings (ABS_GAIN) +{0xb8e, 0x01, 0}, {0xb8f, 0x00, 0}, // GR +{0xb90, 0x02, 0}, {0xb91, 0x2b, 0}, // R +{0xb92, 0x01, 0}, {0xb93, 0xd4, 0}, // B +{0xb94, 0x01, 0}, {0xb95, 0x00, 0}, // GB + +// phase detection settings +{0x3058, 0x00, 0}, // NML_NR_EN +{0x3103, 0x01, 0}, // NML_PD_CAL_ENABLE = enable +{0x3108, 0x00, 0}, {0x3109, 0x2c, 0}, //PD_AREA_X_OFFSET +{0x310a, 0x00, 0}, {0x310b, 0x24, 0}, //PD_AREA_Y_OFFSET +{0x310c, 0x01, 0}, {0x310d, 0xa4, 0}, //PD_AREA_WIDTH +{0x310e, 0x01, 0}, {0x310f, 0xa4, 0}, //PD_AREA_HEIGHT +// whole size is 0x918 x 0x6d4 +{0x3110, 0x03, 0}, // PD_AREA_0 = 0x375-0x4d1, 0x258-0x3b6 +{0x3111, 0x75, 0}, +{0x3112, 0x02, 0}, +{0x3113, 0x58, 0}, +{0x3114, 0x04, 0}, +{0x3115, 0xd1, 0}, +{0x3116, 0x03, 0}, +{0x3117, 0xb6, 0}, +{0x3118, 0x04, 0}, // PD_AREA_1 = 0x446-0x5a2, 0x258-0x3b6 +{0x3119, 0x46, 0}, +{0x311a, 0x02, 0}, +{0x311b, 0x58, 0}, +{0x311c, 0x05, 0}, +{0x311d, 0xa2, 0}, +{0x311e, 0x03, 0}, +{0x311f, 0xb6, 0}, +{0x3120, 0x03, 0}, // PD_AREA_2 = 0x375-0x4d1, 0x32a-0x488 +{0x3121, 0x75, 0}, +{0x3122, 0x03, 0}, +{0x3123, 0x2a, 0}, +{0x3124, 0x04, 0}, +{0x3125, 0xd1, 0}, +{0x3126, 0x04, 0}, +{0x3127, 0x88, 0}, +{0x3128, 0x04, 0}, // PD_AREA_3 = 0x446-0x5a2, 0x32a-0x488 +{0x3129, 0x46, 0}, +{0x312a, 0x03, 0}, +{0x312b, 0x2a, 0}, +{0x312c, 0x05, 0}, +{0x312d, 0xa2, 0}, +{0x312e, 0x04, 0}, +{0x312f, 0x88, 0}, +{0x3130, 0x03, 0}, // PD_AREA_4 = 0x375-0x5a2, 0x258-0x488 +{0x3131, 0x75, 0}, +{0x3132, 0x02, 0}, +{0x3133, 0x58, 0}, +{0x3134, 0x05, 0}, +{0x3135, 0xa2, 0}, +{0x3136, 0x04, 0}, +{0x3137, 0x88, 0}, +{0x3138, 0x02, 0}, // PD_AREA_5 = 0x2ba-0x65d, 0x210-0x4d0 +{0x3139, 0xba, 0}, +{0x313a, 0x02, 0}, +{0x313b, 0x10, 0}, +{0x313c, 0x06, 0}, +{0x313d, 0x5d, 0}, +{0x313e, 0x04, 0}, +{0x313f, 0xd0, 0}, +{0x3140, 0x00, 0}, // PD_AREA_6 = 0xa1-0x876, 0x6b-0x676 +{0x3141, 0xa1, 0}, +{0x3142, 0x00, 0}, +{0x3143, 0x6b, 0}, +{0x3144, 0x08, 0}, +{0x3145, 0x76, 0}, +{0x3146, 0x06, 0}, +{0x3147, 0x76, 0}, +{0x3148, 0x00, 0}, // PD_AREA_7 = 0xa1-0x876, 0x5e-0x34c +{0x3149, 0xa1, 0}, +{0x314a, 0x00, 0}, +{0x314b, 0x5e, 0}, +{0x314c, 0x08, 0}, +{0x314d, 0x76, 0}, +{0x314e, 0x03, 0}, +{0x314f, 0x4c, 0}, +{0x3165, 0x02, 0}, // AREA_EN_0 = free area +}; + +// static struct msm_camera_i2c_reg_array reg_array3[] = { +// // REG_HOLD ON +// {0x104,0x1,0}, +// // from regression +// {0x3002,0x0,0}, +// // FRM_LENGTH, 1802 vs 3554 +// // {0x340,0x7,0}, {0x341,0xa,0}, // camera start {0x340,0xd,0}, {0x341,0xe2,0}, +// // INTEG_TIME aka coarse_int_time_addr aka shutter speed +// {0x202,0x03,0}, {0x203,0xda,0}, +// // global_gain_addr +// {0x204,0x0,0}, {0x205,0x0,0}, + +// //?? +// {0x20e,0x1,0}, {0x20f,0x0,0}, +// {0x210,0x1,0}, {0x211,0x0,0}, +// {0x212,0x1,0}, {0x213,0x0,0}, +// {0x214,0x1,0}, {0x215,0x0,0}, + +// // REG_HOLD: mode setting +// {0x104,0x0,0}, +// }; + +// start, remove standby mode +static struct msm_camera_i2c_reg_array start_reg_array[] = {{0x100,0x1,0}}; + +// stop, enable standby mode +static struct msm_camera_i2c_reg_array stop_reg_array[] = {{0x100,0x0,0}}; + + +/////////////////// + + +static struct msm_camera_i2c_reg_array init_array_imx179[] = { + { 0x100, 0x0, 0}, // MODE_SELECT + { 0x101, 0x0, 0}, // IMAGE_ORIENT + { 0x202, 0x9, 0}, { 0x203, 0xd2, 0}, // COARSE_INTEGRATION_TIME + { 0x301, 0x5, 0}, // vt_pix_clk_div + { 0x303, 0x1, 0}, // vt_sys_clk_div + { 0x305, 0x6, 0}, // pre_pll_clk_div + { 0x309, 0x5, 0}, // op_pix_clk_div + { 0x30b, 0x1, 0}, // op_sys_clk_div + { 0x30c, 0x0, 0}, { 0x30d, 0x9d, 0}, + + { 0x340, 0x9, 0}, { 0x341, 0xd6, 0}, // frame_length_lines + { 0x342, 0xd, 0}, { 0x343, 0x70, 0}, // line_length_pclk + { 0x344, 0x0, 0}, { 0x345, 0x0, 0}, // x_addr_start + { 0x346, 0x0, 0}, { 0x347, 0x0, 0}, // y_addr_start + { 0x348, 0xc, 0}, { 0x349, 0xcf, 0}, // last_pixel / x_addr_end + { 0x34a, 0x9, 0}, { 0x34b, 0x9f, 0}, // last_line / y_addr_end + { 0x34c, 0xc, 0}, { 0x34d, 0xd0, 0}, // pixels_per_line / x_output_size + { 0x34e, 0x9, 0}, { 0x34f, 0xa0, 0}, // lines_per_frame / y_output_size + { 0x383, 0x1, 0}, // x_odd_inc + { 0x387, 0x1, 0}, // y_odd_inc + { 0x390, 0x0, 0}, // binning_mode + { 0x401, 0x0, 0}, // SCALING_MODE + { 0x405, 0x10, 0}, // SCALE_M + + {0x3020, 0x10, 0}, + {0x3041, 0x15, 0}, // READ_MODE? + {0x3042, 0x87, 0}, + {0x3089, 0x4f, 0}, + {0x3309, 0x9a, 0}, + {0x3344, 0x57, 0}, + {0x3345, 0x1f, 0}, + {0x3362, 0xa, 0}, + {0x3363, 0xa, 0}, + {0x3364, 0x0, 0}, + {0x3368, 0x18, 0}, + {0x3369, 0x0, 0}, + {0x3370, 0x6f, 0}, + {0x3371, 0x27, 0}, + {0x3372, 0x4f, 0}, + {0x3373, 0x2f, 0}, + {0x3374, 0x27, 0}, + {0x3375, 0x2f, 0}, + {0x3376, 0x97, 0}, + {0x3377, 0x37, 0}, + {0x33c8, 0x0, 0}, + {0x33d4, 0xc, 0}, + {0x33d5, 0xd0, 0}, + {0x33d6, 0x9, 0}, + {0x33d7, 0xa0, 0}, + // znr + {0x4100, 0xe, 0}, + {0x4108, 0x1, 0}, + {0x4109, 0x7c, 0}, +}; + + + +/////////////// ois stuff /////////////// + +/* +#define _OP_FIRM_DWNLD 0x80 +#define _OP_Periphe_RW 0x82 +#define _OP_Memory__RW 0x84 +#define _OP_AD_TRNSFER 0x86 +#define _OP_COEF_DWNLD 0x88 +#define _OP_PrgMem__RD 0x8A +#define _OP_SpecialCMD 0x8C +*/ + +static struct reg_settings_ois_t ois_init_settings[] = { + { + .reg_addr = 0x8262, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0xbf03, + .data_type = MSM_CAMERA_I2C_WORD_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "", + .reg_data_seq_size = 0, + },{ + .reg_addr = 0x8263, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x9f05, + .data_type = MSM_CAMERA_I2C_WORD_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "", + .reg_data_seq_size = 0, + },{ + .reg_addr = 0x8264, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x6040, + .data_type = MSM_CAMERA_I2C_WORD_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "", + .reg_data_seq_size = 0, + },{ + .reg_addr = 0x8260, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x1130, + .data_type = MSM_CAMERA_I2C_WORD_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "", + .reg_data_seq_size = 0, + },{ + .reg_addr = 0x8265, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x8000, + .data_type = MSM_CAMERA_I2C_WORD_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "", + .reg_data_seq_size = 0, + },{ + .reg_addr = 0x8261, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0280, + .data_type = MSM_CAMERA_I2C_WORD_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "", + .reg_data_seq_size = 0, + },{ + .reg_addr = 0x8261, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0380, + .data_type = MSM_CAMERA_I2C_WORD_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "", + .reg_data_seq_size = 0, + },{ + .reg_addr = 0x8261, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0988, + .data_type = MSM_CAMERA_I2C_WORD_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "", + .reg_data_seq_size = 0, + },{ + .reg_addr = 0x8000, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x34\x84\x00\x03\xff\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8000, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8000, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8000, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8000, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8000, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8000, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8000, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8000, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8000, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8000, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8000, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x00\x00\x00\x00\x03\x00\x10\x7e\x84\x50\x00\x08\x40\x7e\xa0\x00\x03\x00\x10\x7e\x84\x60\x00\x08\x40\x7e\xa0\x00\x03\x00\x90\x00", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8084, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x00\x10\x08\x80\x00\xa0\x10\x00\x08\x7f\xff\x11\x8f\x02\x07\x80\x00\x11\x40\xff\xa0\x90\x01\x84\x20\x8f\x08\x40\xfe\x90\x40\xf5", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x80a0, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x00\x00\x08\x80\x01\xa0\x00\x01\x11\x8f\x02\x07\xff\xff\x11\x08\x00\x20\x50\x12\x07\x00\x10\x08\x80\x00\xa0\x10\xff\x84\x20\x0a", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8008, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x7f\xff\x21\x08\xfe\x84\x00\x04\x07\x20\x0c\x08\x7f\xff\x21\x08\xfe\x84\x00\x03\x00\x90\x17\x84\x20\x1f\x08\x80\x17\xa0\x10\x10", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8008, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x7f\xff\x21\x10\x00\x08\x01\x00\x11\x40\x51\xa0\x90\x17\x84\x20\x0f\x08\x80\x47\xa0\x8d\x0c\x07\x00\x00\x11\x30\x03\x07\x80\x41", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8090, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x50\x00\x08\x40\xfc\x90\x88\x2f\x84\x00\x00\x11\x30\x02\x07\x40\xff\x90\x50\x00\x08\x40\xfd\x90\x40\x7f\xa0\x10\xff\x84\x20\x2c", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8008, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x7f\xff\x11\x20\x0d\x08\x80\x0f\x90\x80\x26\xa0\x90\x2e\x84\x00\x10\x08\x90\x26\x84\x00\x10\x08\x80\x1f\xa0\x20\x2e\x08\x40\xed", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8090, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x20\x0f\x08\x80\x0e\x90\x00\x00\x21\x30\x02\x07\x40\xeb\xa0\x50\x00\x08\x40\xfe\x90\x40\x7f\xa0\x04\xeb\x84\x10\x00\x20\x20\x0f", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8008, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x80\x00\x21\x60\x04\x07\x40\xff\xa0\x10\x00\x08\x40\xea\x90\x10\x00\x20\x20\x0f\x08\x80\x00\x11\x00\x0b\x07\x08\x00\x20\x60\x0d", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8007, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x10\x00\x08\x40\xea\x90\x8f\x06\x07\x04\xff\x84\x20\x09\x60\x10\xfc\x84\x08\xfd\x84\x04\xfe\x84\x00\x03\x00\x00\x10\x08\x80\x37", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x80a0, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x90\x69\x84\x00\x10\x08\x80\x69\xa0\x20\x1a\x08\x40\x64\xa0\x10\x10\x08\x80\x4f\xa0\x20\x1d\x08\x40\x5f\xa0\x20\x1e\x08\x40\x5d", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x80a0, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x10\x00\x08\x80\x68\x90\x40\xfe\xa0\x20\x0e\x07\x50\x00\x08\x40\x7f\xa0\x04\xfe\x84\x00\x04\x00\x10\xf0\x44\x50\x00\x08\x00\x7f", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8011, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x20\xf0\x60\x04\x5c\x84\x04\x61\x84\x04\x57\x84\x00\x00\x21\x04\x74\x84\x00\x40\x21\x00\x0b\x07\x04\x74\x84\x00\x00\x21\x10\x57", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8084, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x30\x20\x08\x00\x04\x11\x50\x00\x08\x03\xff\x11\x20\xfa\x60\x10\xf0\x44\x50\x20\x08\x00\x7f\x11\x60\x20\x08\x40\x00\x08\x00\x08", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8011, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x30\x1a\x07\x50\x00\x08\x07\x00\x11\x9f\x1d\x07\x8b\x1e\x07\x9c\x15\x07\x20\xf8\x60\x10\x28\x44\x60\x00\x08\x01\x00\x11\x20\x28", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8060, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x87\x1b\x07\x40\xf7\xa0\x81\x27\x07\x20\x48\x60\x10\x0a\x44\x10\xf4\x84\x3b\xd4\x00\xe0\x14\x43\x08\x00\x20\x00\x06\x07\x89\x02", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8007, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x40\xae\x90\x81\x04\x07\x40\x2e\x90\x40\x7f\xa0\x10\x2e\x44\x20\x2f\x08\x9f\x02\x07\x00\x00\x11\x10\x00\x20\x00\x00\x08\x40\x67", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x80a0, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x00\x00\x11\x84\x02\x07\x20\xf0\x60\x9f\x03\x07\x40\x7e\xa0\x40\x65\x90\x10\x62\x84\x10\x10\x08\x40\x61\xa0\x20\x1d\x08\x40\x5f", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x80a0, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x20\x1e\x08\x40\x5d\xa0\x10\x00\x08\x40\x5e\x90\x20\x30\x60\x10\xcf\x84\x20\x1c\x08\x7f\xff\x21\x3b\xf7\x00\xc8\x14\x43\x10\x00", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8020, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x00\x00\x08\x40\xb5\x90\x40\xad\xa0\x00\x0a\x07\x10\x4f\x84\x20\x1c\x08\x7f\xff\x21\x3c\x01\x00\x48\x14\x43\x10\x00\x20\x00\x00", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8008, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x40\x35\x90\x40\x2d\xa0\x00\x14\x07\x80\x0c\x07\x82\x03\x07\x04\x50\x84\x10\x00\x20\x20\x02\x07\x00\x08\x21\x40\x00\x08\x00\x01", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8011, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x40\x50\xa0\x00\x04\x00\x20\x7f\x00\x80\x14\x43\x01\x00\x01\x04\x00\x11\x02\x00\x21\x10\x9f\x84\x10\x20\x08\x40\x97\x90\x10\xbf", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8084, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x20\x1d\x08\x40\xc6\xa0\x20\x8e\x08\x40\x72\x90\x40\x16\xa0\x10\x96\x84\x10\x00\x08\x40\x9e\x90\x20\x36\x60\x20\x91\x00\x00\x14", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8043, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x00\x01\x01\x00\x04\x11\x00\x02\x21\x10\x1f\x84\x10\x20\x08\x40\x17\x90\x10\x3f\x84\x20\x1d\x08\x40\x46\xa0\x20\x8e\x08\x40\x70", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8090, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x40\x96\xa0\x10\x16\x84\x10\x00\x08\x40\x1e\x90\x20\x34\x60\x10\x65\x84\x50\x10\x08\x00\x00\x21\x84\x03\x07\x20\xf0\x60\x9f\x03", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8007, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x40\x7e\xa0\x00\x10\x08\x40\x65\xa0\x20\x0d\x08\x40\x64\x90\x40\x62\xa0\x00\x04\x00\x04\x1c\x44\x04\x1b\x44\xc3\xff\x21\x87\x04", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8007, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x40\x7f\xa0\x10\x42\x84\x20\x1e\x08\x7f\xff\x21\x10\x20\x08\x40\x1c\x90\x10\x07\x84\x10\x00\x08\x40\x06\x90\x40\x55\xa0\x10\xc2", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8084, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x20\x1e\x08\x7f\xff\x21\x10\x20\x08\x40\x9c\x90\x10\x87\x84\x10\x00\x08\x40\x86\x90\x40\x56\xa0\x10\x56\x84\x20\x0f\x08\x40\x7b", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8090, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x22\x00\x60\x40\x00\x08\x40\x79\xa0\x00\x08\x11\x10\x55\x84\x20\x0f\x08\x40\x7a\x90\x22\x00\x60\x50\x00\x08\x40\x79\xa0\x00\xff", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8011, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x04\x6f\x84\x00\x05\x21\x21\x39\x00\x04\x00\x11\x10\xc1\x84\x20\x0f\x08\x70\x07\x07\x10\x10\x08\x40\xc0\xa0\x20\x0f\x08\x7f\xff", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8011, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x8f\x02\x07\x80\x00\x11\x08\x00\x20\x08\xc1\x84\x40\xbd\x90\x9e\x02\x07\x40\x7f\xa0\x40\xec\x90\x04\x6e\x84\x00\x05\x21\x21\x4c", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8000, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x00\x04\x11\x10\x41\x84\x20\x0f\x08\x70\x07\x07\x10\x10\x08\x40\x40\xa0\x20\x0f\x08\x7f\xff\x11\x8f\x02\x07\x80\x00\x11\x08\x00", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8020, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x08\x41\x84\x40\x3d\x90\x9e\x02\x07\x40\x7f\xa0\x40\x6d\x90\x10\x2d\x44\x20\xe7\x00\x08\x00\x11\x20\x32\x60\x80\x14\x43\x10\x2c", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8044, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x20\xec\x00\x00\x08\x11\x20\x31\x60\x00\x14\x43\x04\x34\x44\x40\x5b\xa0\x00\x04\x00\x21\x6a\x00\x80\x00\x11\x21\x70\x00\x3f\xff", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8011, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x08\xe8\x84\x20\x32\x50\x08\x68\x84\x20\x31\x50\x08\x5e\x84\x20\x30\x50\x0f\xc4\x07\x10\x34\x44\x10\x5b\x84\x6f\xf3\x07\x00\x00", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8008, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x02\x00\x21\x40\xfc\x90\x3d\xd4\x00\x04\xfc\x84\x00\x00\x21\x04\xfd\x84\x00\x08\x21\x00\x04\x00\x21\x81\x00\xc0\x00\x11\x04\x5b", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8084, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x02\x00\x21\x70\x06\x07\x10\xfe\x84\x30\x20\x08\x00\x03\x11\x10\x00\x08\x40\x59\x90\x04\xff\x84\x40\x58\xa0\x10\x59\x84\x20\x0f", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8008, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x40\x59\xa0\x20\x00\x11\x70\x1e\x07\x10\x00\x08\x00\x0b\x11\x0f\xe4\x07\x10\x59\x84\x00\x00\x08\x20\x30\x50\x40\x59\xa0\x70\x06", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8007, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x10\x00\x08\x00\x0a\x11\x0f\xec\x07\x08\x34\x44\x02\x10\x11\x10\x58\x84\x20\x0f\x08\x40\x58\xa0\x20\x00\x11\x30\x08\x07\x0f\xf4", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8007, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x10\x58\x84\x00\x00\x08\x20\x30\x50\x40\x58\xa0\x70\x06\x07\x10\x00\x08\x00\x05\x11\x00\x04\x00\x10\x5a\x84\x00\x00\x08\x00\x01", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8011, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x40\x5a\xa0\x08\x34\x44\x02\x00\x11\x30\x08\x07\x60\x00\x08\x00\x00\x11\x40\x5a\xa0\x8f\x4f\x07\x40\x7e\xa0\x00\x04\x00\x3c\xdd", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8000, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x10\x00\x20\xa8\x14\x43\x04\xa7\x84\x20\x8e\x08\x40\xc4\x90\x40\xaf\xa0\x20\x0f\x08\x40\xc5\x90\x40\xa7\xa0\x3c\xe7\x00\x10\x00", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8020, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x28\x14\x43\x04\x27\x84\x20\x8e\x08\x40\x44\x90\x40\x2f\xa0\x20\x0f\x08\x40\x45\x90\x40\x27\xa0\x00\x04\x00\x10\xf0\x44\x50\x00", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8008, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\xff\xf7\x11\x93\x04\x07\x20\xf0\x60\x04\x61\x84\x04\x5c\x84\x40\x57\xa0\x00\x04\x00\x10\x61\x84\x00\x20\x08\x20\x1f\x08\x40\xff", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x80a0, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x10\x00\x08\x40\x5c\x90\x40\x57\xa0\x04\x74\x84\x10\x00\x20\x00\x00\x08\x40\x74\xa0\x00\x01\x11\x20\x05\x07\x00\x40\x21\x70\x00", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8008, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x7f\xff\x21\x08\xff\x84\x42\x00\x90\x85\x02\x07\x20\xf0\x60\x7f\xff\x11\x60\x20\x08\x00\xd0\x11\x40\x00\x08\x00\x02\x11\x86\x1b", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8007, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x40\x74\xa0\x08\x6f\x84\x00\x00\x11\x04\xf1\x84\x00\x40\x21\x21\xf7\x00\x02\x00\x11\x60\x07\x07\x10\x20\x08\x40\xc3\x90\x20\x2f", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8008, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x80\x00\x11\x70\x02\x07\x7f\xff\x11\x10\x00\x08\x40\x8d\x90\x40\x85\xa0\x08\x6e\x84\x00\x00\x11\x04\xf0\x84\x00\x40\x21\x22\x07", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8000, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x00\x02\x11\x60\x07\x07\x10\x20\x08\x40\x43\x90\x20\x2f\x08\x80\x00\x11\x70\x02\x07\x7f\xff\x11\x10\x00\x08\x40\x0d\x90\x40\x05", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x80a0, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x10\xec\x84\x00\x10\x08\x10\xe7\x84\x40\xe7\xa0\x20\x0f\x08\x40\xef\xa0\x10\x6d\x84\x00\x10\x08\x10\x6c\x84\x40\x6c\xa0\x20\x0f", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8008, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x40\x7d\xa0\x7f\xff\x11\x00\x04\x00\x10\xef\x84\x00\x10\x08\x10\xee\x84\x40\xee\xa0\x20\x0f\x08\x40\xbd\xa0\x10\x7d\x84\x00\x10", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8008, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x10\x7c\x84\x40\x7c\xa0\x20\x0f\x08\x40\x3d\xa0\x40\x00\x11\x3e\x9b\x00\xfb\xff\x21\x6f\x14\x43\x3e\x9e\x00\xff\xfb\x21\x6e\x14", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8043, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x3d\x57\x00\x40\xaf\xa0\xa0\x14\x43\x3d\x5a\x00\x40\x2f\xa0\x20\x14\x43\x00\x04\x00\x3d\x5e\x00\x40\xa5\xa0\xb0\x14\x43\x3d\x61", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8000, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x40\x25\xa0\x30\x14\x43\x00\x00\x00\x22\x28\x00\x00\x02\x07\x22\x26\x00\x8a\x03\x07\x89\x04\x07\x40\x7e\xa0\x40\xbd\x90\x98\x14", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8043, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x10\x9c\x84\x20\x8f\x08\x40\x9a\x90\x40\x99\xa0\x20\x2e\x08\x40\xbd\x90\x00\x10\x08\x40\x9b\xa0\x20\x0e\x08\x7f\xff\x21\x40\xf5", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8090, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x00\x00\x00\x22\x3c\x00\x00\x02\x07\x22\x3a\x00\x82\x03\x07\x81\x04\x07\x40\x7e\xa0\x40\x3d\x90\x18\x14\x43\x10\x1c\x84\x20\x8f", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8008, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x40\x1a\x90\x40\x19\xa0\x20\x2e\x08\x40\x3d\x90\x00\x10\x08\x40\x1b\xa0\x20\x0e\x08\x7f\xff\x21\x40\xf5\x90\x3d\x8c\x00\xb8\x14", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8043, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x40\xc2\xa0\x3d\x8f\x00\x38\x14\x43\x40\x42\xa0\x00\x04\x00\x10\x51\x84\x20\x0f\x08\x7f\xc0\x11\x40\x51\xa0\x08\xbb\x84\x08\x3b", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8084, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\xcb\x90\x11\x9e\x02\x07\xc7\x00\x11\x40\x7f\xa0\x08\xba\x84\x08\x3a\x84\x74\x70\x11\x9e\x02\x07\x59\x00\x11\x40\x7f\xa0\x3e\xed", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8000, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\xfd\xff\x21\xf1\x14\x43\x3e\xf0\x00\xff\xfd\x21\xf0\x14\x43\x00\x04\x00\x04\xb9\x84\x40\xb6\xa0\x04\x39\x84\x40\x36\xa0\x00\x04", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8000, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x3e\xc3\x00\x40\x87\xa0\x80\x14\x43\x3e\xc6\x00\x40\x07\xa0\x00\x14\x43\x00\x04\x00\x00\x00\x00\x04\xf5\x84\x00\x00\x21\x70\x03", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8007, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x10\xf5\x84\x10\x00\x08\x40\xf3\x90\x40\xf5\xa0\x3e\xd2\x00\x40\x85\xa0\x88\x14\x43\x3e\xd5\x00\x40\x05\xa0\x08\x14\x43\x00\x04", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8000, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x00\x01\x07\x00\x02\x07\x00\x03\x07\x00\x04\x07\x00\x06\x07\x00\x16\x07\x00\x1e\x07\x00\x24\x07\x00\x3c\x07\x00\x72\x07\x00\x8d", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8007, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x00\xe0\x07\x00\xf6\x07\x01\x9f\x07\x01\xd1\x07\x00\x10\x07\x1f\xff\x07\x20\x03\x60\x0f\x5f\x07\x08\xfa\x84\x04\x11\x44\xff\x00", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8011, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x2f\x63\x07\x70\x10\x08\x00\xf0\x21\x50\x00\x08\x00\xf0\x21\x40\xf9\x90\x00\x08\x07\x3e\x79\x00\x0f\x6b\x07\x90\x01\x07\x40\xf9", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x80a0, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x3f\x6e\x07\x70\x00\x08\x00\x7f\x11\x40\xf8\xa0\x9d\x07\x07\x20\x12\x60\x08\xfa\x84\x04\x11\x44\x3e\x54\x00\x00\x16\x07\x48\x80", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8011, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x08\x09\x44\x40\x75\x90\x7f\xef\x07\x10\x00\x20\x00\x10\x08\xff\xff\x21\x06\x00\x84\x40\xfb\xa0\x60\x00\x08\x00\x00\x21\x40\xff", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8090, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x10\xfb\x84\x60\x20\x08\x40\xfb\x90\x30\x00\x08\x00\x08\x11\x3d\xea\x00\x04\xfb\x84\x3d\xec\x00\x04\xff\x84\x40\xf8\xa0\x04\x11", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8044, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x8f\xff\x07\x20\x19\x60\x3e\xd2\x00\x00\x31\x07\x00\x01\x00\x00\x33\x07\x00\x02\x00\x27\x18\x43\x75\x00\x43\x8f\xff\x07\x20\x19", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8060, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x04\xf5\x84\x40\xf2\xa0\x04\x51\x84\x7f\xff\x21\x04\xf5\x84\x00\x00\x21\x04\xf3\x84\x00\x10\x21\x04\xf2\x84\x0c\x00\x21\x04\x72", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8044, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x00\x77\x21\x3f\xfa\x07\x70\x20\x08\x00\x00\x11\x10\x2d\x44\x10\x2c\x44\x00\x20\x08\x10\x00\x11\x00\x00\x08\x00\x00\x11\x80\x00", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8021, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x04\x73\x44\x07\x07\x21\x04\x72\x44\x00\x07\x21\x04\x73\x44\x07\x77\x21\x04\x73\x44\x00\x70\x21\x04\x2e\x44\x04\x2d\x44\x04\x2c", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8044, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x80\x00\x21\x04\x1c\x44\x04\x1b\x44\x0d\x00\x21\x04\x1c\x44\x04\x1b\x44\x0c\x80\x21\x04\x1c\x44\x04\x1b\x44\x1f\x08\x21\x0f\x18", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8043, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x08\x28\x44\x01\x11\x11\x08\x5d\x84\x10\x00\x10\x10\x00\x08\x40\x00\x21\x30\x04\x07\x40\xff\x90\x50\x20\x08\xc0\x00\x11\x10\xff", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8084, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x00\x20\x08\x00\x40\x11\x40\x00\x08\x00\x01\x11\x20\x51\x60\x10\x00\x44\x60\x00\x08\x40\x54\x90\x20\x00\x60\x00\x79\x07\x81\x48", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8007, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x80\x03\x07\x40\xf8\xa0\x48\xc0\x11\x00\x77\x07\x00\x78\x07\x00\x79\x07\x00\x04\x07\x00\x7b\x07\x00\x7c\x07\x00\x7d\x07\x00\x55", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8007, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x00\x7f\x07\x00\x80\x07\x00\x81\x07\x00\x74\x07\x00\x83\x07\x00\x82\x07\x00\x85\x07\x00\x86\x07\x0f\xef\x07\x1f\xff\x07\xff\x00", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8011, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x10\x00\x20\x30\x10\x08\x00\x01\x21\x50\x00\x08\x00\x0f\x21\x40\xf9\x90\x30\x90\x07\x70\x10\x08\x00\x80\x21\x50\x00\x08\x00\xf0", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8021, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x08\xf9\x84\x04\xf8\x84\x2f\xff\x07\x3e\x59\x00\x04\xf1\x84\x04\xf0\x84\x04\x5a\x84\x00\x00\x21\x04\xf6\x84\x00\x02\x21\x04\xfa", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8084, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x40\x00\x21\x04\xf7\x84\x01\x04\x21\x04\x1c\x44\x04\x1b\x44\x0b\x23\x21\x0f\x18\x43\x04\x70\x44\x06\x66\x21\x04\x3b\x44\x04\x39", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8044, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x00\x80\x21\x04\x3c\x44\x2a\x0a\x21\x04\x2f\x44\x00\x44\x21\x04\x29\x44\x00\x00\x21\x03\x19\x42\x4e\x19\x43\x0c\x59\x43\x27\x18", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8043, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x15\x00\x43\x04\x22\x44\x03\x07\x21\x04\x21\x44\x11\x11\x21\x04\x20\x44\x33\x33\x21\x00\x00\x42\xc0\x3d\x42\x80\x3d\x43\x04\x35", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8044, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x00\x00\x21\x04\x05\x43\x42\xcd\x00", + .reg_data_seq_size = 9, + },{ + .reg_addr = 0x88ef, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x00\x00\x00\x20\x00\x18\x00\x00\x00\x00\xab\x0a\x00\x40\x00\x40\x00\x00\x00\x00\x00\x00\x00\x80\x00\x00\x27\x83\x64\x7e\xca\x00", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x88b2, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x7f\x59\x7f\xbe\x7f\xfe\x7f\xfe\x7f\xee\x73\x54\x4c\x70\x5a\x00\x6b\x0e\x6b\x1c\x5b\xcb\x32\x8c\x0b\xd2\x13\x07\x28\x01\x49\x00", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8800, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x00\x00\x00\x00\xff\x7f\x0b\x97\x14\xae\xf7\x53\x26\x63\x07\x46\x00\x20\x00\x89\x00\x40\x80\x41\x00\x7f\xff\x7f\xd3\x09\x00\x00", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x88ff, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x7f\x00\x00\x00\x00\x90\xcb\x70\x74\xfe\x7f\x52\x09\x00\x00\xfe\x7f\x00\x00\x00\x00\x00\xf2\x00\x40\xf0\x7f\x00\x0c\x00\x00\x00", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8800, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x00\x00\x00\x00\x00\x4a\x00\x4a\x00\x24\xff\x7f\x00\x00\x00\x00\x00\x00\x00\x00\xff\x7f\x00\x00\x00\x50\x00\x30\x00\x00\x00\x00", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8800, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x00\x00\x00\xa0\x00\x00\x03\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x20\xff\x7f\x00", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8800, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x00\x00\x00\x00\xff\x7f\x00\x78\x00\x08\x00\x00\x10\x00\x00\x00\x00\x00\x00\x00\xff\x7f\x00\x40\x00\x40\x00\x00\x00\x00\x00\x00", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8800, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x00\x00\x80\xff\x7f\x1c\x1b\xc5\x07\xc0\x20\x12\xf0\x00\x10\x10\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8800, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x02\x00\x00\x00\x00\x00\x00\x00\x00\xcc\x59\x00\x00\x00\x40\x00\x00", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8800, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x0a\x00\x00\x00\x00\x00\x00\x08\x00\x00\x00\x00\x00\x00\x00\xff\x7f\x0b", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8897, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x14\xae\xf7\x53\x26\x63\x07\x46\x00\x20\x00\x89\x00\x40\x80\x41\x00\x7f\xff\x7f\xd3\x09\x00\x00\xff\x7f\x00\x00\x00\x00\x90\xcb", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8870, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x74\xfe\x7f\x52\x09\x00\x00\xfe\x7f\x00\x00\x00\x00\x00\xf2\x00\x40\xf0\x7f\x00\x0c\x00\x00\x00\x00\x00\x00\x00\x00\x00\x4a\x00", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x884a, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x00\x24\xff\x7f\x00\x00\x00\x00\x00\x00\x00\x00\xff\x7f\x00\x00\x00\x50\x00\x30\x00\x00\x00\x00\x00\x00\x00\x00\xa0\x00\x00\x03", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8800, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x20\xff\x7f\x00\x00\x00\x00\x00\x00\xff\x7f\x00", + .reg_data_seq_size = 32, + },{ + .reg_addr = 0x8878, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0000, + .data_type = MSM_CAMERA_I2C_SEQ_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "\x00\x08\x00\x00\x10\x00\x00\x00\x00\x00\x00\x00\xff\x7f\x00\x40\x00\x40", + .reg_data_seq_size = 18, + },{ + .reg_addr = 0x8205, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0c00, + .data_type = MSM_CAMERA_I2C_WORD_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "", + .reg_data_seq_size = 0, + },{ + .reg_addr = 0x8205, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0d00, + .data_type = MSM_CAMERA_I2C_WORD_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "", + .reg_data_seq_size = 0, + },{ + .reg_addr = 0x8c01, + .addr_type = MSM_CAMERA_I2C_WORD_ADDR, + .reg_data = 0x0001, + .data_type = MSM_CAMERA_I2C_BYTE_DATA, + .i2c_operation = MSM_OIS_WRITE, + .delay = 0, + .reg_data_seq = "", + .reg_data_seq_size = 0, + } +}; + + +/* +// still mode settings: + {0x847f, 0x0c0c,}, //_M_EQCTL + + {0x8436, 0xfd7f,}, //_M_Kgxdr + {0x8440, 0xf07f,}, //_M_X_LMT + {0x8443, 0xb41e,}, //_M_X_TGT + {0x841b, 0x4001,}, //_M_Kgx10 + + {0x84b6, 0xfd7f,}, //_M_Kgydr + {0x84c0, 0xf07f,}, //_M_Y_LMT + {0x84c3, 0xb41e,}, //_M_Y_TGT + {0x849b, 0x4001,}, //_M_Kgy10 + + {0x8438, 0x2d0f,}, //_M_Kgx11 + {0x84b8, 0x2d0f,}, //_M_Kgy11 + {0x8447, 0x002b,}, //_M_KgxTG + {0x84c7, 0x002b,}, //_M_KgyTG + + {0x847f, 0x0d0d,}, //_M_EQCTL +*/ + +static struct msm_camera_i2c_reg_array init_array_s5k3p8sp[] = { + {0x6028,0x2000,0}, {0x6214,0x7971,0}, {0x6218,0x7150,0}, {0x30e,0x3d,0}, + {0x6028,0x2000,0}, {0x602a,0x2f38,0}, {0x6f12,0x88,0}, {0x6f12,0xd70,0}, + {0x344,0x18,0}, + {0x348,0x1217,0}, // last_pixel = 0x90C*2 + {0x346,0x18,0}, + {0x34a,0xd97,0}, // last_line = 0x6CC*2 + {0x34c,0x900,0}, // width? + {0x34e,0x6c0,0}, // height? + {0x342,0x1400,0}, // line_length_pclk + {0x340,0xe3b,0}, // frame_length_lines + {0x202,0x200,0}, // integ_time + {0x200,0x618,0}, + {0x900,0x122,0}, {0x380,0x1,0}, {0x382,0x3,0}, {0x384,0x3,0}, {0x386,0x1,0}, {0x400,0x0,0}, {0x404,0x10,0}, + {0x3604,0x2,0}, {0x3606,0x103,0}, {0xf496,0x48,0}, {0xf470,0x20,0}, {0xf43a,0x15,0}, {0xf484,0x6,0}, {0xf440,0xaf,0}, {0xf442,0x44c6,0}, + {0xf408,0xfff7,0}, {0x3664,0x19,0}, {0xf494,0x1010,0}, {0x367a,0x100,0}, {0x362a,0x104,0}, {0x362e,0x404,0}, {0x32b2,0x8,0}, {0x3286,0x3,0}, {0x328a,0x5,0}, + {0xf47c,0x1f,0}, {0xf62e,0xc5,0}, {0xf630,0xcd,0}, {0xf632,0xdd,0}, {0xf634,0xe5,0}, {0xf636,0xf5,0}, {0xf638,0xfd,0}, {0xf63a,0x10d,0}, {0xf63c,0x115,0}, {0xf63e,0x125,0}, {0xf640,0x12d,0}, + {0x6028,0x2000,0}, {0x602a,0x1704,0}, {0x6f12,0x8011,0}, {0x3070,0x0,0}, {0xb0e,0x0,0}, {0x317a,0x7,0}, {0x31c0,0xc8,0}, {0x1006,0x4,0}, {0x31a4,0x102,0}, +}; + +static struct msm_camera_i2c_reg_array init_array_ov8865[] = { +// round 1 +//{0x103,0x1,0}, // software reset +{0x100,0x0,0}, // standby on +{0x3638,0xff,0}, +{0x302,0x1e,0}, {0x303,0x0,0}, {0x304,0x3,0}, {0x30d,0x1e,0}, {0x30e,0x0,0}, {0x30f,0x9,0}, {0x312,0x1,0}, {0x31e,0xc,0}, // PLL control +{0x3015,0x1,0}, {0x3018,0x72,0}, {0x3020,0x93,0}, {0x3022,0x1,0}, +{0x3031,0xa,0}, // 10-bit mode +{0x3106,0x1,0}, {0x3305,0xf1,0}, {0x3308,0x0,0}, {0x3309,0x28,0}, {0x330a,0x0,0}, {0x330b,0x20,0}, {0x330c,0x0,0}, {0x330d,0x0,0}, {0x330e,0x0,0}, {0x330f,0x40,0}, {0x3307,0x4,0}, {0x3604,0x4,0}, {0x3602,0x30,0}, {0x3605,0x0,0}, {0x3607,0x20,0}, {0x3608,0x11,0}, {0x3609,0x68,0}, {0x360a,0x40,0}, {0x360c,0xdd,0}, {0x360e,0xc,0}, {0x3610,0x7,0}, {0x3612,0x86,0}, {0x3613,0x58,0}, {0x3614,0x28,0}, {0x3617,0x40,0}, {0x3618,0x5a,0}, {0x3619,0x9b,0}, {0x361c,0x0,0}, {0x361d,0x60,0}, {0x3631,0x60,0}, {0x3633,0x10,0}, {0x3634,0x10,0}, {0x3635,0x10,0}, {0x3636,0x10,0}, {0x3641,0x55,0}, {0x3646,0x86,0}, {0x3647,0x27,0}, {0x364a,0x1b,0}, {0x3500,0x0,0}, {0x3501,0x4c,0}, {0x3502,0x0,0}, {0x3503,0x0,0}, {0x3508,0x2,0}, +{0x3509,0x0,0}, // AEC GAIN +{0x3700,0x24,0}, {0x3701,0xc,0}, {0x3702,0x28,0}, {0x3703,0x19,0}, {0x3704,0x14,0}, {0x3705,0x0,0}, {0x3706,0x38,0}, {0x3707,0x4,0}, {0x3708,0x24,0}, {0x3709,0x40,0}, {0x370a,0x0,0}, {0x370b,0xb8,0}, {0x370c,0x4,0}, {0x3718,0x12,0}, {0x3719,0x31,0}, {0x3712,0x42,0}, {0x3714,0x12,0}, {0x371e,0x19,0}, {0x371f,0x40,0}, {0x3720,0x5,0}, {0x3721,0x5,0}, {0x3724,0x2,0}, {0x3725,0x2,0}, {0x3726,0x6,0}, {0x3728,0x5,0}, {0x3729,0x2,0}, {0x372a,0x3,0}, {0x372b,0x53,0}, {0x372c,0xa3,0}, {0x372d,0x53,0}, {0x372e,0x6,0}, {0x372f,0x10,0}, {0x3730,0x1,0}, {0x3731,0x6,0}, {0x3732,0x14,0}, {0x3733,0x10,0}, {0x3734,0x40,0}, {0x3736,0x20,0}, {0x373a,0x2,0}, {0x373b,0xc,0}, {0x373c,0xa,0}, {0x373e,0x3,0}, {0x3755,0x40,0}, {0x3758,0x0,0}, {0x3759,0x4c,0}, {0x375a,0x6,0}, {0x375b,0x13,0}, {0x375c,0x40,0}, {0x375d,0x2,0}, {0x375e,0x0,0}, {0x375f,0x14,0}, {0x3767,0x1c,0}, {0x3768,0x4,0}, {0x3769,0x20,0}, {0x376c,0xc0,0}, {0x376d,0xc0,0}, {0x376a,0x8,0}, {0x3761,0x0,0}, {0x3762,0x0,0}, {0x3763,0x0,0}, {0x3766,0xff,0}, {0x376b,0x42,0}, {0x3772,0x23,0}, {0x3773,0x2,0}, {0x3774,0x16,0}, {0x3775,0x12,0}, {0x3776,0x8,0}, {0x37a0,0x44,0}, {0x37a1,0x3d,0}, {0x37a2,0x3d,0}, {0x37a3,0x1,0}, {0x37a4,0x0,0}, {0x37a5,0x8,0}, {0x37a6,0x0,0}, {0x37a7,0x44,0}, {0x37a8,0x58,0}, {0x37a9,0x58,0}, {0x3760,0x0,0}, {0x376f,0x1,0}, {0x37aa,0x44,0}, {0x37ab,0x2e,0}, {0x37ac,0x2e,0}, {0x37ad,0x33,0}, {0x37ae,0xd,0}, {0x37af,0xd,0}, {0x37b0,0x0,0}, {0x37b1,0x0,0}, {0x37b2,0x0,0}, {0x37b3,0x42,0}, {0x37b4,0x42,0}, {0x37b5,0x33,0}, {0x37b6,0x0,0}, {0x37b7,0x0,0}, {0x37b8,0x0,0}, {0x37b9,0xff,0}, {0x3800,0x0,0}, {0x3801,0xc,0}, {0x3802,0x0,0}, {0x3803,0xc,0}, +{0x3804,0xc,0}, {0x3805,0xd3,0}, // 3283 +{0x3806,0x9,0}, {0x3807,0xa3,0}, // 2467 +{0x3808,0x6,0}, {0x3809,0x60,0}, // 0x660 = 1632 (width) +{0x380a,0x4,0}, {0x380b,0xc8,0}, // 0x4c8 = 1224 (height) +{0x380c,0x7,0}, {0x380d,0x83,0}, // 0x783 = 1923 (stride) +{0x380e,0x4,0}, {0x380f,0xe0,0}, // 0x4e0 = 1248 (vstride) +{0x3810,0x0,0}, {0x3811,0x4,0}, {0x3813,0x4,0}, +{0x3814,0x3,0}, {0x3815,0x1,0}, // H-binning +{0x3820,0x6,0}, // format1 +{0x3821,0x40,0}, // format2 +{0x382a,0x3,0}, {0x382b,0x1,0}, // V-binning +{0x382d,0x7f,0}, {0x3830,0x8,0}, {0x3836,0x2,0}, {0x3837,0x18,0}, +{0x3841,0xff,0}, +{0x3846,0x88,0}, {0x3d85,0x6,0}, {0x3d8c,0x75,0}, {0x3d8d,0xef,0}, {0x3f08,0xb,0}, {0x4000,0xf1,0}, {0x4001,0x14,0}, {0x4005,0x10,0}, {0x4006,0x1,0}, {0x4007,0x1,0}, {0x400b,0xc,0}, {0x400d,0x10,0}, {0x401b,0x0,0}, {0x401d,0x0,0}, {0x4020,0x0,0}, {0x4021,0x0,0}, {0x4022,0x4,0}, {0x4023,0x1f,0}, {0x4024,0x6,0}, {0x4025,0x20,0}, {0x4026,0x6,0}, {0x4027,0x4f,0}, {0x4028,0x0,0}, {0x4029,0x2,0}, {0x402a,0x4,0}, {0x402b,0x4,0}, {0x402c,0x2,0}, {0x402d,0x2,0}, {0x402e,0x8,0}, {0x402f,0x2,0}, {0x401f,0x0,0}, {0x4034,0x3f,0}, {0x4300,0xff,0}, {0x4301,0x0,0}, {0x4302,0xf,0}, {0x4500,0x40,0}, {0x4503,0x10,0}, {0x4601,0x74,0}, {0x481f,0x32,0}, {0x4837,0x15,0}, {0x4850,0x10,0}, {0x4851,0x32,0}, {0x4b00,0x2a,0}, {0x4b0d,0x0,0}, {0x4d00,0x4,0}, {0x4d01,0x18,0}, {0x4d02,0xc3,0}, {0x4d03,0xff,0}, {0x4d04,0xff,0}, {0x4d05,0xff,0}, {0x5000,0x96,0}, {0x5001,0x1,0}, {0x5002,0x8,0}, {0x5901,0x0,0}, +{0x5e00,0x0,0}, +//{0x5e00,0x80,0}, +{0x5e01,0x41,0}, {0x5b00,0x2,0}, {0x5b01,0xd0,0}, {0x5b02,0x3,0}, {0x5b03,0xff,0}, {0x5b05,0x6c,0}, {0x5780,0xfc,0}, {0x5781,0xdf,0}, {0x5782,0x3f,0}, {0x5783,0x8,0}, {0x5784,0xc,0}, {0x5786,0x20,0}, {0x5787,0x40,0}, {0x5788,0x8,0}, {0x5789,0x8,0}, {0x578a,0x2,0}, {0x578b,0x1,0}, {0x578c,0x1,0}, {0x578d,0xc,0}, {0x578e,0x2,0}, {0x578f,0x1,0}, {0x5790,0x1,0}, {0x5800,0x1d,0}, {0x5801,0xe,0}, {0x5802,0xc,0}, {0x5803,0xc,0}, {0x5804,0xf,0}, {0x5805,0x22,0}, {0x5806,0xa,0}, {0x5807,0x6,0}, {0x5808,0x5,0}, {0x5809,0x5,0}, {0x580a,0x7,0}, {0x580b,0xa,0}, {0x580c,0x6,0}, {0x580d,0x2,0}, {0x580e,0x0,0}, {0x580f,0x0,0}, {0x5810,0x3,0}, {0x5811,0x7,0}, {0x5812,0x6,0}, {0x5813,0x2,0}, {0x5814,0x0,0}, {0x5815,0x0,0}, {0x5816,0x3,0}, {0x5817,0x7,0}, {0x5818,0x9,0}, {0x5819,0x6,0}, {0x581a,0x4,0}, {0x581b,0x4,0}, {0x581c,0x6,0}, {0x581d,0xa,0}, {0x581e,0x19,0}, {0x581f,0xd,0}, {0x5820,0xb,0}, {0x5821,0xb,0}, {0x5822,0xe,0}, {0x5823,0x22,0}, {0x5824,0x23,0}, {0x5825,0x28,0}, {0x5826,0x29,0}, {0x5827,0x27,0}, {0x5828,0x13,0}, {0x5829,0x26,0}, {0x582a,0x33,0}, {0x582b,0x32,0}, {0x582c,0x33,0}, {0x582d,0x16,0}, {0x582e,0x14,0}, {0x582f,0x30,0}, {0x5830,0x31,0}, {0x5831,0x30,0}, {0x5832,0x15,0}, {0x5833,0x26,0}, {0x5834,0x23,0}, {0x5835,0x21,0}, {0x5836,0x23,0}, {0x5837,0x5,0}, {0x5838,0x36,0}, {0x5839,0x27,0}, {0x583a,0x28,0}, {0x583b,0x26,0}, {0x583c,0x24,0}, {0x583d,0xdf,0}, +//{0x100,0x1,0}, +// round 2 (color calibration) +{0x7010,0x0,0}, {0x7011,0x0,0}, {0x7012,0x0,0}, {0x7013,0x0,0}, {0x7014,0x0,0}, {0x7015,0x0,0}, {0x7016,0x0,0}, {0x7017,0x0,0}, {0x7018,0x0,0}, {0x7019,0x0,0}, {0x701a,0x0,0}, {0x701b,0x0,0}, {0x701c,0x0,0}, {0x701d,0x0,0}, {0x701e,0x0,0}, {0x701f,0x0,0}, {0x7020,0x0,0}, {0x7021,0x0,0}, {0x7022,0x0,0}, {0x7023,0x0,0}, {0x7024,0x0,0}, {0x7025,0x0,0}, {0x7026,0x0,0}, {0x7027,0x0,0}, {0x7028,0x0,0}, {0x7029,0x0,0}, {0x702a,0x0,0}, {0x702b,0x0,0}, {0x702c,0x0,0}, {0x702d,0x0,0}, {0x702e,0x0,0}, {0x702f,0x0,0}, {0x7030,0x0,0}, {0x7031,0x0,0}, {0x7032,0x0,0}, {0x7033,0x0,0}, {0x7034,0x0,0}, {0x7035,0x0,0}, {0x7036,0x0,0}, {0x7037,0x0,0}, {0x7038,0x0,0}, {0x7039,0x0,0}, {0x703a,0x0,0}, {0x703b,0x0,0}, {0x703c,0x0,0}, {0x703d,0x0,0}, {0x703e,0x0,0}, {0x703f,0x0,0}, {0x7040,0x0,0}, {0x7041,0x0,0}, {0x7042,0x0,0}, {0x7043,0x0,0}, {0x7044,0x0,0}, {0x7045,0x0,0}, {0x7046,0x0,0}, {0x7047,0x0,0}, {0x7048,0x0,0}, {0x7049,0x0,0}, {0x704a,0x0,0}, {0x704b,0x0,0}, {0x704c,0x0,0}, {0x704d,0x0,0}, {0x704e,0x0,0}, {0x704f,0x0,0}, {0x7050,0x0,0}, {0x7051,0x0,0}, {0x7052,0x0,0}, {0x7053,0x0,0}, {0x7054,0x0,0}, {0x7055,0x0,0}, {0x7056,0x0,0}, {0x7057,0x0,0}, {0x7058,0x0,0}, {0x7059,0x0,0}, {0x705a,0x0,0}, {0x705b,0x0,0}, {0x705c,0x0,0}, {0x705d,0x0,0}, {0x705e,0x0,0}, {0x705f,0x0,0}, {0x7060,0x0,0}, {0x7061,0x0,0}, {0x7062,0x0,0}, {0x7063,0x0,0}, {0x7064,0x0,0}, {0x7065,0x0,0}, {0x7066,0x0,0}, {0x7067,0x0,0}, {0x7068,0x0,0}, {0x7069,0x0,0}, {0x706a,0x0,0}, {0x706b,0x0,0}, {0x706c,0x0,0}, {0x706d,0x0,0}, {0x706e,0x0,0}, {0x706f,0x0,0}, {0x7070,0x0,0}, {0x7071,0x0,0}, {0x7072,0x0,0}, {0x7073,0x0,0}, {0x7074,0x0,0}, {0x7075,0x0,0}, {0x7076,0x0,0}, {0x7077,0x0,0}, {0x7078,0x0,0}, {0x7079,0x0,0}, {0x707a,0x0,0}, {0x707b,0x0,0}, {0x707c,0x0,0}, {0x707d,0x0,0}, {0x707e,0x0,0}, {0x707f,0x0,0}, {0x7080,0x0,0}, {0x7081,0x0,0}, {0x7082,0x0,0}, {0x7083,0x0,0}, {0x7084,0x0,0}, {0x7085,0x0,0}, {0x7086,0x0,0}, {0x7087,0x0,0}, {0x7088,0x0,0}, {0x7089,0x0,0}, {0x708a,0x0,0}, {0x708b,0x0,0}, {0x708c,0x0,0}, {0x708d,0x0,0}, {0x708e,0x0,0}, {0x708f,0x0,0}, {0x7090,0x0,0}, {0x7091,0x0,0}, {0x7092,0x0,0}, {0x7093,0x0,0}, {0x7094,0x0,0}, {0x7095,0x0,0}, {0x7096,0x0,0}, {0x7097,0x0,0}, {0x7098,0x0,0}, {0x7099,0x0,0}, {0x709a,0x0,0}, {0x709b,0x0,0}, {0x709c,0x0,0}, {0x709d,0x0,0}, {0x709e,0x0,0}, {0x709f,0x0,0}, {0x70a0,0x0,0}, {0x70a1,0x0,0}, {0x70a2,0x0,0}, {0x70a3,0x0,0}, {0x70a4,0x0,0}, {0x70a5,0x0,0}, {0x70a6,0x0,0}, {0x70a7,0x0,0}, {0x70a8,0x0,0}, {0x70a9,0x0,0}, {0x70aa,0x0,0}, {0x70ab,0x0,0}, {0x70ac,0x0,0}, {0x70ad,0x0,0}, {0x70ae,0x0,0}, {0x70af,0x0,0}, {0x70b0,0x0,0}, {0x70b1,0x0,0}, {0x70b2,0x0,0}, {0x70b3,0x0,0}, {0x70b4,0x0,0}, {0x70b5,0x0,0}, {0x70b6,0x0,0}, {0x70b7,0x0,0}, {0x70b8,0x0,0}, {0x70b9,0x0,0}, {0x70ba,0x0,0}, {0x70bb,0x0,0}, {0x70bc,0x0,0}, {0x70bd,0x0,0}, {0x70be,0x0,0}, {0x70bf,0x0,0}, {0x70c0,0x0,0}, {0x70c1,0x0,0}, {0x70c2,0x0,0}, {0x70c3,0x0,0}, {0x70c4,0x0,0}, {0x70c5,0x0,0}, {0x70c6,0x0,0}, {0x70c7,0x0,0}, {0x70c8,0x0,0}, {0x70c9,0x0,0}, {0x70ca,0x0,0}, {0x70cb,0x0,0}, {0x70cc,0x0,0}, {0x70cd,0x0,0}, {0x70ce,0x0,0}, {0x70cf,0x0,0}, {0x70d0,0x0,0}, {0x70d1,0x0,0}, {0x70d2,0x0,0}, {0x70d3,0x0,0}, {0x70d4,0x0,0}, {0x70d5,0x0,0}, {0x70d6,0x0,0}, {0x70d7,0x0,0}, {0x70d8,0x0,0}, {0x70d9,0x0,0}, {0x70da,0x0,0}, {0x70db,0x0,0}, {0x70dc,0x0,0}, {0x70dd,0x0,0}, {0x70de,0x0,0}, {0x70df,0x0,0}, {0x70e0,0x0,0}, {0x70e1,0x0,0}, {0x70e2,0x0,0}, {0x70e3,0x0,0}, {0x70e4,0x0,0}, {0x70e5,0x0,0}, {0x70e6,0x0,0}, {0x70e7,0x0,0}, {0x70e8,0x0,0}, {0x70e9,0x0,0}, {0x70ea,0x0,0}, {0x70eb,0x0,0}, {0x70ec,0x0,0}, {0x70ed,0x0,0}, {0x70ee,0x0,0}, {0x70ef,0x0,0}, {0x70f0,0x0,0}, {0x70f1,0x0,0}, {0x70f2,0x0,0}, {0x70f3,0x0,0}, {0x70f4,0x0,0}, {0x70f5,0x0,0}, {0x70f6,0x0,0}, {0x70f7,0x0,0}, {0x70f8,0x0,0}, {0x70f9,0x0,0}, {0x70fa,0x0,0}, {0x70fb,0x0,0}, {0x70fc,0x0,0}, {0x70fd,0x0,0}, {0x70fe,0x0,0}, {0x70ff,0x0,0}, {0x7100,0x0,0}, {0x7101,0x0,0}, {0x7102,0x0,0}, {0x7103,0x0,0}, {0x7104,0x0,0}, {0x7105,0x0,0}, {0x7106,0x0,0}, {0x7107,0x0,0}, {0x7108,0x0,0}, {0x7109,0x0,0}, {0x710a,0x0,0}, {0x710b,0x0,0}, {0x710c,0x0,0}, {0x710d,0x0,0}, {0x710e,0x0,0}, {0x710f,0x0,0}, {0x7110,0x0,0}, {0x7111,0x0,0}, {0x7112,0x0,0}, {0x7113,0x0,0}, {0x7114,0x0,0}, {0x7115,0x0,0}, {0x7116,0x0,0}, {0x7117,0x0,0}, {0x7118,0x0,0}, {0x7119,0x0,0}, {0x711a,0x0,0}, {0x711b,0x0,0}, {0x711c,0x0,0}, {0x711d,0x0,0}, {0x711e,0x0,0}, {0x711f,0x0,0}, {0x7120,0x0,0}, {0x7121,0x0,0}, {0x7122,0x0,0}, {0x7123,0x0,0}, {0x7124,0x0,0}, {0x7125,0x0,0}, {0x7126,0x0,0}, {0x7127,0x0,0}, {0x7128,0x0,0}, {0x7129,0x0,0}, {0x712a,0x0,0}, {0x712b,0x0,0}, {0x712c,0x0,0}, {0x712d,0x0,0}, {0x712e,0x0,0}, {0x712f,0x0,0}, {0x7130,0x0,0}, {0x7131,0x0,0}, {0x7132,0x0,0}, {0x501a,0x10,0}, {0x501b,0xd,0}, {0x501c,0x10,0}, {0x501d,0x13,0}, {0x5000,0x96,0}, {0x5800,0x14,0}, {0x5801,0xd,0}, {0x5802,0xa,0}, {0x5803,0xa,0}, {0x5804,0xd,0}, {0x5805,0x13,0}, {0x5806,0xa,0}, {0x5807,0x5,0}, {0x5808,0x3,0}, {0x5809,0x3,0}, {0x580a,0x5,0}, {0x580b,0x9,0}, {0x580c,0x6,0}, {0x580d,0x2,0}, {0x580e,0x0,0}, {0x580f,0x0,0}, {0x5810,0x2,0}, {0x5811,0x5,0}, {0x5812,0x6,0}, {0x5813,0x2,0}, {0x5814,0x0,0}, {0x5815,0x0,0}, {0x5816,0x2,0}, {0x5817,0x5,0}, {0x5818,0xb,0}, {0x5819,0x6,0}, {0x581a,0x3,0}, {0x581b,0x3,0}, {0x581c,0x5,0}, {0x581d,0xa,0}, {0x581e,0x16,0}, {0x581f,0xf,0}, {0x5820,0xb,0}, {0x5821,0xb,0}, {0x5822,0xf,0}, {0x5823,0x15,0}, {0x5824,0x32,0}, {0x5825,0x23,0}, {0x5826,0x23,0}, {0x5827,0x23,0}, {0x5828,0x22,0}, {0x5829,0x21,0}, {0x582a,0x21,0}, {0x582b,0x22,0}, {0x582c,0x21,0},{0x582d,0x11,0}, {0x582e,0x22,0}, {0x582f,0x31,0}, {0x5830,0x41,0}, {0x5831,0x31,0}, {0x5832,0x1,0}, {0x5833,0x21,0}, {0x5834,0x21,0}, {0x5835,0x21,0}, {0x5836,0x11,0}, {0x5837,0x11,0}, {0x5838,0x22,0}, {0x5839,0x22,0}, {0x583a,0x12,0}, {0x583b,0x22,0}, {0x583c,0x22,0}, {0x583d,0xdf,0}, +}; + diff --git a/selfdrive/visiond/snpemodel.cc b/selfdrive/visiond/snpemodel.cc new file mode 100644 index 00000000000000..ae7b7f10a1531e --- /dev/null +++ b/selfdrive/visiond/snpemodel.cc @@ -0,0 +1,94 @@ +#include "snpemodel.h" + +void PrintErrorStringAndExit() { + const char* const errStr = zdl::DlSystem::getLastErrorString(); + std::cerr << zdl::DlSystem::getLastErrorString() << std::endl; + std::exit(EXIT_FAILURE); +} + +SNPEModel::SNPEModel(const uint8_t *model_data, const size_t model_size, float *output, size_t output_size) { + assert(zdl::SNPE::SNPEFactory::isRuntimeAvailable(zdl::DlSystem::Runtime_t::GPU)); + + // load model + std::unique_ptr container = zdl::DlContainer::IDlContainer::open(model_data, model_size); + if (!container) { PrintErrorStringAndExit(); } + printf("loaded model with size: %d\n", model_size); + + // create model runner + zdl::SNPE::SNPEBuilder snpeBuilder(container.get()); + while (!snpe) { + snpe = snpeBuilder.setOutputLayers({}) + .setRuntimeProcessor(zdl::DlSystem::Runtime_t::GPU) + .setUseUserSuppliedBuffers(true) + .setPerformanceProfile(zdl::DlSystem::PerformanceProfile_t::HIGH_PERFORMANCE) + .build(); + if (!snpe) std::cerr << zdl::DlSystem::getLastErrorString() << std::endl; + } + + // get input and output names + const auto &strListi_opt = snpe->getInputTensorNames(); + if (!strListi_opt) throw std::runtime_error("Error obtaining Input tensor names"); + const auto &strListi = *strListi_opt; + //assert(strListi.size() == 1); + const char *input_tensor_name = strListi.at(0); + + const auto &strListo_opt = snpe->getOutputTensorNames(); + if (!strListo_opt) throw std::runtime_error("Error obtaining Output tensor names"); + const auto &strListo = *strListo_opt; + assert(strListo.size() == 1); + const char *output_tensor_name = strListo.at(0); + + printf("model: %s -> %s\n", input_tensor_name, output_tensor_name); + + zdl::DlSystem::UserBufferEncodingFloat userBufferEncodingFloat; + zdl::DlSystem::IUserBufferFactory& ubFactory = zdl::SNPE::SNPEFactory::getUserBufferFactory(); + + // create input buffer + { + const auto &inputDims_opt = snpe->getInputDimensions(input_tensor_name); + const zdl::DlSystem::TensorShape& bufferShape = *inputDims_opt; + std::vector strides(bufferShape.rank()); + strides[strides.size() - 1] = sizeof(float); + size_t product = 1; + for (size_t i = 0; i < bufferShape.rank(); i++) product *= bufferShape[i]; + size_t stride = strides[strides.size() - 1]; + for (size_t i = bufferShape.rank() - 1; i > 0; i--) { + stride *= bufferShape[i]; + strides[i-1] = stride; + } + printf("input product is %u\n", product); + inputBuffer = ubFactory.createUserBuffer(NULL, product*sizeof(float), strides, &userBufferEncodingFloat); + + inputMap.add(input_tensor_name, inputBuffer.get()); + } + + // create output buffer + { + std::vector outputStrides = {output_size * sizeof(float), sizeof(float)}; + outputBuffer = ubFactory.createUserBuffer(output, output_size * sizeof(float), outputStrides, &userBufferEncodingFloat); + outputMap.add(output_tensor_name, outputBuffer.get()); + } +} + +void SNPEModel::addRecurrent(float *state, int state_size) { + // get input and output names + const auto &strListi_opt = snpe->getInputTensorNames(); + if (!strListi_opt) throw std::runtime_error("Error obtaining Input tensor names"); + const auto &strListi = *strListi_opt; + const char *input_tensor_name = strListi.at(1); + printf("adding recurrent: %s\n", input_tensor_name); + + zdl::DlSystem::UserBufferEncodingFloat userBufferEncodingFloat; + zdl::DlSystem::IUserBufferFactory& ubFactory = zdl::SNPE::SNPEFactory::getUserBufferFactory(); + std::vector recurrentStrides = {state_size * sizeof(float), sizeof(float)}; + recurrentBuffer = ubFactory.createUserBuffer(state, state_size * sizeof(float), recurrentStrides, &userBufferEncodingFloat); + inputMap.add(input_tensor_name, recurrentBuffer.get()); +} + +void SNPEModel::execute(float *net_input_buf) { + assert(inputBuffer->setBufferAddress(net_input_buf)); + if (!snpe->execute(inputMap, outputMap)) { + PrintErrorStringAndExit(); + } +} + diff --git a/selfdrive/visiond/snpemodel.h b/selfdrive/visiond/snpemodel.h new file mode 100644 index 00000000000000..a7fc6083db3541 --- /dev/null +++ b/selfdrive/visiond/snpemodel.h @@ -0,0 +1,37 @@ +#ifndef SNPEMODEL_H +#define SNPEMODEL_H + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +class SNPEModel { +public: + SNPEModel(const uint8_t *model_data, const size_t model_size, float *output, size_t output_size); + void addRecurrent(float *state, int state_size); + void execute(float *net_input_buf); +private: + // snpe model stuff + std::unique_ptr snpe; + + // snpe input stuff + zdl::DlSystem::UserBufferMap inputMap; + std::unique_ptr inputBuffer; + + // snpe output stuff + zdl::DlSystem::UserBufferMap outputMap; + std::unique_ptr outputBuffer; + float *output; + + // recurrent + std::unique_ptr recurrentBuffer; +}; + +#endif + diff --git a/selfdrive/visiond/transform.c b/selfdrive/visiond/transform.c new file mode 100644 index 00000000000000..5f3d7ad5a11c95 --- /dev/null +++ b/selfdrive/visiond/transform.c @@ -0,0 +1,149 @@ +#include +#include + +#include "clutil.h" + +#include "transform.h" + +void transform_init(Transform* s, cl_context ctx, cl_device_id device_id) { + int err = 0; + memset(s, 0, sizeof(*s)); + + cl_program prg = CLU_LOAD_FROM_FILE(ctx, device_id, "transform.cl", ""); + + s->krnl = clCreateKernel(prg, "warpPerspective", &err); + assert(err == 0); + + // done with this + err = clReleaseProgram(prg); + assert(err == 0); + + s->m_y_cl = clCreateBuffer(ctx, CL_MEM_READ_WRITE, 3*3*sizeof(float), NULL, &err); + assert(err == 0); + + s->m_uv_cl = clCreateBuffer(ctx, CL_MEM_READ_WRITE, 3*3*sizeof(float), NULL, &err); + assert(err == 0); +} + +void transform_destroy(Transform* s) { + int err = 0; + + err = clReleaseMemObject(s->m_y_cl); + assert(err == 0); + err = clReleaseMemObject(s->m_uv_cl); + assert(err == 0); + + err = clReleaseKernel(s->krnl); + assert(err == 0); +} + +void transform_queue(Transform* s, + cl_command_queue q, + cl_mem in_yuv, int in_width, int in_height, + cl_mem out_y, cl_mem out_u, cl_mem out_v, + int out_width, int out_height, + mat3 projection) { + int err = 0; + const int zero = 0; + + // sampled using pixel center origin + // (because thats how fastcv and opencv does it) + + mat3 projection_y = projection; + + // in and out uv is half the size of y. + mat3 projection_uv = transform_scale_buffer(projection, 0.5); + + err = clEnqueueWriteBuffer(q, s->m_y_cl, CL_TRUE, 0, 3*3*sizeof(float), (void*)projection_y.v, 0, NULL, NULL); + assert(err == 0); + err = clEnqueueWriteBuffer(q, s->m_uv_cl, CL_TRUE, 0, 3*3*sizeof(float), (void*)projection_uv.v, 0, NULL, NULL); + assert(err == 0); + + const int in_y_width = in_width; + const int in_y_height = in_height; + const int in_uv_width = in_width/2; + const int in_uv_height = in_height/2; + const int in_y_offset = 0; + const int in_u_offset = in_y_offset + in_y_width*in_y_height; + const int in_v_offset = in_u_offset + in_uv_width*in_uv_height; + + const int out_y_width = out_width; + const int out_y_height = out_height; + const int out_uv_width = out_width/2; + const int out_uv_height = out_height/2; + + err = clSetKernelArg(s->krnl, 0, sizeof(cl_mem), &in_yuv); + assert(err == 0); + + err = clSetKernelArg(s->krnl, 1, sizeof(cl_int), &in_y_width); + assert(err == 0); + err = clSetKernelArg(s->krnl, 2, sizeof(cl_int), &in_y_offset); + assert(err == 0); + err = clSetKernelArg(s->krnl, 3, sizeof(cl_int), &in_y_height); + assert(err == 0); + err = clSetKernelArg(s->krnl, 4, sizeof(cl_int), &in_y_width); + assert(err == 0); + + err = clSetKernelArg(s->krnl, 5, sizeof(cl_mem), &out_y); + assert(err == 0); + + err = clSetKernelArg(s->krnl, 6, sizeof(cl_int), &out_y_width); + assert(err == 0); + err = clSetKernelArg(s->krnl, 7, sizeof(cl_int), &zero); + assert(err == 0); + err = clSetKernelArg(s->krnl, 8, sizeof(cl_int), &out_y_height); + assert(err == 0); + err = clSetKernelArg(s->krnl, 9, sizeof(cl_int), &out_y_width); + assert(err == 0); + + err = clSetKernelArg(s->krnl, 10, sizeof(cl_mem), &s->m_y_cl); + assert(err == 0); + + const size_t work_size_y[2] = {out_y_width, out_y_height}; + + err = clEnqueueNDRangeKernel(q, s->krnl, 2, NULL, + (const size_t*)&work_size_y, NULL, 0, 0, NULL); + assert(err == 0); + + + const size_t work_size_uv[2] = {out_uv_width, out_uv_height}; + + err = clSetKernelArg(s->krnl, 1, sizeof(cl_int), &in_uv_width); + assert(err == 0); + err = clSetKernelArg(s->krnl, 2, sizeof(cl_int), &in_u_offset); + assert(err == 0); + err = clSetKernelArg(s->krnl, 3, sizeof(cl_int), &in_uv_height); + assert(err == 0); + err = clSetKernelArg(s->krnl, 4, sizeof(cl_int), &in_uv_width); + assert(err == 0); + + err = clSetKernelArg(s->krnl, 5, sizeof(cl_mem), &out_u); + assert(err == 0); + + err = clSetKernelArg(s->krnl, 6, sizeof(cl_int), &out_uv_width); + assert(err == 0); + err = clSetKernelArg(s->krnl, 7, sizeof(cl_int), &zero); + assert(err == 0); + err = clSetKernelArg(s->krnl, 8, sizeof(cl_int), &out_uv_height); + assert(err == 0); + err = clSetKernelArg(s->krnl, 9, sizeof(cl_int), &out_uv_width); + assert(err == 0); + + err = clSetKernelArg(s->krnl, 10, sizeof(cl_mem), &s->m_uv_cl); + assert(err == 0); + + err = clEnqueueNDRangeKernel(q, s->krnl, 2, NULL, + (const size_t*)&work_size_uv, NULL, 0, 0, NULL); + assert(err == 0); + + + err = clSetKernelArg(s->krnl, 2, sizeof(cl_int), &in_v_offset); + assert(err == 0); + err = clSetKernelArg(s->krnl, 5, sizeof(cl_mem), &out_v); + assert(err == 0); + + + err = clEnqueueNDRangeKernel(q, s->krnl, 2, NULL, + (const size_t*)&work_size_uv, NULL, 0, 0, NULL); + assert(err == 0); +} diff --git a/selfdrive/visiond/transform.cl b/selfdrive/visiond/transform.cl new file mode 100644 index 00000000000000..8ad186935114c9 --- /dev/null +++ b/selfdrive/visiond/transform.cl @@ -0,0 +1,54 @@ +#define INTER_BITS 5 +#define INTER_TAB_SIZE (1 << INTER_BITS) +#define INTER_SCALE 1.f / INTER_TAB_SIZE + +#define INTER_REMAP_COEF_BITS 15 +#define INTER_REMAP_COEF_SCALE (1 << INTER_REMAP_COEF_BITS) + +__kernel void warpPerspective(__global const uchar * src, + int src_step, int src_offset, int src_rows, int src_cols, + __global uchar * dst, + int dst_step, int dst_offset, int dst_rows, int dst_cols, + __constant float * M) +{ + int dx = get_global_id(0); + int dy = get_global_id(1); + + if (dx < dst_cols && dy < dst_rows) + { + float X0 = M[0] * dx + M[1] * dy + M[2]; + float Y0 = M[3] * dx + M[4] * dy + M[5]; + float W = M[6] * dx + M[7] * dy + M[8]; + W = W != 0.0f ? INTER_TAB_SIZE / W : 0.0f; + int X = rint(X0 * W), Y = rint(Y0 * W); + + short sx = convert_short_sat(X >> INTER_BITS); + short sy = convert_short_sat(Y >> INTER_BITS); + short ay = (short)(Y & (INTER_TAB_SIZE - 1)); + short ax = (short)(X & (INTER_TAB_SIZE - 1)); + + int v0 = (sx >= 0 && sx < src_cols && sy >= 0 && sy < src_rows) ? + convert_int(src[mad24(sy, src_step, src_offset + sx)]) : 0; + int v1 = (sx+1 >= 0 && sx+1 < src_cols && sy >= 0 && sy < src_rows) ? + convert_int(src[mad24(sy, src_step, src_offset + (sx+1))]) : 0; + int v2 = (sx >= 0 && sx < src_cols && sy+1 >= 0 && sy+1 < src_rows) ? + convert_int(src[mad24(sy+1, src_step, src_offset + sx)]) : 0; + int v3 = (sx+1 >= 0 && sx+1 < src_cols && sy+1 >= 0 && sy+1 < src_rows) ? + convert_int(src[mad24(sy+1, src_step, src_offset + (sx+1))]) : 0; + + float taby = 1.f/INTER_TAB_SIZE*ay; + float tabx = 1.f/INTER_TAB_SIZE*ax; + + int dst_index = mad24(dy, dst_step, dst_offset + dx); + + int itab0 = convert_short_sat_rte( (1.0f-taby)*(1.0f-tabx) * INTER_REMAP_COEF_SCALE ); + int itab1 = convert_short_sat_rte( (1.0f-taby)*tabx * INTER_REMAP_COEF_SCALE ); + int itab2 = convert_short_sat_rte( taby*(1.0f-tabx) * INTER_REMAP_COEF_SCALE ); + int itab3 = convert_short_sat_rte( taby*tabx * INTER_REMAP_COEF_SCALE ); + + int val = v0 * itab0 + v1 * itab1 + v2 * itab2 + v3 * itab3; + + uchar pix = convert_uchar_sat((val + (1 << (INTER_REMAP_COEF_BITS-1))) >> INTER_REMAP_COEF_BITS); + dst[dst_index] = pix; + } +} diff --git a/selfdrive/visiond/transform.h b/selfdrive/visiond/transform.h new file mode 100644 index 00000000000000..3854be9da62db6 --- /dev/null +++ b/selfdrive/visiond/transform.h @@ -0,0 +1,38 @@ +#ifndef TRANSFORM_H +#define TRANSFORM_H + +#include +#include + +#ifdef __APPLE__ +#include +#else +#include +#endif + +#include "common/mat.h" + +#ifdef __cplusplus +extern "C" { +#endif + +typedef struct { + cl_kernel krnl; + cl_mem m_y_cl, m_uv_cl; +} Transform; + +void transform_init(Transform* s, cl_context ctx, cl_device_id device_id); + +void transform_destroy(Transform* transform); + +void transform_queue(Transform* s, cl_command_queue q, + cl_mem yuv, int in_width, int in_height, + cl_mem out_y, cl_mem out_u, cl_mem out_v, + int out_width, int out_height, + mat3 projection); + +#ifdef __cplusplus +} +#endif + +#endif // TRANSFORM_H diff --git a/selfdrive/visiond/visiond-wiggly b/selfdrive/visiond/visiond-wiggly new file mode 100644 index 00000000000000..b26fbdeda38674 Binary files /dev/null and b/selfdrive/visiond/visiond-wiggly differ diff --git a/selfdrive/visiond/visiond.056 b/selfdrive/visiond/visiond.056 new file mode 100755 index 00000000000000..40259afc55c789 Binary files /dev/null and b/selfdrive/visiond/visiond.056 differ diff --git a/selfdrive/visiond/visiond.057 b/selfdrive/visiond/visiond.057 new file mode 100644 index 00000000000000..caf5de38ae68a7 Binary files /dev/null and b/selfdrive/visiond/visiond.057 differ diff --git a/selfdrive/visiond/visiond.cc b/selfdrive/visiond/visiond.cc new file mode 100644 index 00000000000000..a64eaa054c1965 --- /dev/null +++ b/selfdrive/visiond/visiond.cc @@ -0,0 +1,1340 @@ +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include + +#ifdef __APPLE__ +#include +#else +#include +#endif + +#include +#include +#include + +#include "common/version.h" +#include "common/util.h" +#include "common/timing.h" +#include "common/mat.h" +#include "common/swaglog.h" +#include "common/visionipc.h" +#include "common/visionbuf.h" +#include "common/visionimg.h" +#include "common/buffering.h" + +#include "clutil.h" +#include "bufs.h" + +#ifdef QCOM +#include "camera_qcom.h" +#else +#include "camera_fake.h" +#endif + +#include "model.h" +#include "monitoring.h" + +#include "cereal/gen/cpp/log.capnp.h" + +#define UI_BUF_COUNT 4 + +//#define DUMP_RGB + +//#define DEBUG_DRIVER_MONITOR + +// send net input on port 9000 +//#define SEND_NET_INPUT + +#define YUV_COUNT 40 +#define MAX_CLIENTS 5 + +#ifdef __APPLE__ +typedef void (*sighandler_t) (int); +#endif + +extern "C" { +volatile int do_exit = 0; +} + +namespace { + +struct VisionState; + +struct VisionClientState { + VisionState *s; + int fd; + pthread_t thread_handle; + bool running; +}; + +struct VisionClientStreamState { + bool subscribed; + int bufs_outstanding; + bool tb; + TBuffer* tbuffer; + PoolQueue* queue; +}; + +struct VisionState { + + int frame_width, frame_height; + int frame_stride; + int frame_size; + + int ion_fd; + + // cl state + cl_device_id device_id; + cl_context context; + + cl_program prg_debayer_rear; + cl_program prg_debayer_front; + cl_kernel krnl_debayer_rear; + cl_kernel krnl_debayer_front; + + // processing + TBuffer ui_tb; + TBuffer ui_front_tb; + + mat3 yuv_transform; + TBuffer *yuv_tb; + + // TODO: refactor for both cameras? + Pool yuv_pool; + VisionBuf yuv_ion[YUV_COUNT]; + cl_mem yuv_cl[YUV_COUNT]; + YUVBuf yuv_bufs[YUV_COUNT]; + FrameMetadata yuv_metas[YUV_COUNT]; + size_t yuv_buf_size; + int yuv_width, yuv_height; + + // for front camera recording + Pool yuv_front_pool; + VisionBuf yuv_front_ion[YUV_COUNT]; + cl_mem yuv_front_cl[YUV_COUNT]; + YUVBuf yuv_front_bufs[YUV_COUNT]; + FrameMetadata yuv_front_metas[YUV_COUNT]; + size_t yuv_front_buf_size; + int yuv_front_width, yuv_front_height; + + size_t rgb_buf_size; + int rgb_width, rgb_height, rgb_stride; + VisionBuf rgb_bufs[UI_BUF_COUNT]; + cl_mem rgb_bufs_cl[UI_BUF_COUNT]; + + size_t rgb_front_buf_size; + int rgb_front_width, rgb_front_height, rgb_front_stride; + VisionBuf rgb_front_bufs[UI_BUF_COUNT]; + cl_mem rgb_front_bufs_cl[UI_BUF_COUNT]; + + ModelState model; + ModelData model_bufs[UI_BUF_COUNT]; + + MonitoringState monitoring; + zsock_t *monitoring_sock; + void* monitoring_sock_raw; + + // Protected by transform_lock. + bool run_model; + mat3 cur_transform; + pthread_mutex_t transform_lock; + + cl_mem camera_bufs_cl[FRAME_BUF_COUNT]; + VisionBuf camera_bufs[FRAME_BUF_COUNT]; + VisionBuf focus_bufs[FRAME_BUF_COUNT]; + VisionBuf stats_bufs[FRAME_BUF_COUNT]; + + cl_mem front_camera_bufs_cl[FRAME_BUF_COUNT]; + VisionBuf front_camera_bufs[FRAME_BUF_COUNT]; + + DualCameraState cameras; + + zsock_t *terminate_pub; + zsock_t *recorder_sock; + void* recorder_sock_raw; + + pthread_mutex_t clients_lock; + VisionClientState clients[MAX_CLIENTS]; + +}; + +void hexdump(uint8_t *d, int l) { + for (int i = 0; i < l; i++) { + if (i%0x10 == 0 && i != 0) printf("\n"); + printf("%02X ", d[i]); + } + printf("\n"); +} + +int mkpath(char* file_path, mode_t mode) { + assert(file_path && *file_path); + char* p; + for (p=strchr(file_path+1, '/'); p; p=strchr(p+1, '/')) { + *p='\0'; + if (mkdir(file_path, mode)==-1) { + if (errno!=EEXIST) { *p='/'; return -1; } + } + *p='/'; + } + return 0; +} + +////////// cl stuff + +cl_program build_debayer_program(VisionState *s, + int frame_width, int frame_height, int frame_stride, + int rgb_width, int rgb_height, int rgb_stride, + int bayer_flip, int hdr) { + assert(rgb_width == frame_width/2); + assert(rgb_height == frame_height/2); + + char args[4096]; + snprintf(args, sizeof(args), + "-cl-fast-relaxed-math -cl-denorms-are-zero " + "-DFRAME_WIDTH=%d -DFRAME_HEIGHT=%d -DFRAME_STRIDE=%d " + "-DRGB_WIDTH=%d -DRGB_HEIGHT=%d -DRGB_STRIDE=%d " + "-DBAYER_FLIP=%d -DHDR=%d", + frame_width, frame_height, frame_stride, + rgb_width, rgb_height, rgb_stride, + bayer_flip, hdr); + return CLU_LOAD_FROM_FILE(s->context, s->device_id, "debayer.cl", args); +} + +void cl_init(VisionState *s) { + int err; + cl_platform_id platform_id = NULL; + cl_uint num_devices; + cl_uint num_platforms; + + err = clGetPlatformIDs(1, &platform_id, &num_platforms); + assert(err == 0); + err = clGetDeviceIDs(platform_id, CL_DEVICE_TYPE_DEFAULT, 1, + &s->device_id, &num_devices); + assert(err == 0); + + cl_print_info(platform_id, s->device_id); + printf("\n"); + + s->context = clCreateContext(NULL, 1, &s->device_id, NULL, NULL, &err); + assert(err == 0); +} + +void cl_free(VisionState *s) { + int err; + + err = clReleaseContext(s->context); + assert(err == 0); +} + +////////// + +#if 0 +// from libadreno_utils.so +extern "C" void compute_aligned_width_and_height(int width, + int height, + int bpp, + int tile_mode, + int raster_mode, + int padding_threshold, + int *aligned_w, + int *aligned_h); + +// TODO: move to visionbuf +void alloc_rgb888_bufs_cl(cl_device_id device_id, cl_context ctx, + int width, int height, int count, + int *out_stride, size_t *out_size, + VisionBuf *out_bufs, cl_mem *out_cl) { + + int aligned_w = 0, aligned_h = 0; +#ifdef QCOM + compute_aligned_width_and_height(ALIGN(width, 32), ALIGN(height, 32), 3, 0, 0, 512, &aligned_w, &aligned_h); +#else + aligned_w = width; aligned_h = height; +#endif + + int stride = aligned_w * 3; + size_t size = aligned_w * aligned_h * 3; + + for (int i=0; icamera_bufs[i] = visionbuf_allocate_cl(s->frame_size, s->device_id, s->context, + &s->camera_bufs_cl[i]); + // TODO: make lengths correct + s->focus_bufs[i] = visionbuf_allocate(0xb80); + s->stats_bufs[i] = visionbuf_allocate(0xb80); + } + + for (int i=0; ifront_camera_bufs[i] = visionbuf_allocate_cl(s->cameras.front.frame_size, + s->device_id, s->context, + &s->front_camera_bufs_cl[i]); + } + + // processing buffers + if (s->cameras.rear.ci.bayer) { + s->rgb_width = s->frame_width/2; + s->rgb_height = s->frame_height/2; + } else { + s->rgb_width = s->frame_width; + s->rgb_height = s->frame_height; + } + + for (int i=0; irgb_width, s->rgb_height, &s->rgb_bufs[i]); + s->rgb_bufs_cl[i] = visionbuf_to_cl(&s->rgb_bufs[i], s->device_id, s->context); + if (i == 0){ + s->rgb_stride = img.stride; + s->rgb_buf_size = img.size; + } + } + tbuffer_init(&s->ui_tb, UI_BUF_COUNT, "rgb"); + + assert(s->cameras.front.ci.bayer); + s->rgb_front_width = s->cameras.front.ci.frame_width/2; + s->rgb_front_height = s->cameras.front.ci.frame_height/2; + + for (int i=0; irgb_front_width, s->rgb_front_height, &s->rgb_front_bufs[i]); + s->rgb_front_bufs_cl[i] = visionbuf_to_cl(&s->rgb_front_bufs[i], s->device_id, s->context); + if (i == 0){ + s->rgb_front_stride = img.stride; + s->rgb_front_buf_size = img.size; + } + } + tbuffer_init(&s->ui_front_tb, UI_BUF_COUNT, "frontrgb"); + + // yuv back for recording and orbd + pool_init(&s->yuv_pool, YUV_COUNT); + + s->yuv_tb = pool_get_tbuffer(&s->yuv_pool); //only for visionserver... + + s->yuv_width = s->rgb_width; + s->yuv_height = s->rgb_height; + s->yuv_buf_size = s->rgb_width * s->rgb_height * 3 / 2; + + for (int i=0; iyuv_ion[i] = visionbuf_allocate_cl(s->yuv_buf_size, s->device_id, s->context, &s->yuv_cl[i]); + s->yuv_bufs[i].y = (uint8_t*)s->yuv_ion[i].addr; + s->yuv_bufs[i].u = s->yuv_bufs[i].y + (s->yuv_width * s->yuv_height); + s->yuv_bufs[i].v = s->yuv_bufs[i].u + (s->yuv_width/2 * s->yuv_height/2); + } + + // yuv front for recording + pool_init(&s->yuv_front_pool, YUV_COUNT); + + s->yuv_front_width = s->rgb_front_width; + s->yuv_front_height = s->rgb_front_height; + s->yuv_front_buf_size = s->rgb_front_width * s->rgb_front_height * 3 / 2; + + for (int i=0; iyuv_front_ion[i] = visionbuf_allocate_cl(s->yuv_front_buf_size, s->device_id, s->context, &s->yuv_front_cl[i]); + s->yuv_front_bufs[i].y = (uint8_t*)s->yuv_front_ion[i].addr; + s->yuv_front_bufs[i].u = s->yuv_front_bufs[i].y + (s->yuv_front_width * s->yuv_front_height); + s->yuv_front_bufs[i].v = s->yuv_front_bufs[i].u + (s->yuv_front_width/2 * s->yuv_front_height/2); + } + + if (s->cameras.rear.ci.bayer) { + // debayering does a 2x downscale + s->yuv_transform = transform_scale_buffer(s->cameras.rear.transform, 0.5); + } else { + s->yuv_transform = s->cameras.rear.transform; + } + + // build all the camera debayer programs + for (int i=0; iprg_debayer_rear = build_debayer_program(s, s->cameras.rear.ci.frame_width, s->cameras.rear.ci.frame_height, + s->cameras.rear.ci.frame_stride, + s->rgb_width, s->rgb_height, s->rgb_stride, + s->cameras.rear.ci.bayer_flip, s->cameras.rear.ci.hdr); + + s->prg_debayer_front = build_debayer_program(s, s->cameras.front.ci.frame_width, s->cameras.front.ci.frame_height, + s->cameras.front.ci.frame_stride, + s->rgb_front_width, s->rgb_front_height, s->rgb_front_stride, + s->cameras.front.ci.bayer_flip, s->cameras.front.ci.hdr); + + s->krnl_debayer_rear = clCreateKernel(s->prg_debayer_rear, "debayer10", &err); + assert(err == 0); + s->krnl_debayer_front = clCreateKernel(s->prg_debayer_front, "debayer10", &err); + assert(err == 0); +} + +void free_buffers(VisionState *s) { + // free bufs + for (int i=0; icamera_bufs[i]); + visionbuf_free(&s->focus_bufs[i]); + visionbuf_free(&s->stats_bufs[i]); + } + + for (int i=0; ifront_camera_bufs[i]); + } + + for (int i=0; irgb_bufs[i]); + } + + for (int i=0; irgb_front_bufs[i]); + } + + for (int i=0; iyuv_ion[i]); + } +} + +void* visionserver_client_thread(void* arg) { + int err; + VisionClientState *client = (VisionClientState*)arg; + VisionState *s = client->s; + int fd = client->fd; + + set_thread_name("clientthread"); + + zsock_t *terminate = zsock_new_sub(">inproc://terminate", ""); + assert(terminate); + void* terminate_raw = zsock_resolve(terminate); + + VisionClientStreamState streams[VISION_STREAM_MAX] = {{0}}; + + LOG("client start fd %d\n", fd); + + while (true) { + zmq_pollitem_t polls[2+VISION_STREAM_MAX] = {{0}}; + polls[0].socket = terminate_raw; + polls[0].events = ZMQ_POLLIN; + polls[1].fd = fd; + polls[1].events = ZMQ_POLLIN; + + int poll_to_stream[2+VISION_STREAM_MAX] = {0}; + int num_polls = 2; + for (int i=0; i= 2) { + continue; + } + if (streams[i].tb) { + polls[num_polls].fd = tbuffer_efd(streams[i].tbuffer); + } else { + polls[num_polls].fd = poolq_efd(streams[i].queue); + } + poll_to_stream[num_polls] = i; + num_polls++; + } + int ret = zmq_poll(polls, num_polls, -1); + if (ret < 0) { + LOGE("poll failed (%d)", ret); + break; + } + if (polls[0].revents) { + break; + } else if (polls[1].revents) { + VisionPacket p; + err = vipc_recv(fd, &p); + // printf("recv %d\n", p.type); + if (err <= 0) { + break; + } else if (p.type == VIPC_STREAM_SUBSCRIBE) { + VisionStreamType stream_type = p.d.stream_sub.type; + VisionPacket rep = { + .type = VIPC_STREAM_BUFS, + .d = { .stream_bufs = { .type = stream_type }, }, + }; + + VisionClientStreamState *stream = &streams[stream_type]; + stream->tb = p.d.stream_sub.tbuffer; + + VisionStreamBufs *stream_bufs = &rep.d.stream_bufs; + if (stream_type == VISION_STREAM_RGB_BACK) { + stream_bufs->width = s->rgb_width; + stream_bufs->height = s->rgb_height; + stream_bufs->stride = s->rgb_stride; + stream_bufs->buf_len = s->rgb_bufs[0].len; + rep.num_fds = UI_BUF_COUNT; + for (int i=0; irgb_bufs[i].fd; + } + if (stream->tb) { + stream->tbuffer = &s->ui_tb; + } else { + assert(false); + } + } else if (stream_type == VISION_STREAM_RGB_FRONT) { + stream_bufs->width = s->rgb_front_width; + stream_bufs->height = s->rgb_front_height; + stream_bufs->stride = s->rgb_front_stride; + stream_bufs->buf_len = s->rgb_front_bufs[0].len; + rep.num_fds = UI_BUF_COUNT; + for (int i=0; irgb_front_bufs[i].fd; + } + if (stream->tb) { + stream->tbuffer = &s->ui_front_tb; + } else { + assert(false); + } + } else if (stream_type == VISION_STREAM_YUV) { + stream_bufs->width = s->yuv_width; + stream_bufs->height = s->yuv_height; + stream_bufs->stride = s->yuv_width; + stream_bufs->buf_len = s->yuv_buf_size; + rep.num_fds = YUV_COUNT; + for (int i=0; iyuv_ion[i].fd; + } + if (stream->tb) { + stream->tbuffer = s->yuv_tb; + } else { + stream->queue = pool_get_queue(&s->yuv_pool); + } + } else if (stream_type == VISION_STREAM_YUV_FRONT) { + stream_bufs->width = s->yuv_front_width; + stream_bufs->height = s->yuv_front_height; + stream_bufs->stride = s->yuv_front_width; + stream_bufs->buf_len = s->yuv_front_buf_size; + rep.num_fds = YUV_COUNT; + for (int i=0; iyuv_front_ion[i].fd; + } + if (stream->tb) { + assert(false); + } else { + stream->queue = pool_get_queue(&s->yuv_front_pool); + } + } else { + assert(false); + } + + if (stream_type == VISION_STREAM_RGB_BACK || + stream_type == VISION_STREAM_RGB_FRONT) { + stream_bufs->buf_info.ui_info = (VisionUIInfo){ + .transformed_width = s->model.in.transformed_width, + .transformed_height = s->model.in.transformed_height, + }; + } + vipc_send(fd, &rep); + streams[stream_type].subscribed = true; + } else if (p.type == VIPC_STREAM_RELEASE) { + // printf("client release f %d %d\n", p.d.stream_rel.type, p.d.stream_rel.idx); + int si = p.d.stream_rel.type; + assert(si < VISION_STREAM_MAX); + if (streams[si].tb) { + tbuffer_release(streams[si].tbuffer, p.d.stream_rel.idx); + } else { + poolq_release(streams[si].queue, p.d.stream_rel.idx); + } + streams[p.d.stream_rel.type].bufs_outstanding--; + } else { + assert(false); + } + } else { + int stream_i = VISION_STREAM_MAX; + for (int i=2; iyuv_metas[idx].frame_id; + rep.d.stream_acq.extra.timestamp_eof = s->yuv_metas[idx].timestamp_eof; + } else if (stream_i == VISION_STREAM_YUV_FRONT) { + rep.d.stream_acq.extra.frame_id = s->yuv_front_metas[idx].frame_id; + rep.d.stream_acq.extra.timestamp_eof = s->yuv_front_metas[idx].timestamp_eof; + } + vipc_send(fd, &rep); + } + } + } + + LOG("client end fd %d\n", fd); + + for (int i=0; iclients_lock); + client->running = false; + pthread_mutex_unlock(&s->clients_lock); + + return NULL; +} + +void* visionserver_thread(void* arg) { + int err; + VisionState *s = (VisionState*)arg; + + set_thread_name("visionserver"); + + zsock_t *terminate = zsock_new_sub(">inproc://terminate", ""); + assert(terminate); + void* terminate_raw = zsock_resolve(terminate); + + unlink(VIPC_SOCKET_PATH); + + int sock = socket(AF_UNIX, SOCK_SEQPACKET, 0); + struct sockaddr_un addr = { + .sun_family = AF_UNIX, + .sun_path = VIPC_SOCKET_PATH, + }; + err = bind(sock, (struct sockaddr *)&addr, sizeof(addr)); + assert(err == 0); + + err = listen(sock, 3); + assert(err == 0); + + // printf("waiting\n"); + + while (!do_exit) { + zmq_pollitem_t polls[2] = {{0}}; + polls[0].socket = terminate_raw; + polls[0].events = ZMQ_POLLIN; + polls[1].fd = sock; + polls[1].events = ZMQ_POLLIN; + + int ret = zmq_poll(polls, ARRAYSIZE(polls), -1); + if (ret < 0) { + LOGE("poll failed (%d)", ret); + break; + } + if (polls[0].revents) { + break; + } else if (!polls[1].revents) { + continue; + } + + int fd = accept(sock, NULL, NULL); + assert(fd >= 0); + + pthread_mutex_lock(&s->clients_lock); + + int client_idx = 0; + for (; client_idx < MAX_CLIENTS; client_idx++) { + if (!s->clients[client_idx].running) break; + } + + if (client_idx >= MAX_CLIENTS) { + LOG("ignoring visionserver connection, max clients connected"); + close(fd); + + pthread_mutex_unlock(&s->clients_lock); + continue; + } + + VisionClientState *client = &s->clients[client_idx]; + client->s = s; + client->fd = fd; + client->running = true; + + err = pthread_create(&client->thread_handle, NULL, + visionserver_client_thread, client); + assert(err == 0); + + pthread_mutex_unlock(&s->clients_lock); + } + + for (int i=0; iclients_lock); + bool running = s->clients[i].running; + pthread_mutex_unlock(&s->clients_lock); + if (running) { + err = pthread_join(s->clients[i].thread_handle, NULL); + assert(err == 0); + } + } + + close(sock); + zsock_destroy(&terminate); + + return NULL; +} + +void* monitoring_thread(void *arg) { + int err; + VisionState *s = (VisionState*)arg; + + set_thread_name("monitoring"); + + TBuffer *tb = pool_get_tbuffer(&s->yuv_front_pool); + + cl_command_queue q = clCreateCommandQueue(s->context, s->device_id, 0, &err); + assert(err == 0); + + double last = 0; + while (!do_exit) { + int buf_idx = tbuffer_acquire(tb); + if (buf_idx < 0) { + break; + } + + FrameMetadata frame_data = s->yuv_front_metas[buf_idx]; + + // only process every frame + if ((frame_data.frame_id % 1) == 0) { + + double t1 = millis_since_boot(); + + MonitoringResult res = monitoring_eval_frame(&s->monitoring, q, + s->yuv_front_cl[buf_idx], s->yuv_front_width, s->yuv_front_height); + + // for (int i=0; i<6; i++) { + // printf("%f ", res.vs[i]); + // } + // printf("\n"); + + // send driver monitoring packet + { + capnp::MallocMessageBuilder msg; + cereal::Event::Builder event = msg.initRoot(); + event.setLogMonoTime(nanos_since_boot()); + + auto framed = event.initDriverMonitoring(); + framed.setFrameId(frame_data.frame_id); + + kj::ArrayPtr descriptor_vs(&res.vs[0], ARRAYSIZE(res.vs)); + framed.setDescriptor(descriptor_vs); + + framed.setStd(res.std); + + auto words = capnp::messageToFlatArray(msg); + auto bytes = words.asBytes(); + zmq_send(s->monitoring_sock_raw, bytes.begin(), bytes.size(), ZMQ_DONTWAIT); + } + + double t2 = millis_since_boot(); + + LOGD("monitoring process: %.2fms, from last %.2fms", t2-t1, t1-last); + last = t1; + } + + tbuffer_release(tb, buf_idx); + } + + return NULL; +} + +void* frontview_thread(void *arg) { + int err; + VisionState *s = (VisionState*)arg; + + set_thread_name("frontview"); + + cl_command_queue q = clCreateCommandQueue(s->context, s->device_id, 0, &err); + assert(err == 0); + + for (int cnt = 0; !do_exit; cnt++) { + int buf_idx = tbuffer_acquire(&s->cameras.front.camera_tb); + if (buf_idx < 0) { + break; + } + + int ui_idx = tbuffer_select(&s->ui_front_tb); + FrameMetadata frame_data = s->cameras.front.camera_bufs_metadata[buf_idx]; + + double t1 = millis_since_boot(); + + err = clSetKernelArg(s->krnl_debayer_front, 0, sizeof(cl_mem), &s->front_camera_bufs_cl[buf_idx]); + assert(err == 0); + err = clSetKernelArg(s->krnl_debayer_front, 1, sizeof(cl_mem), &s->rgb_front_bufs_cl[ui_idx]); + assert(err == 0); + float digital_gain = 1.0; + err = clSetKernelArg(s->krnl_debayer_front, 2, sizeof(float), &digital_gain); + assert(err == 0); + + cl_event debayer_event; + const size_t debayer_work_size = s->rgb_front_height; + const size_t debayer_local_work_size = 128; + err = clEnqueueNDRangeKernel(q, s->krnl_debayer_front, 1, NULL, + &debayer_work_size, &debayer_local_work_size, 0, 0, &debayer_event); + assert(err == 0); + clWaitForEvents(1, &debayer_event); + clReleaseEvent(debayer_event); + + tbuffer_release(&s->cameras.front.camera_tb, buf_idx); + + visionbuf_sync(&s->rgb_front_bufs[ui_idx], VISIONBUF_SYNC_FROM_DEVICE); + + // auto exposure + const uint8_t *bgr_front_ptr = (const uint8_t*)s->rgb_front_bufs[ui_idx].addr; +#ifndef DEBUG_DRIVER_MONITOR + if (cnt % 3 == 0) +#endif + { + + // for driver autoexposure, use bottom right corner + const int y_start = s->rgb_front_height / 3; + const int y_end = s->rgb_front_height; + const int x_start = s->rgb_front_width * 2 / 3; + const int x_end = s->rgb_front_width; + + uint32_t lum_binning[256] = {0,}; + for (int y = y_start; y < y_end; ++y) { + for (int x = x_start; x < x_end; x += 2) { // every 2nd col + const uint8_t *pix = &bgr_front_ptr[y * s->rgb_front_stride + x * 3]; + unsigned int lum = (unsigned int)pix[0] + pix[1] + pix[2]; +#ifdef DEBUG_DRIVER_MONITOR + uint8_t *pix_rw = (uint8_t *)pix; + + // set all the autoexposure pixels to pure green (pixel format is bgr) + pix_rw[0] = pix_rw[2] = 0; + pix_rw[1] = 0xff; +#endif + lum_binning[std::min(lum / 3, 255u)]++; + } + } + const unsigned int lum_total = (y_end - y_start) * (x_end - x_start)/2; + unsigned int lum_cur = 0; + int lum_med = 0; + for (lum_med=0; lum_med<256; lum_med++) { + lum_cur += lum_binning[lum_med]; + if (lum_cur >= lum_total / 2) { + break; + } + } + camera_autoexposure(&s->cameras.front, lum_med / 256.0); + } + + // push YUV buffer + int yuv_idx = pool_select(&s->yuv_front_pool); + s->yuv_front_metas[yuv_idx] = frame_data; + + uint8_t *bgr_ptr = (uint8_t*)s->rgb_front_bufs[ui_idx].addr; + libyuv::RGB24ToI420(bgr_ptr, s->rgb_front_stride, + s->yuv_front_bufs[yuv_idx].y, s->yuv_front_width, + s->yuv_front_bufs[yuv_idx].u, s->yuv_front_width/2, + s->yuv_front_bufs[yuv_idx].v, s->yuv_front_width/2, + s->rgb_front_width, s->rgb_front_height); + + s->yuv_front_metas[yuv_idx] = frame_data; + visionbuf_sync(&s->yuv_front_ion[yuv_idx], VISIONBUF_SYNC_TO_DEVICE); + + // no reference required cause we don't use this in visiond + //pool_acquire(&s->yuv_front_pool, yuv_idx); + pool_push(&s->yuv_front_pool, yuv_idx); + //pool_release(&s->yuv_front_pool, yuv_idx); + + /*FILE *f = fopen("/tmp/test2", "wb"); + printf("%d %d\n", s->rgb_front_height, s->rgb_front_stride); + fwrite(bgr_front_ptr, 1, s->rgb_front_stride * s->rgb_front_height, f); + fclose(f);*/ + + tbuffer_dispatch(&s->ui_front_tb, ui_idx); + + double t2 = millis_since_boot(); + + LOGD("front process: %.2fms", t2-t1); + } + + return NULL; +} + +void* processing_thread(void *arg) { + int err; + VisionState *s = (VisionState*)arg; + + set_thread_name("processing"); + + err = set_realtime_priority(1); + LOG("setpriority returns %d", err); + + // init cl stuff + const cl_queue_properties props[] = {0}; //CL_QUEUE_PRIORITY_KHR, CL_QUEUE_PRIORITY_HIGH_KHR, 0}; + cl_command_queue q = clCreateCommandQueueWithProperties(s->context, s->device_id, props, &err); + assert(err == 0); + + zsock_t *model_sock = zsock_new_pub("@tcp://*:8009"); + assert(model_sock); + void *model_sock_raw = zsock_resolve(model_sock); + +#ifdef SEND_NET_INPUT + zsock_t *img_sock = zsock_new_pub("@tcp://*:9000"); + assert(img_sock); + void *img_sock_raw = zsock_resolve(img_sock); +#else + void *img_sock_raw = NULL; +#endif + +#ifdef DUMP_RGB + FILE *dump_rgb_file = fopen("/sdcard/dump.rgb", "wb"); +#endif + + // init the net + LOG("processing start!"); + + for (int cnt = 0; !do_exit; cnt++) { + int buf_idx = tbuffer_acquire(&s->cameras.rear.camera_tb); + // int buf_idx = camera_acquire_buffer(s); + if (buf_idx < 0) { + break; + } + + double t1 = millis_since_boot(); + + FrameMetadata frame_data = s->cameras.rear.camera_bufs_metadata[buf_idx]; + uint32_t frame_id = frame_data.frame_id; + + if (frame_id == -1) { + LOGE("no frame data? wtf"); + tbuffer_release(&s->cameras.rear.camera_tb, buf_idx); + continue; + } + + int ui_idx = tbuffer_select(&s->ui_tb); + int rgb_idx = ui_idx; + // printf("idx %d\n", rgb_idx); + + /*FILE *f = fopen("/tmp/test_dump", "wb"); + fwrite(s->camera_bufs[buf_idx].addr, 1, s->camera_bufs[buf_idx].len, f); + fclose(f);*/ + + cl_event debayer_event; + if (s->cameras.rear.ci.bayer) { + err = clSetKernelArg(s->krnl_debayer_rear, 0, sizeof(cl_mem), &s->camera_bufs_cl[buf_idx]); + cl_check_error(err); + err = clSetKernelArg(s->krnl_debayer_rear, 1, sizeof(cl_mem), &s->rgb_bufs_cl[rgb_idx]); + cl_check_error(err); + err = clSetKernelArg(s->krnl_debayer_rear, 2, sizeof(float), &s->cameras.rear.digital_gain); + assert(err == 0); + + const size_t debayer_work_size = s->rgb_height; // doesn't divide evenly, is this okay? + const size_t debayer_local_work_size = 128; + err = clEnqueueNDRangeKernel(q, s->krnl_debayer_rear, 1, NULL, + &debayer_work_size, &debayer_local_work_size, 0, 0, &debayer_event); + assert(err == 0); + } else { + assert(s->rgb_buf_size >= s->frame_size); + assert(s->rgb_stride == s->frame_stride); + err = clEnqueueCopyBuffer(q, s->camera_bufs_cl[buf_idx], s->rgb_bufs_cl[rgb_idx], + 0, 0, s->rgb_buf_size, 0, 0, &debayer_event); + assert(err == 0); + } + + clWaitForEvents(1, &debayer_event); + clReleaseEvent(debayer_event); + + tbuffer_release(&s->cameras.rear.camera_tb, buf_idx); + + visionbuf_sync(&s->rgb_bufs[rgb_idx], VISIONBUF_SYNC_FROM_DEVICE); + + + double t2 = millis_since_boot(); + + uint8_t *bgr_ptr = (uint8_t*)s->rgb_bufs[rgb_idx].addr; + +#ifdef DUMP_RGB + if (cnt % 20 == 0) { + fwrite(bgr_ptr, s->rgb_buf_size, 1, dump_rgb_file); + } +#endif + + double yt1 = millis_since_boot(); + + int yuv_idx = pool_select(&s->yuv_pool); + + s->yuv_metas[yuv_idx] = frame_data; + + uint8_t* yuv_ptr_y = s->yuv_bufs[yuv_idx].y; + uint8_t* yuv_ptr_u = s->yuv_bufs[yuv_idx].u; + uint8_t* yuv_ptr_v = s->yuv_bufs[yuv_idx].v; + cl_mem yuv_cl = s->yuv_cl[yuv_idx]; + + libyuv::RGB24ToI420(bgr_ptr, s->rgb_stride, + yuv_ptr_y, s->yuv_width, + yuv_ptr_u, s->yuv_width/2, + yuv_ptr_v, s->yuv_width/2, + s->rgb_width, s->rgb_height); + + double yt2 = millis_since_boot(); + + visionbuf_sync(&s->yuv_ion[yuv_idx], VISIONBUF_SYNC_TO_DEVICE); + + // keep another reference around till were done processing + pool_acquire(&s->yuv_pool, yuv_idx); + + pool_push(&s->yuv_pool, yuv_idx); + + pthread_mutex_lock(&s->transform_lock); + mat3 transform = s->cur_transform; + const bool run_model_this_iter = s->run_model; + pthread_mutex_unlock(&s->transform_lock); + + double mt1 = 0, mt2 = 0; + if (run_model_this_iter) { + + mat3 model_transform = matmul3(s->yuv_transform, transform); + + mt1 = millis_since_boot(); + s->model_bufs[ui_idx] = + model_eval_frame(&s->model, q, yuv_cl, s->yuv_width, s->yuv_height, + model_transform, img_sock_raw); + mt2 = millis_since_boot(); + + model_publish(model_sock_raw, frame_id, model_transform, s->model_bufs[ui_idx]); + } + + // send frame event + { + capnp::MallocMessageBuilder msg; + cereal::Event::Builder event = msg.initRoot(); + event.setLogMonoTime(nanos_since_boot()); + + auto framed = event.initFrame(); + framed.setFrameId(frame_data.frame_id); + framed.setEncodeId(cnt); + framed.setTimestampEof(frame_data.timestamp_eof); + framed.setFrameLength(frame_data.frame_length); + framed.setIntegLines(frame_data.integ_lines); + framed.setGlobalGain(frame_data.global_gain); + framed.setLensPos(frame_data.lens_pos); + framed.setLensSag(frame_data.lens_sag); + framed.setLensErr(frame_data.lens_err); + framed.setLensTruePos(frame_data.lens_true_pos); + +#ifndef QCOM + framed.setImage(kj::arrayPtr((const uint8_t*)s->yuv_ion[yuv_idx].addr, s->yuv_buf_size)); +#endif + + kj::ArrayPtr transform_vs(&s->yuv_transform.v[0], 9); + framed.setTransform(transform_vs); + + auto words = capnp::messageToFlatArray(msg); + auto bytes = words.asBytes(); + zmq_send(s->recorder_sock_raw, bytes.begin(), bytes.size(), ZMQ_DONTWAIT); + } + + + tbuffer_dispatch(&s->ui_tb, ui_idx); + + // auto exposure over big box + const int exposure_x = 290; + const int exposure_y = 282 + 40; + const int exposure_height = 314; + const int exposure_width = 560; + if (cnt % 3 == 0) { + // find median box luminance for AE + uint32_t lum_binning[256] = {0,}; + for (int y=0; yyuv_width) + exposure_x + x]; + lum_binning[lum]++; + } + } + const unsigned int lum_total = exposure_height * exposure_width; + unsigned int lum_cur = 0; + int lum_med = 0; + for (lum_med=0; lum_med<256; lum_med++) { + // shouldn't be any values less than 16 - yuv footroom + lum_cur += lum_binning[lum_med]; + if (lum_cur >= lum_total / 2) { + break; + } + } + // double avg = (double)acc / (big_box_width * big_box_height) - 16; + // printf("avg %d\n", lum_med); + + camera_autoexposure(&s->cameras.rear, lum_med / 256.0); + } + + pool_release(&s->yuv_pool, yuv_idx); + + // if (cnt%40 == 0) { + // FILE* of = fopen("/sdcard/tmp.yuv", "wb"); + // fwrite(transformed_ptr_y, 1, s->transformed_width*s->transformed_height, of); + // fwrite(transformed_ptr_u, 1, (s->transformed_width/2)*(s->transformed_height/2), of); + // fwrite(transformed_ptr_v, 1, (s->transformed_width/2)*(s->transformed_height/2), of); + // fclose(of); + // } + + double t5 = millis_since_boot(); + + LOGD("queued: %.2fms, yuv: %.2f, model: %.2fms | processing: %.3fms", + (t2-t1), (yt2-yt1), (mt2-mt1), (t5-t1)); + } + +#ifdef DUMP_RGB + fclose(dump_rgb_file); +#endif + + zsock_destroy(&model_sock); + + return NULL; +} + +void* live_thread(void *arg) { + int err; + VisionState *s = (VisionState*)arg; + + set_thread_name("live"); + + zsock_t *terminate = zsock_new_sub(">inproc://terminate", ""); + assert(terminate); + + zsock_t *liveCalibration_sock = zsock_new_sub(">tcp://127.0.0.1:8019", ""); + assert(liveCalibration_sock); + + zpoller_t *poller = zpoller_new(liveCalibration_sock, terminate, NULL); + assert(poller); + + while (!do_exit) { + zsock_t *which = (zsock_t*)zpoller_wait(poller, -1); + if (which == terminate || which == NULL) { + break; + } + + zmq_msg_t msg; + err = zmq_msg_init(&msg); + assert(err == 0); + + err = zmq_msg_recv(&msg, zsock_resolve(which), 0); + assert(err >= 0); + size_t len = zmq_msg_size(&msg); + + // make copy due to alignment issues, will be freed on out of scope + auto amsg = kj::heapArray((len / sizeof(capnp::word)) + 1); + memcpy(amsg.begin(), (const uint8_t*)zmq_msg_data(&msg), len); + + // track camera frames to sync to encoder + capnp::FlatArrayMessageReader cmsg(amsg); + cereal::Event::Reader event = cmsg.getRoot(); + + if (event.isLiveCalibration()) { + pthread_mutex_lock(&s->transform_lock); +#ifdef BIGMODEL + auto wm2 = event.getLiveCalibration().getWarpMatrixBig(); +#else + auto wm2 = event.getLiveCalibration().getWarpMatrix2(); +#endif + assert(wm2.size() == 3*3); + for (int i=0; i<3*3; i++) { + s->cur_transform.v[i] = wm2[i]; + } + s->run_model = true; + pthread_mutex_unlock(&s->transform_lock); + } + + zmq_msg_close(&msg); + } + + zpoller_destroy(&poller); + zsock_destroy(&terminate); + + zsock_destroy(&liveCalibration_sock); + + return NULL; +} + +void set_do_exit(int sig) { + do_exit = 1; +} + +void party(VisionState *s, bool nomodel) { + int err; + + s->terminate_pub = zsock_new_pub("@inproc://terminate"); + assert(s->terminate_pub); + +#ifndef __APPLE__ + pthread_t visionserver_thread_handle; + err = pthread_create(&visionserver_thread_handle, NULL, + visionserver_thread, s); + assert(err == 0); +#endif + + pthread_t proc_thread_handle; + err = pthread_create(&proc_thread_handle, NULL, + processing_thread, s); + assert(err == 0); + + + pthread_t frontview_thread_handle; + err = pthread_create(&frontview_thread_handle, NULL, + frontview_thread, s); + assert(err == 0); + + pthread_t monitoring_thread_handle; + err = pthread_create(&monitoring_thread_handle, NULL, monitoring_thread, s); + assert(err == 0); + + pthread_t live_thread_handle; + err = pthread_create(&live_thread_handle, NULL, + live_thread, s); + assert(err == 0); + + // priority for cameras + err = set_realtime_priority(1); + LOG("setpriority returns %d", err); + + cameras_run(&s->cameras); + + tbuffer_stop(&s->ui_tb); + tbuffer_stop(&s->ui_front_tb); + pool_stop(&s->yuv_pool); + pool_stop(&s->yuv_front_pool); + + zsock_signal(s->terminate_pub, 0); + + LOG("joining frontview_thread"); + err = pthread_join(frontview_thread_handle, NULL); + assert(err == 0); + +#ifndef __APPLE__ + LOG("joining visionserver_thread"); + err = pthread_join(visionserver_thread_handle, NULL); + assert(err == 0); +#endif + + LOG("joining proc_thread"); + err = pthread_join(proc_thread_handle, NULL); + assert(err == 0); + + LOG("joining live_thread"); + err = pthread_join(live_thread_handle, NULL); + assert(err == 0); + + zsock_destroy (&s->terminate_pub); +} + +} + +// TODO: make a version of visiond that runs on pc using streamed video from EON. +// BOUNTY: free EON+panda+giraffe + +int main(int argc, char **argv) { + int err; + + zsys_handler_set(NULL); + signal(SIGINT, (sighandler_t)set_do_exit); + signal(SIGTERM, (sighandler_t)set_do_exit); + + // boringssl via curl via the calibration api can sometimes + // try to write to a closed socket. just ignore SIGPIPE + signal(SIGPIPE, SIG_IGN); + + bool test_run = false; + if (argc > 1 && strcmp(argv[1], "-t") == 0) { + // immediately tear everything down. useful for caching opencl + test_run = true; + } + + bool no_model = false; + if (argc > 1 && strcmp(argv[1], "--no-model") == 0) { + no_model = true; + } + + VisionState state = {0}; + VisionState *s = &state; + + clu_init(); + cl_init(s); + + model_init(&s->model, s->device_id, s->context, true); + monitoring_init(&s->monitoring, s->device_id, s->context); + + // s->zctx = zctx_shadow_zmq_ctx(zsys_init()); + + cameras_init(&s->cameras); + + s->frame_width = s->cameras.rear.ci.frame_width; + s->frame_height = s->cameras.rear.ci.frame_height; + s->frame_stride = s->cameras.rear.ci.frame_stride; + s->frame_size = s->cameras.rear.frame_size; + + // Do not run the model until we receive valid calibration. + s->run_model = false; + pthread_mutex_init(&s->transform_lock, NULL); + + init_buffers(s); + + s->recorder_sock = zsock_new_pub("@tcp://*:8002"); + assert(s->recorder_sock); + s->recorder_sock_raw = zsock_resolve(s->recorder_sock); + + s->monitoring_sock = zsock_new_pub("@tcp://*:8063"); + assert(s->monitoring_sock); + s->monitoring_sock_raw = zsock_resolve(s->monitoring_sock); + + cameras_open(&s->cameras, &s->camera_bufs[0], &s->focus_bufs[0], &s->stats_bufs[0], &s->front_camera_bufs[0]); + + if (test_run) { + do_exit = true; + } + party(s, no_model); + + zsock_destroy(&s->recorder_sock); + zsock_destroy(&s->monitoring_sock); + // zctx_destroy(&s->zctx); + + model_free(&s->model); + monitoring_free(&s->monitoring); + free_buffers(s); + + cl_free(s); + + return 0; +}
    %s